Skip to content

Commit

Permalink
refactor SwerveDrive and SwerveModule; adjust motor configurations an…
Browse files Browse the repository at this point in the history
…d clean up commented code
  • Loading branch information
Ishan1522 committed Dec 25, 2024
1 parent f90e65a commit e04dec9
Show file tree
Hide file tree
Showing 3 changed files with 9 additions and 26 deletions.
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/subsystems/swerve/SwerveDrive.java
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ public class SwerveDrive extends SubsystemBase {
new SwerveSetpointGenerator(
DriveConstants.MODULE_TRANSLATIONS,
DCMotor.getKrakenX60(1).withReduction(ModuleConstants.DRIVE_GEAR_RATIO),
DCMotor.getFalcon500(1).withReduction(11),
DCMotor.getFalcon500(1).withReduction(1),
60,
58,
7,
Expand Down Expand Up @@ -214,7 +214,7 @@ xSpeed, ySpeed, rotationSpeed, getOdometryAllianceRelativeRotation2d())
* @return Value is Counter-clockwise positive.
*/
public double getHeading() {
return -gyroInputs.yawDegrees;
return gyroInputs.yawDegrees;
}

/**
Expand Down
25 changes: 4 additions & 21 deletions src/main/java/frc/robot/subsystems/swerve/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -43,23 +43,6 @@ public void periodic() {
// updateOdometryPositions();
}

// private void updateOdometryPositions() {
// odometryPositions = new SwerveModulePosition[inputs.odometryDriveWheelRevolutions.length];
// for (int i = 0; i < odometryPositions.length; i++) {
// double positionMeters = inputs.odometryDriveWheelRevolutions[i];
// Rotation2d angle = inputs.odometrySteerPositions[i];
// odometryPositions[i] = new SwerveModulePosition(positionMeters, angle);

// SmartDashboard.putNumber("updated drive position", positionMeters);
// SmartDashboard.putNumber("updated angle", angle.getDegrees());
// }
// }

// private double driveRevolutionsToMeters(double driveWheelRevolutions) {
// return Rotations.of(driveWheelRevolutions).in(Radians)
// * SimulationConstants.WHEEL_RADIUS_METERS;
// }

public void setVoltage(Voltage volts) {
io.setDriveVoltage(volts);
io.setTurnVoltage(Volts.zero());
Expand All @@ -75,10 +58,10 @@ public double getCharacterizationVelocity() {

/** Runs the module with the specified setpoint state. Returns optimized setpoint */
public void runSetPoint(SwerveModuleState state) {
// state.optimize(getTurnRotation());
// if (state.speedMetersPerSecond < 0.01) {
// io.stopModule();
// }
state.optimize(getTurnRotation());
if (state.speedMetersPerSecond < 0.01) {
io.stopModule();
}
io.setDesiredState(state);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,12 +24,12 @@ public class SimulatedModule implements ModuleInterface {
ModuleConstants.MAX_ANGULAR_SPEED_ROTATIONS_PER_SECOND,
ModuleConstants.MAX_ANGULAR_ACCELERATION_ROTATIONS_PER_SECOND_SQUARED);
private final ProfiledPIDController turnPID =
new ProfiledPIDController(3.5, 0, 0, turnConstraints);
private final SimpleMotorFeedforward turnFF = new SimpleMotorFeedforward(4, 10, 0);
new ProfiledPIDController(5, 0, 0, turnConstraints);
private final SimpleMotorFeedforward turnFF = new SimpleMotorFeedforward(6, 8, 0);

public SimulatedModule(SwerveModuleSimulation moduleSimulation) {
this.moduleSimulation = moduleSimulation;
// turnPID.enableContinuousInput(-Math.PI, Math.PI);
turnPID.enableContinuousInput(-Math.PI, Math.PI);
}

@Override
Expand Down

0 comments on commit e04dec9

Please sign in to comment.