[wpilib] Rename MotorController setDutyCycle() to setThrottle() (#8720)

Fixes #8716.
This commit is contained in:
Tyler Veness
2026-04-09 22:28:01 -07:00
committed by GitHub
parent a4e035ba64
commit b6849a8da3
160 changed files with 659 additions and 706 deletions

View File

@@ -18,7 +18,7 @@ public class Robot extends TimedRobot {
private final PWMSparkMax m_leftMotor = new PWMSparkMax(0);
private final PWMSparkMax m_rightMotor = new PWMSparkMax(1);
private final DifferentialDrive m_robotDrive =
new DifferentialDrive(m_leftMotor::setDutyCycle, m_rightMotor::setDutyCycle);
new DifferentialDrive(m_leftMotor::setThrottle, m_rightMotor::setThrottle);
private final Gamepad m_driverController = new Gamepad(0);
/** Called once at the beginning of the robot program. */

View File

@@ -86,7 +86,7 @@ public class Arm implements AutoCloseable {
public void simulationPeriodic() {
// In this method, we update our simulation of what our arm is doing
// First, we set our "inputs" (voltages)
m_armSim.setInput(m_motor.getDutyCycle() * RobotController.getBatteryVoltage());
m_armSim.setInput(m_motor.getThrottle() * RobotController.getBatteryVoltage());
// Next, we update it. The standard loop time is 20ms.
m_armSim.update(0.020);
@@ -120,7 +120,7 @@ public class Arm implements AutoCloseable {
}
public void stop() {
m_motor.setDutyCycle(0.0);
m_motor.setThrottle(0.0);
}
@Override

View File

@@ -248,8 +248,8 @@ public class Drivetrain {
// simulation, and write the simulated positions and velocities to our
// simulated encoder and gyro.
m_drivetrainSimulator.setInputs(
m_leftLeader.getDutyCycle() * RobotController.getInputVoltage(),
m_rightLeader.getDutyCycle() * RobotController.getInputVoltage());
m_leftLeader.getThrottle() * RobotController.getInputVoltage(),
m_rightLeader.getThrottle() * RobotController.getInputVoltage());
m_drivetrainSimulator.update(0.02);
m_leftEncoderSim.setDistance(m_drivetrainSimulator.getLeftPosition());

View File

@@ -72,11 +72,11 @@ public class ExampleSmartMotorController {
/** Resets the encoder to zero distance. */
public void resetEncoder() {}
public void setDutyCycle(double dutyCycle) {
m_value = dutyCycle;
public void setThrottle(double throttle) {
m_value = throttle;
}
public double getDutyCycle() {
public double getThrottle() {
return m_value;
}

View File

@@ -37,7 +37,7 @@ public class DriveSubsystem extends SubsystemBase {
// The robot's drive
private final DifferentialDrive m_drive =
new DifferentialDrive(m_leftLeader::setDutyCycle, m_rightLeader::setDutyCycle);
new DifferentialDrive(m_leftLeader::setThrottle, m_rightLeader::setThrottle);
// The trapezoid profile
private final TrapezoidProfile m_profile =

View File

@@ -70,9 +70,9 @@ public class ExampleSmartMotorController {
/** Resets the encoder to zero distance. */
public void resetEncoder() {}
public void setDutyCycle(double dutyCycle) {}
public void setThrottle(double throttle) {}
public double getDutyCycle() {
public double getThrottle() {
return 0;
}

View File

@@ -85,7 +85,7 @@ public class Elevator implements AutoCloseable {
public void simulationPeriodic() {
// In this method, we update our simulation of what our elevator is doing
// First, we set our "inputs" (voltages)
m_elevatorSim.setInput(m_motorSim.getDutyCycle() * RobotController.getBatteryVoltage());
m_elevatorSim.setInput(m_motorSim.getThrottle() * RobotController.getBatteryVoltage());
// Next, we update it. The standard loop time is 20ms.
m_elevatorSim.update(0.020);
@@ -118,7 +118,7 @@ public class Elevator implements AutoCloseable {
/** Stop the control loop and motor output. */
public void stop() {
m_motor.setDutyCycle(0.0);
m_motor.setThrottle(0.0);
}
/** Reset Exponential profile to begin from current position on enable. */

View File

@@ -78,7 +78,7 @@ public class Elevator implements AutoCloseable {
public void simulationPeriodic() {
// In this method, we update our simulation of what our elevator is doing
// First, we set our "inputs" (voltages)
m_elevatorSim.setInput(m_motorSim.getDutyCycle() * RobotController.getBatteryVoltage());
m_elevatorSim.setInput(m_motorSim.getThrottle() * RobotController.getBatteryVoltage());
// Next, we update it. The standard loop time is 20ms.
m_elevatorSim.update(0.020);
@@ -107,7 +107,7 @@ public class Elevator implements AutoCloseable {
/** Stop the control loop and motor output. */
public void stop() {
m_controller.setGoal(0.0);
m_motor.setDutyCycle(0.0);
m_motor.setThrottle(0.0);
}
/** Update telemetry, including the mechanism visualization. */

View File

@@ -70,9 +70,9 @@ public class ExampleSmartMotorController {
/** Resets the encoder to zero distance. */
public void resetEncoder() {}
public void setDutyCycle(double dutyCycle) {}
public void setThrottle(double throttle) {}
public double getDutyCycle() {
public double getThrottle() {
return 0;
}

View File

@@ -20,7 +20,7 @@ public class Robot extends TimedRobot {
private final PWMSparkMax m_leftDrive = new PWMSparkMax(0);
private final PWMSparkMax m_rightDrive = new PWMSparkMax(1);
private final DifferentialDrive m_robotDrive =
new DifferentialDrive(m_leftDrive::setDutyCycle, m_rightDrive::setDutyCycle);
new DifferentialDrive(m_leftDrive::setThrottle, m_rightDrive::setThrottle);
private final Gamepad m_controller = new Gamepad(0);
private final Timer m_timer = new Timer();

View File

@@ -29,7 +29,7 @@ public class Robot extends TimedRobot {
private final PWMSparkMax m_leftDrive = new PWMSparkMax(kLeftMotorPort);
private final PWMSparkMax m_rightDrive = new PWMSparkMax(kRightMotorPort);
private final DifferentialDrive m_robotDrive =
new DifferentialDrive(m_leftDrive::setDutyCycle, m_rightDrive::setDutyCycle);
new DifferentialDrive(m_leftDrive::setThrottle, m_rightDrive::setThrottle);
private final OnboardIMU m_imu = new OnboardIMU(kIMUMountOrientation);
private final Joystick m_joystick = new Joystick(kJoystickPort);

View File

@@ -23,7 +23,7 @@ public class DriveSubsystem extends SubsystemBase {
// The robot's drive
private final DifferentialDrive m_drive =
new DifferentialDrive(m_leftLeader::setDutyCycle, m_rightLeader::setDutyCycle);
new DifferentialDrive(m_leftLeader::setThrottle, m_rightLeader::setThrottle);
// The left-side drive encoder
private final Encoder m_leftEncoder =

View File

@@ -23,7 +23,7 @@ public class DriveSubsystem extends SubsystemBase {
// The robot's drive
private final DifferentialDrive m_drive =
new DifferentialDrive(m_leftLeader::setDutyCycle, m_rightLeader::setDutyCycle);
new DifferentialDrive(m_leftLeader::setThrottle, m_rightLeader::setThrottle);
// The left-side drive encoder
private final Encoder m_leftEncoder =

View File

@@ -42,10 +42,10 @@ public class Robot extends TimedRobot {
m_robotDrive =
new MecanumDrive(
frontLeft::setDutyCycle,
rearLeft::setDutyCycle,
frontRight::setDutyCycle,
rearRight::setDutyCycle);
frontLeft::setThrottle,
rearLeft::setThrottle,
frontRight::setThrottle,
rearRight::setThrottle);
SendableRegistry.addChild(m_robotDrive, frontLeft);
SendableRegistry.addChild(m_robotDrive, rearLeft);

View File

@@ -65,7 +65,7 @@ public class Robot extends TimedRobot {
@Override
public void teleopPeriodic() {
m_elevatorMotor.setDutyCycle(m_joystick.getRawAxis(0));
m_wristMotor.setDutyCycle(m_joystick.getRawAxis(1));
m_elevatorMotor.setThrottle(m_joystick.getRawAxis(0));
m_wristMotor.setThrottle(m_joystick.getRawAxis(1));
}
}

View File

@@ -33,7 +33,7 @@ public class Drive extends SubsystemBase {
// The robot's drive
@NotLogged // Would duplicate motor data, there's no point sending it twice
private final DifferentialDrive m_drive =
new DifferentialDrive(m_leftLeader::setDutyCycle, m_rightLeader::setDutyCycle);
new DifferentialDrive(m_leftLeader::setThrottle, m_rightLeader::setThrottle);
// The left-side drive encoder
private final Encoder m_leftEncoder =

View File

@@ -29,7 +29,7 @@ public class Intake extends SubsystemBase {
/** Returns a command that deploys the intake, and then runs the intake motor indefinitely. */
public Command intakeCommand() {
return runOnce(() -> m_pistons.set(DoubleSolenoid.Value.FORWARD))
.andThen(run(() -> m_motor.setDutyCycle(1.0)))
.andThen(run(() -> m_motor.setThrottle(1.0)))
.withName("Intake");
}

View File

@@ -56,14 +56,14 @@ public class Shooter extends SubsystemBase {
// Run the shooter flywheel at the desired setpoint using feedforward and feedback
run(
() -> {
m_shooterMotor.setDutyCycle(
m_shooterMotor.setThrottle(
m_shooterFeedforward.calculate(setpointRotationsPerSecond)
+ m_shooterFeedback.calculate(
m_shooterEncoder.getRate(), setpointRotationsPerSecond));
}),
// Wait until the shooter has reached the setpoint, and then run the feeder
waitUntil(m_shooterFeedback::atSetpoint).andThen(() -> m_feederMotor.setDutyCycle(1)))
waitUntil(m_shooterFeedback::atSetpoint).andThen(() -> m_feederMotor.setThrottle(1)))
.withName("Shoot");
}
}

View File

@@ -34,6 +34,6 @@ public class Storage extends SubsystemBase {
/** Returns a command that runs the storage motor indefinitely. */
public Command runCommand() {
return run(() -> m_motor.setDutyCycle(1)).withName("run");
return run(() -> m_motor.setThrottle(1)).withName("run");
}
}

View File

@@ -27,7 +27,7 @@ public class Drivetrain extends SubsystemBase {
// Set up the differential drive controller
private final DifferentialDrive m_diffDrive =
new DifferentialDrive(m_leftMotor::setDutyCycle, m_rightMotor::setDutyCycle);
new DifferentialDrive(m_leftMotor::setThrottle, m_rightMotor::setThrottle);
// Set up the RomiGyro
private final RomiGyro m_gyro = new RomiGyro();

View File

@@ -136,8 +136,8 @@ public class Drivetrain {
// simulated encoder and gyro. We negate the right side so that positive
// voltages make the right side move forward.
m_drivetrainSimulator.setInputs(
m_leftLeader.getDutyCycle() * RobotController.getInputVoltage(),
m_rightLeader.getDutyCycle() * RobotController.getInputVoltage());
m_leftLeader.getThrottle() * RobotController.getInputVoltage(),
m_rightLeader.getThrottle() * RobotController.getInputVoltage());
m_drivetrainSimulator.update(0.02);
m_leftEncoderSim.setDistance(m_drivetrainSimulator.getLeftPosition());

View File

@@ -27,7 +27,7 @@ public class Drive extends SubsystemBase {
// The robot's drive
private final DifferentialDrive m_drive =
new DifferentialDrive(m_leftMotor::setDutyCycle, m_rightMotor::setDutyCycle);
new DifferentialDrive(m_leftMotor::setThrottle, m_rightMotor::setThrottle);
// The left-side drive encoder
private final Encoder m_leftEncoder =
@@ -61,14 +61,14 @@ public class Drive extends SubsystemBase {
// the entire group to be one motor.
log.motor("drive-left")
.voltage(
Volts.of(m_leftMotor.getDutyCycle() * RobotController.getBatteryVoltage()))
Volts.of(m_leftMotor.getThrottle() * RobotController.getBatteryVoltage()))
.linearPosition(Meters.of(m_leftEncoder.getDistance()))
.linearVelocity(MetersPerSecond.of(m_leftEncoder.getRate()));
// Record a frame for the right motors. Since these share an encoder, we consider
// the entire group to be one motor.
log.motor("drive-right")
.voltage(
Volts.of(m_rightMotor.getDutyCycle() * RobotController.getBatteryVoltage()))
Volts.of(m_rightMotor.getThrottle() * RobotController.getBatteryVoltage()))
.linearPosition(Meters.of(m_rightEncoder.getDistance()))
.linearVelocity(MetersPerSecond.of(m_rightEncoder.getRate()));
},

View File

@@ -48,7 +48,7 @@ public class Shooter extends SubsystemBase {
log.motor("shooter-wheel")
.voltage(
Volts.of(
m_shooterMotor.getDutyCycle() * RobotController.getBatteryVoltage()))
m_shooterMotor.getThrottle() * RobotController.getBatteryVoltage()))
.angularPosition(Rotations.of(m_shooterEncoder.getDistance()))
.angularVelocity(RotationsPerSecond.of(m_shooterEncoder.getRate()));
},
@@ -80,7 +80,7 @@ public class Shooter extends SubsystemBase {
m_shooterMotor.setVoltage(
m_shooterFeedback.calculate(m_shooterEncoder.getRate(), shooterVelocity.getAsDouble())
+ m_shooterFeedforward.calculate(shooterVelocity.getAsDouble()));
m_feederMotor.setDutyCycle(ShooterConstants.kFeederVelocity);
m_feederMotor.setThrottle(ShooterConstants.kFeederVelocity);
})
.finallyDo(
() -> {

View File

@@ -18,7 +18,7 @@ public class Robot extends TimedRobot {
private final PWMSparkMax m_leftMotor = new PWMSparkMax(0);
private final PWMSparkMax m_rightMotor = new PWMSparkMax(1);
private final DifferentialDrive m_robotDrive =
new DifferentialDrive(m_leftMotor::setDutyCycle, m_rightMotor::setDutyCycle);
new DifferentialDrive(m_leftMotor::setThrottle, m_rightMotor::setThrottle);
private final Gamepad m_driverController = new Gamepad(0);
/** Called once at the beginning of the robot program. */

View File

@@ -29,14 +29,14 @@ public class Intake implements AutoCloseable {
public void retract() {
m_piston.set(DoubleSolenoid.Value.REVERSE);
m_motor.setDutyCycle(0); // turn off the motor
m_motor.setThrottle(0); // turn off the motor
}
public void activate(double velocity) {
if (isDeployed()) {
m_motor.setDutyCycle(velocity);
m_motor.setThrottle(velocity);
} else { // if piston isn't open, do nothing
m_motor.setDutyCycle(0);
m_motor.setThrottle(0);
}
}

View File

@@ -30,7 +30,7 @@ public class Drivetrain extends SubsystemBase {
// Set up the differential drive controller
private final DifferentialDrive m_diffDrive =
new DifferentialDrive(m_leftMotor::setDutyCycle, m_rightMotor::setDutyCycle);
new DifferentialDrive(m_leftMotor::setThrottle, m_rightMotor::setThrottle);
// Set up the XRPGyro
private final XRPGyro m_gyro = new XRPGyro();

View File

@@ -20,7 +20,7 @@ public class Robot extends TimedRobot {
private final XRPMotor m_leftDrive = new XRPMotor(0);
private final XRPMotor m_rightDrive = new XRPMotor(1);
private final DifferentialDrive m_robotDrive =
new DifferentialDrive(m_leftDrive::setDutyCycle, m_rightDrive::setDutyCycle);
new DifferentialDrive(m_leftDrive::setThrottle, m_rightDrive::setThrottle);
// Assumes a gamepad plugged into channel 0
private final Joystick m_controller = new Joystick(0);
private final Timer m_timer = new Timer();

View File

@@ -22,7 +22,7 @@ public class Robot extends TimedRobot {
Spark m_rightLeader = new Spark(2);
Spark m_rightFollower = new Spark(3);
DifferentialDrive m_drive =
new DifferentialDrive(m_leftLeader::setDutyCycle, m_rightLeader::setDutyCycle);
new DifferentialDrive(m_leftLeader::setThrottle, m_rightLeader::setThrottle);
/** Called once at the beginning of the robot program. */
public Robot() {

View File

@@ -26,9 +26,9 @@ public class Robot extends TimedRobot {
@Override
public void autonomousPeriodic() {
if (!m_limit.get()) {
m_spark.setDutyCycle(-0.5);
m_spark.setThrottle(-0.5);
} else {
m_spark.setDutyCycle(0.0);
m_spark.setThrottle(0.0);
m_encoder.reset();
}
}

View File

@@ -42,7 +42,7 @@ public class Robot extends TimedRobot {
// and there is not a ball at the kicker
.and(isBallAtKicker.negate())
// activate the intake
.ifHigh(() -> m_intake.setDutyCycle(0.5));
.ifHigh(() -> m_intake.setThrottle(0.5));
// if the thumb button is not held
intakeButton
@@ -73,7 +73,7 @@ public class Robot extends TimedRobot {
.debounce(0.2);
// if we're at the target velocity, kick the ball into the shooter wheel
atTargetVelocity.ifHigh(() -> m_kicker.setDutyCycle(0.7));
atTargetVelocity.ifHigh(() -> m_kicker.setThrottle(0.7));
// when we stop being at the target velocity, it means the ball was shot
atTargetVelocity

View File

@@ -95,7 +95,7 @@ public class Robot extends TimedRobot {
// To update our simulation, we set motor voltage inputs, update the
// simulation, and write the simulated velocities to our simulated encoder
m_flywheelSim.setInputVoltage(
m_flywheelMotor.getDutyCycle() * RobotController.getInputVoltage());
m_flywheelMotor.getThrottle() * RobotController.getInputVoltage());
m_flywheelSim.update(0.02);
m_encoderSim.setRate(m_flywheelSim.getAngularVelocity());
}

View File

@@ -33,18 +33,18 @@ public class Robot extends TimedRobot {
if (velocity > 0) {
if (m_toplimitSwitch.get()) {
// We are going up and top limit is tripped so stop
m_motor.setDutyCycle(0);
m_motor.setThrottle(0);
} else {
// We are going up but top limit is not tripped so go at commanded velocity
m_motor.setDutyCycle(velocity);
m_motor.setThrottle(velocity);
}
} else {
if (m_bottomlimitSwitch.get()) {
// We are going down and bottom limit is tripped so stop
m_motor.setDutyCycle(0);
m_motor.setThrottle(0);
} else {
// We are going down but bottom limit is not tripped so go at commanded velocity
m_motor.setDutyCycle(velocity);
m_motor.setThrottle(velocity);
}
}
}

View File

@@ -52,6 +52,6 @@ public class Robot extends TimedRobot {
/** The teleop periodic function is called every control packet in teleop. */
@Override
public void teleopPeriodic() {
m_motor.setDutyCycle(m_joystick.getY());
m_motor.setThrottle(m_joystick.getY());
}
}

View File

@@ -25,7 +25,7 @@ public class RomiDrivetrain extends SubsystemBase {
// Set up the differential drive controller
private final DifferentialDrive m_diffDrive =
new DifferentialDrive(m_leftMotor::setDutyCycle, m_rightMotor::setDutyCycle);
new DifferentialDrive(m_leftMotor::setThrottle, m_rightMotor::setThrottle);
/** Creates a new RomiDrivetrain. */
public RomiDrivetrain() {

View File

@@ -24,7 +24,7 @@ public class RomiDrivetrain {
// Set up the differential drive controller
private final DifferentialDrive m_diffDrive =
new DifferentialDrive(m_leftMotor::setDutyCycle, m_rightMotor::setDutyCycle);
new DifferentialDrive(m_leftMotor::setThrottle, m_rightMotor::setThrottle);
/** Creates a new RomiDrivetrain. */
public RomiDrivetrain() {

View File

@@ -24,7 +24,7 @@ public class RomiDrivetrain {
// Set up the differential drive controller
private final DifferentialDrive m_diffDrive =
new DifferentialDrive(m_leftMotor::setDutyCycle, m_rightMotor::setDutyCycle);
new DifferentialDrive(m_leftMotor::setThrottle, m_rightMotor::setThrottle);
/** Creates a new RomiDrivetrain. */
public RomiDrivetrain() {

View File

@@ -28,7 +28,7 @@ public class XRPDrivetrain extends SubsystemBase {
// Set up the differential drive controller
private final DifferentialDrive m_diffDrive =
new DifferentialDrive(m_leftMotor::setDutyCycle, m_rightMotor::setDutyCycle);
new DifferentialDrive(m_leftMotor::setThrottle, m_rightMotor::setThrottle);
/** Creates a new XRPDrivetrain. */
public XRPDrivetrain() {

View File

@@ -27,7 +27,7 @@ public class XRPDrivetrain {
// Set up the differential drive controller
private final DifferentialDrive m_diffDrive =
new DifferentialDrive(m_leftMotor::setDutyCycle, m_rightMotor::setDutyCycle);
new DifferentialDrive(m_leftMotor::setThrottle, m_rightMotor::setThrottle);
/** Creates a new XRPDrivetrain. */
public XRPDrivetrain() {

View File

@@ -27,7 +27,7 @@ public class XRPDrivetrain {
// Set up the differential drive controller
private final DifferentialDrive m_diffDrive =
new DifferentialDrive(m_leftMotor::setDutyCycle, m_rightMotor::setDutyCycle);
new DifferentialDrive(m_leftMotor::setThrottle, m_rightMotor::setThrottle);
/** Creates a new XRPDrivetrain. */
public XRPDrivetrain() {

View File

@@ -142,7 +142,7 @@ class ArmSimulationTest {
// advance 75 timesteps
SimHooks.stepTiming(3.5);
assertEquals(0.0, m_motorSim.getDutyCycle(), 0.01);
assertEquals(0.0, m_motorSim.getThrottle(), 0.01);
assertEquals(Constants.kMinAngleRads, m_encoderSim.getDistance(), 2.0);
}
}

View File

@@ -131,7 +131,7 @@ class ElevatorSimulationTest {
// advance 75 timesteps
SimHooks.stepTiming(1.5);
assertEquals(0.0, m_motorSim.getDutyCycle(), 0.05);
assertEquals(0.0, m_motorSim.getThrottle(), 0.05);
assertEquals(0.0, m_encoderSim.getDistance(), 0.05);
}
}

View File

@@ -47,14 +47,14 @@ class IntakeTest {
m_intake.retract(); // close the intake
m_intake.activate(0.5); // try to activate the motor
assertEquals(
0.0, m_simMotor.getDutyCycle(), DELTA); // make sure that the value set to the motor is 0
0.0, m_simMotor.getThrottle(), DELTA); // make sure that the value set to the motor is 0
}
@Test
void worksWhenOpen() {
m_intake.deploy();
m_intake.activate(0.5);
assertEquals(0.5, m_simMotor.getDutyCycle(), DELTA);
assertEquals(0.5, m_simMotor.getThrottle(), DELTA);
}
@Test