Skip to content

Commit fe80d72

Browse files
authored
[wpimath] Add cosineScale method to SwerveModuleState and instance optimize (wpilibsuite#7114)
1 parent fde264b commit fe80d72

File tree

13 files changed

+311
-64
lines changed

13 files changed

+311
-64
lines changed

wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/SwerveModule.cpp

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -46,29 +46,29 @@ frc::SwerveModulePosition SwerveModule::GetPosition() const {
4646
units::radian_t{m_turningEncoder.GetDistance()}};
4747
}
4848

49-
void SwerveModule::SetDesiredState(
50-
const frc::SwerveModuleState& referenceState) {
49+
void SwerveModule::SetDesiredState(frc::SwerveModuleState& referenceState) {
5150
frc::Rotation2d encoderRotation{
5251
units::radian_t{m_turningEncoder.GetDistance()}};
5352

5453
// Optimize the reference state to avoid spinning further than 90 degrees
55-
auto state =
56-
frc::SwerveModuleState::Optimize(referenceState, encoderRotation);
54+
referenceState.Optimize(encoderRotation);
5755

5856
// Scale speed by cosine of angle error. This scales down movement
5957
// perpendicular to the desired direction of travel that can occur when
6058
// modules change directions. This results in smoother driving.
61-
state.speed *= (state.angle - encoderRotation).Cos();
59+
referenceState.CosineScale(encoderRotation);
6260

6361
// Calculate the drive output from the drive PID controller.
6462
const auto driveOutput = m_drivePIDController.Calculate(
65-
m_driveEncoder.GetRate(), state.speed.value());
63+
m_driveEncoder.GetRate(), referenceState.speed.value());
6664

67-
const auto driveFeedforward = m_driveFeedforward.Calculate(state.speed);
65+
const auto driveFeedforward =
66+
m_driveFeedforward.Calculate(referenceState.speed);
6867

6968
// Calculate the turning motor output from the turning PID controller.
7069
const auto turnOutput = m_turningPIDController.Calculate(
71-
units::radian_t{m_turningEncoder.GetDistance()}, state.angle.Radians());
70+
units::radian_t{m_turningEncoder.GetDistance()},
71+
referenceState.angle.Radians());
7272

7373
const auto turnFeedforward = m_turnFeedforward.Calculate(
7474
m_turningPIDController.GetSetpoint().velocity);

wpilibcExamples/src/main/cpp/examples/SwerveBot/include/SwerveModule.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@ class SwerveModule {
2525
int turningEncoderChannelA, int turningEncoderChannelB);
2626
frc::SwerveModuleState GetState() const;
2727
frc::SwerveModulePosition GetPosition() const;
28-
void SetDesiredState(const frc::SwerveModuleState& state);
28+
void SetDesiredState(frc::SwerveModuleState& state);
2929

3030
private:
3131
static constexpr double kWheelRadius = 0.0508;

wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/subsystems/SwerveModule.cpp

Lines changed: 6 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -53,27 +53,26 @@ frc::SwerveModulePosition SwerveModule::GetPosition() {
5353
units::radian_t{m_turningEncoder.GetDistance()}};
5454
}
5555

56-
void SwerveModule::SetDesiredState(
57-
const frc::SwerveModuleState& referenceState) {
56+
void SwerveModule::SetDesiredState(frc::SwerveModuleState& referenceState) {
5857
frc::Rotation2d encoderRotation{
5958
units::radian_t{m_turningEncoder.GetDistance()}};
6059

6160
// Optimize the reference state to avoid spinning further than 90 degrees
62-
auto state =
63-
frc::SwerveModuleState::Optimize(referenceState, encoderRotation);
61+
referenceState.Optimize(encoderRotation);
6462

6563
// Scale speed by cosine of angle error. This scales down movement
6664
// perpendicular to the desired direction of travel that can occur when
6765
// modules change directions. This results in smoother driving.
68-
state.speed *= (state.angle - encoderRotation).Cos();
66+
referenceState.CosineScale(encoderRotation);
6967

7068
// Calculate the drive output from the drive PID controller.
7169
const auto driveOutput = m_drivePIDController.Calculate(
72-
m_driveEncoder.GetRate(), state.speed.value());
70+
m_driveEncoder.GetRate(), referenceState.speed.value());
7371

7472
// Calculate the turning motor output from the turning PID controller.
7573
auto turnOutput = m_turningPIDController.Calculate(
76-
units::radian_t{m_turningEncoder.GetDistance()}, state.angle.Radians());
74+
units::radian_t{m_turningEncoder.GetDistance()},
75+
referenceState.angle.Radians());
7776

7877
// Set the motor outputs.
7978
m_driveMotor.Set(driveOutput);

wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/subsystems/SwerveModule.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ class SwerveModule {
2727

2828
frc::SwerveModulePosition GetPosition();
2929

30-
void SetDesiredState(const frc::SwerveModuleState& state);
30+
void SetDesiredState(frc::SwerveModuleState& state);
3131

3232
void ResetEncoders();
3333

wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/SwerveModule.cpp

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -46,29 +46,29 @@ frc::SwerveModulePosition SwerveModule::GetPosition() const {
4646
units::radian_t{m_turningEncoder.GetDistance()}};
4747
}
4848

49-
void SwerveModule::SetDesiredState(
50-
const frc::SwerveModuleState& referenceState) {
49+
void SwerveModule::SetDesiredState(frc::SwerveModuleState& referenceState) {
5150
frc::Rotation2d encoderRotation{
5251
units::radian_t{m_turningEncoder.GetDistance()}};
5352

5453
// Optimize the reference state to avoid spinning further than 90 degrees
55-
auto state =
56-
frc::SwerveModuleState::Optimize(referenceState, encoderRotation);
54+
referenceState.Optimize(encoderRotation);
5755

5856
// Scale speed by cosine of angle error. This scales down movement
5957
// perpendicular to the desired direction of travel that can occur when
6058
// modules change directions. This results in smoother driving.
61-
state.speed *= (state.angle - encoderRotation).Cos();
59+
referenceState.CosineScale(encoderRotation);
6260

6361
// Calculate the drive output from the drive PID controller.
6462
const auto driveOutput = m_drivePIDController.Calculate(
65-
m_driveEncoder.GetRate(), state.speed.value());
63+
m_driveEncoder.GetRate(), referenceState.speed.value());
6664

67-
const auto driveFeedforward = m_driveFeedforward.Calculate(state.speed);
65+
const auto driveFeedforward =
66+
m_driveFeedforward.Calculate(referenceState.speed);
6867

6968
// Calculate the turning motor output from the turning PID controller.
7069
const auto turnOutput = m_turningPIDController.Calculate(
71-
units::radian_t{m_turningEncoder.GetDistance()}, state.angle.Radians());
70+
units::radian_t{m_turningEncoder.GetDistance()},
71+
referenceState.angle.Radians());
7272

7373
const auto turnFeedforward = m_turnFeedforward.Calculate(
7474
m_turningPIDController.GetSetpoint().velocity);

wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/SwerveModule.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@ class SwerveModule {
2525
int turningEncoderChannelA, int turningEncoderChannelB);
2626
frc::SwerveModuleState GetState() const;
2727
frc::SwerveModulePosition GetPosition() const;
28-
void SetDesiredState(const frc::SwerveModuleState& state);
28+
void SetDesiredState(frc::SwerveModuleState& state);
2929

3030
private:
3131
static constexpr auto kWheelRadius = 0.0508_m;

wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/SwerveModule.java

Lines changed: 8 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -115,24 +115,27 @@ public void setDesiredState(SwerveModuleState desiredState) {
115115
var encoderRotation = new Rotation2d(m_turningEncoder.getDistance());
116116

117117
// Optimize the reference state to avoid spinning further than 90 degrees
118-
SwerveModuleState state = SwerveModuleState.optimize(desiredState, encoderRotation);
118+
desiredState.optimize(encoderRotation);
119119

120120
// Scale speed by cosine of angle error. This scales down movement perpendicular to the desired
121121
// direction of travel that can occur when modules change directions. This results in smoother
122122
// driving.
123-
state.speedMetersPerSecond *= state.angle.minus(encoderRotation).getCos();
123+
desiredState.cosineScale(encoderRotation);
124124

125125
// Calculate the drive output from the drive PID controller.
126126

127127
final double driveOutput =
128-
m_drivePIDController.calculate(m_driveEncoder.getRate(), state.speedMetersPerSecond);
128+
m_drivePIDController.calculate(m_driveEncoder.getRate(), desiredState.speedMetersPerSecond);
129129

130130
final double driveFeedforward =
131-
m_driveFeedforward.calculate(MetersPerSecond.of(state.speedMetersPerSecond)).in(Volts);
131+
m_driveFeedforward
132+
.calculate(MetersPerSecond.of(desiredState.speedMetersPerSecond))
133+
.in(Volts);
132134

133135
// Calculate the turning motor output from the turning PID controller.
134136
final double turnOutput =
135-
m_turningPIDController.calculate(m_turningEncoder.getDistance(), state.angle.getRadians());
137+
m_turningPIDController.calculate(
138+
m_turningEncoder.getDistance(), desiredState.angle.getRadians());
136139

137140
final double turnFeedforward =
138141
m_turnFeedforward

wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/SwerveModule.java

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -108,20 +108,21 @@ public void setDesiredState(SwerveModuleState desiredState) {
108108
var encoderRotation = new Rotation2d(m_turningEncoder.getDistance());
109109

110110
// Optimize the reference state to avoid spinning further than 90 degrees
111-
SwerveModuleState state = SwerveModuleState.optimize(desiredState, encoderRotation);
111+
desiredState.optimize(encoderRotation);
112112

113113
// Scale speed by cosine of angle error. This scales down movement perpendicular to the desired
114114
// direction of travel that can occur when modules change directions. This results in smoother
115115
// driving.
116-
state.speedMetersPerSecond *= state.angle.minus(encoderRotation).getCos();
116+
desiredState.cosineScale(encoderRotation);
117117

118118
// Calculate the drive output from the drive PID controller.
119119
final double driveOutput =
120-
m_drivePIDController.calculate(m_driveEncoder.getRate(), state.speedMetersPerSecond);
120+
m_drivePIDController.calculate(m_driveEncoder.getRate(), desiredState.speedMetersPerSecond);
121121

122122
// Calculate the turning motor output from the turning PID controller.
123123
final double turnOutput =
124-
m_turningPIDController.calculate(m_turningEncoder.getDistance(), state.angle.getRadians());
124+
m_turningPIDController.calculate(
125+
m_turningEncoder.getDistance(), desiredState.angle.getRadians());
125126

126127
// Calculate the turning motor output from the turning PID controller.
127128
m_driveMotor.set(driveOutput);

wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/SwerveModule.java

Lines changed: 8 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -115,23 +115,26 @@ public void setDesiredState(SwerveModuleState desiredState) {
115115
var encoderRotation = new Rotation2d(m_turningEncoder.getDistance());
116116

117117
// Optimize the reference state to avoid spinning further than 90 degrees
118-
SwerveModuleState state = SwerveModuleState.optimize(desiredState, encoderRotation);
118+
desiredState.optimize(encoderRotation);
119119

120120
// Scale speed by cosine of angle error. This scales down movement perpendicular to the desired
121121
// direction of travel that can occur when modules change directions. This results in smoother
122122
// driving.
123-
state.speedMetersPerSecond *= state.angle.minus(encoderRotation).getCos();
123+
desiredState.cosineScale(encoderRotation);
124124

125125
// Calculate the drive output from the drive PID controller.
126126
final double driveOutput =
127-
m_drivePIDController.calculate(m_driveEncoder.getRate(), state.speedMetersPerSecond);
127+
m_drivePIDController.calculate(m_driveEncoder.getRate(), desiredState.speedMetersPerSecond);
128128

129129
final double driveFeedforward =
130-
m_driveFeedforward.calculate(MetersPerSecond.of(state.speedMetersPerSecond)).in(Volts);
130+
m_driveFeedforward
131+
.calculate(MetersPerSecond.of(desiredState.speedMetersPerSecond))
132+
.in(Volts);
131133

132134
// Calculate the turning motor output from the turning PID controller.
133135
final double turnOutput =
134-
m_turningPIDController.calculate(m_turningEncoder.getDistance(), state.angle.getRadians());
136+
m_turningPIDController.calculate(
137+
m_turningEncoder.getDistance(), desiredState.angle.getRadians());
135138

136139
final double turnFeedforward =
137140
m_turnFeedforward

wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModuleState.java

Lines changed: 28 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -83,6 +83,21 @@ public String toString() {
8383
"SwerveModuleState(Speed: %.2f m/s, Angle: %s)", speedMetersPerSecond, angle);
8484
}
8585

86+
/**
87+
* Minimize the change in heading this swerve module state would require by potentially reversing
88+
* the direction the wheel spins. If this is used with the PIDController class's continuous input
89+
* functionality, the furthest a wheel will ever rotate is 90 degrees.
90+
*
91+
* @param currentAngle The current module angle.
92+
*/
93+
public void optimize(Rotation2d currentAngle) {
94+
var delta = angle.minus(currentAngle);
95+
if (Math.abs(delta.getDegrees()) > 90.0) {
96+
speedMetersPerSecond *= -1;
97+
angle = angle.rotateBy(Rotation2d.kPi);
98+
}
99+
}
100+
86101
/**
87102
* Minimize the change in heading the desired swerve module state would require by potentially
88103
* reversing the direction the wheel spins. If this is used with the PIDController class's
@@ -91,7 +106,9 @@ public String toString() {
91106
* @param desiredState The desired state.
92107
* @param currentAngle The current module angle.
93108
* @return Optimized swerve module state.
109+
* @deprecated Use the instance method instead.
94110
*/
111+
@Deprecated
95112
public static SwerveModuleState optimize(
96113
SwerveModuleState desiredState, Rotation2d currentAngle) {
97114
var delta = desiredState.angle.minus(currentAngle);
@@ -102,4 +119,15 @@ public static SwerveModuleState optimize(
102119
return new SwerveModuleState(desiredState.speedMetersPerSecond, desiredState.angle);
103120
}
104121
}
122+
123+
/**
124+
* Scales speed by cosine of angle error. This scales down movement perpendicular to the desired
125+
* direction of travel that can occur when modules change directions. This results in smoother
126+
* driving.
127+
*
128+
* @param currentAngle The current module angle.
129+
*/
130+
public void cosineScale(Rotation2d currentAngle) {
131+
speedMetersPerSecond *= angle.minus(currentAngle).getCos();
132+
}
105133
}

0 commit comments

Comments
 (0)