Skip to content
Merged
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 @@ -155,7 +155,6 @@ public SN_SuperSwerve(SN_SwerveConstants swerveConstants, SN_SwerveModule[] modu
SN_SwerveModule.driveGearRatio = swerveConstants.driveGearRatio;
SN_SwerveModule.steerGearRatio = swerveConstants.steerGearRatio;

SN_SwerveModule.CANBusName = CANBusName;
SN_SwerveModule.minimumSteerSpeedPercent = minimumSteerPercent;

SN_SwerveModule.driveInversion = driveInversion;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,6 @@ public class SN_SwerveModule extends SubsystemBase {
public static InvertedValue driveInversion = InvertedValue.CounterClockwise_Positive;
public static InvertedValue steerInversion = InvertedValue.Clockwise_Positive;
public static SensorDirectionValue cancoderInversion = SensorDirectionValue.CounterClockwise_Positive;
public static String CANBusName = "Swerve";
public static double minimumSteerSpeedPercent = 0.01;

// -*- Static Physical Constants -*-
Expand Down Expand Up @@ -85,9 +84,11 @@ public class SN_SwerveModule extends SubsystemBase {
* The offset of the CANcoder in rotations. This is typically
* obtained by aligning all of the wheels in the appropriate
* direction and then copying the Raw Absolute encoder value.
* @param CANBusName
* The name of the CANBus that the module is connected to.
*/
public SN_SwerveModule(int moduleNumber, int driveMotorID, int steerMotorID, int absoluteEncoderID,
double absoluteEncoderOffset) {
double absoluteEncoderOffset, String CANBusName) {

simTimer.start();

Expand Down Expand Up @@ -136,7 +137,7 @@ public void configure() {
*/
public double getRawAbsoluteEncoder() {
// TODO: change to units using .getValue
return absoluteEncoder.getAbsolutePosition().getValueAsDouble();
return absoluteEncoder.getAbsolutePosition().getValueAsDouble();
}

/**
Expand Down Expand Up @@ -179,9 +180,10 @@ public void resetDriveMotorEncoder() {
public SwerveModuleState getActualModuleState() {
// TODO: change to units using .getValue
double velocity = SN_Math.rotationsToMeters(driveMotor.getVelocity().getValueAsDouble(), wheelCircumference, 1);

// TODO: change to units using .getValue
Rotation2d angle = Rotation2d.fromDegrees(Units.rotationsToDegrees(steerMotor.getPosition().getValueAsDouble()));
Rotation2d angle = Rotation2d
.fromDegrees(Units.rotationsToDegrees(steerMotor.getPosition().getValueAsDouble()));

return new SwerveModuleState(velocity, angle);
}
Expand Down Expand Up @@ -212,7 +214,8 @@ public SwerveModulePosition getModulePosition() {
// TODO: change to units using .getValue
double distance = SN_Math.rotationsToMeters(driveMotor.getPosition().getValueAsDouble(), wheelCircumference, 1);
// TODO: change to units using .getValue
Rotation2d angle = Rotation2d.fromDegrees(Units.rotationsToDegrees(steerMotor.getPosition().getValueAsDouble()));
Rotation2d angle = Rotation2d
.fromDegrees(Units.rotationsToDegrees(steerMotor.getPosition().getValueAsDouble()));

return new SwerveModulePosition(distance, angle);
}
Expand Down