Skip to content
This repository has been archived by the owner on May 19, 2024. It is now read-only.

Commit

Permalink
refactor: Rename setSetpoint to runSetpoint.
Browse files Browse the repository at this point in the history
  • Loading branch information
haydenheroux committed Feb 8, 2024
1 parent a9afb6f commit 35f7e21
Show file tree
Hide file tree
Showing 16 changed files with 27 additions and 27 deletions.
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/arm/ElbowMotorIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -29,11 +29,11 @@ public static class ElbowMotorIOValues {
public void setPosition(double positionRotations);

/**
* Sets the elbow motor's setpoint.
* Runs the elbow motor's setpoint.
*
* @param positionRotations the elbow motor's setpoint.
*/
public void setSetpoint(double positionRotations);
public void runSetpoint(double positionRotations);

// TODO Remove, only for characterization
/**
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/arm/ElbowMotorIOSparkMax.java
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ public void setPosition(double positionRotations) {
}

@Override
public void setSetpoint(double positionRotations) {
public void runSetpoint(double positionRotations) {
double measuredPositionRotations = getPositionRotations();

double feedbackVolts = feedback.calculate(positionRotations, measuredPositionRotations);
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/arm/ShoulderMotorIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -30,11 +30,11 @@ public static class ShoulderMotorIOValues {
public void setPosition(double positionRotations);

/**
* Sets the shoulder motor's setpoint.
* Runs the shoulder motor's setpoint.
*
* @param positionRotations the shoulder motor's setpoint.
*/
public void setSetpoint(double positionRotations);
public void runSetpoint(double positionRotations);

// TODO Remove, only for characterization
/**
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/arm/ShoulderMotorIOSparkMax.java
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ public void setPosition(double positionRotations) {
}

@Override
public void setSetpoint(double positionRotations) {
public void runSetpoint(double positionRotations) {
double measuredPositionRotations = getPositionRotations();

double feedbackVolts = feedback.calculate(positionRotations, measuredPositionRotations);
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/swerve/DriveMotorIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -30,11 +30,11 @@ public static class DriveMotorIOValues {
public void setPosition(double positionMeters);

/**
* Sets the drive motor's setpoint.
* Runs the drive motor's setpoint.
*
* @param velocityMetersPerSecond the drive motor's setpoint.
*/
public void setSetpoint(double velocityMetersPerSecond);
public void runSetpoint(double velocityMetersPerSecond);

/**
* Sets the drive motor's brake mode.
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/swerve/DriveMotorIOSim.java
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ public void setPosition(double positionMeters) {
}

@Override
public void setSetpoint(double velocityMetersPerSecond) {
public void runSetpoint(double velocityMetersPerSecond) {
this.velocityMetersPerSecond = velocityMetersPerSecond;
}

Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/swerve/DriveMotorIOTalonFX.java
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ public void setPosition(double positionMeters) {
}

@Override
public abstract void setSetpoint(double velocityMetersPerSecond);
public abstract void runSetpoint(double velocityMetersPerSecond);

@Override
public void setBrake(boolean brake) {
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/swerve/DriveMotorIOTalonFXPID.java
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ public void configure() {
}

@Override
public void setSetpoint(double velocityMetersPerSecond) {
public void runSetpoint(double velocityMetersPerSecond) {
if (velocityMetersPerSecond == 0.0) {
talonFX.setControl(new CoastOut());
} else {
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/swerve/SteerMotorIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,9 @@ public static class SteerMotorIOValues {
public void setPosition(double positionRotations);

/**
* Sets the steer motor's setpoint.
* Runs the steer motor's setpoint.
*
* @param positionRotations the steer motor's setpoint.
*/
public void setSetpoint(double positionRotations);
public void runSetpoint(double positionRotations);
}
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/swerve/SteerMotorIOSim.java
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ public void setPosition(double positionRotations) {
}

@Override
public void setSetpoint(double positionRotations) {
public void runSetpoint(double positionRotations) {
double voltage =
pidf.calculate(
Rotation2d.fromRotations(this.positionRotations),
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/swerve/SteerMotorIOTalonFX.java
Original file line number Diff line number Diff line change
Expand Up @@ -67,5 +67,5 @@ public void setPosition(double positionRotations) {
}

@Override
public abstract void setSetpoint(double positionRotations);
public abstract void runSetpoint(double positionRotations);
}
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ public void configure() {
}

@Override
public void setSetpoint(double positionRotations) {
public void runSetpoint(double positionRotations) {
talonFX.setControl(motionMagicVoltageSetter.withPosition(positionRotations));
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ public void configure() {
}

@Override
public void setSetpoint(double positionRotations) {
public void runSetpoint(double positionRotations) {
if (pidf.atGoal()) {
// TODO Doesn't work for some reason...
// talonFX.setControl(new CoastOut());
Expand Down
10 changes: 5 additions & 5 deletions src/main/java/frc/robot/swerve/Swerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -165,21 +165,21 @@ public ChassisSpeeds getChassisSpeeds() {
public void setChassisSpeeds(ChassisSpeeds speeds) {
SwerveModuleState[] setpoints = swerveKinematics.toSwerveModuleStates(speeds);

setSetpoints(setpoints, true);
runSetpoints(setpoints, true);
}

/**
* Set the setpoints for each of the swerve's modules.
* Runs each of the swerve modules' setpoints.
*
* @param setpoints the setpoints for each of the swerve's modules.
* @param lazy if true, optimize the module setpoint.
*/
public void setSetpoints(SwerveModuleState[] setpoints, boolean lazy) {
public void runSetpoints(SwerveModuleState[] setpoints, boolean lazy) {
SwerveDriveKinematics.desaturateWheelSpeeds(
setpoints, SwerveConstants.MAXIMUM_ATTAINABLE_SPEED);

for (int i = 0; i < 4; i++) {
swerveModules[i].setSetpoint(setpoints[i], lazy);
swerveModules[i].runSetpoint(setpoints[i], lazy);
}
}

Expand All @@ -192,7 +192,7 @@ public void setSetpoints(SwerveModuleState[] setpoints, boolean lazy) {
public Command orientModules(Rotation2d[] orientations) {
return run(
() -> {
setSetpoints(
runSetpoints(
new SwerveModuleState[] {
new SwerveModuleState(0.0, orientations[0]),
new SwerveModuleState(0.0, orientations[1]),
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/swerve/SwerveModuleIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -29,12 +29,12 @@ public interface SwerveModuleIO {
public SwerveModuleState getSetpoint();

/**
* Sets the swerve module setpoint.
* Runs the swerve module setpoint.
*
* @param setpoint the swerve module setpoint.
* @param lazy if true, optimize the swerve module setpoint.
*/
public void setSetpoint(SwerveModuleState setpoint, boolean lazy);
public void runSetpoint(SwerveModuleState setpoint, boolean lazy);

/**
* Gets the position of the swerve module.
Expand Down
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/swerve/SwerveModuleIOCustom.java
Original file line number Diff line number Diff line change
Expand Up @@ -75,13 +75,13 @@ public SwerveModuleState getSetpoint() {
}

@Override
public void setSetpoint(SwerveModuleState setpoint, boolean lazy) {
public void runSetpoint(SwerveModuleState setpoint, boolean lazy) {
if (lazy) {
setpoint = optimize(setpoint, getState());
}

steerMotor.setSetpoint(setpoint.angle.getRotations());
driveMotor.setSetpoint(setpoint.speedMetersPerSecond);
steerMotor.runSetpoint(setpoint.angle.getRotations());
driveMotor.runSetpoint(setpoint.speedMetersPerSecond);

this.setpoint = setpoint;
}
Expand Down

0 comments on commit 35f7e21

Please sign in to comment.