My team has used MAX Swerve since last season and we have always had a problem while moving forward with the Swerve. When we just move it forward, the robot turns too, not being a straight translation and it’s so visible. We tried to calibrate it a lot of times. Does anyone know what can be our problem?
there are many things that could cause this, the main 3 that come to mind: the chassis frame isnt perfectly square, the modules absolute offsets are slightly misaligned, the desired and achieved wheel speeds dont match.
try plotting the module setpoints and actual speeds and see if theres a difference, is an easy place to start.
another solution (after trying to find he route cause) is making the swerve snap to angle with the gyro when theres no turning input
There are alot of optimizations that go into this one action, i would recommend YAGSL after the beta
release today because they are built in and by far the easiest option.
If you are deadset on using your own code you should tune your PIDs better using graphs the. try implementing a ChassisSpeed discretization then Angular Velocity Compensation.
You can also try to implement feedforward, cosine compensation, and more.
i wrote a longer more detailed post here.
We’ve also been using MaxSwerve for a little over a year now and have had that exact same problem. We’ve diagnosed the issue as a “drift” in the chassis. After over 6 months of pure logging, we’ve concluded it is not hardware-related but instead something wrong with the code that we wrote. I don’t remember which MaxSwerve code library we copied and then modified from, but a potential solution would be to use a different code library. Currently, we have a hotfix with an adaptive pid roll, meaning the robot will auto-center at the end of its path.
Our MaxSwerve chassis is still in service with our new hotfix. I would suggest looking into a new code library sooner rather than later. We have since bought an MK4n drivetrain to use.
If you want more information or help, I can try to loop in our SW lead because I am not an expert in this matter.
Out of curiosity, have you built and actually tested whether the MK4n drivetrain exhibits the same issue?
Nope, not yet. We just got our parts yesterday.
Our SW team has developed an entirely new SW architecture so there won’t be anything shared in common. I have a feeling we won’t have any issues also given the success other teams are having with the same code libraries.
We’re currently using REV’s template to program our MaxSwerve chassis, and we also suspect the issue lies in the code rather than the hardware. Your suggestion to explore other libraries is very helpful, and we’ll definitely consider it. If possible, we’d appreciate any further insights or advice from your software lead. Thank you!
Sorry for the delayed response! Our team faced some challenges last week and couldn’t run tests until yesterday. However, we now have some data to share about the issue.
Plan
Our plan was to drive the robot forward. To eliminate potential interference from the joystick, we used the POV controls to drive and aligned the robot with the wall for consistency.
Expected
We expected that:
-
- The real positions of the modules might drift while moving forward, but the setpoints would remain stable.
-
- When we lifted the robot off the ground, the modules would realign with the setpoints and face forward as intended.
What Actually Happened
-
- Both the setpoints and the real positions of the modules turned while driving forward.
-
- When we lifted the robot off the ground, the modules did not return to alignment with the setpoints. Instead, they remained turned as though the robot’s “front” had changed.
-
- Despite this behavior, the gyro readings and the robot’s pose front remained unchanged.
Observations
-
The value of
RotSpeedDelivered
did not change while moving forward. -
We don’t believe the issue is related to the PID tuning because:
- The modules face forward correctly when there is no friction with the ground.
- We experimented with various PID values, but the issue persists.
To provide more context and help clarify the issue, here is the code we’re using to drive the robot:
public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelative, boolean rateLimit) {
double xSpeedCommanded;
double ySpeedCommanded;
if (rateLimit) {
// Convert XY to polar for rate limiting
double inputTranslationDir = Math.atan2(ySpeed, xSpeed);
double inputTranslationMag = Math.sqrt(Math.pow(xSpeed, 2) + Math.pow(ySpeed, 2));
// Calculate the direction slew rate based on an estimate of the lateral acceleration
double directionSlewRate;
if (m_currentTranslationMag != 0.0) {
directionSlewRate = Math.abs(DriveConstants.kDirectionSlewRate / m_currentTranslationMag);
} else {
directionSlewRate = 500.0; //some high number that means the slew rate is effectively instantaneous
}
double currentTime = WPIUtilJNI.now() * 1e-6;
double elapsedTime = currentTime - m_prevTime;
double angleDif = SwerveUtils.AngleDifference(inputTranslationDir, m_currentTranslationDir);
if (angleDif < 0.45*Math.PI) {
m_currentTranslationDir = SwerveUtils.StepTowardsCircular(m_currentTranslationDir, inputTranslationDir, directionSlewRate * elapsedTime);
m_currentTranslationMag = m_magLimiter.calculate(inputTranslationMag);
}
else if (angleDif > 0.85*Math.PI) {
if (m_currentTranslationMag > 1e-4) { //some small number to avoid floating-point errors with equality checking
// keep currentTranslationDir unchanged
m_currentTranslationMag = m_magLimiter.calculate(0.0);
}
else {
m_currentTranslationDir = SwerveUtils.WrapAngle(m_currentTranslationDir + Math.PI);
m_currentTranslationMag = m_magLimiter.calculate(inputTranslationMag);
}
}
else {
m_currentTranslationDir = SwerveUtils.StepTowardsCircular(m_currentTranslationDir, inputTranslationDir, directionSlewRate * elapsedTime);
m_currentTranslationMag = m_magLimiter.calculate(0.0);
}
m_prevTime = currentTime;
xSpeedCommanded = m_currentTranslationMag * Math.cos(m_currentTranslationDir);
ySpeedCommanded = m_currentTranslationMag * Math.sin(m_currentTranslationDir);
m_currentRotation = m_rotLimiter.calculate(rot);
} else {
xSpeedCommanded = xSpeed;
ySpeedCommanded = ySpeed;
m_currentRotation = rot;
}
// Convert the commanded speeds into the correct units for the drivetrain
double xSpeedDelivered = xSpeedCommanded * DriveConstants.kMaxSpeedMetersPerSecond;
double ySpeedDelivered = ySpeedCommanded * DriveConstants.kMaxSpeedMetersPerSecond;
double rotDelivered = m_currentRotation * DriveConstants.kMaxAngularSpeed;
Logger.recordOutput("SwerveStates/Velocity/X", xSpeedDelivered);
Logger.recordOutput("SwerveStates/Velocity/y", ySpeedDelivered);
Logger.recordOutput("SwerveStates/Velocity/rot", rotDelivered);
var swerveModuleStates = DriveConstants.kDriveKinematics.toSwerveModuleStates(
fieldRelative
? ChassisSpeeds.fromFieldRelativeSpeeds(xSpeedDelivered, ySpeedDelivered, rotDelivered, poseEstimator.getEstimatedPosition().getRotation())
: new ChassisSpeeds(xSpeedDelivered, ySpeedDelivered, rotDelivered)
);
SwerveDriveKinematics.desaturateWheelSpeeds(
swerveModuleStates, DriveConstants.kMaxSpeedMetersPerSecond
);
Logger.recordOutput("SwerveStates/Setpoints", getModuleSetpoints(swerveModuleStates));
setModuleStates(swerveModuleStates);
}
We are now exploring other libraries, as suggested by Ethan_L.
so the robot rotates, and the gyro doesn’t? or the gyro rotates but the pose doesn’t? what gyro are you using? are you using the gyro or the wheel odometry to update the rotation of the robot’s pose?
Have you checked the modules for any signs of resistance? If one module has resistance it can easily offset the movement of the bot.
Just posting an update from our team here, we’ve developed our MK4n code and it works perfectly in our sim, no drift. In the same sim the MaxSwerve modules still have drift. Your code library is the same one we used and have had issues with.
I’m curious if you’ve run something very simple, like “set every module to zero steering and 0.1 m/s velocity” … do you still see this phenomenon?
Note that mechanically, all the COTS swerve modules couple driving and steering, so if you steering “P” value is too soft, the drive force will tend to affect steering. If all the bevels are facing the same way, you’ll see a sort of “crabbing,” and if they’re not all facing the same way, you’ll see turning. It’s surprising how high you can make “P” without really hurting anything. For awhile we tried to compensate for the coupling force, but it didn’t seem to help much; we just make steering “P” really high.
Check your magnets in the absolute encoders. We had this situation with the MK4i swerves and found that the locktite either failed or was not used during assembly. We learned long ago to verify mechanical before we determine it is software related. May not be your issue but literally takes a couple minutes to check it.
Has anyone successfully fixed this issue by retuning the PID controller on their turning motor? Or has anyone even tried manually tuning their PIDs when using the MAX swerve template code? I have seen many people suggest this as the issue.
My team has seen similar symptoms on our MAX swerve and interestingly enough I have never heard this issue from someone using other swerve modules.
Is it possible that a single swerve module has a different speed pinion set than the others, and one corner is being driven faster/slower than all the others, thus causing the turning?
Or maybe something is rubbing, causing friction and one of the wheels to spin slower than the others?
One thing you can try is unplugging the power from one drive motor at a time and try driving. The steering motor should still work and the wheel will go into freespin mode. You can test driving with once with one drive unplugged and see which corner is the problem.
Uneven wheel wear could be another source of the issue you mention (especially colsons)