Skip to content

Commit cbb10ae

Browse files
committed
2 parents a4846f6 + 2d9e358 commit cbb10ae

25 files changed

+1501
-655
lines changed

src/main/java/frc/crevolib/configs/CTREConfigs.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
import com.ctre.phoenix6.configs.CANcoderConfiguration;
44
import com.ctre.phoenix6.configs.TalonFXConfiguration;
55

6-
import frc.robot.drivetrain.DrivetrainConfig.DriveConstants;
6+
import frc.robot.drivetrain2.DrivetrainConfig.DriveConstants;
77

88
public final class CTREConfigs {
99
public TalonFXConfiguration angleMotorConfig = new TalonFXConfiguration();

src/main/java/frc/robot/ElbowPivot/ElbowPivot.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -63,7 +63,7 @@ public ElbowPivot() {
6363

6464
mPPIDController = new ProfiledPIDController(Settings.kP, Settings.kI, Settings.kD, mConstraints);
6565
mAFFController = new ArmFeedforward(Settings.kS, Settings.kG, Settings.kV, Settings.kA);
66-
mConstraints = new Constraints( Settings.kMaxAngularVelocity.getRadians(), Settings.kMaxAngularAcceleration.getRadians());
66+
mConstraints = new Constraints(Settings.kMaxAngularVelocity.getRadians(), Settings.kMaxAngularAcceleration.getRadians());
6767

6868
}
6969

src/main/java/frc/robot/Robot.java

Lines changed: 106 additions & 49 deletions
Original file line numberDiff line numberDiff line change
@@ -4,29 +4,64 @@
44

55
package frc.robot;
66

7+
import org.littletonrobotics.junction.LoggedRobot;
8+
import org.littletonrobotics.junction.Logger;
9+
710
import edu.wpi.first.wpilibj.TimedRobot;
811
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
912
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
13+
import edu.wpi.first.wpilibj2.command.Command;
14+
import edu.wpi.first.wpilibj2.command.CommandScheduler;
15+
import frc.crevolib.configs.CTREConfigs;
16+
import frc.robot.driver.DriverXbox;
17+
import frc.robot.operator.OperatorXbox;
1018

1119
/**
1220
* The methods in this class are called automatically corresponding to each mode, as described in
1321
* the TimedRobot documentation. If you change the name of this class or the package after creating
1422
* this project, you must also update the Main.java file in the project.
1523
*/
16-
public class Robot extends TimedRobot {
17-
private static final String kDefaultAuto = "Default";
18-
private static final String kCustomAuto = "My Auto";
19-
private String m_autoSelected;
20-
private final SendableChooser<String> m_chooser = new SendableChooser<>();
24+
/**
25+
* The VM is configured to automatically run this class, and to call the functions corresponding to
26+
* each mode, as described in the TimedRobot documentation. If you change the name of this class or
27+
* the package after creating this project, you must also update the build.gradle file in the
28+
* project.
29+
*/
30+
public class Robot extends LoggedRobot {
31+
public static final CTREConfigs ctreConfigs = new CTREConfigs();
32+
33+
private Command m_autonomousCommand;
34+
private RobotContainer m_robotContainer;
35+
// private boolean constantRPM;
36+
37+
/**
38+
* This method cancels all commands and returns subsystems to their default commands and the
39+
* gamepad configs are reset so that new bindings can be assigned based on mode This method
40+
* should be called when each mode is intialized
41+
*/
42+
public static void resetCommandsAndButtons() {
43+
CommandScheduler.getInstance().cancelAll(); // Disable any currently running commands
44+
CommandScheduler.getInstance().getActiveButtonLoop().clear();
45+
46+
// Reset Config for all gamepads and other button bindings
47+
// Driver.getInstance().resetConfig();
48+
// Operator.getInstance().resetConfig();
49+
DriverXbox.getInstance().resetConfig();
50+
OperatorXbox.getInstance().resetConfig();
51+
}
52+
2153

2254
/**
2355
* This function is run when the robot is first started up and should be used for any
2456
* initialization code.
2557
*/
26-
public Robot() {
27-
m_chooser.setDefaultOption("Default Auto", kDefaultAuto);
28-
m_chooser.addOption("My Auto", kCustomAuto);
29-
SmartDashboard.putData("Auto choices", m_chooser);
58+
@Override
59+
public void robotInit() {
60+
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
61+
// autonomous chooser on the dashboard.
62+
Logger.start();
63+
//CameraServer.startAutomaticCapture();
64+
m_robotContainer = new RobotContainer();
3065
}
3166

3267
/**
@@ -37,68 +72,90 @@ public Robot() {
3772
* SmartDashboard integrated updating.
3873
*/
3974
@Override
40-
public void robotPeriodic() {}
75+
public void robotPeriodic() {
76+
// Runs the Scheduler. This is responsible for polling buttons, adding newly-scheduled
77+
// commands, running already-scheduled commands, removing finished or interrupted commands,
78+
// and running subsystem periodic() methods. This must be called from the robot's periodic
79+
// block in order for anything in the Command-based framework to work.
80+
81+
CommandScheduler.getInstance().run();
82+
}
4183

4284
/**
43-
* This autonomous (along with the chooser code above) shows how to select between different
44-
* autonomous modes using the dashboard. The sendable chooser code works with the Java
45-
* SmartDashboard. If you prefer the LabVIEW Dashboard, remove all of the chooser code and
46-
* uncomment the getString line to get the auto name from the text box below the Gyro
47-
*
48-
* <p>You can add additional auto modes by adding additional comparisons to the switch structure
49-
* below with additional strings. If using the SendableChooser make sure to add them to the
50-
* chooser code above as well.
85+
* This function is called once each time the robot enters Disabled mode.
5186
*/
5287
@Override
53-
public void autonomousInit() {
54-
m_autoSelected = m_chooser.getSelected();
55-
// m_autoSelected = SmartDashboard.getString("Auto Selector", kDefaultAuto);
56-
System.out.println("Auto selected: " + m_autoSelected);
88+
public void disabledInit() {
89+
resetCommandsAndButtons();
5790
}
5891

59-
/** This function is called periodically during autonomous. */
6092
@Override
61-
public void autonomousPeriodic() {
62-
switch (m_autoSelected) {
63-
case kCustomAuto:
64-
// Put custom auto code here
65-
break;
66-
case kDefaultAuto:
67-
default:
68-
// Put default auto code here
69-
break;
70-
}
93+
public void disabledPeriodic() {
94+
7195
}
7296

73-
/** This function is called once when teleop is enabled. */
97+
/**
98+
* This autonomous runs the autonomous command selected by your {@link RobotContainer} class.
99+
*/
74100
@Override
75-
public void teleopInit() {}
101+
public void autonomousInit() {
102+
resetCommandsAndButtons();
103+
m_autonomousCommand = m_robotContainer.getAutonomousCommand();
76104

77-
/** This function is called periodically during operator control. */
105+
// schedule the autonomous command (example)
106+
if (m_autonomousCommand != null) {
107+
m_autonomousCommand.schedule();
108+
}
109+
}
110+
111+
/**
112+
* This function is called periodically during autonomous.
113+
*/
78114
@Override
79-
public void teleopPeriodic() {}
115+
public void autonomousPeriodic() {
116+
117+
}
80118

81-
/** This function is called once when the robot is disabled. */
82119
@Override
83-
public void disabledInit() {}
120+
public void teleopInit() {
121+
// This makes sure that the autonomous stops running when
122+
// teleop starts running. If you want the autonomous to
123+
// continue until interrupted by another command, remove
124+
// this line or comment it out.
125+
resetCommandsAndButtons();
126+
}
84127

85-
/** This function is called periodically when disabled. */
128+
/**
129+
* This function is called periodically during operator control.
130+
*/
86131
@Override
87-
public void disabledPeriodic() {}
132+
public void teleopPeriodic() {
133+
}
88134

89-
/** This function is called once when test mode is enabled. */
90135
@Override
91-
public void testInit() {}
136+
public void testInit() {
137+
// Cancels all running commands at the start of test mode.
138+
resetCommandsAndButtons();
139+
}
92140

93-
/** This function is called periodically during test mode. */
141+
/**
142+
* This function is called periodically during test mode.
143+
*/
94144
@Override
95-
public void testPeriodic() {}
145+
public void testPeriodic() {
146+
}
96147

97-
/** This function is called once when the robot is first started up. */
148+
/**
149+
* This function is called once when the robot is first started up.
150+
*/
98151
@Override
99-
public void simulationInit() {}
152+
public void simulationInit() {
153+
}
100154

101-
/** This function is called periodically whilst in simulation. */
155+
/**
156+
* This function is called periodically whilst in simulation.
157+
*/
102158
@Override
103-
public void simulationPeriodic() {}
159+
public void simulationPeriodic() {
160+
}
104161
}

src/main/java/frc/robot/RobotContainer.java

Lines changed: 9 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -58,11 +58,16 @@ public void setDefaultCommands() {
5858
final var driver = Driver.getInstance();
5959
// final var driver = DriverXbox.getInstance();
6060

61+
// Drivetrain.getInstance().setDefaultCommand(DrivetrainCommands.drive(
62+
// -driver.controller.getLeftX()*DriveConstants.MaxSpeed,
63+
// -driver.controller.getLeftY()*DriveConstants.MaxSpeed,
64+
// -driver.controller.getRightX()*DriveConstants.MaxAngularRate)
65+
// );
66+
6167
Drivetrain.getInstance().setDefaultCommand(DrivetrainCommands.drive(
62-
-driver.controller.getLeftX()*DriveConstants.MaxSpeed,
63-
-driver.controller.getLeftY()*DriveConstants.MaxSpeed,
64-
-driver.controller.getRightX()*DriveConstants.MaxAngularRate)
65-
);
68+
driver::getDriveTranslation,
69+
driver::getDriveRotation
70+
));
6671
}
6772
}
6873

src/main/java/frc/robot/algaeflywheel/AlgaeFlyWheel.java

Lines changed: 27 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@
66

77
import com.ctre.phoenix6.configs.MotorOutputConfigs;
88
import com.ctre.phoenix6.configs.Slot0Configs;
9+
import com.ctre.phoenix6.configs.TalonFXConfigurator;
910
import com.ctre.phoenix6.controls.VelocityVoltage;
1011
import com.ctre.phoenix6.hardware.TalonFX;
1112
import com.ctre.phoenix6.signals.InvertedValue;
@@ -20,10 +21,15 @@ public static class Settings {
2021
static final int kLeftId = 27;
2122
static final int kRightId = 28;
2223

23-
static final Slot0Configs kFlywheelConfigs = new Slot0Configs()
24-
.withKS(0.0)
25-
.withKV(0.115)
26-
.withKP(0.0);
24+
static final InvertedValue kAlgaeScoringInverted = InvertedValue.Clockwise_Positive;
25+
static final InvertedValue kAlgaeIntakingInverted = InvertedValue.CounterClockwise_Positive;
26+
27+
static final Slot0Configs kAlgaeFlyWheelConfigs = new Slot0Configs()
28+
.withKS(0.0)
29+
.withKV(0.115)
30+
.withKA(0.1)
31+
.withKP(0.01)
32+
;
2733

2834
// 5800 RPM at motor; 11600 RPM at wheels
2935
public static final Rotation2d kMaxAngularVelocity = Rotation2d.fromRotations(6000.0 / 60.0);
@@ -33,38 +39,45 @@ public static class Settings {
3339

3440
private static AlgaeFlyWheel mInstance;
3541
private final TalonFX mKrakenLeft, mKrakenRight;
42+
private MotorOutputConfigs leftMotorConfigs, rightMotorConfigs;
43+
private TalonFXConfigurator leftTalonFXConfigurator, rightTalonFXConfigurator;
44+
3645

3746
private AlgaeFlyWheel() {
3847
mKrakenLeft = new TalonFX(Settings.kLeftId);
3948
var leftTalonFXConfigurator = mKrakenLeft.getConfigurator();
40-
var leftMotorConfigs = new MotorOutputConfigs();
49+
leftMotorConfigs = new MotorOutputConfigs();
4150

42-
leftMotorConfigs.Inverted = InvertedValue.Clockwise_Positive;
43-
leftTalonFXConfigurator.apply(leftMotorConfigs);
51+
leftTalonFXConfigurator.apply(Settings.kAlgaeFlyWheelConfigs);
4452

4553

4654
mKrakenRight = new TalonFX(Settings.kRightId);
4755
var rightTalonFXConfigurator = mKrakenRight.getConfigurator();
48-
var righttMotorConfigs = new MotorOutputConfigs();
56+
rightMotorConfigs = new MotorOutputConfigs();
4957

50-
righttMotorConfigs.Inverted = InvertedValue.CounterClockwise_Positive;
51-
rightTalonFXConfigurator.apply(righttMotorConfigs);
58+
rightTalonFXConfigurator.apply(Settings.kAlgaeFlyWheelConfigs);
5259
}
5360

54-
// 57 degreedf
55-
5661
public static AlgaeFlyWheel getInstance() {
5762
if (mInstance == null) {
5863
mInstance = new AlgaeFlyWheel();
5964
}
6065
return mInstance;
6166
}
6267

63-
public void setLeftFlywheelVelocity(Rotation2d velocity) {
68+
public void setLeftFlywheelVelocity(Rotation2d velocity, InvertedValue kInvertedValue) {
69+
// set invert to CW+ and apply config change
70+
leftMotorConfigs.Inverted = kInvertedValue;
71+
leftTalonFXConfigurator.apply(leftMotorConfigs);
72+
6473
mKrakenLeft.setControl(new VelocityVoltage(velocity.getRotations()));
6574
}
6675

67-
public void setRightFlywheelVelocity(Rotation2d velocity) {
76+
public void setRightFlywheelVelocity(Rotation2d velocity, InvertedValue kInvertedValue) {
77+
// set invert to CW+ and apply config change
78+
rightMotorConfigs.Inverted = kInvertedValue;
79+
rightTalonFXConfigurator.apply(rightMotorConfigs);
80+
6881
mKrakenRight.setControl(new VelocityVoltage(velocity.getRotations()));
6982
}
7083

src/main/java/frc/robot/algaeflywheel/commands/AlgaeFlyWheelCommands.java

Lines changed: 7 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -5,12 +5,14 @@
55

66
import java.util.function.Supplier;
77

8+
import com.ctre.phoenix6.signals.InvertedValue;
9+
810
public class AlgaeFlyWheelCommands {
9-
public static Command setAngularVelocity(Supplier<Rotation2d> leftVelocitySupplier, Supplier<Rotation2d> rightVelocitySupplier) {
10-
return new SetVelocityAlgaeFlyWheel(leftVelocitySupplier, rightVelocitySupplier);
11+
public static Command setAngularVelocity(Supplier<Rotation2d> leftVelocitySupplier, Supplier<Rotation2d> rightVelocitySupplier, InvertedValue kInvertedValue) {
12+
return new SetVelocityAlgaeFlyWheel(leftVelocitySupplier, rightVelocitySupplier, kInvertedValue);
1113
}
1214

13-
public static Command setAngularVelocity(Supplier<Rotation2d> velocitySupplier) {
14-
return setAngularVelocity(velocitySupplier, velocitySupplier);
15+
public static Command setAngularVelocity(Supplier<Rotation2d> velocitySupplier, InvertedValue kInvertedValue) {
16+
return setAngularVelocity(velocitySupplier, velocitySupplier, kInvertedValue);
1517
}
16-
}
18+
}

src/main/java/frc/robot/algaeflywheel/commands/SetVelocityAlgaeFlyWheel.java

Lines changed: 11 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -9,28 +9,32 @@
99

1010
import java.util.function.Supplier;
1111

12+
import com.ctre.phoenix6.signals.InvertedValue;
13+
1214
public class SetVelocityAlgaeFlyWheel extends Command {
1315
private final AlgaeFlyWheel flywheel;
1416
private final Supplier<Rotation2d> leftVelocitySupplier, rightVelocitySupplier;
17+
private final InvertedValue kInvertedValue;
1518

1619
private final Rotation2d kAllowedError = Rotation2d.fromRotations(5); // 300 RPM
1720

18-
SetVelocityAlgaeFlyWheel(Supplier<Rotation2d> leftVelocitySupplier, Supplier<Rotation2d> rightVelocitySupplier) {
21+
SetVelocityAlgaeFlyWheel(Supplier<Rotation2d> leftVelocitySupplier, Supplier<Rotation2d> rightVelocitySupplier, InvertedValue kInvertedValue) {
1922
flywheel = AlgaeFlyWheel.getInstance();
2023
this.leftVelocitySupplier = leftVelocitySupplier;
2124
this.rightVelocitySupplier = rightVelocitySupplier;
25+
this.kInvertedValue = kInvertedValue;
2226
}
2327

24-
SetVelocityAlgaeFlyWheel(Supplier<Rotation2d> velocitySupplier) {
25-
this(velocitySupplier, velocitySupplier);
28+
SetVelocityAlgaeFlyWheel(Supplier<Rotation2d> velocitySupplier, InvertedValue kInvertedValue) {
29+
this(velocitySupplier, velocitySupplier, kInvertedValue);
2630
}
2731

2832
@Override
2933
public void execute() {
3034
final var leftVel = leftVelocitySupplier.get();
3135
final var rightVel = rightVelocitySupplier.get();
32-
flywheel.setRightFlywheelVelocity(leftVel);
33-
flywheel.setLeftFlywheelVelocity(rightVel);
36+
flywheel.setRightFlywheelVelocity(leftVel, kInvertedValue);
37+
flywheel.setLeftFlywheelVelocity(rightVel, kInvertedValue);
3438

3539
SmartDashboard.putBoolean("Shooter Ready (left)", (Math.abs(leftVel.getRotations()) - (Math.abs(flywheel.getLeftFlywheelVelocity().getRotations()))) < kAllowedError.getRotations());
3640
SmartDashboard.putBoolean("Shooter Ready (right)", (Math.abs(rightVel.getRotations()) - (Math.abs(flywheel.getRightFlywheelVelocity().getRotations()))) < kAllowedError.getRotations());
@@ -51,7 +55,7 @@ public boolean isFinished() {
5155

5256
@Override
5357
public void end(boolean isInterrupted) {
54-
flywheel.setRightFlywheelVelocity(Rotation2d.fromDegrees(0));
55-
flywheel.setLeftFlywheelVelocity(Rotation2d.fromDegrees(0));
58+
flywheel.setRightFlywheelVelocity(Rotation2d.fromDegrees(0), kInvertedValue);
59+
flywheel.setLeftFlywheelVelocity(Rotation2d.fromDegrees(0), kInvertedValue);
5660
}
5761
}

0 commit comments

Comments
 (0)