-
Notifications
You must be signed in to change notification settings - Fork 0
Improved Swerve #26
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
Improved Swerve #26
Changes from 4 commits
fb362ef
3c3b589
ddebcde
a5b5130
64b548f
84bb74f
218c8f3
c01495f
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change | ||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
@@ -2,7 +2,6 @@ | |||||||||||||||||||||||||||||
|
||||||||||||||||||||||||||||||
import com.pathplanner.lib.util.DriveFeedforwards; | ||||||||||||||||||||||||||||||
import com.pathplanner.lib.util.swerve.SwerveSetpoint; | ||||||||||||||||||||||||||||||
import com.pathplanner.lib.util.swerve.SwerveSetpointGenerator; | ||||||||||||||||||||||||||||||
import edu.wpi.first.math.geometry.Pose2d; | ||||||||||||||||||||||||||||||
import edu.wpi.first.math.geometry.Rotation2d; | ||||||||||||||||||||||||||||||
import edu.wpi.first.math.geometry.Translation3d; | ||||||||||||||||||||||||||||||
|
@@ -19,7 +18,6 @@ | |||||||||||||||||||||||||||||
import frc.trigon.robot.subsystems.MotorSubsystem; | ||||||||||||||||||||||||||||||
import frc.trigon.robot.subsystems.swerve.swervemodule.SwerveModule; | ||||||||||||||||||||||||||||||
import frc.trigon.robot.subsystems.swerve.swervemodule.SwerveModuleConstants; | ||||||||||||||||||||||||||||||
import lib.hardware.RobotHardwareStats; | ||||||||||||||||||||||||||||||
import lib.hardware.phoenix6.Phoenix6SignalThread; | ||||||||||||||||||||||||||||||
import lib.hardware.phoenix6.pigeon2.Pigeon2Gyro; | ||||||||||||||||||||||||||||||
import lib.hardware.phoenix6.pigeon2.Pigeon2Signal; | ||||||||||||||||||||||||||||||
|
@@ -33,7 +31,6 @@ public class Swerve extends MotorSubsystem { | |||||||||||||||||||||||||||||
private final Pigeon2Gyro gyro = SwerveConstants.GYRO; | ||||||||||||||||||||||||||||||
private final SwerveModule[] swerveModules = SwerveConstants.SWERVE_MODULES; | ||||||||||||||||||||||||||||||
private final Phoenix6SignalThread phoenix6SignalThread = Phoenix6SignalThread.getInstance(); | ||||||||||||||||||||||||||||||
private final SwerveSetpointGenerator setpointGenerator = new SwerveSetpointGenerator(AutonomousConstants.ROBOT_CONFIG, SwerveModuleConstants.MAXIMUM_MODULE_ROTATIONAL_SPEED_RADIANS_PER_SECOND); | ||||||||||||||||||||||||||||||
public Pose2d targetPathPlannerPose = new Pose2d(); | ||||||||||||||||||||||||||||||
public boolean isPathPlannerDriving = false; | ||||||||||||||||||||||||||||||
private SwerveSetpoint previousSetpoint = new SwerveSetpoint(getSelfRelativeVelocity(), getModuleStates(), DriveFeedforwards.zeros(AutonomousConstants.ROBOT_CONFIG.numModules)); | ||||||||||||||||||||||||||||||
|
@@ -53,7 +50,7 @@ public void setBrake(boolean brake) { | |||||||||||||||||||||||||||||
public void sysIDDrive(double targetCurrent) { | ||||||||||||||||||||||||||||||
SwerveModuleState[] a = SwerveConstants.KINEMATICS.toSwerveModuleStates(new ChassisSpeeds(0, 0, 2)); | ||||||||||||||||||||||||||||||
for (int i = 0; i < 4; i++) { | ||||||||||||||||||||||||||||||
swerveModules[i].setDriveMotorTargetCurrent(targetCurrent); | ||||||||||||||||||||||||||||||
swerveModules[i].setDriveMotorTargetVoltage(targetCurrent); | ||||||||||||||||||||||||||||||
swerveModules[i].setTargetAngle(a[i].angle); | ||||||||||||||||||||||||||||||
} | ||||||||||||||||||||||||||||||
} | ||||||||||||||||||||||||||||||
|
@@ -176,22 +173,15 @@ public void drivePathPlanner(ChassisSpeeds targetPathPlannerFeedforwardSpeeds, b | |||||||||||||||||||||||||||||
* Used for PathPlanner because it generates setpoints automatically. | ||||||||||||||||||||||||||||||
* | ||||||||||||||||||||||||||||||
* @param targetSpeeds the pre generated robot relative target speeds | ||||||||||||||||||||||||||||||
* @param feedforwards the feedforwards to use | ||||||||||||||||||||||||||||||
*/ | ||||||||||||||||||||||||||||||
public void selfRelativeDriveWithoutSetpointGeneration(ChassisSpeeds targetSpeeds, DriveFeedforwards feedforwards) { | ||||||||||||||||||||||||||||||
public void selfRelativeDriveWithoutSetpointGeneration(ChassisSpeeds targetSpeeds) { | ||||||||||||||||||||||||||||||
// if (isStill(targetSpeeds)) { | ||||||||||||||||||||||||||||||
// stop(); | ||||||||||||||||||||||||||||||
// return; | ||||||||||||||||||||||||||||||
// } | ||||||||||||||||||||||||||||||
|
||||||||||||||||||||||||||||||
final SwerveModuleState[] swerveModuleStates = SwerveConstants.KINEMATICS.toSwerveModuleStates(targetSpeeds); | ||||||||||||||||||||||||||||||
final double[] targetForcesNm; | ||||||||||||||||||||||||||||||
if (feedforwards == null) | ||||||||||||||||||||||||||||||
targetForcesNm = new double[]{0, 0, 0, 0}; | ||||||||||||||||||||||||||||||
else | ||||||||||||||||||||||||||||||
targetForcesNm = feedforwards.linearForcesNewtons(); | ||||||||||||||||||||||||||||||
|
||||||||||||||||||||||||||||||
setTargetModuleStates(swerveModuleStates, targetForcesNm); | ||||||||||||||||||||||||||||||
setTargetModuleStates(swerveModuleStates); | ||||||||||||||||||||||||||||||
} | ||||||||||||||||||||||||||||||
|
||||||||||||||||||||||||||||||
public Rotation2d getDriveRelativeAngle() { | ||||||||||||||||||||||||||||||
|
@@ -279,23 +269,18 @@ void selfRelativeDrive(double xPower, double yPower, FlippableRotation2d targetA | |||||||||||||||||||||||||||||
* @param targetSpeeds the desired robot-relative targetSpeeds | ||||||||||||||||||||||||||||||
*/ | ||||||||||||||||||||||||||||||
public void selfRelativeDrive(ChassisSpeeds targetSpeeds) { | ||||||||||||||||||||||||||||||
previousSetpoint = setpointGenerator.generateSetpoint( | ||||||||||||||||||||||||||||||
previousSetpoint, | ||||||||||||||||||||||||||||||
targetSpeeds, | ||||||||||||||||||||||||||||||
RobotHardwareStats.getPeriodicTimeSeconds() | ||||||||||||||||||||||||||||||
); | ||||||||||||||||||||||||||||||
|
||||||||||||||||||||||||||||||
// if (isStill(previousSetpoint.robotRelativeSpeeds())) { | ||||||||||||||||||||||||||||||
// if (isStill(targetSpeeds) { | ||||||||||||||||||||||||||||||
// stop(); | ||||||||||||||||||||||||||||||
// return; | ||||||||||||||||||||||||||||||
// } | ||||||||||||||||||||||||||||||
|
||||||||||||||||||||||||||||||
setTargetModuleStates(previousSetpoint.moduleStates(), previousSetpoint.feedforwards().linearForcesNewtons()); | ||||||||||||||||||||||||||||||
final SwerveModuleState[] swerveModuleStates = SwerveConstants.KINEMATICS.toSwerveModuleStates(targetSpeeds); | ||||||||||||||||||||||||||||||
setTargetModuleStates(swerveModuleStates); | ||||||||||||||||||||||||||||||
} | ||||||||||||||||||||||||||||||
|
||||||||||||||||||||||||||||||
private void setTargetModuleStates(SwerveModuleState[] swerveModuleStates, double[] targetForcesNm) { | ||||||||||||||||||||||||||||||
private void setTargetModuleStates(SwerveModuleState[] swerveModuleStates) { | ||||||||||||||||||||||||||||||
for (int i = 0; i < swerveModules.length; i++) | ||||||||||||||||||||||||||||||
swerveModules[i].setTargetState(swerveModuleStates[i], targetForcesNm[i]); | ||||||||||||||||||||||||||||||
swerveModules[i].setTargetState(swerveModuleStates[i]); | ||||||||||||||||||||||||||||||
} | ||||||||||||||||||||||||||||||
Comment on lines
+276
to
279
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Desaturate wheel speeds before commanding modules. Pulling raw states from - private void setTargetModuleStates(SwerveModuleState[] swerveModuleStates) {
- for (int i = 0; i < swerveModules.length; i++)
- swerveModules[i].setTargetState(swerveModuleStates[i]);
+ private void setTargetModuleStates(SwerveModuleState[] swerveModuleStates) {
+ SwerveDriveKinematics.desaturateWheelSpeeds(
+ swerveModuleStates,
+ AutonomousConstants.ROBOT_CONFIG.moduleConfig.maxDriveVelocityMPS
+ );
+ for (int i = 0; i < swerveModules.length; i++)
+ swerveModules[i].setTargetState(swerveModuleStates[i]);
} Add the corresponding 📝 Committable suggestion
Suggested change
|
||||||||||||||||||||||||||||||
|
||||||||||||||||||||||||||||||
private void setClosedLoop(boolean shouldUseClosedLoop) { | ||||||||||||||||||||||||||||||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
🛠️ Refactor suggestion | 🟠 Major
Rename parameter
targetCurrent
to reflect voltage-based control.The method now uses
setDriveMotorTargetVoltage
, but the parameter is still namedtargetCurrent
, which is misleading.Apply this diff to rename the parameter:
📝 Committable suggestion
🤖 Prompt for AI Agents