Skip to content
This repository was archived by the owner on May 19, 2024. It is now read-only.

Commit 5630e26

Browse files
committed
refactor(swerve): Change how module speed deadband is calculated.
1 parent 4642109 commit 5630e26

File tree

1 file changed

+3
-6
lines changed

1 file changed

+3
-6
lines changed

Diff for: src/main/java/frc/robot/swerve/SwerveModuleIOCustom.java

+3-6
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,9 @@
11
package frc.robot.swerve;
22

3-
import edu.wpi.first.math.MathUtil;
43
import edu.wpi.first.math.geometry.Rotation2d;
54
import edu.wpi.first.math.kinematics.SwerveModulePosition;
65
import edu.wpi.first.math.kinematics.SwerveModuleState;
6+
import edu.wpi.first.math.util.Units;
77
import frc.lib.controller.PositionControllerIO;
88
import frc.lib.controller.PositionControllerIO.PositionControllerIOValues;
99
import frc.lib.controller.VelocityControllerIO;
@@ -25,9 +25,6 @@ public class SwerveModuleIOCustom implements SwerveModuleIO {
2525
/** Drive motor values. */
2626
private final VelocityControllerIOValues driveMotorValues = new VelocityControllerIOValues();
2727

28-
/** Speeds below this speed are zeroed. */
29-
private final double kSpeedDeadbandMetersPerSecond = 0.025;
30-
3128
/** Module setpoint */
3229
private SwerveModuleState setpoint;
3330

@@ -92,11 +89,11 @@ private SwerveModuleState optimize(
9289
// Since we are lazy, perform additional optimizations
9390

9491
// Deadband the module speed
95-
if (MathUtil.isNear(0.0, setpoint.speedMetersPerSecond, kSpeedDeadbandMetersPerSecond)) {
92+
if (Math.abs(setpoint.speedMetersPerSecond) < Units.inchesToMeters(1)) {
9693
setpoint.speedMetersPerSecond = 0.0;
9794
}
9895

99-
// Keep previous angle if we aren't moving
96+
// Keep previous angle if the module isn't moving
10097
if (setpoint.speedMetersPerSecond == 0.0) {
10198
setpoint.angle = state.angle;
10299
}

0 commit comments

Comments
 (0)