1
1
package frc .robot .swerve ;
2
2
3
- import edu .wpi .first .math .MathUtil ;
4
3
import edu .wpi .first .math .geometry .Rotation2d ;
5
4
import edu .wpi .first .math .kinematics .SwerveModulePosition ;
6
5
import edu .wpi .first .math .kinematics .SwerveModuleState ;
6
+ import edu .wpi .first .math .util .Units ;
7
7
import frc .lib .controller .PositionControllerIO ;
8
8
import frc .lib .controller .PositionControllerIO .PositionControllerIOValues ;
9
9
import frc .lib .controller .VelocityControllerIO ;
@@ -25,9 +25,6 @@ public class SwerveModuleIOCustom implements SwerveModuleIO {
25
25
/** Drive motor values. */
26
26
private final VelocityControllerIOValues driveMotorValues = new VelocityControllerIOValues ();
27
27
28
- /** Speeds below this speed are zeroed. */
29
- private final double kSpeedDeadbandMetersPerSecond = 0.025 ;
30
-
31
28
/** Module setpoint */
32
29
private SwerveModuleState setpoint ;
33
30
@@ -92,11 +89,11 @@ private SwerveModuleState optimize(
92
89
// Since we are lazy, perform additional optimizations
93
90
94
91
// Deadband the module speed
95
- if (MathUtil . isNear ( 0.0 , setpoint .speedMetersPerSecond , kSpeedDeadbandMetersPerSecond )) {
92
+ if (Math . abs ( setpoint .speedMetersPerSecond ) < Units . inchesToMeters ( 1 )) {
96
93
setpoint .speedMetersPerSecond = 0.0 ;
97
94
}
98
95
99
- // Keep previous angle if we aren 't moving
96
+ // Keep previous angle if the module isn 't moving
100
97
if (setpoint .speedMetersPerSecond == 0.0 ) {
101
98
setpoint .angle = state .angle ;
102
99
}
0 commit comments