Skip to content
Open
Show file tree
Hide file tree
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 @@ -8,14 +8,14 @@
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.units.Units;
import edu.wpi.first.wpilibj.sysid.SysIdRoutineLog;
import frc.trigon.robot.constants.RobotConstants;
import frc.trigon.robot.poseestimation.robotposeestimator.RobotPoseEstimatorConstants;
import frc.trigon.robot.subsystems.swerve.SwerveConstants;
import frc.trigon.lib.hardware.phoenix6.cancoder.CANcoderEncoder;
import frc.trigon.lib.hardware.phoenix6.cancoder.CANcoderSignal;
import frc.trigon.lib.hardware.phoenix6.talonfx.TalonFXMotor;
import frc.trigon.lib.hardware.phoenix6.talonfx.TalonFXSignal;
import frc.trigon.lib.utilities.Conversions;
import frc.trigon.robot.constants.RobotConstants;
import frc.trigon.robot.poseestimation.robotposeestimator.RobotPoseEstimatorConstants;
import frc.trigon.robot.subsystems.swerve.SwerveConstants;

public class SwerveModule {
private final TalonFXMotor
Expand Down Expand Up @@ -102,7 +102,9 @@ public void setTargetSteerAngle(Rotation2d angle) {
}

public SwerveModuleState getCurrentState() {
return new SwerveModuleState(driveWheelRotationsToMeters(driveMotor.getSignal(TalonFXSignal.VELOCITY)), getCurrentSteerAngle());
final Rotation2d currentSteerAngle = getCurrentSteerAngle();
final double currentDriveVelocity = driveMotor.getSignal(TalonFXSignal.VELOCITY) - (currentSteerAngle.getRotations() * SwerveModuleConstants.COUPLED_RATIO);
return new SwerveModuleState(driveWheelRotationsToMeters(currentDriveVelocity), currentSteerAngle);
}

public SwerveModuleState getTargetState() {
Expand All @@ -115,7 +117,10 @@ public SwerveModuleState getTargetState() {
* @return the position of the drive wheel in meters
*/
public double getDriveWheelPositionRadians() {
return edu.wpi.first.math.util.Units.rotationsToRadians(driveMotor.getSignal(TalonFXSignal.POSITION));
final double driveWheelPositionRotations = driveMotor.getSignal(TalonFXSignal.POSITION);
final double wheelAngleRotations = getCurrentSteerAngle().getRotations();
final double driveWheelPositionWithCouplingRatioRotations = driveWheelPositionRotations - (wheelAngleRotations * SwerveModuleConstants.COUPLED_RATIO);
return edu.wpi.first.math.util.Units.rotationsToRadians(driveWheelPositionWithCouplingRatioRotations);
}

/**
Expand Down Expand Up @@ -144,6 +149,7 @@ private boolean willOptimize(SwerveModuleState state) {
* @param targetVelocityMetersPerSecond the target drive velocity, in meters per second
*/
private void setTargetDriveVelocity(double targetVelocityMetersPerSecond) {
targetVelocityMetersPerSecond -= steerMotor.getSignal(TalonFXSignal.VELOCITY) * SwerveModuleConstants.COUPLED_RATIO;
if (shouldDriveMotorUseClosedLoop) {
setTargetClosedLoopDriveVelocity(targetVelocityMetersPerSecond);
return;
Expand All @@ -154,7 +160,6 @@ private void setTargetDriveVelocity(double targetVelocityMetersPerSecond) {

private void setTargetClosedLoopDriveVelocity(double targetVelocityMetersPerSecond) {
final double targetDriveVelocityRotationsPerSecond = metersToDriveWheelRotations(targetVelocityMetersPerSecond);

driveMotor.setControl(driveVelocityRequest.withVelocity(targetDriveVelocityRotationsPerSecond));
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
import frc.trigon.robot.constants.AutonomousConstants;

public class SwerveModuleConstants {
static final double COUPLED_RATIO = 3;
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

🧹 Nitpick | 🔵 Trivial

Add a brief comment explaining what this ratio represents.

COUPLED_RATIO is not self-evident to someone unfamiliar with the mechanical coupling between the steer and drive gears. A one-liner explaining it (e.g., the gear ratio between the steer and drive shafts that causes drive encoder drift when steering) would go a long way. Based on learnings, comments should explain "why" or non-obvious decisions.

private static final double
DRIVE_MOTOR_GEAR_RATIO = 6.03,//R1: 7.03, R2: 6.03, R3: 5.27
STEER_MOTOR_GEAR_RATIO = 287.0 / 11.0;
Expand Down
Loading