Skip to content

Commit 85e47f8

Browse files
limited joystick power
1 parent c1878fb commit 85e47f8

2 files changed

Lines changed: 18 additions & 6 deletions

File tree

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

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -63,7 +63,8 @@ public static final class DriveConstants {
6363
// Slow mode stuff
6464
public static final double slowModeSpeedMultiplier = 0.3;
6565

66-
66+
public static final double joystickAccelLimit = 0.4;
67+
public static final double joystickVelLimit = 0.5;
6768

6869
// public static final double possibleBumperWidth = 0.57912 + Units.inchesToMeters(3); // 0.6553199999999999
6970
// public static final double possibleBumperLength = 0.65024 + Units.inchesToMeters(3); // 0.72644

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

Lines changed: 16 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -50,8 +50,8 @@ public class DriveCommands {
5050
private static final double WHEEL_RADIUS_RAMP_RATE = 0.05; // Rad/Sec^2
5151

5252
// The value here is totatlly arbitrary
53-
private static final SlewRateLimiter mJoystickXLimiter = new SlewRateLimiter(25.0); // I think this %/20ms
54-
private static final SlewRateLimiter mJoystickYLimiter = new SlewRateLimiter(25.0); // I think this is in m/s/s
53+
// This is probably doing very little, but it works and I don't have more testing time
54+
private static final SlewRateLimiter mJoystickAccelLimiter = new SlewRateLimiter(Constants.DriveConstants.joystickAccelLimit); // I think this joystick percentage
5555

5656

5757
private DriveCommands() {}
@@ -64,6 +64,17 @@ private static Translation2d getLinearVelocityFromJoysticks(double x, double y)
6464
// Square magnitude for more precise control
6565
linearMagnitude = linearMagnitude * linearMagnitude;
6666

67+
linearMagnitude = MathUtil.clamp(
68+
linearMagnitude,
69+
-Constants.DriveConstants.joystickVelLimit,
70+
Constants.DriveConstants.joystickVelLimit
71+
);
72+
73+
if (linearMagnitude < 0.3) {
74+
// Limit the rate of change for velocity (accel)
75+
linearMagnitude = mJoystickAccelLimiter.calculate(linearMagnitude);
76+
}
77+
6778
// Return new linear velocity
6879
return new Pose2d(new Translation2d(), linearDirection)
6980
.transformBy(new Transform2d(linearMagnitude, 0.0, new Rotation2d()))
@@ -86,12 +97,12 @@ public static Command joystickDrive(
8697
// Get linear velocity
8798
// Limit the magnitude of the velocity vector via a slew rate limiter
8899
// We can't really limit the magnitude directly, because we'd also need to
89-
// limit the angle, and it we'd be creating another object here.
100+
// limit the angle, and it we'd be creating another object here.
90101
// so we apply the limit to the joystick input (doubles) instead
91102
Translation2d linearVelocity =
92103
getLinearVelocityFromJoysticks(
93-
mJoystickXLimiter.calculate(xSupplier.getAsDouble()),
94-
mJoystickYLimiter.calculate(ySupplier.getAsDouble())
104+
xSupplier.getAsDouble(),
105+
ySupplier.getAsDouble()
95106
);
96107

97108
// Apply rotation deadband

0 commit comments

Comments
 (0)