Skip to content

Commit

Permalink
Adds Slow Mode (Untested)
Browse files Browse the repository at this point in the history
  • Loading branch information
taj-maharj08 committed Jan 20, 2025
1 parent bf96ff2 commit b5b9cf5
Show file tree
Hide file tree
Showing 2 changed files with 18 additions and 2 deletions.
18 changes: 16 additions & 2 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -23,9 +23,13 @@
public class RobotContainer {
private double MaxSpeed =
TunerConstants.kSpeedAt12Volts.in(MetersPerSecond); // kSpeedAt12Volts desired top speed
private double SlowSpeed =
TunerConstants.kSlowSpeed.in(MetersPerSecond);
private double MaxAngularRate =
RotationsPerSecond.of(0.75)
.in(RadiansPerSecond); // 3/4 of a rotation per second max angular velocity
private double SlowAngularRate =
RotationsPerSecond.of(0.5).in(RadiansPerSecond);

/* Setting up bindings for necessary control of the swerve drive platform */
private final SwerveRequest.FieldCentric drive =
Expand Down Expand Up @@ -74,6 +78,16 @@ private void configureBindings() {
));

joystick.a().whileTrue(drivetrain.applyRequest(() -> brake));
joystick.rightStick().whileTrue(
drivetrain.applyRequest(() ->
drive
.withVelocityX(
-joystick.getLeftX() * SlowSpeed)
.withVelocityY(
-joystick.getLeftY() * SlowSpeed)
.withRotationalRate(
-joystick.getRightX() * SlowAngularRate)
));
// joystick
// .b()
// .whileTrue(
Expand All @@ -82,9 +96,9 @@ private void configureBindings() {
// point.withModuleDirection(
// new Rotation2d(-joystick.getLeftY(), -joystick.getLeftX()))));

joystick.rightTrigger().whileTrue(s_Shooter.shootL2()).onFalse(s_Shooter.stop());
joystick.rightTrigger().whileTrue(s_Shooter.shootTrough()).onFalse(s_Shooter.stop());
joystick.y().whileTrue(s_Shooter.intake()).onFalse(s_Shooter.stop());
joystick.a().whileTrue(s_Shooter.shootTrough()).onFalse(s_Shooter.stop());
// joystick.a().whileTrue(s_Shooter.shootTrough()).onFalse(s_Shooter.stop());

joystick.b().onTrue(s_Elevator.goToL1()).onFalse(s_Elevator.stop());
joystick.leftBumper().onTrue(s_Elevator.goToL2
Expand Down
2 changes: 2 additions & 0 deletions src/main/java/frc/robot/generated/TunerConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,7 @@ public class TunerConstants {
// Theoretical free speed (m/s) at 12 V applied output;
// This needs to be tuned to your individual robot
public static final LinearVelocity kSpeedAt12Volts = MetersPerSecond.of(5.21); //∞
public static final LinearVelocity kSlowSpeed = MetersPerSecond.of(3);

// Every 1 rotation of the azimuth results in kCoupleRatio drive motor turns;
// This may need to be tuned to your individual robot
Expand Down Expand Up @@ -134,6 +135,7 @@ public class TunerConstants {
.withDriveMotorClosedLoopOutput(kDriveClosedLoopOutput)
.withSlipCurrent(kSlipCurrent)
.withSpeedAt12Volts(kSpeedAt12Volts)
.withSpeedAt12Volts(kSlowSpeed)
.withDriveMotorType(kDriveMotorType)
.withSteerMotorType(kSteerMotorType)
.withFeedbackSource(kSteerFeedbackType)
Expand Down

0 comments on commit b5b9cf5

Please sign in to comment.