Skip to content

Commit 7bb216e

Browse files
committed
Added slow mode (only tested in simulation)
1 parent bc36c9c commit 7bb216e

3 files changed

Lines changed: 16 additions & 4 deletions

File tree

src/main/java/frc/robot/Constants.java

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -60,6 +60,13 @@ public static final class DriveConstants {
6060
public static final double wheelBase = Units.inchesToMeters(25.6);
6161
public static final double driveBaseRadius = Math.hypot(trackWidth / 2.0, wheelBase / 2.0);
6262

63+
64+
65+
// Slow mode stuff
66+
public static final double slowModeSpeedMultiplier = 0.3;
67+
68+
69+
6370
// public static final double possibleBumperWidth = 0.57912 + Units.inchesToMeters(3); // 0.6553199999999999
6471
// public static final double possibleBumperLength = 0.65024 + Units.inchesToMeters(3); // 0.72644
6572

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

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -191,6 +191,7 @@ private void competitionButtonBindings(){
191191
new LimelightAlignWithReef(drive, true)
192192
);
193193

194+
194195
}
195196

196197

@@ -359,7 +360,9 @@ private void configureDriveBindings() {
359360
drive,
360361
() -> -flightStick.getRawAxis(1),
361362
() -> -flightStick.getRawAxis(0),
362-
() -> -flightStick.getRawAxis(2)));
363+
() -> -flightStick.getRawAxis(2),
364+
() -> flightStick.getRawButton(1))
365+
);
363366

364367

365368

src/main/java/frc/robot/commands/DriveCommands.java

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@
3434
import java.text.NumberFormat;
3535
import java.util.LinkedList;
3636
import java.util.List;
37+
import java.util.function.BooleanSupplier;
3738
import java.util.function.DoubleSupplier;
3839
import java.util.function.Supplier;
3940

@@ -71,7 +72,8 @@ public static Command joystickDrive(
7172
Drive drive,
7273
DoubleSupplier xSupplier,
7374
DoubleSupplier ySupplier,
74-
DoubleSupplier omegaSupplier) {
75+
DoubleSupplier omegaSupplier,
76+
BooleanSupplier slowModeSupplier) {
7577

7678
return Commands.run(
7779
() -> {
@@ -89,8 +91,8 @@ public static Command joystickDrive(
8991
// Convert to field relative speeds & send command
9092
ChassisSpeeds speeds =
9193
new ChassisSpeeds(
92-
linearVelocity.getX() * drive.getMaxLinearSpeedMetersPerSec(),
93-
linearVelocity.getY() * drive.getMaxLinearSpeedMetersPerSec(),
94+
linearVelocity.getX() * drive.getMaxLinearSpeedMetersPerSec() * (slowModeSupplier.getAsBoolean() ? Constants.DriveConstants.slowModeSpeedMultiplier: 1.0),
95+
linearVelocity.getY() * drive.getMaxLinearSpeedMetersPerSec() * (slowModeSupplier.getAsBoolean() ? Constants.DriveConstants.slowModeSpeedMultiplier: 1.0),
9496
omega * drive.getMaxAngularSpeedRadPerSec());
9597
boolean isFlipped =
9698
DriverStation.getAlliance().isPresent()

0 commit comments

Comments
 (0)