Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[Swerve Setpoint Generator] Prevent force from being applied to chassisTorque if the magnitude of the force is 0 #927

Merged
merged 2 commits into from
Dec 18, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -273,9 +273,11 @@ public SwerveSetpoint generateSetpoint(
chassisForceVec = chassisForceVec.plus(moduleForceVec);

// Calculate the torque this module will apply to the chassis
Rotation2d angleToModule = config.moduleLocations[m].getAngle();
Rotation2d theta = moduleForceVec.getAngle().minus(angleToModule);
chassisTorque += forceAtCarpet * config.modulePivotDistance[m] * theta.getSin();
if (!epsilonEquals(0, moduleForceVec.getNorm())) {
Rotation2d angleToModule = config.moduleLocations[m].getAngle();
Rotation2d theta = moduleForceVec.getAngle().minus(angleToModule);
chassisTorque += forceAtCarpet * config.modulePivotDistance[m] * theta.getSin();
}
}

Translation2d chassisAccelVec = chassisForceVec.div(config.massKG);
Expand Down
Loading