[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

@@ -15,8 +15,8 @@ class Robot : public wpi::TimedRobot {
wpi::PWMSparkMax m_leftMotor{0};
wpi::PWMSparkMax m_rightMotor{1};
wpi::DifferentialDrive m_robotDrive{
[&](double output) { m_leftMotor.SetDutyCycle(output); },
[&](double output) { m_rightMotor.SetDutyCycle(output); }};
[&](double output) { m_leftMotor.SetThrottle(output); },
[&](double output) { m_rightMotor.SetThrottle(output); }};
wpi::Gamepad m_driverController{0};
public:

View File

@@ -24,7 +24,7 @@ void Arm::SimulationPeriodic() {
// In this method, we update our simulation of what our arm is doing
// First, we set our "inputs" (voltages)
m_armSim.SetInput(wpi::math::Vectord<1>{
m_motor.GetDutyCycle() * wpi::RobotController::GetInputVoltage()});
m_motor.GetThrottle() * wpi::RobotController::GetInputVoltage()});
// Next, we update it. The standard loop time is 20ms.
m_armSim.Update(20_ms);
@@ -59,5 +59,5 @@ void Arm::ReachSetpoint() {
}
void Arm::Stop() {
m_motor.SetDutyCycle(0.0);
m_motor.SetThrottle(0.0);
}

View File

@@ -123,9 +123,9 @@ void Drivetrain::SimulationPeriodic() {
// simulation, and write the simulated positions and velocities to our
// simulated encoder and gyro.
m_drivetrainSimulator.SetInputs(
wpi::units::volt_t{m_leftLeader.GetDutyCycle()} *
wpi::units::volt_t{m_leftLeader.GetThrottle()} *
wpi::RobotController::GetInputVoltage(),
wpi::units::volt_t{m_rightLeader.GetDutyCycle()} *
wpi::units::volt_t{m_rightLeader.GetThrottle()} *
wpi::RobotController::GetInputVoltage());
m_drivetrainSimulator.Update(20_ms);

View File

@@ -20,7 +20,7 @@ void Elevator::SimulationPeriodic() {
// In this method, we update our simulation of what our elevator is doing
// First, we set our "inputs" (voltages)
m_elevatorSim.SetInput(wpi::math::Vectord<1>{
m_motorSim.GetDutyCycle() * wpi::RobotController::GetInputVoltage()});
m_motorSim.GetThrottle() * wpi::RobotController::GetInputVoltage()});
// Next, we update it. The standard loop time is 20ms.
m_elevatorSim.Update(20_ms);
@@ -59,5 +59,5 @@ void Elevator::Reset() {
}
void Elevator::Stop() {
m_motor.SetDutyCycle(0.0);
m_motor.SetThrottle(0.0);
}

View File

@@ -20,7 +20,7 @@ void Elevator::SimulationPeriodic() {
// In this method, we update our simulation of what our elevator is doing
// First, we set our "inputs" (voltages)
m_elevatorSim.SetInput(wpi::math::Vectord<1>{
m_motorSim.GetDutyCycle() * wpi::RobotController::GetInputVoltage()});
m_motorSim.GetThrottle() * wpi::RobotController::GetInputVoltage()});
// Next, we update it. The standard loop time is 20ms.
m_elevatorSim.Update(20_ms);
@@ -50,5 +50,5 @@ void Elevator::ReachGoal(wpi::units::meter_t goal) {
void Elevator::Stop() {
m_controller.SetGoal(0.0_m);
m_motor.SetDutyCycle(0.0);
m_motor.SetThrottle(0.0);
}

View File

@@ -52,8 +52,8 @@ class Robot : public wpi::TimedRobot {
wpi::PWMSparkMax m_left{0};
wpi::PWMSparkMax m_right{1};
wpi::DifferentialDrive m_robotDrive{
[&](double output) { m_left.SetDutyCycle(output); },
[&](double output) { m_right.SetDutyCycle(output); }};
[&](double output) { m_left.SetThrottle(output); },
[&](double output) { m_right.SetThrottle(output); }};
wpi::Gamepad m_controller{0};
wpi::Timer m_timer;

View File

@@ -51,8 +51,8 @@ class Robot : public wpi::TimedRobot {
wpi::PWMSparkMax m_left{kLeftMotorPort};
wpi::PWMSparkMax m_right{kRightMotorPort};
wpi::DifferentialDrive m_drive{
[&](double output) { m_left.SetDutyCycle(output); },
[&](double output) { m_right.SetDutyCycle(output); }};
[&](double output) { m_left.SetThrottle(output); },
[&](double output) { m_right.SetThrottle(output); }};
wpi::OnboardIMU m_imu{kIMUMountOrientation};
wpi::Joystick m_joystick{kJoystickPort};

View File

@@ -63,8 +63,8 @@ class DriveSubsystem : public wpi::cmd::SubsystemBase {
// The robot's drive
wpi::DifferentialDrive m_drive{
[&](double output) { m_left1.SetDutyCycle(output); },
[&](double output) { m_right1.SetDutyCycle(output); }};
[&](double output) { m_left1.SetThrottle(output); },
[&](double output) { m_right1.SetThrottle(output); }};
// The left-side drive encoder
wpi::Encoder m_leftEncoder;

View File

@@ -63,8 +63,8 @@ class DriveSubsystem : public wpi::cmd::SubsystemBase {
// The robot's drive
wpi::DifferentialDrive m_drive{
[&](double output) { m_left1.SetDutyCycle(output); },
[&](double output) { m_right1.SetDutyCycle(output); }};
[&](double output) { m_left1.SetThrottle(output); },
[&](double output) { m_right1.SetThrottle(output); }};
// The left-side drive encoder
wpi::Encoder m_leftEncoder;

View File

@@ -52,10 +52,10 @@ class Robot : public wpi::TimedRobot {
wpi::PWMSparkMax m_frontRight{kFrontRightMotorPort};
wpi::PWMSparkMax m_rearRight{kRearRightMotorPort};
wpi::MecanumDrive m_robotDrive{
[&](double output) { m_frontLeft.SetDutyCycle(output); },
[&](double output) { m_rearLeft.SetDutyCycle(output); },
[&](double output) { m_frontRight.SetDutyCycle(output); },
[&](double output) { m_rearRight.SetDutyCycle(output); }};
[&](double output) { m_frontLeft.SetThrottle(output); },
[&](double output) { m_rearLeft.SetThrottle(output); },
[&](double output) { m_frontRight.SetThrottle(output); },
[&](double output) { m_rearRight.SetThrottle(output); }};
wpi::OnboardIMU m_imu{kIMUMountOrientation};
wpi::Joystick m_joystick{kJoystickPort};

View File

@@ -44,8 +44,8 @@ class Robot : public wpi::TimedRobot {
}
void TeleopPeriodic() override {
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));
}
private:

View File

@@ -6,7 +6,7 @@
wpi::cmd::CommandPtr Intake::IntakeCommand() {
return RunOnce([this] { m_piston.Set(wpi::DoubleSolenoid::FORWARD); })
.AndThen(Run([this] { m_motor.SetDutyCycle(1.0); }))
.AndThen(Run([this] { m_motor.SetThrottle(1.0); }))
.WithName("Intake");
}

View File

@@ -34,6 +34,6 @@ wpi::cmd::CommandPtr Shooter::ShootCommand(
// run the feeder
wpi::cmd::cmd::WaitUntil([this] {
return m_shooterFeedback.AtSetpoint();
}).AndThen([this] { m_feederMotor.SetDutyCycle(1.0); }))
}).AndThen([this] { m_feederMotor.SetThrottle(1.0); }))
.WithName("Shoot");
}

View File

@@ -10,5 +10,5 @@ Storage::Storage() {
}
wpi::cmd::CommandPtr Storage::RunCommand() {
return Run([this] { m_motor.SetDutyCycle(1.0); }).WithName("Run");
return Run([this] { m_motor.SetThrottle(1.0); }).WithName("Run");
}

View File

@@ -55,8 +55,8 @@ class Drive : public wpi::cmd::SubsystemBase {
wpi::PWMSparkMax m_rightFollower{DriveConstants::kRightMotor2Port};
wpi::DifferentialDrive m_drive{
[&](double output) { m_leftLeader.SetDutyCycle(output); },
[&](double output) { m_rightLeader.SetDutyCycle(output); }};
[&](double output) { m_leftLeader.SetThrottle(output); },
[&](double output) { m_rightLeader.SetThrottle(output); }};
wpi::Encoder m_leftEncoder{DriveConstants::kLeftEncoderPorts[0],
DriveConstants::kLeftEncoderPorts[1],

View File

@@ -106,8 +106,8 @@ class Drivetrain : public wpi::cmd::SubsystemBase {
wpi::Encoder m_rightEncoder{6, 7};
wpi::DifferentialDrive m_drive{
[&](double output) { m_leftMotor.SetDutyCycle(output); },
[&](double output) { m_rightMotor.SetDutyCycle(output); }};
[&](double output) { m_leftMotor.SetThrottle(output); },
[&](double output) { m_rightMotor.SetThrottle(output); }};
wpi::romi::RomiGyro m_gyro;
};

View File

@@ -43,9 +43,9 @@ void Drivetrain::SimulationPeriodic() {
// simulated encoder and gyro. We negate the right side so that positive
// voltages make the right side move forward.
m_drivetrainSimulator.SetInputs(
wpi::units::volt_t{m_leftLeader.GetDutyCycle()} *
wpi::units::volt_t{m_leftLeader.GetThrottle()} *
wpi::RobotController::GetInputVoltage(),
wpi::units::volt_t{m_rightLeader.GetDutyCycle()} *
wpi::units::volt_t{m_rightLeader.GetThrottle()} *
wpi::RobotController::GetInputVoltage());
m_drivetrainSimulator.Update(20_ms);

View File

@@ -22,7 +22,7 @@ wpi::cmd::CommandPtr Shooter::RunShooterCommand(
m_shooterEncoder.GetRate(), shooterVelocity())} +
m_shooterFeedforward.Calculate(
wpi::units::turns_per_second_t{shooterVelocity()}));
m_feederMotor.SetDutyCycle(constants::shooter::kFeederVelocity);
m_feederMotor.SetThrottle(constants::shooter::kFeederVelocity);
},
{this})
.WithName("Set Shooter Velocity");

View File

@@ -27,8 +27,8 @@ class Drive : public wpi::cmd::SubsystemBase {
wpi::PWMSparkMax m_leftMotor{constants::drive::kLeftMotor1Port};
wpi::PWMSparkMax m_rightMotor{constants::drive::kRightMotor1Port};
wpi::DifferentialDrive m_drive{
[this](auto val) { m_leftMotor.SetDutyCycle(val); },
[this](auto val) { m_rightMotor.SetDutyCycle(val); }};
[this](auto val) { m_leftMotor.SetThrottle(val); },
[this](auto val) { m_rightMotor.SetThrottle(val); }};
wpi::Encoder m_leftEncoder{constants::drive::kLeftEncoderPorts[0],
constants::drive::kLeftEncoderPorts[1],
@@ -48,13 +48,13 @@ class Drive : public wpi::cmd::SubsystemBase {
},
[this](wpi::sysid::SysIdRoutineLog* log) {
log->Motor("drive-left")
.voltage(m_leftMotor.GetDutyCycle() *
.voltage(m_leftMotor.GetThrottle() *
wpi::RobotController::GetBatteryVoltage())
.position(wpi::units::meter_t{m_leftEncoder.GetDistance()})
.velocity(
wpi::units::meters_per_second_t{m_leftEncoder.GetRate()});
log->Motor("drive-right")
.voltage(m_rightMotor.GetDutyCycle() *
.voltage(m_rightMotor.GetThrottle() *
wpi::RobotController::GetBatteryVoltage())
.position(wpi::units::meter_t{m_rightEncoder.GetDistance()})
.velocity(

View File

@@ -41,7 +41,7 @@ class Shooter : public wpi::cmd::SubsystemBase {
},
[this](wpi::sysid::SysIdRoutineLog* log) {
log->Motor("shooter-wheel")
.voltage(m_shooterMotor.GetDutyCycle() *
.voltage(m_shooterMotor.GetThrottle() *
wpi::RobotController::GetBatteryVoltage())
.position(wpi::units::turn_t{m_shooterEncoder.GetDistance()})
.velocity(

View File

@@ -15,8 +15,8 @@ class Robot : public wpi::TimedRobot {
wpi::PWMSparkMax m_leftMotor{0};
wpi::PWMSparkMax m_rightMotor{1};
wpi::DifferentialDrive m_robotDrive{
[&](double output) { m_leftMotor.SetDutyCycle(output); },
[&](double output) { m_rightMotor.SetDutyCycle(output); }};
[&](double output) { m_leftMotor.SetThrottle(output); },
[&](double output) { m_rightMotor.SetThrottle(output); }};
wpi::Gamepad m_driverController{0};
public:

View File

@@ -10,14 +10,14 @@ void Intake::Deploy() {
void Intake::Retract() {
m_piston.Set(wpi::DoubleSolenoid::Value::REVERSE);
m_motor.SetDutyCycle(0); // turn off the motor
m_motor.SetThrottle(0); // turn off the motor
}
void Intake::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

@@ -111,8 +111,8 @@ class Drivetrain : public wpi::cmd::SubsystemBase {
wpi::Encoder m_rightEncoder{6, 7};
wpi::DifferentialDrive m_drive{
[&](double output) { m_leftMotor.SetDutyCycle(output); },
[&](double output) { m_rightMotor.SetDutyCycle(output); }};
[&](double output) { m_leftMotor.SetThrottle(output); },
[&](double output) { m_rightMotor.SetThrottle(output); }};
wpi::xrp::XRPGyro m_gyro;
};

View File

@@ -27,6 +27,6 @@ class Robot : public wpi::TimedRobot {
wpi::Timer m_timer;
wpi::DifferentialDrive m_drive{
[&](double output) { m_leftMotor.SetDutyCycle(output); },
[&](double output) { m_rightMotor.SetDutyCycle(output); }};
[&](double output) { m_leftMotor.SetThrottle(output); },
[&](double output) { m_rightMotor.SetThrottle(output); }};
};

View File

@@ -44,8 +44,8 @@ class Robot : public wpi::TimedRobot {
wpi::Spark rightLeader{2};
wpi::Spark rightFollower{3};
wpi::DifferentialDrive drive{
[&](double output) { leftLeader.SetDutyCycle(output); },
[&](double output) { rightLeader.SetDutyCycle(output); }};
[&](double output) { leftLeader.SetThrottle(output); },
[&](double output) { rightLeader.SetThrottle(output); }};
};
#ifndef RUNNING_WPILIB_TESTS

View File

@@ -17,9 +17,9 @@ class Robot : public wpi::TimedRobot {
// Runs the motor backwards at half velocity until the limit switch is
// pressed then turn off the motor and reset the encoder
if (!m_limit.Get()) {
m_spark.SetDutyCycle(-0.5);
m_spark.SetThrottle(-0.5);
} else {
m_spark.SetDutyCycle(0);
m_spark.SetThrottle(0);
m_encoder.Reset();
}
}

View File

@@ -36,14 +36,14 @@ class Robot : public wpi::TimedRobot {
// and there is not a ball at the kicker
&& !isBallAtKicker)
// activate the intake
.IfHigh([&intake = m_intake] { intake.SetDutyCycle(0.5); });
.IfHigh([&intake = m_intake] { intake.SetThrottle(0.5); });
// if the thumb button is not held
(!intakeButton
// or there is a ball in the kicker
|| isBallAtKicker)
// stop the intake
.IfHigh([&intake = m_intake] { intake.SetDutyCycle(0.0); });
.IfHigh([&intake = m_intake] { intake.SetThrottle(0.0); });
wpi::BooleanEvent shootTrigger{
&m_loop, [&joystick = m_joystick] { return joystick.GetTrigger(); }};
@@ -60,7 +60,7 @@ class Robot : public wpi::TimedRobot {
});
// if not, stop
(!shootTrigger).IfHigh([&shooter = m_shooter] {
shooter.SetDutyCycle(0.0);
shooter.SetThrottle(0.0);
});
wpi::BooleanEvent atTargetVelocity =
@@ -71,13 +71,13 @@ class Robot : public wpi::TimedRobot {
.Debounce(0.2_s);
// if we're at the target velocity, kick the ball into the shooter wheel
atTargetVelocity.IfHigh([&kicker = m_kicker] { kicker.SetDutyCycle(0.7); });
atTargetVelocity.IfHigh([&kicker = m_kicker] { kicker.SetThrottle(0.7); });
// when we stop being at the target velocity, it means the ball was shot
atTargetVelocity
.Falling()
// so stop the kicker
.IfHigh([&kicker = m_kicker] { kicker.SetDutyCycle(0.0); });
.IfHigh([&kicker = m_kicker] { kicker.SetThrottle(0.0); });
}
void RobotPeriodic() override { m_loop.Poll(); }

View File

@@ -52,7 +52,7 @@ class Robot : public wpi::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() *
m_flywheelMotor.GetThrottle() *
wpi::units::volt_t{wpi::RobotController::GetInputVoltage()});
m_flywheelSim.Update(20_ms);
m_encoderSim.SetRate(m_flywheelSim.GetAngularVelocity().value());

View File

@@ -18,20 +18,20 @@ class Robot : public wpi::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

@@ -23,7 +23,7 @@
*/
class Robot : public wpi::TimedRobot {
public:
void TeleopPeriodic() override { m_motor.SetDutyCycle(m_stick.GetY()); }
void TeleopPeriodic() override { m_motor.SetThrottle(m_stick.GetY()); }
/*
* The RobotPeriodic function is called every control packet no matter the

View File

@@ -134,7 +134,7 @@ TEST_P(ArmSimulationTest, Teleop) {
wpi::sim::StepTiming(3_s);
ASSERT_NEAR(0.0, m_motorSim.GetDutyCycle(), 0.05);
ASSERT_NEAR(0.0, m_motorSim.GetThrottle(), 0.05);
EXPECT_NEAR(kMinAngle.value(), m_encoderSim.GetDistance(), 2.0);
}
}

View File

@@ -118,7 +118,7 @@ TEST_F(ElevatorSimulationTest, Teleop) {
// advance 75 timesteps
wpi::sim::StepTiming(1.5_s);
ASSERT_NEAR(0.0, m_motorSim.GetDutyCycle(), 0.05);
ASSERT_NEAR(0.0, m_motorSim.GetThrottle(), 0.05);
ASSERT_NEAR(0.0, m_encoderSim.GetDistance(), 0.05);
}
}

View File

@@ -27,13 +27,13 @@ TEST_F(IntakeTest, DoesntWorkWhenClosed) {
EXPECT_DOUBLE_EQ(
0.0,
simMotor
.GetDutyCycle()); // make sure that the value set to the motor is 0
.GetThrottle()); // make sure that the value set to the motor is 0
}
TEST_F(IntakeTest, WorksWhenOpen) {
intake.Deploy();
intake.Activate(0.5);
EXPECT_DOUBLE_EQ(0.5, simMotor.GetDutyCycle());
EXPECT_DOUBLE_EQ(0.5, simMotor.GetThrottle());
}
TEST_F(IntakeTest, Retract) {