diff --git a/robotpyExamples/ArmSimulation/subsystems/arm.py b/robotpyExamples/ArmSimulation/subsystems/arm.py index e35e7e5700..ca8e1b8b11 100644 --- a/robotpyExamples/ArmSimulation/subsystems/arm.py +++ b/robotpyExamples/ArmSimulation/subsystems/arm.py @@ -76,7 +76,7 @@ class Arm: # In this method, we update our simulation of what our arm is doing # First, we set our "inputs" (voltages) self.armSim.setInput( - [self.motor.getDutyCycle() * wpilib.RobotController.getBatteryVoltage()] + [self.motor.getThrottle() * wpilib.RobotController.getBatteryVoltage()] ) # Next, we update it. The standard loop time is 20ms. @@ -111,4 +111,4 @@ class Arm: self.motor.setVoltage(pidOutput) def stop(self) -> None: - self.motor.setDutyCycle(0.0) + self.motor.setThrottle(0.0) diff --git a/robotpyExamples/DifferentialDrivePoseEstimator/drivetrain.py b/robotpyExamples/DifferentialDrivePoseEstimator/drivetrain.py index d8efdc8f7a..3b90cb1b71 100644 --- a/robotpyExamples/DifferentialDrivePoseEstimator/drivetrain.py +++ b/robotpyExamples/DifferentialDrivePoseEstimator/drivetrain.py @@ -244,8 +244,8 @@ class Drivetrain: # simulation, and write the simulated positions and velocities to our # simulated encoder and gyro. self.drivetrainSimulator.setInputs( - self.leftLeader.getDutyCycle() * wpilib.RobotController.getInputVoltage(), - self.rightLeader.getDutyCycle() * wpilib.RobotController.getInputVoltage(), + self.leftLeader.getThrottle() * wpilib.RobotController.getInputVoltage(), + self.rightLeader.getThrottle() * wpilib.RobotController.getInputVoltage(), ) self.drivetrainSimulator.update(0.02) diff --git a/robotpyExamples/ElevatorExponentialSimulation/subsystems/elevator.py b/robotpyExamples/ElevatorExponentialSimulation/subsystems/elevator.py index f20ee52b7c..71a2c10334 100644 --- a/robotpyExamples/ElevatorExponentialSimulation/subsystems/elevator.py +++ b/robotpyExamples/ElevatorExponentialSimulation/subsystems/elevator.py @@ -84,7 +84,7 @@ class Elevator: # In this method, we update our simulation of what our elevator is doing # First, we set our "inputs" (voltages) self.elevatorSim.setInputVoltage( - self.motorSim.getDutyCycle() * wpilib.RobotController.getBatteryVoltage() + self.motorSim.getThrottle() * wpilib.RobotController.getBatteryVoltage() ) # Next, we update it. The standard loop time is 20ms. @@ -120,7 +120,7 @@ class Elevator: def stop(self) -> None: """Stop the control loop and motor output.""" - self.motor.setDutyCycle(0.0) + self.motor.setThrottle(0.0) def reset(self) -> None: """Reset Exponential profile to begin from current position on enable.""" diff --git a/robotpyExamples/ElevatorSimulation/subsystems/elevator.py b/robotpyExamples/ElevatorSimulation/subsystems/elevator.py index 7ea78107fc..001531faac 100644 --- a/robotpyExamples/ElevatorSimulation/subsystems/elevator.py +++ b/robotpyExamples/ElevatorSimulation/subsystems/elevator.py @@ -68,7 +68,7 @@ class Elevator: # In this method, we update our simulation of what our elevator is doing # First, we set our "inputs" (voltages) self.elevatorSim.setInputVoltage( - self.motorSim.getDutyCycle() * wpilib.RobotController.getBatteryVoltage() + self.motorSim.getThrottle() * wpilib.RobotController.getBatteryVoltage() ) # Next, we update it. The standard loop time is 20ms. @@ -99,7 +99,7 @@ class Elevator: def stop(self) -> None: """Stop the control loop and motor output.""" self.controller.setGoal(0.0) - self.motor.setDutyCycle(0.0) + self.motor.setThrottle(0.0) def updateTelemetry(self) -> None: """Update telemetry, including the mechanism visualization.""" diff --git a/robotpyExamples/FlywheelBangBangController/robot.py b/robotpyExamples/FlywheelBangBangController/robot.py index 67eac98d36..a2e199c583 100755 --- a/robotpyExamples/FlywheelBangBangController/robot.py +++ b/robotpyExamples/FlywheelBangBangController/robot.py @@ -102,7 +102,7 @@ class MyRobot(wpilib.TimedRobot): # To update our simulation, we set motor voltage inputs, update the # simulation, and write the simulated velocities to our simulated encoder self.flywheelSim.setInputVoltage( - self.flywheelMotor.getDutyCycle() * wpilib.RobotController.getInputVoltage() + self.flywheelMotor.getThrottle() * wpilib.RobotController.getInputVoltage() ) self.flywheelSim.update(0.02) self.encoderSim.setRate(self.flywheelSim.getAngularVelocity()) diff --git a/robotpyExamples/Mechanism2d/robot.py b/robotpyExamples/Mechanism2d/robot.py index 75f82fc281..5a7135c9ef 100755 --- a/robotpyExamples/Mechanism2d/robot.py +++ b/robotpyExamples/Mechanism2d/robot.py @@ -56,5 +56,5 @@ class MyRobot(wpilib.TimedRobot): self.wrist.setAngle(self.wristPot.get()) def teleopPeriodic(self): - self.elevatorMotor.setDutyCycle(self.joystick.getRawAxis(0)) - self.wristMotor.setDutyCycle(self.joystick.getRawAxis(1)) + self.elevatorMotor.setThrottle(self.joystick.getRawAxis(0)) + self.wristMotor.setThrottle(self.joystick.getRawAxis(1)) diff --git a/robotpyExamples/MotorControl/robot.py b/robotpyExamples/MotorControl/robot.py index a41b2428e8..c8c23d73f9 100755 --- a/robotpyExamples/MotorControl/robot.py +++ b/robotpyExamples/MotorControl/robot.py @@ -43,4 +43,4 @@ class MyRobot(wpilib.TimedRobot): wpilib.SmartDashboard.putNumber("Encoder", self.encoder.getDistance()) def teleopPeriodic(self): - self.motor.setDutyCycle(self.joystick.getY()) + self.motor.setThrottle(self.joystick.getY()) diff --git a/robotpyExamples/SimpleDifferentialDriveSimulation/drivetrain.py b/robotpyExamples/SimpleDifferentialDriveSimulation/drivetrain.py index c6b426be3f..ca551c7c0f 100644 --- a/robotpyExamples/SimpleDifferentialDriveSimulation/drivetrain.py +++ b/robotpyExamples/SimpleDifferentialDriveSimulation/drivetrain.py @@ -145,8 +145,8 @@ class Drivetrain: # simulated encoder and gyro. We negate the right side so that positive # voltages make the right side move forward. self.drivetrainSimulator.setInputs( - self.leftLeader.getDutyCycle() * wpilib.RobotController.getInputVoltage(), - self.rightLeader.getDutyCycle() * wpilib.RobotController.getInputVoltage(), + self.leftLeader.getThrottle() * wpilib.RobotController.getInputVoltage(), + self.rightLeader.getThrottle() * wpilib.RobotController.getInputVoltage(), ) self.drivetrainSimulator.update(0.02) diff --git a/robotpyExamples/SysId/subsystems/shooter.py b/robotpyExamples/SysId/subsystems/shooter.py index 841f6f8b75..3bf3c11d96 100644 --- a/robotpyExamples/SysId/subsystems/shooter.py +++ b/robotpyExamples/SysId/subsystems/shooter.py @@ -93,7 +93,7 @@ class Shooter(Subsystem): ) + self.shooter_feedforward.calculate(target_velocity_radians) ) - self.feeder_motor.setDutyCycle(ShooterConstants.kFeederVelocity) + self.feeder_motor.setThrottle(ShooterConstants.kFeederVelocity) def _stop_motors(interrupted: bool) -> None: self.shooter_motor.stopMotor() diff --git a/robotpyExamples/UnitTest/subsystems/intake.py b/robotpyExamples/UnitTest/subsystems/intake.py index d330d9b6ea..1d617a31ff 100644 --- a/robotpyExamples/UnitTest/subsystems/intake.py +++ b/robotpyExamples/UnitTest/subsystems/intake.py @@ -20,17 +20,17 @@ class Intake: ) def deploy(self) -> None: - self.piston.setDutyCycle(wpilib.DoubleSolenoid.Value.FORWARD) + self.piston.setThrottle(wpilib.DoubleSolenoid.Value.FORWARD) def retract(self) -> None: - self.piston.setDutyCycle(wpilib.DoubleSolenoid.Value.REVERSE) - self.motor.setDutyCycle(0) # turn off the motor + self.piston.setThrottle(wpilib.DoubleSolenoid.Value.REVERSE) + self.motor.setThrottle(0) # turn off the motor def activate(self, velocity: float) -> None: if self.isDeployed(): - self.motor.setDutyCycle(velocity) + self.motor.setThrottle(velocity) else: # if piston isn't open, do nothing - self.motor.setDutyCycle(0) + self.motor.setThrottle(0) def isDeployed(self) -> bool: return self.piston.get() == wpilib.DoubleSolenoid.Value.FORWARD diff --git a/robotpyExamples/XrpReference/subsystems/drivetrain.py b/robotpyExamples/XrpReference/subsystems/drivetrain.py index 8918b1b49e..ae0b1ccf03 100644 --- a/robotpyExamples/XrpReference/subsystems/drivetrain.py +++ b/robotpyExamples/XrpReference/subsystems/drivetrain.py @@ -32,7 +32,7 @@ class Drivetrain(commands2.Subsystem): # Set up the differential drive controller self.drive = wpilib.DifferentialDrive( - self.leftMotor.setDutyCycle, self.rightMotor.setDutyCycle + self.leftMotor.setThrottle, self.rightMotor.setThrottle ) # TODO: these don't work diff --git a/romiVendordep/src/main/java/org/wpilib/romi/RomiMotor.java b/romiVendordep/src/main/java/org/wpilib/romi/RomiMotor.java index ab112d77da..c6ae05c9eb 100644 --- a/romiVendordep/src/main/java/org/wpilib/romi/RomiMotor.java +++ b/romiVendordep/src/main/java/org/wpilib/romi/RomiMotor.java @@ -15,7 +15,7 @@ public class RomiMotor extends PWMMotorController { /** Common initialization code called by all constructors. */ protected final void initRomiMotor() { m_pwm.setOutputPeriod(5); - setDutyCycle(0.0); + setThrottle(0.0); } /** diff --git a/romiVendordep/src/main/native/cpp/romi/RomiMotor.cpp b/romiVendordep/src/main/native/cpp/romi/RomiMotor.cpp index bb1d5b9fbc..1686b2cc9b 100644 --- a/romiVendordep/src/main/native/cpp/romi/RomiMotor.cpp +++ b/romiVendordep/src/main/native/cpp/romi/RomiMotor.cpp @@ -8,5 +8,5 @@ using namespace wpi::romi; RomiMotor::RomiMotor(int channel) : PWMMotorController("Romi Motor", channel) { m_pwm.SetOutputPeriod(5_ms); - SetDutyCycle(0.0); + SetThrottle(0.0); } diff --git a/wpilibc/src/generate/main/native/cpp/hardware/motor/pwm_motor_controller.cpp.jinja b/wpilibc/src/generate/main/native/cpp/hardware/motor/pwm_motor_controller.cpp.jinja index de2d66fe3d..111483d4f5 100644 --- a/wpilibc/src/generate/main/native/cpp/hardware/motor/pwm_motor_controller.cpp.jinja +++ b/wpilibc/src/generate/main/native/cpp/hardware/motor/pwm_motor_controller.cpp.jinja @@ -13,7 +13,7 @@ using namespace wpi; {{ name }}::{{ name }}(int channel) : PWMMotorController("{{ name }}", channel) { SetBounds({{ pulse_width_ms.max }}_ms, {{ pulse_width_ms.deadbandMax }}_ms, {{ pulse_width_ms.center }}_ms, {{ pulse_width_ms.deadbandMin }}_ms, {{ pulse_width_ms.min }}_ms); m_pwm.SetOutputPeriod({{ OutputPeriod | default("5", true)}}_ms); - SetDutyCycle(0.0); + SetThrottle(0.0); HAL_ReportUsage("IO", GetChannel(), "{{ ResourceName }}"); } diff --git a/wpilibc/src/generated/main/native/cpp/hardware/motor/Koors40.cpp b/wpilibc/src/generated/main/native/cpp/hardware/motor/Koors40.cpp index 107a5243d2..116e3753b8 100644 --- a/wpilibc/src/generated/main/native/cpp/hardware/motor/Koors40.cpp +++ b/wpilibc/src/generated/main/native/cpp/hardware/motor/Koors40.cpp @@ -13,7 +13,7 @@ using namespace wpi; Koors40::Koors40(int channel) : PWMMotorController("Koors40", channel) { SetBounds(2.004_ms, 1.52_ms, 1.5_ms, 1.48_ms, 0.997_ms); m_pwm.SetOutputPeriod(20_ms); - SetDutyCycle(0.0); + SetThrottle(0.0); HAL_ReportUsage("IO", GetChannel(), "Koors40"); } diff --git a/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMSparkFlex.cpp b/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMSparkFlex.cpp index 3b95e977b3..1baf628e8b 100644 --- a/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMSparkFlex.cpp +++ b/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMSparkFlex.cpp @@ -13,7 +13,7 @@ using namespace wpi; PWMSparkFlex::PWMSparkFlex(int channel) : PWMMotorController("PWMSparkFlex", channel) { SetBounds(2.003_ms, 1.55_ms, 1.5_ms, 1.46_ms, 0.999_ms); m_pwm.SetOutputPeriod(5_ms); - SetDutyCycle(0.0); + SetThrottle(0.0); HAL_ReportUsage("IO", GetChannel(), "RevSparkFlexPWM"); } diff --git a/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMSparkMax.cpp b/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMSparkMax.cpp index 4e85e75b6d..54bb620cf8 100644 --- a/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMSparkMax.cpp +++ b/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMSparkMax.cpp @@ -13,7 +13,7 @@ using namespace wpi; PWMSparkMax::PWMSparkMax(int channel) : PWMMotorController("PWMSparkMax", channel) { SetBounds(2.003_ms, 1.55_ms, 1.5_ms, 1.46_ms, 0.999_ms); m_pwm.SetOutputPeriod(5_ms); - SetDutyCycle(0.0); + SetThrottle(0.0); HAL_ReportUsage("IO", GetChannel(), "RevSparkMaxPWM"); } diff --git a/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMTalonFX.cpp b/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMTalonFX.cpp index 2d743b1518..f33e0fcd52 100644 --- a/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMTalonFX.cpp +++ b/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMTalonFX.cpp @@ -13,7 +13,7 @@ using namespace wpi; PWMTalonFX::PWMTalonFX(int channel) : PWMMotorController("PWMTalonFX", channel) { SetBounds(2.004_ms, 1.52_ms, 1.5_ms, 1.48_ms, 0.997_ms); m_pwm.SetOutputPeriod(5_ms); - SetDutyCycle(0.0); + SetThrottle(0.0); HAL_ReportUsage("IO", GetChannel(), "TalonFX"); } diff --git a/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMTalonSRX.cpp b/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMTalonSRX.cpp index d5e00d310b..57adf949f6 100644 --- a/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMTalonSRX.cpp +++ b/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMTalonSRX.cpp @@ -13,7 +13,7 @@ using namespace wpi; PWMTalonSRX::PWMTalonSRX(int channel) : PWMMotorController("PWMTalonSRX", channel) { SetBounds(2.004_ms, 1.52_ms, 1.5_ms, 1.48_ms, 0.997_ms); m_pwm.SetOutputPeriod(5_ms); - SetDutyCycle(0.0); + SetThrottle(0.0); HAL_ReportUsage("IO", GetChannel(), "PWMTalonSRX"); } diff --git a/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMVenom.cpp b/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMVenom.cpp index b3d791bbb0..ed079c4e76 100644 --- a/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMVenom.cpp +++ b/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMVenom.cpp @@ -13,7 +13,7 @@ using namespace wpi; PWMVenom::PWMVenom(int channel) : PWMMotorController("PWMVenom", channel) { SetBounds(2.004_ms, 1.52_ms, 1.5_ms, 1.48_ms, 0.997_ms); m_pwm.SetOutputPeriod(5_ms); - SetDutyCycle(0.0); + SetThrottle(0.0); HAL_ReportUsage("IO", GetChannel(), "FusionVenom"); } diff --git a/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMVictorSPX.cpp b/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMVictorSPX.cpp index 1450847760..f651181a76 100644 --- a/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMVictorSPX.cpp +++ b/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMVictorSPX.cpp @@ -13,7 +13,7 @@ using namespace wpi; PWMVictorSPX::PWMVictorSPX(int channel) : PWMMotorController("PWMVictorSPX", channel) { SetBounds(2.004_ms, 1.52_ms, 1.5_ms, 1.48_ms, 0.997_ms); m_pwm.SetOutputPeriod(5_ms); - SetDutyCycle(0.0); + SetThrottle(0.0); HAL_ReportUsage("IO", GetChannel(), "PWMVictorSPX"); } diff --git a/wpilibc/src/generated/main/native/cpp/hardware/motor/Spark.cpp b/wpilibc/src/generated/main/native/cpp/hardware/motor/Spark.cpp index 0912b84529..889011e917 100644 --- a/wpilibc/src/generated/main/native/cpp/hardware/motor/Spark.cpp +++ b/wpilibc/src/generated/main/native/cpp/hardware/motor/Spark.cpp @@ -13,7 +13,7 @@ using namespace wpi; Spark::Spark(int channel) : PWMMotorController("Spark", channel) { SetBounds(2.003_ms, 1.55_ms, 1.5_ms, 1.46_ms, 0.999_ms); m_pwm.SetOutputPeriod(5_ms); - SetDutyCycle(0.0); + SetThrottle(0.0); HAL_ReportUsage("IO", GetChannel(), "RevSPARK"); } diff --git a/wpilibc/src/generated/main/native/cpp/hardware/motor/SparkMini.cpp b/wpilibc/src/generated/main/native/cpp/hardware/motor/SparkMini.cpp index 7a6290e22e..609cf7181f 100644 --- a/wpilibc/src/generated/main/native/cpp/hardware/motor/SparkMini.cpp +++ b/wpilibc/src/generated/main/native/cpp/hardware/motor/SparkMini.cpp @@ -13,7 +13,7 @@ using namespace wpi; SparkMini::SparkMini(int channel) : PWMMotorController("SparkMini", channel) { SetBounds(2.5_ms, 1.51_ms, 1.5_ms, 1.49_ms, 0.5_ms); m_pwm.SetOutputPeriod(5_ms); - SetDutyCycle(0.0); + SetThrottle(0.0); HAL_ReportUsage("IO", GetChannel(), "RevSPARK"); } diff --git a/wpilibc/src/generated/main/native/cpp/hardware/motor/Talon.cpp b/wpilibc/src/generated/main/native/cpp/hardware/motor/Talon.cpp index 337e4f20a7..d3c658a145 100644 --- a/wpilibc/src/generated/main/native/cpp/hardware/motor/Talon.cpp +++ b/wpilibc/src/generated/main/native/cpp/hardware/motor/Talon.cpp @@ -13,7 +13,7 @@ using namespace wpi; Talon::Talon(int channel) : PWMMotorController("Talon", channel) { SetBounds(2.037_ms, 1.539_ms, 1.513_ms, 1.487_ms, 0.989_ms); m_pwm.SetOutputPeriod(5_ms); - SetDutyCycle(0.0); + SetThrottle(0.0); HAL_ReportUsage("IO", GetChannel(), "Talon"); } diff --git a/wpilibc/src/generated/main/native/cpp/hardware/motor/VictorSP.cpp b/wpilibc/src/generated/main/native/cpp/hardware/motor/VictorSP.cpp index fbca7e7500..a6c36dacf5 100644 --- a/wpilibc/src/generated/main/native/cpp/hardware/motor/VictorSP.cpp +++ b/wpilibc/src/generated/main/native/cpp/hardware/motor/VictorSP.cpp @@ -13,7 +13,7 @@ using namespace wpi; VictorSP::VictorSP(int channel) : PWMMotorController("VictorSP", channel) { SetBounds(2.004_ms, 1.52_ms, 1.5_ms, 1.48_ms, 0.997_ms); m_pwm.SetOutputPeriod(5_ms); - SetDutyCycle(0.0); + SetThrottle(0.0); HAL_ReportUsage("IO", GetChannel(), "VictorSP"); } diff --git a/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp index bba37f2f58..22f86b58fd 100644 --- a/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp +++ b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp @@ -17,19 +17,15 @@ using namespace wpi; -WPI_IGNORE_DEPRECATED - DifferentialDrive::DifferentialDrive(MotorController& leftMotor, MotorController& rightMotor) : DifferentialDrive{ - [&](double output) { leftMotor.SetDutyCycle(output); }, - [&](double output) { rightMotor.SetDutyCycle(output); }} { + [&](double output) { leftMotor.SetThrottle(output); }, + [&](double output) { rightMotor.SetThrottle(output); }} { wpi::util::SendableRegistry::AddChild(this, &leftMotor); wpi::util::SendableRegistry::AddChild(this, &rightMotor); } -WPI_UNIGNORE_DEPRECATED - DifferentialDrive::DifferentialDrive(std::function leftMotor, std::function rightMotor) : m_leftMotor{std::move(leftMotor)}, m_rightMotor{std::move(rightMotor)} { diff --git a/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp index 7b7f48df60..7278341bbf 100644 --- a/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp +++ b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp @@ -17,25 +17,20 @@ using namespace wpi; -WPI_IGNORE_DEPRECATED - MecanumDrive::MecanumDrive(MotorController& frontLeftMotor, MotorController& rearLeftMotor, MotorController& frontRightMotor, MotorController& rearRightMotor) - : MecanumDrive{ - [&](double output) { frontLeftMotor.SetDutyCycle(output); }, - [&](double output) { rearLeftMotor.SetDutyCycle(output); }, - [&](double output) { frontRightMotor.SetDutyCycle(output); }, - [&](double output) { rearRightMotor.SetDutyCycle(output); }} { + : MecanumDrive{[&](double output) { frontLeftMotor.SetThrottle(output); }, + [&](double output) { rearLeftMotor.SetThrottle(output); }, + [&](double output) { frontRightMotor.SetThrottle(output); }, + [&](double output) { rearRightMotor.SetThrottle(output); }} { wpi::util::SendableRegistry::AddChild(this, &frontLeftMotor); wpi::util::SendableRegistry::AddChild(this, &rearLeftMotor); wpi::util::SendableRegistry::AddChild(this, &frontRightMotor); wpi::util::SendableRegistry::AddChild(this, &rearRightMotor); } -WPI_UNIGNORE_DEPRECATED - MecanumDrive::MecanumDrive(std::function frontLeftMotor, std::function rearLeftMotor, std::function frontRightMotor, diff --git a/wpilibc/src/main/native/cpp/hardware/expansionhub/ExpansionHubMotor.cpp b/wpilibc/src/main/native/cpp/hardware/expansionhub/ExpansionHubMotor.cpp index bb1f6b1489..f856356699 100644 --- a/wpilibc/src/main/native/cpp/hardware/expansionhub/ExpansionHubMotor.cpp +++ b/wpilibc/src/main/native/cpp/hardware/expansionhub/ExpansionHubMotor.cpp @@ -92,10 +92,10 @@ ExpansionHubMotor::~ExpansionHubMotor() noexcept { m_hub.UnreserveMotor(m_channel); } -void ExpansionHubMotor::SetDutyCycle(double dutyCycle) { +void ExpansionHubMotor::SetThrottle(double throttle) { SetEnabled(true); m_modePublisher.Set(kPercentageMode); - m_setpointPublisher.Set(dutyCycle); + m_setpointPublisher.Set(throttle); } void ExpansionHubMotor::SetVoltage(wpi::units::volt_t voltage) { diff --git a/wpilibc/src/main/native/cpp/hardware/motor/MotorController.cpp b/wpilibc/src/main/native/cpp/hardware/motor/MotorController.cpp index 2a286a7d1d..712dfe8cdc 100644 --- a/wpilibc/src/main/native/cpp/hardware/motor/MotorController.cpp +++ b/wpilibc/src/main/native/cpp/hardware/motor/MotorController.cpp @@ -10,5 +10,5 @@ using namespace wpi; void MotorController::SetVoltage(wpi::units::volt_t voltage) { // NOLINTNEXTLINE(bugprone-integer-division) - SetDutyCycle(voltage / RobotController::GetBatteryVoltage()); + SetThrottle(voltage / RobotController::GetBatteryVoltage()); } diff --git a/wpilibc/src/main/native/cpp/hardware/motor/PWMMotorController.cpp b/wpilibc/src/main/native/cpp/hardware/motor/PWMMotorController.cpp index b9dc956b11..f6d7b8fb93 100644 --- a/wpilibc/src/main/native/cpp/hardware/motor/PWMMotorController.cpp +++ b/wpilibc/src/main/native/cpp/hardware/motor/PWMMotorController.cpp @@ -14,28 +14,28 @@ using namespace wpi; -void PWMMotorController::SetDutyCycle(double dutyCycle) { +void PWMMotorController::SetThrottle(double throttle) { if (m_isInverted) { - dutyCycle = -dutyCycle; + throttle = -throttle; } - SetDutyCycleInternal(dutyCycle); + SetDutyCycleInternal(throttle); for (auto& follower : m_nonowningFollowers) { - follower->SetDutyCycle(dutyCycle); + follower->SetThrottle(throttle); } for (auto& follower : m_owningFollowers) { - follower->SetDutyCycle(dutyCycle); + follower->SetThrottle(throttle); } Feed(); } -double PWMMotorController::GetDutyCycle() const { +double PWMMotorController::GetThrottle() const { return GetDutyCycleInternal() * (m_isInverted ? -1.0 : 1.0); } wpi::units::volt_t PWMMotorController::GetVoltage() const { - return GetDutyCycle() * RobotController::GetBatteryVoltage(); + return GetThrottle() * RobotController::GetBatteryVoltage(); } void PWMMotorController::SetInverted(bool isInverted) { @@ -49,8 +49,8 @@ bool PWMMotorController::GetInverted() const { void PWMMotorController::Disable() { m_pwm.SetDisabled(); - if (m_simDutyCycle) { - m_simDutyCycle.Set(0.0); + if (m_simThrottle) { + m_simThrottle.Set(0.0); } for (auto& follower : m_nonowningFollowers) { @@ -81,28 +81,24 @@ void PWMMotorController::AddFollower(PWMMotorController& follower) { m_nonowningFollowers.emplace_back(&follower); } -WPI_IGNORE_DEPRECATED - PWMMotorController::PWMMotorController(std::string_view name, int channel) : m_pwm(channel, false) { wpi::util::SendableRegistry::Add(this, name, channel); m_simDevice = wpi::hal::SimDevice{"PWMMotorController", channel}; if (m_simDevice) { - m_simDutyCycle = m_simDevice.CreateDouble( - "DutyCycle", wpi::hal::SimDevice::Direction::OUTPUT, 0.0); + m_simThrottle = m_simDevice.CreateDouble( + "Throttle", wpi::hal::SimDevice::Direction::OUTPUT, 0.0); m_pwm.SetSimDevice(m_simDevice); } } -WPI_UNIGNORE_DEPRECATED - void PWMMotorController::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("Motor Controller"); builder.SetActuator(true); builder.AddDoubleProperty( - "Value", [=, this] { return GetDutyCycle(); }, - [=, this](double value) { SetDutyCycle(value); }); + "Value", [=, this] { return GetThrottle(); }, + [=, this](double value) { SetThrottle(value); }); } wpi::units::microsecond_t PWMMotorController::GetMinPositivePwm() const { @@ -136,8 +132,8 @@ void PWMMotorController::SetDutyCycleInternal(double dutyCycle) { dutyCycle = 0.0; } - if (m_simDutyCycle) { - m_simDutyCycle.Set(dutyCycle); + if (m_simThrottle) { + m_simThrottle.Set(dutyCycle); } wpi::units::microsecond_t rawValue; diff --git a/wpilibc/src/main/native/cpp/simulation/PWMMotorControllerSim.cpp b/wpilibc/src/main/native/cpp/simulation/PWMMotorControllerSim.cpp index 45210585f8..54a4b1f61a 100644 --- a/wpilibc/src/main/native/cpp/simulation/PWMMotorControllerSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/PWMMotorControllerSim.cpp @@ -16,9 +16,9 @@ PWMMotorControllerSim::PWMMotorControllerSim( PWMMotorControllerSim::PWMMotorControllerSim(int channel) { wpi::sim::SimDeviceSim deviceSim{"PWMMotorController", channel}; - m_simDutyCycle = deviceSim.GetDouble("DutyCycle"); + m_simThrottle = deviceSim.GetDouble("Throttle"); } -double PWMMotorControllerSim::GetDutyCycle() const { - return m_simDutyCycle.Get(); +double PWMMotorControllerSim::GetThrottle() const { + return m_simThrottle.Get(); } diff --git a/wpilibc/src/main/native/include/wpi/drive/DifferentialDrive.hpp b/wpilibc/src/main/native/include/wpi/drive/DifferentialDrive.hpp index a38c884493..7378246d01 100644 --- a/wpilibc/src/main/native/include/wpi/drive/DifferentialDrive.hpp +++ b/wpilibc/src/main/native/include/wpi/drive/DifferentialDrive.hpp @@ -8,7 +8,6 @@ #include #include "wpi/drive/RobotDriveBase.hpp" -#include "wpi/util/deprecated.hpp" #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" @@ -70,8 +69,6 @@ class DifferentialDrive : public RobotDriveBase, double right = 0.0; }; - WPI_IGNORE_DEPRECATED - /** * Construct a DifferentialDrive. * @@ -84,8 +81,6 @@ class DifferentialDrive : public RobotDriveBase, */ DifferentialDrive(MotorController& leftMotor, MotorController& rightMotor); - WPI_UNIGNORE_DEPRECATED - /** * Construct a DifferentialDrive. * diff --git a/wpilibc/src/main/native/include/wpi/drive/MecanumDrive.hpp b/wpilibc/src/main/native/include/wpi/drive/MecanumDrive.hpp index 237ccebdac..8e6dcf8b89 100644 --- a/wpilibc/src/main/native/include/wpi/drive/MecanumDrive.hpp +++ b/wpilibc/src/main/native/include/wpi/drive/MecanumDrive.hpp @@ -5,13 +5,11 @@ #pragma once #include -#include #include #include "wpi/drive/RobotDriveBase.hpp" #include "wpi/math/geometry/Rotation2d.hpp" #include "wpi/units/angle.hpp" -#include "wpi/util/deprecated.hpp" #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" @@ -71,8 +69,6 @@ class MecanumDrive : public RobotDriveBase, double rearRight = 0.0; }; - WPI_IGNORE_DEPRECATED - /** * Construct a MecanumDrive. * @@ -87,8 +83,6 @@ class MecanumDrive : public RobotDriveBase, MotorController& frontRightMotor, MotorController& rearRightMotor); - WPI_UNIGNORE_DEPRECATED - /** * Construct a MecanumDrive. * diff --git a/wpilibc/src/main/native/include/wpi/drive/RobotDriveBase.hpp b/wpilibc/src/main/native/include/wpi/drive/RobotDriveBase.hpp index 02f5cf6ba3..6d8c7f8ed7 100644 --- a/wpilibc/src/main/native/include/wpi/drive/RobotDriveBase.hpp +++ b/wpilibc/src/main/native/include/wpi/drive/RobotDriveBase.hpp @@ -4,7 +4,6 @@ #pragma once -#include #include #include diff --git a/wpilibc/src/main/native/include/wpi/hardware/expansionhub/ExpansionHubMotor.hpp b/wpilibc/src/main/native/include/wpi/hardware/expansionhub/ExpansionHubMotor.hpp index 56a53e4594..18c05a6fa6 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/expansionhub/ExpansionHubMotor.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/expansionhub/ExpansionHubMotor.hpp @@ -4,16 +4,12 @@ #pragma once -#include - #include "wpi/hardware/expansionhub/ExpansionHub.hpp" #include "wpi/hardware/expansionhub/ExpansionHubPidConstants.hpp" #include "wpi/nt/BooleanTopic.hpp" #include "wpi/nt/DoubleTopic.hpp" #include "wpi/nt/IntegerTopic.hpp" -#include "wpi/units/angle.hpp" #include "wpi/units/current.hpp" -#include "wpi/units/time.hpp" #include "wpi/units/voltage.hpp" namespace wpi { @@ -33,12 +29,12 @@ class ExpansionHubMotor { ~ExpansionHubMotor() noexcept; /** - * Sets the duty cycle. + * Sets the throttle. * - * @param dutyCycle The duty cycle between -1 and 1 (sign indicates - * direction). + * @param throttle The throttle where -1 indicates full reverse and 1 + * indicates full forward. */ - void SetDutyCycle(double dutyCycle); + void SetThrottle(double throttle); /** * Sets the voltage to run the motor at. This value will be continously scaled diff --git a/wpilibc/src/main/native/include/wpi/hardware/motor/MotorController.hpp b/wpilibc/src/main/native/include/wpi/hardware/motor/MotorController.hpp index 4e186e2898..25dbc2ac1f 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/motor/MotorController.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/motor/MotorController.hpp @@ -16,12 +16,12 @@ class MotorController { virtual ~MotorController() = default; /** - * Sets the duty cycle of the motor controller. + * Sets the throttle of the motor controller. * - * @param dutyCycle The duty cycle between -1 and 1 (sign indicates - * direction). + * @param throttle The throttle where -1 indicates full reverse and 1 + * indicates full forward. */ - virtual void SetDutyCycle(double dutyCycle) = 0; + virtual void SetThrottle(double throttle) = 0; /** * Sets the voltage output of the motor controller. @@ -40,11 +40,12 @@ class MotorController { virtual void SetVoltage(wpi::units::volt_t voltage); /** - * Gets the duty cycle of the motor controller. + * Gets the throttle of the motor controller. * - * @return The duty cycle between -1 and 1 (sign indicates direction). + * @return The throttle where -1 represents full reverse and 1 represents full + * forward. */ - virtual double GetDutyCycle() const = 0; + virtual double GetThrottle() const = 0; /** * Sets the inversion state of the motor controller. diff --git a/wpilibc/src/main/native/include/wpi/hardware/motor/PWMMotorController.hpp b/wpilibc/src/main/native/include/wpi/hardware/motor/PWMMotorController.hpp index 289ade70eb..89e5fab8cb 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/motor/PWMMotorController.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/motor/PWMMotorController.hpp @@ -17,14 +17,11 @@ #include "wpi/hardware/motor/MotorController.hpp" #include "wpi/hardware/motor/MotorSafety.hpp" #include "wpi/units/voltage.hpp" -#include "wpi/util/deprecated.hpp" #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" namespace wpi { -WPI_IGNORE_DEPRECATED - /** * Common base class for all PWM Motor Controllers. */ @@ -37,9 +34,9 @@ class PWMMotorController PWMMotorController(PWMMotorController&&) = default; PWMMotorController& operator=(PWMMotorController&&) = default; - void SetDutyCycle(double dutyCycle) override; + void SetThrottle(double throttle) override; - double GetDutyCycle() const override; + double GetThrottle() const override; /** * Gets the voltage output of the motor controller, nominally between -12 V @@ -119,7 +116,7 @@ class PWMMotorController std::vector> m_owningFollowers; wpi::hal::SimDevice m_simDevice; - wpi::hal::SimDouble m_simDutyCycle; + wpi::hal::SimDouble m_simThrottle; bool m_eliminateDeadband{0}; wpi::units::microsecond_t m_minPwm{0}; @@ -136,6 +133,4 @@ class PWMMotorController PWM* GetPwm() { return &m_pwm; } }; -WPI_UNIGNORE_DEPRECATED - } // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/simulation/PWMMotorControllerSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/PWMMotorControllerSim.hpp index e0ed551588..f6d44910b5 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/PWMMotorControllerSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/PWMMotorControllerSim.hpp @@ -19,10 +19,10 @@ class PWMMotorControllerSim { explicit PWMMotorControllerSim(int channel); - double GetDutyCycle() const; + double GetThrottle() const; private: - wpi::hal::SimDouble m_simDutyCycle; + wpi::hal::SimDouble m_simThrottle; }; } // namespace sim } // namespace wpi diff --git a/wpilibc/src/main/python/semiwrap/ExpansionHubMotor.yml b/wpilibc/src/main/python/semiwrap/ExpansionHubMotor.yml index 8fe86dff21..cdc2f67712 100644 --- a/wpilibc/src/main/python/semiwrap/ExpansionHubMotor.yml +++ b/wpilibc/src/main/python/semiwrap/ExpansionHubMotor.yml @@ -2,7 +2,7 @@ classes: wpi::ExpansionHubMotor: methods: ExpansionHubMotor: - SetDutyCycle: + SetThrottle: SetVoltage: SetPositionSetpoint: SetVelocitySetpoint: diff --git a/wpilibc/src/main/python/semiwrap/MotorController.yml b/wpilibc/src/main/python/semiwrap/MotorController.yml index 7b8ee821aa..db9fdd8e79 100644 --- a/wpilibc/src/main/python/semiwrap/MotorController.yml +++ b/wpilibc/src/main/python/semiwrap/MotorController.yml @@ -1,9 +1,9 @@ classes: wpi::MotorController: methods: - SetDutyCycle: + SetThrottle: SetVoltage: - GetDutyCycle: + GetThrottle: SetInverted: GetInverted: Disable: diff --git a/wpilibc/src/main/python/semiwrap/MotorControllerGroup.yml b/wpilibc/src/main/python/semiwrap/MotorControllerGroup.yml index 9ead657137..7bf24ec224 100644 --- a/wpilibc/src/main/python/semiwrap/MotorControllerGroup.yml +++ b/wpilibc/src/main/python/semiwrap/MotorControllerGroup.yml @@ -33,9 +33,9 @@ classes: param_override: args: ignore: true - SetDutyCycle: + SetThrottle: SetVoltage: - GetDutyCycle: + GetThrottle: SetInverted: GetInverted: Disable: diff --git a/wpilibc/src/main/python/semiwrap/PWMMotorController.yml b/wpilibc/src/main/python/semiwrap/PWMMotorController.yml index 4ace69f85c..f07466974b 100644 --- a/wpilibc/src/main/python/semiwrap/PWMMotorController.yml +++ b/wpilibc/src/main/python/semiwrap/PWMMotorController.yml @@ -8,8 +8,8 @@ classes: attributes: m_pwm: methods: - SetDutyCycle: - GetDutyCycle: + SetThrottle: + GetThrottle: GetVoltage: SetInverted: GetInverted: diff --git a/wpilibc/src/main/python/semiwrap/simulation/PWMMotorControllerSim.yml b/wpilibc/src/main/python/semiwrap/simulation/PWMMotorControllerSim.yml index 7915857848..c193adfafe 100644 --- a/wpilibc/src/main/python/semiwrap/simulation/PWMMotorControllerSim.yml +++ b/wpilibc/src/main/python/semiwrap/simulation/PWMMotorControllerSim.yml @@ -5,4 +5,4 @@ classes: overloads: const PWMMotorController&: int: - GetDutyCycle: + GetThrottle: diff --git a/wpilibc/src/main/python/wpilib/src/rpy/MotorControllerGroup.cpp b/wpilibc/src/main/python/wpilib/src/rpy/MotorControllerGroup.cpp index a03af5028f..9db4fb9313 100644 --- a/wpilibc/src/main/python/wpilib/src/rpy/MotorControllerGroup.cpp +++ b/wpilibc/src/main/python/wpilib/src/rpy/MotorControllerGroup.cpp @@ -17,9 +17,9 @@ void PyMotorControllerGroup::Initialize() { wpi::util::SendableRegistry::Add(this, "MotorControllerGroup", instances); } -void PyMotorControllerGroup::SetDutyCycle(double dutyCycle) { +void PyMotorControllerGroup::SetThrottle(double throttle) { for (auto motorController : m_motorControllers) { - motorController->SetDutyCycle(m_isInverted ? -dutyCycle : dutyCycle); + motorController->SetThrottle(m_isInverted ? -throttle : throttle); } } @@ -29,9 +29,9 @@ void PyMotorControllerGroup::SetVoltage(wpi::units::volt_t voltage) { } } -double PyMotorControllerGroup::GetDutyCycle() const { +double PyMotorControllerGroup::GetThrottle() const { if (!m_motorControllers.empty()) { - return m_motorControllers.front()->GetDutyCycle() * (m_isInverted ? -1 : 1); + return m_motorControllers.front()->GetThrottle() * (m_isInverted ? -1 : 1); } return 0.0; } @@ -51,6 +51,6 @@ void PyMotorControllerGroup::Disable() { void PyMotorControllerGroup::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("Motor Controller"); builder.SetActuator(true); - builder.AddDoubleProperty("Value", [=, this]() { return GetDutyCycle(); }, - [=, this](double value) { SetDutyCycle(value); }); + builder.AddDoubleProperty("Value", [=, this]() { return GetThrottle(); }, + [=, this](double value) { SetThrottle(value); }); } diff --git a/wpilibc/src/main/python/wpilib/src/rpy/MotorControllerGroup.h b/wpilibc/src/main/python/wpilib/src/rpy/MotorControllerGroup.h index a7728119c3..df5fa26f0f 100644 --- a/wpilibc/src/main/python/wpilib/src/rpy/MotorControllerGroup.h +++ b/wpilibc/src/main/python/wpilib/src/rpy/MotorControllerGroup.h @@ -26,9 +26,9 @@ class PyMotorControllerGroup : public wpi::util::Sendable, PyMotorControllerGroup(PyMotorControllerGroup&&) = default; PyMotorControllerGroup& operator=(PyMotorControllerGroup&&) = default; - void SetDutyCycle(double dutyCycle) override; + void SetThrottle(double throttle) override; void SetVoltage(wpi::units::volt_t voltage) override; - double GetDutyCycle() const override; + double GetThrottle() const override; void SetInverted(bool isInverted) override; bool GetInverted() const override; void Disable() override; diff --git a/wpilibc/src/test/native/cpp/drive/DifferentialDriveTest.cpp b/wpilibc/src/test/native/cpp/drive/DifferentialDriveTest.cpp index a0c53b695c..f562086292 100644 --- a/wpilibc/src/test/native/cpp/drive/DifferentialDriveTest.cpp +++ b/wpilibc/src/test/native/cpp/drive/DifferentialDriveTest.cpp @@ -244,232 +244,232 @@ TEST(DifferentialDriveTest, ArcadeDrive) { wpi::MockPWMMotorController left; wpi::MockPWMMotorController right; wpi::DifferentialDrive drive{ - [&](double output) { left.SetDutyCycle(output); }, - [&](double output) { right.SetDutyCycle(output); }}; + [&](double output) { left.SetThrottle(output); }, + [&](double output) { right.SetThrottle(output); }}; drive.SetDeadband(0.0); // Forward drive.ArcadeDrive(1.0, 0.0, false); - EXPECT_DOUBLE_EQ(1.0, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(1.0, left.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, right.GetThrottle()); // Forward left turn drive.ArcadeDrive(0.5, 0.5, false); - EXPECT_DOUBLE_EQ(0.0, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(0.5, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(0.0, left.GetThrottle()); + EXPECT_DOUBLE_EQ(0.5, right.GetThrottle()); // Forward right turn drive.ArcadeDrive(0.5, -0.5, false); - EXPECT_DOUBLE_EQ(0.5, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(0.0, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(0.5, left.GetThrottle()); + EXPECT_DOUBLE_EQ(0.0, right.GetThrottle()); // Backward drive.ArcadeDrive(-1.0, 0.0, false); - EXPECT_DOUBLE_EQ(-1.0, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(-1.0, left.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, right.GetThrottle()); // Backward left turn drive.ArcadeDrive(-0.5, 0.5, false); - EXPECT_DOUBLE_EQ(-0.5, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(0.0, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(-0.5, left.GetThrottle()); + EXPECT_DOUBLE_EQ(0.0, right.GetThrottle()); // Backward right turn drive.ArcadeDrive(-0.5, -0.5, false); - EXPECT_DOUBLE_EQ(0.0, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-0.5, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(0.0, left.GetThrottle()); + EXPECT_DOUBLE_EQ(-0.5, right.GetThrottle()); } TEST(DifferentialDriveTest, ArcadeDriveSquared) { wpi::MockPWMMotorController left; wpi::MockPWMMotorController right; wpi::DifferentialDrive drive{ - [&](double output) { left.SetDutyCycle(output); }, - [&](double output) { right.SetDutyCycle(output); }}; + [&](double output) { left.SetThrottle(output); }, + [&](double output) { right.SetThrottle(output); }}; drive.SetDeadband(0.0); // Forward drive.ArcadeDrive(1.0, 0.0, true); - EXPECT_DOUBLE_EQ(1.0, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(1.0, left.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, right.GetThrottle()); // Forward left turn drive.ArcadeDrive(0.5, 0.5, true); - EXPECT_DOUBLE_EQ(0.0, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(0.25, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(0.0, left.GetThrottle()); + EXPECT_DOUBLE_EQ(0.25, right.GetThrottle()); // Forward right turn drive.ArcadeDrive(0.5, -0.5, true); - EXPECT_DOUBLE_EQ(0.25, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(0.0, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(0.25, left.GetThrottle()); + EXPECT_DOUBLE_EQ(0.0, right.GetThrottle()); // Backward drive.ArcadeDrive(-1.0, 0.0, true); - EXPECT_DOUBLE_EQ(-1.0, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(-1.0, left.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, right.GetThrottle()); // Backward left turn drive.ArcadeDrive(-0.5, 0.5, true); - EXPECT_DOUBLE_EQ(-0.25, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(0.0, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(-0.25, left.GetThrottle()); + EXPECT_DOUBLE_EQ(0.0, right.GetThrottle()); // Backward right turn drive.ArcadeDrive(-0.5, -0.5, true); - EXPECT_DOUBLE_EQ(0.0, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-0.25, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(0.0, left.GetThrottle()); + EXPECT_DOUBLE_EQ(-0.25, right.GetThrottle()); } TEST(DifferentialDriveTest, CurvatureDrive) { wpi::MockPWMMotorController left; wpi::MockPWMMotorController right; wpi::DifferentialDrive drive{ - [&](double output) { left.SetDutyCycle(output); }, - [&](double output) { right.SetDutyCycle(output); }}; + [&](double output) { left.SetThrottle(output); }, + [&](double output) { right.SetThrottle(output); }}; drive.SetDeadband(0.0); // Forward drive.CurvatureDrive(1.0, 0.0, false); - EXPECT_DOUBLE_EQ(1.0, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(1.0, left.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, right.GetThrottle()); // Forward left turn drive.CurvatureDrive(0.5, 0.5, false); - EXPECT_DOUBLE_EQ(0.25, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(0.75, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(0.25, left.GetThrottle()); + EXPECT_DOUBLE_EQ(0.75, right.GetThrottle()); // Forward right turn drive.CurvatureDrive(0.5, -0.5, false); - EXPECT_DOUBLE_EQ(0.75, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(0.25, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(0.75, left.GetThrottle()); + EXPECT_DOUBLE_EQ(0.25, right.GetThrottle()); // Backward drive.CurvatureDrive(-1.0, 0.0, false); - EXPECT_DOUBLE_EQ(-1.0, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(-1.0, left.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, right.GetThrottle()); // Backward left turn drive.CurvatureDrive(-0.5, 0.5, false); - EXPECT_DOUBLE_EQ(-0.75, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-0.25, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(-0.75, left.GetThrottle()); + EXPECT_DOUBLE_EQ(-0.25, right.GetThrottle()); // Backward right turn drive.CurvatureDrive(-0.5, -0.5, false); - EXPECT_DOUBLE_EQ(-0.25, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-0.75, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(-0.25, left.GetThrottle()); + EXPECT_DOUBLE_EQ(-0.75, right.GetThrottle()); } TEST(DifferentialDriveTest, CurvatureDriveTurnInPlace) { wpi::MockPWMMotorController left; wpi::MockPWMMotorController right; wpi::DifferentialDrive drive{ - [&](double output) { left.SetDutyCycle(output); }, - [&](double output) { right.SetDutyCycle(output); }}; + [&](double output) { left.SetThrottle(output); }, + [&](double output) { right.SetThrottle(output); }}; drive.SetDeadband(0.0); // Forward drive.CurvatureDrive(1.0, 0.0, true); - EXPECT_DOUBLE_EQ(1.0, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(1.0, left.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, right.GetThrottle()); // Forward left turn drive.CurvatureDrive(0.5, 0.5, true); - EXPECT_DOUBLE_EQ(0.0, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(0.0, left.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, right.GetThrottle()); // Forward right turn drive.CurvatureDrive(0.5, -0.5, true); - EXPECT_DOUBLE_EQ(1.0, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(0.0, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(1.0, left.GetThrottle()); + EXPECT_DOUBLE_EQ(0.0, right.GetThrottle()); // Backward drive.CurvatureDrive(-1.0, 0.0, true); - EXPECT_DOUBLE_EQ(-1.0, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(-1.0, left.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, right.GetThrottle()); // Backward left turn drive.CurvatureDrive(-0.5, 0.5, true); - EXPECT_DOUBLE_EQ(-1.0, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(0.0, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(-1.0, left.GetThrottle()); + EXPECT_DOUBLE_EQ(0.0, right.GetThrottle()); // Backward right turn drive.CurvatureDrive(-0.5, -0.5, true); - EXPECT_DOUBLE_EQ(0.0, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(0.0, left.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, right.GetThrottle()); } TEST(DifferentialDriveTest, TankDrive) { wpi::MockPWMMotorController left; wpi::MockPWMMotorController right; wpi::DifferentialDrive drive{ - [&](double output) { left.SetDutyCycle(output); }, - [&](double output) { right.SetDutyCycle(output); }}; + [&](double output) { left.SetThrottle(output); }, + [&](double output) { right.SetThrottle(output); }}; drive.SetDeadband(0.0); // Forward drive.TankDrive(1.0, 1.0, false); - EXPECT_DOUBLE_EQ(1.0, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(1.0, left.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, right.GetThrottle()); // Forward left turn drive.TankDrive(0.5, 1.0, false); - EXPECT_DOUBLE_EQ(0.5, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(0.5, left.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, right.GetThrottle()); // Forward right turn drive.TankDrive(1.0, 0.5, false); - EXPECT_DOUBLE_EQ(1.0, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(0.5, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(1.0, left.GetThrottle()); + EXPECT_DOUBLE_EQ(0.5, right.GetThrottle()); // Backward drive.TankDrive(-1.0, -1.0, false); - EXPECT_DOUBLE_EQ(-1.0, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(-1.0, left.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, right.GetThrottle()); // Backward left turn drive.TankDrive(-0.5, -1.0, false); - EXPECT_DOUBLE_EQ(-0.5, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(-0.5, left.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, right.GetThrottle()); // Backward right turn drive.TankDrive(-0.5, 1.0, false); - EXPECT_DOUBLE_EQ(-0.5, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(-0.5, left.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, right.GetThrottle()); } TEST(DifferentialDriveTest, TankDriveSquared) { wpi::MockPWMMotorController left; wpi::MockPWMMotorController right; wpi::DifferentialDrive drive{ - [&](double output) { left.SetDutyCycle(output); }, - [&](double output) { right.SetDutyCycle(output); }}; + [&](double output) { left.SetThrottle(output); }, + [&](double output) { right.SetThrottle(output); }}; drive.SetDeadband(0.0); // Forward drive.TankDrive(1.0, 1.0, true); - EXPECT_DOUBLE_EQ(1.0, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(1.0, left.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, right.GetThrottle()); // Forward left turn drive.TankDrive(0.5, 1.0, true); - EXPECT_DOUBLE_EQ(0.25, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(0.25, left.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, right.GetThrottle()); // Forward right turn drive.TankDrive(1.0, 0.5, true); - EXPECT_DOUBLE_EQ(1.0, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(0.25, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(1.0, left.GetThrottle()); + EXPECT_DOUBLE_EQ(0.25, right.GetThrottle()); // Backward drive.TankDrive(-1.0, -1.0, true); - EXPECT_DOUBLE_EQ(-1.0, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(-1.0, left.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, right.GetThrottle()); // Backward left turn drive.TankDrive(-0.5, -1.0, true); - EXPECT_DOUBLE_EQ(-0.25, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(-0.25, left.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, right.GetThrottle()); // Backward right turn drive.TankDrive(-1.0, -0.5, true); - EXPECT_DOUBLE_EQ(-1.0, left.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-0.25, right.GetDutyCycle()); + EXPECT_DOUBLE_EQ(-1.0, left.GetThrottle()); + EXPECT_DOUBLE_EQ(-0.25, right.GetThrottle()); } diff --git a/wpilibc/src/test/native/cpp/drive/MecanumDriveTest.cpp b/wpilibc/src/test/native/cpp/drive/MecanumDriveTest.cpp index 48fe6b2bad..91ad2170b7 100644 --- a/wpilibc/src/test/native/cpp/drive/MecanumDriveTest.cpp +++ b/wpilibc/src/test/native/cpp/drive/MecanumDriveTest.cpp @@ -87,46 +87,46 @@ TEST(MecanumDriveTest, Cartesian) { wpi::MockPWMMotorController rl; wpi::MockPWMMotorController fr; wpi::MockPWMMotorController rr; - wpi::MecanumDrive drive{[&](double output) { fl.SetDutyCycle(output); }, - [&](double output) { rl.SetDutyCycle(output); }, - [&](double output) { fr.SetDutyCycle(output); }, - [&](double output) { rr.SetDutyCycle(output); }}; + wpi::MecanumDrive drive{[&](double output) { fl.SetThrottle(output); }, + [&](double output) { rl.SetThrottle(output); }, + [&](double output) { fr.SetThrottle(output); }, + [&](double output) { rr.SetThrottle(output); }}; drive.SetDeadband(0.0); // Forward drive.DriveCartesian(1.0, 0.0, 0.0); - EXPECT_DOUBLE_EQ(1.0, fl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, fr.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, rl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, rr.GetDutyCycle()); + EXPECT_DOUBLE_EQ(1.0, fl.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, fr.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, rl.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, rr.GetThrottle()); // Left drive.DriveCartesian(0.0, -1.0, 0.0); - EXPECT_DOUBLE_EQ(-1.0, fl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, fr.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, rl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, rr.GetDutyCycle()); + EXPECT_DOUBLE_EQ(-1.0, fl.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, fr.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, rl.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, rr.GetThrottle()); // Right drive.DriveCartesian(0.0, 1.0, 0.0); - EXPECT_DOUBLE_EQ(1.0, fl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, fr.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, rl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, rr.GetDutyCycle()); + EXPECT_DOUBLE_EQ(1.0, fl.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, fr.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, rl.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, rr.GetThrottle()); // Rotate CCW drive.DriveCartesian(0.0, 0.0, -1.0); - EXPECT_DOUBLE_EQ(-1.0, fl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, fr.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, rl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, rr.GetDutyCycle()); + EXPECT_DOUBLE_EQ(-1.0, fl.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, fr.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, rl.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, rr.GetThrottle()); // Rotate CW drive.DriveCartesian(0.0, 0.0, 1.0); - EXPECT_DOUBLE_EQ(1.0, fl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, fr.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, rl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, rr.GetDutyCycle()); + EXPECT_DOUBLE_EQ(1.0, fl.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, fr.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, rl.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, rr.GetThrottle()); } TEST(MecanumDriveTest, CartesianGyro90CW) { @@ -134,46 +134,46 @@ TEST(MecanumDriveTest, CartesianGyro90CW) { wpi::MockPWMMotorController rl; wpi::MockPWMMotorController fr; wpi::MockPWMMotorController rr; - wpi::MecanumDrive drive{[&](double output) { fl.SetDutyCycle(output); }, - [&](double output) { rl.SetDutyCycle(output); }, - [&](double output) { fr.SetDutyCycle(output); }, - [&](double output) { rr.SetDutyCycle(output); }}; + wpi::MecanumDrive drive{[&](double output) { fl.SetThrottle(output); }, + [&](double output) { rl.SetThrottle(output); }, + [&](double output) { fr.SetThrottle(output); }, + [&](double output) { rr.SetThrottle(output); }}; drive.SetDeadband(0.0); // Forward in global frame; left in robot frame drive.DriveCartesian(1.0, 0.0, 0.0, 90_deg); - EXPECT_DOUBLE_EQ(-1.0, fl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, fr.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, rl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, rr.GetDutyCycle()); + EXPECT_DOUBLE_EQ(-1.0, fl.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, fr.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, rl.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, rr.GetThrottle()); // Left in global frame; backward in robot frame drive.DriveCartesian(0.0, -1.0, 0.0, 90_deg); - EXPECT_DOUBLE_EQ(-1.0, fl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, fr.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, rl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, rr.GetDutyCycle()); + EXPECT_DOUBLE_EQ(-1.0, fl.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, fr.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, rl.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, rr.GetThrottle()); // Right in global frame; forward in robot frame drive.DriveCartesian(0.0, 1.0, 0.0, 90_deg); - EXPECT_DOUBLE_EQ(1.0, fl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, fr.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, rl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, rr.GetDutyCycle()); + EXPECT_DOUBLE_EQ(1.0, fl.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, fr.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, rl.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, rr.GetThrottle()); // Rotate CCW drive.DriveCartesian(0.0, 0.0, -1.0, 90_deg); - EXPECT_DOUBLE_EQ(-1.0, fl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, fr.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, rl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, rr.GetDutyCycle()); + EXPECT_DOUBLE_EQ(-1.0, fl.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, fr.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, rl.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, rr.GetThrottle()); // Rotate CW drive.DriveCartesian(0.0, 0.0, 1.0, 90_deg); - EXPECT_DOUBLE_EQ(1.0, fl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, fr.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, rl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, rr.GetDutyCycle()); + EXPECT_DOUBLE_EQ(1.0, fl.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, fr.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, rl.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, rr.GetThrottle()); } TEST(MecanumDriveTest, Polar) { @@ -181,44 +181,44 @@ TEST(MecanumDriveTest, Polar) { wpi::MockPWMMotorController rl; wpi::MockPWMMotorController fr; wpi::MockPWMMotorController rr; - wpi::MecanumDrive drive{[&](double output) { fl.SetDutyCycle(output); }, - [&](double output) { rl.SetDutyCycle(output); }, - [&](double output) { fr.SetDutyCycle(output); }, - [&](double output) { rr.SetDutyCycle(output); }}; + wpi::MecanumDrive drive{[&](double output) { fl.SetThrottle(output); }, + [&](double output) { rl.SetThrottle(output); }, + [&](double output) { fr.SetThrottle(output); }, + [&](double output) { rr.SetThrottle(output); }}; drive.SetDeadband(0.0); // Forward drive.DrivePolar(1.0, 0_deg, 0.0); - EXPECT_DOUBLE_EQ(1.0, fl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, fr.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, rl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, rr.GetDutyCycle()); + EXPECT_DOUBLE_EQ(1.0, fl.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, fr.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, rl.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, rr.GetThrottle()); // Left drive.DrivePolar(1.0, -90_deg, 0.0); - EXPECT_DOUBLE_EQ(-1.0, fl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, fr.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, rl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, rr.GetDutyCycle()); + EXPECT_DOUBLE_EQ(-1.0, fl.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, fr.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, rl.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, rr.GetThrottle()); // Right drive.DrivePolar(1.0, 90_deg, 0.0); - EXPECT_DOUBLE_EQ(1.0, fl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, fr.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, rl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, rr.GetDutyCycle()); + EXPECT_DOUBLE_EQ(1.0, fl.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, fr.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, rl.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, rr.GetThrottle()); // Rotate CCW drive.DrivePolar(0.0, 0_deg, -1.0); - EXPECT_DOUBLE_EQ(-1.0, fl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, fr.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, rl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, rr.GetDutyCycle()); + EXPECT_DOUBLE_EQ(-1.0, fl.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, fr.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, rl.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, rr.GetThrottle()); // Rotate CW drive.DrivePolar(0.0, 0_deg, 1.0); - EXPECT_DOUBLE_EQ(1.0, fl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, fr.GetDutyCycle()); - EXPECT_DOUBLE_EQ(1.0, rl.GetDutyCycle()); - EXPECT_DOUBLE_EQ(-1.0, rr.GetDutyCycle()); + EXPECT_DOUBLE_EQ(1.0, fl.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, fr.GetThrottle()); + EXPECT_DOUBLE_EQ(1.0, rl.GetThrottle()); + EXPECT_DOUBLE_EQ(-1.0, rr.GetThrottle()); } diff --git a/wpilibc/src/test/native/cpp/motorcontrol/MockMotorController.cpp b/wpilibc/src/test/native/cpp/motorcontrol/MockMotorController.cpp index 74d181b00f..a4f8732ca9 100644 --- a/wpilibc/src/test/native/cpp/motorcontrol/MockMotorController.cpp +++ b/wpilibc/src/test/native/cpp/motorcontrol/MockMotorController.cpp @@ -6,12 +6,12 @@ using namespace wpi; -void MockMotorController::SetDutyCycle(double dutyCycle) { - m_dutyCycle = m_isInverted ? -dutyCycle : dutyCycle; +void MockMotorController::SetThrottle(double throttle) { + m_throttle = m_isInverted ? -throttle : throttle; } -double MockMotorController::GetDutyCycle() const { - return m_dutyCycle; +double MockMotorController::GetThrottle() const { + return m_throttle; } void MockMotorController::SetInverted(bool isInverted) { @@ -23,5 +23,5 @@ bool MockMotorController::GetInverted() const { } void MockMotorController::Disable() { - m_dutyCycle = 0; + m_throttle = 0; } diff --git a/wpilibc/src/test/native/cpp/motorcontrol/MockPWMMotorController.cpp b/wpilibc/src/test/native/cpp/motorcontrol/MockPWMMotorController.cpp index e2a4e6dfbc..af6d8e1284 100644 --- a/wpilibc/src/test/native/cpp/motorcontrol/MockPWMMotorController.cpp +++ b/wpilibc/src/test/native/cpp/motorcontrol/MockPWMMotorController.cpp @@ -6,12 +6,12 @@ using namespace wpi; -void MockPWMMotorController::SetDutyCycle(double dutyCycle) { - m_dutyCycle = m_isInverted ? -dutyCycle : dutyCycle; +void MockPWMMotorController::SetThrottle(double throttle) { + m_throttle = m_isInverted ? -throttle : throttle; } -double MockPWMMotorController::GetDutyCycle() const { - return m_dutyCycle; +double MockPWMMotorController::GetThrottle() const { + return m_throttle; } void MockPWMMotorController::SetInverted(bool isInverted) { @@ -23,7 +23,7 @@ bool MockPWMMotorController::GetInverted() const { } void MockPWMMotorController::Disable() { - m_dutyCycle = 0; + m_throttle = 0; } void MockPWMMotorController::StopMotor() { diff --git a/wpilibc/src/test/native/cpp/simulation/DCMotorSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/DCMotorSimTest.cpp index 9db3636b3b..e411933b5a 100644 --- a/wpilibc/src/test/native/cpp/simulation/DCMotorSimTest.cpp +++ b/wpilibc/src/test/native/cpp/simulation/DCMotorSimTest.cpp @@ -37,7 +37,7 @@ TEST(DCMotorSimTest, VoltageSteadyState) { // Then, SimulationPeriodic runs wpi::sim::RoboRioSim::SetVInVoltage( wpi::sim::BatterySim::Calculate({sim.GetCurrentDraw()})); - sim.SetInputVoltage(motor.GetDutyCycle() * + sim.SetInputVoltage(motor.GetThrottle() * wpi::RobotController::GetBatteryVoltage()); sim.Update(20_ms); encoderSim.SetRate(sim.GetAngularVelocity().value()); @@ -53,7 +53,7 @@ TEST(DCMotorSimTest, VoltageSteadyState) { // Then, SimulationPeriodic runs wpi::sim::RoboRioSim::SetVInVoltage( wpi::sim::BatterySim::Calculate({sim.GetCurrentDraw()})); - sim.SetInputVoltage(motor.GetDutyCycle() * + sim.SetInputVoltage(motor.GetThrottle() * wpi::RobotController::GetBatteryVoltage()); sim.Update(20_ms); encoderSim.SetRate(sim.GetAngularVelocity().value()); @@ -80,12 +80,12 @@ TEST(DCMotorSimTest, PositionFeedbackControl) { for (int i = 0; i < 140; i++) { // RobotPeriodic runs first - motor.SetDutyCycle(controller.Calculate(encoder.GetDistance(), 750)); + motor.SetThrottle(controller.Calculate(encoder.GetDistance(), 750)); // Then, SimulationPeriodic runs wpi::sim::RoboRioSim::SetVInVoltage( wpi::sim::BatterySim::Calculate({sim.GetCurrentDraw()})); - sim.SetInputVoltage(motor.GetDutyCycle() * + sim.SetInputVoltage(motor.GetThrottle() * wpi::RobotController::GetBatteryVoltage()); sim.Update(20_ms); encoderSim.SetDistance(sim.GetAngularPosition().value()); diff --git a/wpilibc/src/test/native/cpp/simulation/ElevatorSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/ElevatorSimTest.cpp index 3c34acf4c2..f002a288b6 100644 --- a/wpilibc/src/test/native/cpp/simulation/ElevatorSimTest.cpp +++ b/wpilibc/src/test/native/cpp/simulation/ElevatorSimTest.cpp @@ -30,9 +30,9 @@ TEST(ElevatorSimTest, StateSpaceSim) { for (size_t i = 0; i < 100; ++i) { controller.SetSetpoint(2.0); auto nextVoltage = controller.Calculate(encoderSim.GetDistance()); - motor.SetDutyCycle(nextVoltage / wpi::RobotController::GetInputVoltage()); + motor.SetThrottle(nextVoltage / wpi::RobotController::GetInputVoltage()); - wpi::math::Vectord<1> u{motor.GetDutyCycle() * + wpi::math::Vectord<1> u{motor.GetThrottle() * wpi::RobotController::GetInputVoltage()}; sim.SetInput(u); sim.Update(20_ms); diff --git a/wpilibc/src/test/native/cpp/simulation/PWMMotorControlllerSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/PWMMotorControlllerSimTest.cpp index 0d35f9d779..46336a7333 100644 --- a/wpilibc/src/test/native/cpp/simulation/PWMMotorControlllerSimTest.cpp +++ b/wpilibc/src/test/native/cpp/simulation/PWMMotorControlllerSimTest.cpp @@ -15,13 +15,13 @@ TEST(PWMMotorControllerSimTest, TestMotor) { wpi::Spark spark{0}; wpi::sim::PWMMotorControllerSim sim{spark}; - spark.SetDutyCycle(0); - EXPECT_EQ(0, sim.GetDutyCycle()); + spark.SetThrottle(0); + EXPECT_EQ(0, sim.GetThrottle()); - spark.SetDutyCycle(0.354); - EXPECT_EQ(0.354, sim.GetDutyCycle()); + spark.SetThrottle(0.354); + EXPECT_EQ(0.354, sim.GetThrottle()); - spark.SetDutyCycle(-0.785); - EXPECT_EQ(-0.785, sim.GetDutyCycle()); + spark.SetThrottle(-0.785); + EXPECT_EQ(-0.785, sim.GetThrottle()); } } // namespace wpi::sim diff --git a/wpilibc/src/test/native/cpp/simulation/StateSpaceSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/StateSpaceSimTest.cpp index 07c1f25333..b67a00b832 100644 --- a/wpilibc/src/test/native/cpp/simulation/StateSpaceSimTest.cpp +++ b/wpilibc/src/test/native/cpp/simulation/StateSpaceSimTest.cpp @@ -42,7 +42,7 @@ TEST(StateSpaceSimTest, FlywheelSim) { wpi::sim::RoboRioSim::SetVInVoltage( wpi::sim::BatterySim::Calculate({sim.GetCurrentDraw()})); sim.SetInput(wpi::math::Vectord<1>{ - motor.GetDutyCycle() * wpi::RobotController::GetInputVoltage()}); + motor.GetThrottle() * wpi::RobotController::GetInputVoltage()}); sim.Update(20_ms); encoderSim.SetRate(sim.GetAngularVelocity().value()); } diff --git a/wpilibc/src/test/native/include/motorcontrol/MockMotorController.hpp b/wpilibc/src/test/native/include/motorcontrol/MockMotorController.hpp index 85a0e2d6bc..df0f58ab71 100644 --- a/wpilibc/src/test/native/include/motorcontrol/MockMotorController.hpp +++ b/wpilibc/src/test/native/include/motorcontrol/MockMotorController.hpp @@ -5,25 +5,20 @@ #pragma once #include "wpi/hardware/motor/MotorController.hpp" -#include "wpi/util/deprecated.hpp" namespace wpi { -WPI_IGNORE_DEPRECATED - class MockMotorController : public MotorController { public: - void SetDutyCycle(double dutyCycle) override; - double GetDutyCycle() const override; + void SetThrottle(double throttle) override; + double GetThrottle() const override; void SetInverted(bool isInverted) override; bool GetInverted() const override; void Disable() override; private: - double m_dutyCycle = 0.0; + double m_throttle = 0.0; bool m_isInverted = false; }; -WPI_UNIGNORE_DEPRECATED - } // namespace wpi diff --git a/wpilibc/src/test/native/include/motorcontrol/MockPWMMotorController.hpp b/wpilibc/src/test/native/include/motorcontrol/MockPWMMotorController.hpp index 216d13db8a..188640e7f8 100644 --- a/wpilibc/src/test/native/include/motorcontrol/MockPWMMotorController.hpp +++ b/wpilibc/src/test/native/include/motorcontrol/MockPWMMotorController.hpp @@ -8,15 +8,15 @@ namespace wpi { class MockPWMMotorController { public: - void SetDutyCycle(double dutyCycle); - double GetDutyCycle() const; + void SetThrottle(double throttle); + double GetThrottle() const; void SetInverted(bool isInverted); bool GetInverted() const; void Disable(); void StopMotor(); private: - double m_dutyCycle = 0.0; + double m_throttle = 0.0; bool m_isInverted = false; }; diff --git a/wpilibc/src/test/python/test_wpilib.py b/wpilibc/src/test/python/test_wpilib.py index 901c43272f..8841aa149d 100644 --- a/wpilibc/src/test/python/test_wpilib.py +++ b/wpilibc/src/test/python/test_wpilib.py @@ -27,13 +27,13 @@ def test_motorcontrollergroup(): t2 = wpilib.Talon(8) g = wpilib.MotorControllerGroup(t1, t2) - g.setDutyCycle(1) - assert t1.getDutyCycle() == pytest.approx(1) - assert t2.getDutyCycle() == pytest.approx(1) + g.setThrottle(1) + assert t1.getThrottle() == pytest.approx(1) + assert t2.getThrottle() == pytest.approx(1) - g.setDutyCycle(-1) - assert t1.getDutyCycle() == pytest.approx(-1) - assert t2.getDutyCycle() == pytest.approx(-1) + g.setThrottle(-1) + assert t1.getThrottle() == pytest.approx(-1) + assert t2.getThrottle() == pytest.approx(-1) def test_motorcontrollergroup_error(): diff --git a/wpilibcExamples/src/main/cpp/examples/ArcadeDriveGamepad/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArcadeDriveGamepad/cpp/Robot.cpp index 3de0d20205..d0cd3b477e 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArcadeDriveGamepad/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ArcadeDriveGamepad/cpp/Robot.cpp @@ -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: diff --git a/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/subsystems/Arm.cpp b/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/subsystems/Arm.cpp index 3c71acd4fa..0d2e4f9800 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/subsystems/Arm.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/subsystems/Arm.cpp @@ -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); } diff --git a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Drivetrain.cpp index cb71c3b13f..ddf698a202 100644 --- a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Drivetrain.cpp +++ b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Drivetrain.cpp @@ -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); diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/cpp/subsystems/Elevator.cpp b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/cpp/subsystems/Elevator.cpp index 889d7254d4..82e249ce3c 100644 --- a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/cpp/subsystems/Elevator.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/cpp/subsystems/Elevator.cpp @@ -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); } diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/subsystems/Elevator.cpp b/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/subsystems/Elevator.cpp index 16728793b3..2f9f595e66 100644 --- a/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/subsystems/Elevator.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/subsystems/Elevator.cpp @@ -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); } diff --git a/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp index 76344c27d3..1bdfbece68 100644 --- a/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp @@ -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; diff --git a/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp index 24862fd34d..75cfbc6612 100644 --- a/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp @@ -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}; diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/DriveSubsystem.hpp b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/DriveSubsystem.hpp index 09ebf8401e..0367dd2409 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/DriveSubsystem.hpp +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/DriveSubsystem.hpp @@ -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; diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/DriveSubsystem.hpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/DriveSubsystem.hpp index 09ebf8401e..0367dd2409 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/DriveSubsystem.hpp +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/DriveSubsystem.hpp @@ -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; diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp index f2c32c4e6f..5bc01edabf 100644 --- a/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp @@ -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}; diff --git a/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp index c9b230a60b..2d965a1dd5 100644 --- a/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp @@ -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: diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Intake.cpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Intake.cpp index 588cfc1321..bf6e51f904 100644 --- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Intake.cpp +++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Intake.cpp @@ -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"); } diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Shooter.cpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Shooter.cpp index 72a51de262..69f4d7e7f9 100644 --- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Shooter.cpp +++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Shooter.cpp @@ -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"); } diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Storage.cpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Storage.cpp index 6c4dddf35f..6ff8553290 100644 --- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Storage.cpp +++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Storage.cpp @@ -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"); } diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Drive.hpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Drive.hpp index 97ba7ba6f4..8ac5b46f1b 100644 --- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Drive.hpp +++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Drive.hpp @@ -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], diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/Drivetrain.hpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/Drivetrain.hpp index 6352890298..104584f57f 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/Drivetrain.hpp +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/Drivetrain.hpp @@ -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; }; diff --git a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Drivetrain.cpp index a395ce7cc9..e32dcf358f 100644 --- a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Drivetrain.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Drivetrain.cpp @@ -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); diff --git a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/subsystems/Shooter.cpp b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/subsystems/Shooter.cpp index 43a93237f8..512ef2be72 100644 --- a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/subsystems/Shooter.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/subsystems/Shooter.cpp @@ -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"); diff --git a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/subsystems/Drive.hpp b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/subsystems/Drive.hpp index 578e7db9ce..bf47d51768 100644 --- a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/subsystems/Drive.hpp +++ b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/subsystems/Drive.hpp @@ -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( diff --git a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/subsystems/Shooter.hpp b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/subsystems/Shooter.hpp index 3bcbc59656..ce9c393347 100644 --- a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/subsystems/Shooter.hpp +++ b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/subsystems/Shooter.hpp @@ -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( diff --git a/wpilibcExamples/src/main/cpp/examples/TankDriveGamepad/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/TankDriveGamepad/cpp/Robot.cpp index 0d9301aca8..a4a8e57d89 100644 --- a/wpilibcExamples/src/main/cpp/examples/TankDriveGamepad/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/TankDriveGamepad/cpp/Robot.cpp @@ -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: diff --git a/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/subsystems/Intake.cpp b/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/subsystems/Intake.cpp index 9f1a690306..4b929ee93c 100644 --- a/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/subsystems/Intake.cpp +++ b/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/subsystems/Intake.cpp @@ -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); } } diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/subsystems/Drivetrain.hpp b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/subsystems/Drivetrain.hpp index 207703b854..9481144319 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/subsystems/Drivetrain.hpp +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/subsystems/Drivetrain.hpp @@ -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; }; diff --git a/wpilibcExamples/src/main/cpp/examples/Xrptimed/include/Robot.hpp b/wpilibcExamples/src/main/cpp/examples/Xrptimed/include/Robot.hpp index c172dad6c5..9c536e4ff9 100644 --- a/wpilibcExamples/src/main/cpp/examples/Xrptimed/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/examples/Xrptimed/include/Robot.hpp @@ -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); }}; }; diff --git a/wpilibcExamples/src/main/cpp/snippets/EncoderDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/EncoderDrive/cpp/Robot.cpp index e9f92d1377..8fae070107 100644 --- a/wpilibcExamples/src/main/cpp/snippets/EncoderDrive/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/EncoderDrive/cpp/Robot.cpp @@ -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 diff --git a/wpilibcExamples/src/main/cpp/snippets/EncoderHoming/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/EncoderHoming/cpp/Robot.cpp index fbef12c1f5..8525d7da90 100644 --- a/wpilibcExamples/src/main/cpp/snippets/EncoderHoming/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/EncoderHoming/cpp/Robot.cpp @@ -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(); } } diff --git a/wpilibcExamples/src/main/cpp/snippets/EventLoop/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/EventLoop/cpp/Robot.cpp index 363d48fa43..667eb737e3 100644 --- a/wpilibcExamples/src/main/cpp/snippets/EventLoop/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/EventLoop/cpp/Robot.cpp @@ -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(); } diff --git a/wpilibcExamples/src/main/cpp/snippets/FlywheelBangBangController/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/FlywheelBangBangController/cpp/Robot.cpp index acb3935e63..2dbe0edba9 100644 --- a/wpilibcExamples/src/main/cpp/snippets/FlywheelBangBangController/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/FlywheelBangBangController/cpp/Robot.cpp @@ -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()); diff --git a/wpilibcExamples/src/main/cpp/snippets/LimitSwitch/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/LimitSwitch/cpp/Robot.cpp index aead3fb950..33259d0bba 100644 --- a/wpilibcExamples/src/main/cpp/snippets/LimitSwitch/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/LimitSwitch/cpp/Robot.cpp @@ -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); } } } diff --git a/wpilibcExamples/src/main/cpp/snippets/MotorControl/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/MotorControl/cpp/Robot.cpp index 2ba0bb21f0..f63e8bdc43 100644 --- a/wpilibcExamples/src/main/cpp/snippets/MotorControl/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/MotorControl/cpp/Robot.cpp @@ -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 diff --git a/wpilibcExamples/src/test/cpp/examples/ArmSimulation/cpp/ArmSimulationTest.cpp b/wpilibcExamples/src/test/cpp/examples/ArmSimulation/cpp/ArmSimulationTest.cpp index 69c2c1c498..36a1016e79 100644 --- a/wpilibcExamples/src/test/cpp/examples/ArmSimulation/cpp/ArmSimulationTest.cpp +++ b/wpilibcExamples/src/test/cpp/examples/ArmSimulation/cpp/ArmSimulationTest.cpp @@ -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); } } diff --git a/wpilibcExamples/src/test/cpp/examples/ElevatorSimulation/cpp/ElevatorSimulationTest.cpp b/wpilibcExamples/src/test/cpp/examples/ElevatorSimulation/cpp/ElevatorSimulationTest.cpp index fdc95a76d4..2998b62c5b 100644 --- a/wpilibcExamples/src/test/cpp/examples/ElevatorSimulation/cpp/ElevatorSimulationTest.cpp +++ b/wpilibcExamples/src/test/cpp/examples/ElevatorSimulation/cpp/ElevatorSimulationTest.cpp @@ -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); } } diff --git a/wpilibcExamples/src/test/cpp/examples/UnitTest/cpp/subsystems/IntakeTest.cpp b/wpilibcExamples/src/test/cpp/examples/UnitTest/cpp/subsystems/IntakeTest.cpp index b5caefe11b..6306cf493a 100644 --- a/wpilibcExamples/src/test/cpp/examples/UnitTest/cpp/subsystems/IntakeTest.cpp +++ b/wpilibcExamples/src/test/cpp/examples/UnitTest/cpp/subsystems/IntakeTest.cpp @@ -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) { diff --git a/wpilibj/src/generate/main/java/pwm_motor_controller.java.jinja b/wpilibj/src/generate/main/java/pwm_motor_controller.java.jinja index 3b3bce64f7..75b8a000c0 100644 --- a/wpilibj/src/generate/main/java/pwm_motor_controller.java.jinja +++ b/wpilibj/src/generate/main/java/pwm_motor_controller.java.jinja @@ -37,7 +37,7 @@ public class {{ name }} extends PWMMotorController { setBoundsMicroseconds({{ (pulse_width_ms.max * 1000) | int }}, {{ (pulse_width_ms.deadbandMax * 1000) | int }}, {{ (pulse_width_ms.center * 1000) | int }}, {{ (pulse_width_ms.deadbandMin * 1000) | int }}, {{ (pulse_width_ms.min * 1000) | int }}); m_pwm.setOutputPeriod({{ OutputPeriod | default("5", true)}}); - setDutyCycle(0.0); + setThrottle(0.0); HAL.reportUsage("IO", getChannel(), "{{ ResourceName }}"); } diff --git a/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/Koors40.java b/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/Koors40.java index fe4cdbb94e..74dcfb78f9 100644 --- a/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/Koors40.java +++ b/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/Koors40.java @@ -37,7 +37,7 @@ public class Koors40 extends PWMMotorController { setBoundsMicroseconds(2004, 1520, 1500, 1480, 997); m_pwm.setOutputPeriod(20); - setDutyCycle(0.0); + setThrottle(0.0); HAL.reportUsage("IO", getChannel(), "Koors40"); } diff --git a/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/PWMSparkFlex.java b/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/PWMSparkFlex.java index 4d10bdb576..5125e0c58f 100644 --- a/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/PWMSparkFlex.java +++ b/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/PWMSparkFlex.java @@ -37,7 +37,7 @@ public class PWMSparkFlex extends PWMMotorController { setBoundsMicroseconds(2003, 1550, 1500, 1460, 999); m_pwm.setOutputPeriod(5); - setDutyCycle(0.0); + setThrottle(0.0); HAL.reportUsage("IO", getChannel(), "RevSparkFlexPWM"); } diff --git a/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/PWMSparkMax.java b/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/PWMSparkMax.java index 715fcd5fbe..cf6f60b709 100644 --- a/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/PWMSparkMax.java +++ b/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/PWMSparkMax.java @@ -37,7 +37,7 @@ public class PWMSparkMax extends PWMMotorController { setBoundsMicroseconds(2003, 1550, 1500, 1460, 999); m_pwm.setOutputPeriod(5); - setDutyCycle(0.0); + setThrottle(0.0); HAL.reportUsage("IO", getChannel(), "RevSparkMaxPWM"); } diff --git a/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/PWMTalonFX.java b/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/PWMTalonFX.java index 6f4d320618..d513a7c2d6 100644 --- a/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/PWMTalonFX.java +++ b/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/PWMTalonFX.java @@ -37,7 +37,7 @@ public class PWMTalonFX extends PWMMotorController { setBoundsMicroseconds(2004, 1520, 1500, 1480, 997); m_pwm.setOutputPeriod(5); - setDutyCycle(0.0); + setThrottle(0.0); HAL.reportUsage("IO", getChannel(), "TalonFX"); } diff --git a/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/PWMTalonSRX.java b/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/PWMTalonSRX.java index 9a8b4d5602..6129f87183 100644 --- a/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/PWMTalonSRX.java +++ b/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/PWMTalonSRX.java @@ -37,7 +37,7 @@ public class PWMTalonSRX extends PWMMotorController { setBoundsMicroseconds(2004, 1520, 1500, 1480, 997); m_pwm.setOutputPeriod(5); - setDutyCycle(0.0); + setThrottle(0.0); HAL.reportUsage("IO", getChannel(), "PWMTalonSRX"); } diff --git a/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/PWMVenom.java b/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/PWMVenom.java index 225b245173..0e1f70a814 100644 --- a/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/PWMVenom.java +++ b/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/PWMVenom.java @@ -37,7 +37,7 @@ public class PWMVenom extends PWMMotorController { setBoundsMicroseconds(2004, 1520, 1500, 1480, 997); m_pwm.setOutputPeriod(5); - setDutyCycle(0.0); + setThrottle(0.0); HAL.reportUsage("IO", getChannel(), "FusionVenom"); } diff --git a/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/PWMVictorSPX.java b/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/PWMVictorSPX.java index 641552d0a5..daec60ce78 100644 --- a/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/PWMVictorSPX.java +++ b/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/PWMVictorSPX.java @@ -37,7 +37,7 @@ public class PWMVictorSPX extends PWMMotorController { setBoundsMicroseconds(2004, 1520, 1500, 1480, 997); m_pwm.setOutputPeriod(5); - setDutyCycle(0.0); + setThrottle(0.0); HAL.reportUsage("IO", getChannel(), "PWMVictorSPX"); } diff --git a/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/Spark.java b/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/Spark.java index 51e27bb638..0716d5e5a1 100644 --- a/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/Spark.java +++ b/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/Spark.java @@ -37,7 +37,7 @@ public class Spark extends PWMMotorController { setBoundsMicroseconds(2003, 1550, 1500, 1460, 999); m_pwm.setOutputPeriod(5); - setDutyCycle(0.0); + setThrottle(0.0); HAL.reportUsage("IO", getChannel(), "RevSPARK"); } diff --git a/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/SparkMini.java b/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/SparkMini.java index 2e41ba2491..5abf4f7de2 100644 --- a/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/SparkMini.java +++ b/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/SparkMini.java @@ -37,7 +37,7 @@ public class SparkMini extends PWMMotorController { setBoundsMicroseconds(2500, 1510, 1500, 1490, 500); m_pwm.setOutputPeriod(5); - setDutyCycle(0.0); + setThrottle(0.0); HAL.reportUsage("IO", getChannel(), "RevSPARK"); } diff --git a/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/Talon.java b/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/Talon.java index 3a2237cdea..c00e4f54f9 100644 --- a/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/Talon.java +++ b/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/Talon.java @@ -37,7 +37,7 @@ public class Talon extends PWMMotorController { setBoundsMicroseconds(2037, 1539, 1513, 1487, 989); m_pwm.setOutputPeriod(5); - setDutyCycle(0.0); + setThrottle(0.0); HAL.reportUsage("IO", getChannel(), "Talon"); } diff --git a/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/VictorSP.java b/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/VictorSP.java index e813ff9c26..338d246729 100644 --- a/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/VictorSP.java +++ b/wpilibj/src/generated/main/java/org/wpilib/hardware/motor/VictorSP.java @@ -37,7 +37,7 @@ public class VictorSP extends PWMMotorController { setBoundsMicroseconds(2004, 1520, 1500, 1480, 997); m_pwm.setOutputPeriod(5); - setDutyCycle(0.0); + setThrottle(0.0); HAL.reportUsage("IO", getChannel(), "VictorSP"); } diff --git a/wpilibj/src/main/java/org/wpilib/drive/DifferentialDrive.java b/wpilibj/src/main/java/org/wpilib/drive/DifferentialDrive.java index c11337366a..03fae9a8e3 100644 --- a/wpilibj/src/main/java/org/wpilib/drive/DifferentialDrive.java +++ b/wpilibj/src/main/java/org/wpilib/drive/DifferentialDrive.java @@ -104,8 +104,8 @@ public class DifferentialDrive extends RobotDriveBase implements Sendable, AutoC @SuppressWarnings({"removal", "this-escape"}) public DifferentialDrive(MotorController leftMotor, MotorController rightMotor) { this( - (double output) -> leftMotor.setDutyCycle(output), - (double output) -> rightMotor.setDutyCycle(output)); + (double output) -> leftMotor.setThrottle(output), + (double output) -> rightMotor.setThrottle(output)); SendableRegistry.addChild(this, leftMotor); SendableRegistry.addChild(this, rightMotor); } diff --git a/wpilibj/src/main/java/org/wpilib/drive/MecanumDrive.java b/wpilibj/src/main/java/org/wpilib/drive/MecanumDrive.java index 0da6f5d945..8badcfb676 100644 --- a/wpilibj/src/main/java/org/wpilib/drive/MecanumDrive.java +++ b/wpilibj/src/main/java/org/wpilib/drive/MecanumDrive.java @@ -120,10 +120,10 @@ public class MecanumDrive extends RobotDriveBase implements Sendable, AutoClosea MotorController frontRightMotor, MotorController rearRightMotor) { this( - (double output) -> frontLeftMotor.setDutyCycle(output), - (double output) -> rearLeftMotor.setDutyCycle(output), - (double output) -> frontRightMotor.setDutyCycle(output), - (double output) -> rearRightMotor.setDutyCycle(output)); + (double output) -> frontLeftMotor.setThrottle(output), + (double output) -> rearLeftMotor.setThrottle(output), + (double output) -> frontRightMotor.setThrottle(output), + (double output) -> rearRightMotor.setThrottle(output)); SendableRegistry.addChild(this, frontLeftMotor); SendableRegistry.addChild(this, rearLeftMotor); SendableRegistry.addChild(this, frontRightMotor); diff --git a/wpilibj/src/main/java/org/wpilib/hardware/expansionhub/ExpansionHubMotor.java b/wpilibj/src/main/java/org/wpilib/hardware/expansionhub/ExpansionHubMotor.java index 50f6662e66..2bf42e9bef 100644 --- a/wpilibj/src/main/java/org/wpilib/hardware/expansionhub/ExpansionHubMotor.java +++ b/wpilibj/src/main/java/org/wpilib/hardware/expansionhub/ExpansionHubMotor.java @@ -151,14 +151,14 @@ public class ExpansionHubMotor implements AutoCloseable { } /** - * Sets the duty cycle. + * Sets the throttle. * - * @param dutyCycle The duty cycle between -1 and 1 (sign indicates direction). + * @param throttle The throttle where -1 represents full reverse and 1 represents full forward. */ - public void setDutyCycle(double dutyCycle) { + public void setThrottle(double throttle) { setEnabled(true); m_modePublisher.set(kPercentageMode); - m_setpointPublisher.set(dutyCycle); + m_setpointPublisher.set(throttle); } /** diff --git a/wpilibj/src/main/java/org/wpilib/hardware/motor/MotorController.java b/wpilibj/src/main/java/org/wpilib/hardware/motor/MotorController.java index dceb04bd34..a8f52f107d 100644 --- a/wpilibj/src/main/java/org/wpilib/hardware/motor/MotorController.java +++ b/wpilibj/src/main/java/org/wpilib/hardware/motor/MotorController.java @@ -12,11 +12,11 @@ import org.wpilib.units.measure.Voltage; /** Interface for motor controlling devices. */ public interface MotorController { /** - * Sets the duty cycle of the motor controller. + * Sets the throttle of the motor controller. * - * @param dutyCycle The duty cycle between -1 and 1 (sign indicates direction). + * @param throttle The throttle where -1 indicates full reverse and 1 indicates full forward. */ - void setDutyCycle(double dutyCycle); + void setThrottle(double throttle); /** * Sets the voltage output of the motor controller. @@ -31,7 +31,7 @@ public interface MotorController { * @param voltage The voltage. */ default void setVoltage(double voltage) { - setDutyCycle(voltage / RobotController.getBatteryVoltage()); + setThrottle(voltage / RobotController.getBatteryVoltage()); } /** @@ -51,11 +51,11 @@ public interface MotorController { } /** - * Gets the duty cycle of the motor controller. + * Gets the throttle of the motor controller. * - * @return The duty cycle between -1 and 1 (sign indicates direction). + * @return The throttle where -1 represents full reverse and 1 represents full forward. */ - double getDutyCycle(); + double getThrottle(); /** * Sets the inversion state of the motor controller. diff --git a/wpilibj/src/main/java/org/wpilib/hardware/motor/PWMMotorController.java b/wpilibj/src/main/java/org/wpilib/hardware/motor/PWMMotorController.java index 76389d71dc..190282e5fa 100644 --- a/wpilibj/src/main/java/org/wpilib/hardware/motor/PWMMotorController.java +++ b/wpilibj/src/main/java/org/wpilib/hardware/motor/PWMMotorController.java @@ -25,7 +25,7 @@ public abstract class PWMMotorController extends MotorSafety protected PWM m_pwm; private SimDevice m_simDevice; - private SimDouble m_simDutyCycle; + private SimDouble m_simThrottle; private boolean m_eliminateDeadband; private int m_minPwm; @@ -47,7 +47,7 @@ public abstract class PWMMotorController extends MotorSafety m_simDevice = SimDevice.create("PWMMotorController", channel); if (m_simDevice != null) { - m_simDutyCycle = m_simDevice.createDouble("DutyCycle", Direction.OUTPUT, 0.0); + m_simThrottle = m_simDevice.createDouble("Throttle", Direction.OUTPUT, 0.0); m_pwm.setSimDevice(m_simDevice); } } @@ -61,7 +61,7 @@ public abstract class PWMMotorController extends MotorSafety if (m_simDevice != null) { m_simDevice.close(); m_simDevice = null; - m_simDutyCycle = null; + m_simThrottle = null; } } @@ -102,8 +102,8 @@ public abstract class PWMMotorController extends MotorSafety dutyCycle = 0.0; } - if (m_simDutyCycle != null) { - m_simDutyCycle.set(dutyCycle); + if (m_simThrottle != null) { + m_simThrottle.set(dutyCycle); } int rawValue; @@ -161,21 +161,21 @@ public abstract class PWMMotorController extends MotorSafety } @Override - public void setDutyCycle(double dutyCycle) { + public void setThrottle(double throttle) { if (m_isInverted) { - dutyCycle = -dutyCycle; + throttle = -throttle; } - setDutyCycleInternal(dutyCycle); + setDutyCycleInternal(throttle); for (var follower : m_followers) { - follower.setDutyCycle(dutyCycle); + follower.setThrottle(throttle); } feed(); } @Override - public double getDutyCycle() { + public double getThrottle() { return getDutyCycleInternal() * (m_isInverted ? -1.0 : 1.0); } @@ -185,7 +185,7 @@ public abstract class PWMMotorController extends MotorSafety * @return The voltage of the motor controller, nominally between -12 V and 12 V. */ public double getVoltage() { - return getDutyCycle() * RobotController.getBatteryVoltage(); + return getThrottle() * RobotController.getBatteryVoltage(); } @Override @@ -202,8 +202,8 @@ public abstract class PWMMotorController extends MotorSafety public void disable() { m_pwm.setDisabled(); - if (m_simDutyCycle != null) { - m_simDutyCycle.set(0.0); + if (m_simThrottle != null) { + m_simThrottle.set(0.0); } for (var follower : m_followers) { @@ -263,6 +263,6 @@ public abstract class PWMMotorController extends MotorSafety public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("Motor Controller"); builder.setActuator(true); - builder.addDoubleProperty("Value", this::getDutyCycle, this::setDutyCycle); + builder.addDoubleProperty("Value", this::getThrottle, this::setThrottle); } } diff --git a/wpilibj/src/main/java/org/wpilib/simulation/PWMMotorControllerSim.java b/wpilibj/src/main/java/org/wpilib/simulation/PWMMotorControllerSim.java index d9f480d0ab..d8d9727230 100644 --- a/wpilibj/src/main/java/org/wpilib/simulation/PWMMotorControllerSim.java +++ b/wpilibj/src/main/java/org/wpilib/simulation/PWMMotorControllerSim.java @@ -9,7 +9,7 @@ import org.wpilib.hardware.motor.PWMMotorController; /** Class to control a simulated PWM motor controller. */ public class PWMMotorControllerSim { - private final SimDouble m_simDutyCycle; + private final SimDouble m_simThrottle; /** * Constructor. @@ -27,15 +27,15 @@ public class PWMMotorControllerSim { */ public PWMMotorControllerSim(int channel) { SimDeviceSim simDevice = new SimDeviceSim("PWMMotorController", channel); - m_simDutyCycle = simDevice.getDouble("DutyCycle"); + m_simThrottle = simDevice.getDouble("Throttle"); } /** - * Gets the motor duty cycle. + * Gets the motor throttle. * - * @return Duty cycle + * @return Throttle */ - public double getDutyCycle() { - return m_simDutyCycle.get(); + public double getThrottle() { + return m_simThrottle.get(); } } diff --git a/wpilibj/src/test/java/org/wpilib/drive/DifferentialDriveTest.java b/wpilibj/src/test/java/org/wpilib/drive/DifferentialDriveTest.java index 0b95e1d04f..9403767d04 100644 --- a/wpilibj/src/test/java/org/wpilib/drive/DifferentialDriveTest.java +++ b/wpilibj/src/test/java/org/wpilib/drive/DifferentialDriveTest.java @@ -253,227 +253,227 @@ class DifferentialDriveTest { void testArcadeDrive() { var left = new MockPWMMotorController(); var right = new MockPWMMotorController(); - var drive = new DifferentialDrive(left::setDutyCycle, right::setDutyCycle); + var drive = new DifferentialDrive(left::setThrottle, right::setThrottle); drive.setDeadband(0.0); // Forward drive.arcadeDrive(1.0, 0.0, false); - assertEquals(1.0, left.getDutyCycle(), 1e-9); - assertEquals(1.0, right.getDutyCycle(), 1e-9); + assertEquals(1.0, left.getThrottle(), 1e-9); + assertEquals(1.0, right.getThrottle(), 1e-9); // Forward left turn drive.arcadeDrive(0.5, 0.5, false); - assertEquals(0.0, left.getDutyCycle(), 1e-9); - assertEquals(0.5, right.getDutyCycle(), 1e-9); + assertEquals(0.0, left.getThrottle(), 1e-9); + assertEquals(0.5, right.getThrottle(), 1e-9); // Forward right turn drive.arcadeDrive(0.5, -0.5, false); - assertEquals(0.5, left.getDutyCycle(), 1e-9); - assertEquals(0.0, right.getDutyCycle(), 1e-9); + assertEquals(0.5, left.getThrottle(), 1e-9); + assertEquals(0.0, right.getThrottle(), 1e-9); // Backward drive.arcadeDrive(-1.0, 0.0, false); - assertEquals(-1.0, left.getDutyCycle(), 1e-9); - assertEquals(-1.0, right.getDutyCycle(), 1e-9); + assertEquals(-1.0, left.getThrottle(), 1e-9); + assertEquals(-1.0, right.getThrottle(), 1e-9); // Backward left turn drive.arcadeDrive(-0.5, 0.5, false); - assertEquals(-0.5, left.getDutyCycle(), 1e-9); - assertEquals(0.0, right.getDutyCycle(), 1e-9); + assertEquals(-0.5, left.getThrottle(), 1e-9); + assertEquals(0.0, right.getThrottle(), 1e-9); // Backward right turn drive.arcadeDrive(-0.5, -0.5, false); - assertEquals(0.0, left.getDutyCycle(), 1e-9); - assertEquals(-0.5, right.getDutyCycle(), 1e-9); + assertEquals(0.0, left.getThrottle(), 1e-9); + assertEquals(-0.5, right.getThrottle(), 1e-9); } @Test void testArcadeDriveSquared() { var left = new MockPWMMotorController(); var right = new MockPWMMotorController(); - var drive = new DifferentialDrive(left::setDutyCycle, right::setDutyCycle); + var drive = new DifferentialDrive(left::setThrottle, right::setThrottle); drive.setDeadband(0.0); // Forward drive.arcadeDrive(1.0, 0.0, true); - assertEquals(1.0, left.getDutyCycle(), 1e-9); - assertEquals(1.0, right.getDutyCycle(), 1e-9); + assertEquals(1.0, left.getThrottle(), 1e-9); + assertEquals(1.0, right.getThrottle(), 1e-9); // Forward left turn drive.arcadeDrive(0.5, 0.5, true); - assertEquals(0.0, left.getDutyCycle(), 1e-9); - assertEquals(0.25, right.getDutyCycle(), 1e-9); + assertEquals(0.0, left.getThrottle(), 1e-9); + assertEquals(0.25, right.getThrottle(), 1e-9); // Forward right turn drive.arcadeDrive(0.5, -0.5, true); - assertEquals(0.25, left.getDutyCycle(), 1e-9); - assertEquals(0.0, right.getDutyCycle(), 1e-9); + assertEquals(0.25, left.getThrottle(), 1e-9); + assertEquals(0.0, right.getThrottle(), 1e-9); // Backward drive.arcadeDrive(-1.0, 0.0, true); - assertEquals(-1.0, left.getDutyCycle(), 1e-9); - assertEquals(-1.0, right.getDutyCycle(), 1e-9); + assertEquals(-1.0, left.getThrottle(), 1e-9); + assertEquals(-1.0, right.getThrottle(), 1e-9); // Backward left turn drive.arcadeDrive(-0.5, 0.5, true); - assertEquals(-0.25, left.getDutyCycle(), 1e-9); - assertEquals(0.0, right.getDutyCycle(), 1e-9); + assertEquals(-0.25, left.getThrottle(), 1e-9); + assertEquals(0.0, right.getThrottle(), 1e-9); // Backward right turn drive.arcadeDrive(-0.5, -0.5, true); - assertEquals(0.0, left.getDutyCycle(), 1e-9); - assertEquals(-0.25, right.getDutyCycle(), 1e-9); + assertEquals(0.0, left.getThrottle(), 1e-9); + assertEquals(-0.25, right.getThrottle(), 1e-9); } @Test void testCurvatureDrive() { var left = new MockPWMMotorController(); var right = new MockPWMMotorController(); - var drive = new DifferentialDrive(left::setDutyCycle, right::setDutyCycle); + var drive = new DifferentialDrive(left::setThrottle, right::setThrottle); drive.setDeadband(0.0); // Forward drive.curvatureDrive(1.0, 0.0, false); - assertEquals(1.0, left.getDutyCycle(), 1e-9); - assertEquals(1.0, right.getDutyCycle(), 1e-9); + assertEquals(1.0, left.getThrottle(), 1e-9); + assertEquals(1.0, right.getThrottle(), 1e-9); // Forward left turn drive.curvatureDrive(0.5, 0.5, false); - assertEquals(0.25, left.getDutyCycle(), 1e-9); - assertEquals(0.75, right.getDutyCycle(), 1e-9); + assertEquals(0.25, left.getThrottle(), 1e-9); + assertEquals(0.75, right.getThrottle(), 1e-9); // Forward right turn drive.curvatureDrive(0.5, -0.5, false); - assertEquals(0.75, left.getDutyCycle(), 1e-9); - assertEquals(0.25, right.getDutyCycle(), 1e-9); + assertEquals(0.75, left.getThrottle(), 1e-9); + assertEquals(0.25, right.getThrottle(), 1e-9); // Backward drive.curvatureDrive(-1.0, 0.0, false); - assertEquals(-1.0, left.getDutyCycle(), 1e-9); - assertEquals(-1.0, right.getDutyCycle(), 1e-9); + assertEquals(-1.0, left.getThrottle(), 1e-9); + assertEquals(-1.0, right.getThrottle(), 1e-9); // Backward left turn drive.curvatureDrive(-0.5, 0.5, false); - assertEquals(-0.75, left.getDutyCycle(), 1e-9); - assertEquals(-0.25, right.getDutyCycle(), 1e-9); + assertEquals(-0.75, left.getThrottle(), 1e-9); + assertEquals(-0.25, right.getThrottle(), 1e-9); // Backward right turn drive.curvatureDrive(-0.5, -0.5, false); - assertEquals(-0.25, left.getDutyCycle(), 1e-9); - assertEquals(-0.75, right.getDutyCycle(), 1e-9); + assertEquals(-0.25, left.getThrottle(), 1e-9); + assertEquals(-0.75, right.getThrottle(), 1e-9); } @Test void testCurvatureDriveTurnInPlace() { var left = new MockPWMMotorController(); var right = new MockPWMMotorController(); - var drive = new DifferentialDrive(left::setDutyCycle, right::setDutyCycle); + var drive = new DifferentialDrive(left::setThrottle, right::setThrottle); drive.setDeadband(0.0); // Forward drive.curvatureDrive(1.0, 0.0, true); - assertEquals(1.0, left.getDutyCycle(), 1e-9); - assertEquals(1.0, right.getDutyCycle(), 1e-9); + assertEquals(1.0, left.getThrottle(), 1e-9); + assertEquals(1.0, right.getThrottle(), 1e-9); // Forward left turn drive.curvatureDrive(0.5, 0.5, true); - assertEquals(0.0, left.getDutyCycle(), 1e-9); - assertEquals(1.0, right.getDutyCycle(), 1e-9); + assertEquals(0.0, left.getThrottle(), 1e-9); + assertEquals(1.0, right.getThrottle(), 1e-9); // Forward right turn drive.curvatureDrive(0.5, -0.5, true); - assertEquals(1.0, left.getDutyCycle(), 1e-9); - assertEquals(0.0, right.getDutyCycle(), 1e-9); + assertEquals(1.0, left.getThrottle(), 1e-9); + assertEquals(0.0, right.getThrottle(), 1e-9); // Backward drive.curvatureDrive(-1.0, 0.0, true); - assertEquals(-1.0, left.getDutyCycle(), 1e-9); - assertEquals(-1.0, right.getDutyCycle(), 1e-9); + assertEquals(-1.0, left.getThrottle(), 1e-9); + assertEquals(-1.0, right.getThrottle(), 1e-9); // Backward left turn drive.curvatureDrive(-0.5, 0.5, true); - assertEquals(-1.0, left.getDutyCycle(), 1e-9); - assertEquals(0.0, right.getDutyCycle(), 1e-9); + assertEquals(-1.0, left.getThrottle(), 1e-9); + assertEquals(0.0, right.getThrottle(), 1e-9); // Backward right turn drive.curvatureDrive(-0.5, -0.5, true); - assertEquals(0.0, left.getDutyCycle(), 1e-9); - assertEquals(-1.0, right.getDutyCycle(), 1e-9); + assertEquals(0.0, left.getThrottle(), 1e-9); + assertEquals(-1.0, right.getThrottle(), 1e-9); } @Test void testTankDrive() { var left = new MockPWMMotorController(); var right = new MockPWMMotorController(); - var drive = new DifferentialDrive(left::setDutyCycle, right::setDutyCycle); + var drive = new DifferentialDrive(left::setThrottle, right::setThrottle); drive.setDeadband(0.0); // Forward drive.tankDrive(1.0, 1.0, false); - assertEquals(1.0, left.getDutyCycle(), 1e-9); - assertEquals(1.0, right.getDutyCycle(), 1e-9); + assertEquals(1.0, left.getThrottle(), 1e-9); + assertEquals(1.0, right.getThrottle(), 1e-9); // Forward left turn drive.tankDrive(0.5, 1.0, false); - assertEquals(0.5, left.getDutyCycle(), 1e-9); - assertEquals(1.0, right.getDutyCycle(), 1e-9); + assertEquals(0.5, left.getThrottle(), 1e-9); + assertEquals(1.0, right.getThrottle(), 1e-9); // Forward right turn drive.tankDrive(1.0, 0.5, false); - assertEquals(1.0, left.getDutyCycle(), 1e-9); - assertEquals(0.5, right.getDutyCycle(), 1e-9); + assertEquals(1.0, left.getThrottle(), 1e-9); + assertEquals(0.5, right.getThrottle(), 1e-9); // Backward drive.tankDrive(-1.0, -1.0, false); - assertEquals(-1.0, left.getDutyCycle(), 1e-9); - assertEquals(-1.0, right.getDutyCycle(), 1e-9); + assertEquals(-1.0, left.getThrottle(), 1e-9); + assertEquals(-1.0, right.getThrottle(), 1e-9); // Backward left turn drive.tankDrive(-0.5, -1.0, false); - assertEquals(-0.5, left.getDutyCycle(), 1e-9); - assertEquals(-1.0, right.getDutyCycle(), 1e-9); + assertEquals(-0.5, left.getThrottle(), 1e-9); + assertEquals(-1.0, right.getThrottle(), 1e-9); // Backward right turn drive.tankDrive(-0.5, 1.0, false); - assertEquals(-0.5, left.getDutyCycle(), 1e-9); - assertEquals(1.0, right.getDutyCycle(), 1e-9); + assertEquals(-0.5, left.getThrottle(), 1e-9); + assertEquals(1.0, right.getThrottle(), 1e-9); } @Test void testTankDriveSquared() { var left = new MockPWMMotorController(); var right = new MockPWMMotorController(); - var drive = new DifferentialDrive(left::setDutyCycle, right::setDutyCycle); + var drive = new DifferentialDrive(left::setThrottle, right::setThrottle); drive.setDeadband(0.0); // Forward drive.tankDrive(1.0, 1.0, true); - assertEquals(1.0, left.getDutyCycle(), 1e-9); - assertEquals(1.0, right.getDutyCycle(), 1e-9); + assertEquals(1.0, left.getThrottle(), 1e-9); + assertEquals(1.0, right.getThrottle(), 1e-9); // Forward left turn drive.tankDrive(0.5, 1.0, true); - assertEquals(0.25, left.getDutyCycle(), 1e-9); - assertEquals(1.0, right.getDutyCycle(), 1e-9); + assertEquals(0.25, left.getThrottle(), 1e-9); + assertEquals(1.0, right.getThrottle(), 1e-9); // Forward right turn drive.tankDrive(1.0, 0.5, true); - assertEquals(1.0, left.getDutyCycle(), 1e-9); - assertEquals(0.25, right.getDutyCycle(), 1e-9); + assertEquals(1.0, left.getThrottle(), 1e-9); + assertEquals(0.25, right.getThrottle(), 1e-9); // Backward drive.tankDrive(-1.0, -1.0, true); - assertEquals(-1.0, left.getDutyCycle(), 1e-9); - assertEquals(-1.0, right.getDutyCycle(), 1e-9); + assertEquals(-1.0, left.getThrottle(), 1e-9); + assertEquals(-1.0, right.getThrottle(), 1e-9); // Backward left turn drive.tankDrive(-0.5, -1.0, true); - assertEquals(-0.25, left.getDutyCycle(), 1e-9); - assertEquals(-1.0, right.getDutyCycle(), 1e-9); + assertEquals(-0.25, left.getThrottle(), 1e-9); + assertEquals(-1.0, right.getThrottle(), 1e-9); // Backward right turn drive.tankDrive(-1.0, -0.5, true); - assertEquals(-1.0, left.getDutyCycle(), 1e-9); - assertEquals(-0.25, right.getDutyCycle(), 1e-9); + assertEquals(-1.0, left.getThrottle(), 1e-9); + assertEquals(-0.25, right.getThrottle(), 1e-9); } } diff --git a/wpilibj/src/test/java/org/wpilib/drive/MecanumDriveTest.java b/wpilibj/src/test/java/org/wpilib/drive/MecanumDriveTest.java index 94c7f55a89..556644ff25 100644 --- a/wpilibj/src/test/java/org/wpilib/drive/MecanumDriveTest.java +++ b/wpilibj/src/test/java/org/wpilib/drive/MecanumDriveTest.java @@ -95,43 +95,43 @@ class MecanumDriveTest { var fr = new MockPWMMotorController(); var rr = new MockPWMMotorController(); var drive = - new MecanumDrive(fl::setDutyCycle, rl::setDutyCycle, fr::setDutyCycle, rr::setDutyCycle); + new MecanumDrive(fl::setThrottle, rl::setThrottle, fr::setThrottle, rr::setThrottle); drive.setDeadband(0.0); // Forward drive.driveCartesian(1.0, 0.0, 0.0); - assertEquals(1.0, fl.getDutyCycle(), 1e-9); - assertEquals(1.0, fr.getDutyCycle(), 1e-9); - assertEquals(1.0, rl.getDutyCycle(), 1e-9); - assertEquals(1.0, rr.getDutyCycle(), 1e-9); + assertEquals(1.0, fl.getThrottle(), 1e-9); + assertEquals(1.0, fr.getThrottle(), 1e-9); + assertEquals(1.0, rl.getThrottle(), 1e-9); + assertEquals(1.0, rr.getThrottle(), 1e-9); // Left drive.driveCartesian(0.0, -1.0, 0.0); - assertEquals(-1.0, fl.getDutyCycle(), 1e-9); - assertEquals(1.0, fr.getDutyCycle(), 1e-9); - assertEquals(1.0, rl.getDutyCycle(), 1e-9); - assertEquals(-1.0, rr.getDutyCycle(), 1e-9); + assertEquals(-1.0, fl.getThrottle(), 1e-9); + assertEquals(1.0, fr.getThrottle(), 1e-9); + assertEquals(1.0, rl.getThrottle(), 1e-9); + assertEquals(-1.0, rr.getThrottle(), 1e-9); // Right drive.driveCartesian(0.0, 1.0, 0.0); - assertEquals(1.0, fl.getDutyCycle(), 1e-9); - assertEquals(-1.0, fr.getDutyCycle(), 1e-9); - assertEquals(-1.0, rl.getDutyCycle(), 1e-9); - assertEquals(1.0, rr.getDutyCycle(), 1e-9); + assertEquals(1.0, fl.getThrottle(), 1e-9); + assertEquals(-1.0, fr.getThrottle(), 1e-9); + assertEquals(-1.0, rl.getThrottle(), 1e-9); + assertEquals(1.0, rr.getThrottle(), 1e-9); // Rotate CCW drive.driveCartesian(0.0, 0.0, -1.0); - assertEquals(-1.0, fl.getDutyCycle(), 1e-9); - assertEquals(1.0, fr.getDutyCycle(), 1e-9); - assertEquals(-1.0, rl.getDutyCycle(), 1e-9); - assertEquals(1.0, rr.getDutyCycle(), 1e-9); + assertEquals(-1.0, fl.getThrottle(), 1e-9); + assertEquals(1.0, fr.getThrottle(), 1e-9); + assertEquals(-1.0, rl.getThrottle(), 1e-9); + assertEquals(1.0, rr.getThrottle(), 1e-9); // Rotate CW drive.driveCartesian(0.0, 0.0, 1.0); - assertEquals(1.0, fl.getDutyCycle(), 1e-9); - assertEquals(-1.0, fr.getDutyCycle(), 1e-9); - assertEquals(1.0, rl.getDutyCycle(), 1e-9); - assertEquals(-1.0, rr.getDutyCycle(), 1e-9); + assertEquals(1.0, fl.getThrottle(), 1e-9); + assertEquals(-1.0, fr.getThrottle(), 1e-9); + assertEquals(1.0, rl.getThrottle(), 1e-9); + assertEquals(-1.0, rr.getThrottle(), 1e-9); } @Test @@ -141,43 +141,43 @@ class MecanumDriveTest { var fr = new MockPWMMotorController(); var rr = new MockPWMMotorController(); var drive = - new MecanumDrive(fl::setDutyCycle, rl::setDutyCycle, fr::setDutyCycle, rr::setDutyCycle); + new MecanumDrive(fl::setThrottle, rl::setThrottle, fr::setThrottle, rr::setThrottle); drive.setDeadband(0.0); // Forward in global frame; left in robot frame drive.driveCartesian(1.0, 0.0, 0.0, Rotation2d.kCCW_Pi_2); - assertEquals(-1.0, fl.getDutyCycle(), 1e-9); - assertEquals(1.0, fr.getDutyCycle(), 1e-9); - assertEquals(1.0, rl.getDutyCycle(), 1e-9); - assertEquals(-1.0, rr.getDutyCycle(), 1e-9); + assertEquals(-1.0, fl.getThrottle(), 1e-9); + assertEquals(1.0, fr.getThrottle(), 1e-9); + assertEquals(1.0, rl.getThrottle(), 1e-9); + assertEquals(-1.0, rr.getThrottle(), 1e-9); // Left in global frame; backward in robot frame drive.driveCartesian(0.0, -1.0, 0.0, Rotation2d.kCCW_Pi_2); - assertEquals(-1.0, fl.getDutyCycle(), 1e-9); - assertEquals(-1.0, fr.getDutyCycle(), 1e-9); - assertEquals(-1.0, rl.getDutyCycle(), 1e-9); - assertEquals(-1.0, rr.getDutyCycle(), 1e-9); + assertEquals(-1.0, fl.getThrottle(), 1e-9); + assertEquals(-1.0, fr.getThrottle(), 1e-9); + assertEquals(-1.0, rl.getThrottle(), 1e-9); + assertEquals(-1.0, rr.getThrottle(), 1e-9); // Right in global frame; forward in robot frame drive.driveCartesian(0.0, 1.0, 0.0, Rotation2d.kCCW_Pi_2); - assertEquals(1.0, fl.getDutyCycle(), 1e-9); - assertEquals(1.0, fr.getDutyCycle(), 1e-9); - assertEquals(1.0, rl.getDutyCycle(), 1e-9); - assertEquals(1.0, rr.getDutyCycle(), 1e-9); + assertEquals(1.0, fl.getThrottle(), 1e-9); + assertEquals(1.0, fr.getThrottle(), 1e-9); + assertEquals(1.0, rl.getThrottle(), 1e-9); + assertEquals(1.0, rr.getThrottle(), 1e-9); // Rotate CCW drive.driveCartesian(0.0, 0.0, -1.0, Rotation2d.kCCW_Pi_2); - assertEquals(-1.0, fl.getDutyCycle(), 1e-9); - assertEquals(1.0, fr.getDutyCycle(), 1e-9); - assertEquals(-1.0, rl.getDutyCycle(), 1e-9); - assertEquals(1.0, rr.getDutyCycle(), 1e-9); + assertEquals(-1.0, fl.getThrottle(), 1e-9); + assertEquals(1.0, fr.getThrottle(), 1e-9); + assertEquals(-1.0, rl.getThrottle(), 1e-9); + assertEquals(1.0, rr.getThrottle(), 1e-9); // Rotate CW drive.driveCartesian(0.0, 0.0, 1.0, Rotation2d.kCCW_Pi_2); - assertEquals(1.0, fl.getDutyCycle(), 1e-9); - assertEquals(-1.0, fr.getDutyCycle(), 1e-9); - assertEquals(1.0, rl.getDutyCycle(), 1e-9); - assertEquals(-1.0, rr.getDutyCycle(), 1e-9); + assertEquals(1.0, fl.getThrottle(), 1e-9); + assertEquals(-1.0, fr.getThrottle(), 1e-9); + assertEquals(1.0, rl.getThrottle(), 1e-9); + assertEquals(-1.0, rr.getThrottle(), 1e-9); } @Test @@ -187,42 +187,42 @@ class MecanumDriveTest { var fr = new MockPWMMotorController(); var rr = new MockPWMMotorController(); var drive = - new MecanumDrive(fl::setDutyCycle, rl::setDutyCycle, fr::setDutyCycle, rr::setDutyCycle); + new MecanumDrive(fl::setThrottle, rl::setThrottle, fr::setThrottle, rr::setThrottle); drive.setDeadband(0.0); // Forward drive.drivePolar(1.0, Rotation2d.kZero, 0.0); - assertEquals(1.0, fl.getDutyCycle(), 1e-9); - assertEquals(1.0, fr.getDutyCycle(), 1e-9); - assertEquals(1.0, rl.getDutyCycle(), 1e-9); - assertEquals(1.0, rr.getDutyCycle(), 1e-9); + assertEquals(1.0, fl.getThrottle(), 1e-9); + assertEquals(1.0, fr.getThrottle(), 1e-9); + assertEquals(1.0, rl.getThrottle(), 1e-9); + assertEquals(1.0, rr.getThrottle(), 1e-9); // Left drive.drivePolar(1.0, Rotation2d.kCW_Pi_2, 0.0); - assertEquals(-1.0, fl.getDutyCycle(), 1e-9); - assertEquals(1.0, fr.getDutyCycle(), 1e-9); - assertEquals(1.0, rl.getDutyCycle(), 1e-9); - assertEquals(-1.0, rr.getDutyCycle(), 1e-9); + assertEquals(-1.0, fl.getThrottle(), 1e-9); + assertEquals(1.0, fr.getThrottle(), 1e-9); + assertEquals(1.0, rl.getThrottle(), 1e-9); + assertEquals(-1.0, rr.getThrottle(), 1e-9); // Right drive.drivePolar(1.0, Rotation2d.kCCW_Pi_2, 0.0); - assertEquals(1.0, fl.getDutyCycle(), 1e-9); - assertEquals(-1.0, fr.getDutyCycle(), 1e-9); - assertEquals(-1.0, rl.getDutyCycle(), 1e-9); - assertEquals(1.0, rr.getDutyCycle(), 1e-9); + assertEquals(1.0, fl.getThrottle(), 1e-9); + assertEquals(-1.0, fr.getThrottle(), 1e-9); + assertEquals(-1.0, rl.getThrottle(), 1e-9); + assertEquals(1.0, rr.getThrottle(), 1e-9); // Rotate CCW drive.drivePolar(0.0, Rotation2d.kZero, -1.0); - assertEquals(-1.0, fl.getDutyCycle(), 1e-9); - assertEquals(1.0, fr.getDutyCycle(), 1e-9); - assertEquals(-1.0, rl.getDutyCycle(), 1e-9); - assertEquals(1.0, rr.getDutyCycle(), 1e-9); + assertEquals(-1.0, fl.getThrottle(), 1e-9); + assertEquals(1.0, fr.getThrottle(), 1e-9); + assertEquals(-1.0, rl.getThrottle(), 1e-9); + assertEquals(1.0, rr.getThrottle(), 1e-9); // Rotate CW drive.drivePolar(0.0, Rotation2d.kZero, 1.0); - assertEquals(1.0, fl.getDutyCycle(), 1e-9); - assertEquals(-1.0, fr.getDutyCycle(), 1e-9); - assertEquals(1.0, rl.getDutyCycle(), 1e-9); - assertEquals(-1.0, rr.getDutyCycle(), 1e-9); + assertEquals(1.0, fl.getThrottle(), 1e-9); + assertEquals(-1.0, fr.getThrottle(), 1e-9); + assertEquals(1.0, rl.getThrottle(), 1e-9); + assertEquals(-1.0, rr.getThrottle(), 1e-9); } } diff --git a/wpilibj/src/test/java/org/wpilib/hardware/motor/MockMotorController.java b/wpilibj/src/test/java/org/wpilib/hardware/motor/MockMotorController.java index bf652fda50..fe630418ac 100644 --- a/wpilibj/src/test/java/org/wpilib/hardware/motor/MockMotorController.java +++ b/wpilibj/src/test/java/org/wpilib/hardware/motor/MockMotorController.java @@ -6,17 +6,17 @@ package org.wpilib.hardware.motor; @SuppressWarnings("removal") public class MockMotorController implements MotorController { - private double m_dutyCycle; + private double m_throttle; private boolean m_isInverted; @Override - public void setDutyCycle(double dutyCycle) { - m_dutyCycle = m_isInverted ? -dutyCycle : dutyCycle; + public void setThrottle(double throttle) { + m_throttle = m_isInverted ? -throttle : throttle; } @Override - public double getDutyCycle() { - return m_dutyCycle; + public double getThrottle() { + return m_throttle; } @Override @@ -31,6 +31,6 @@ public class MockMotorController implements MotorController { @Override public void disable() { - m_dutyCycle = 0; + m_throttle = 0; } } diff --git a/wpilibj/src/test/java/org/wpilib/hardware/motor/MockPWMMotorController.java b/wpilibj/src/test/java/org/wpilib/hardware/motor/MockPWMMotorController.java index b5262005bb..7fea4ea8bd 100644 --- a/wpilibj/src/test/java/org/wpilib/hardware/motor/MockPWMMotorController.java +++ b/wpilibj/src/test/java/org/wpilib/hardware/motor/MockPWMMotorController.java @@ -5,15 +5,15 @@ package org.wpilib.hardware.motor; public class MockPWMMotorController { - private double m_dutyCycle; + private double m_throttle; private boolean m_isInverted; - public void setDutyCycle(double dutyCycle) { - m_dutyCycle = m_isInverted ? -dutyCycle : dutyCycle; + public void setThrottle(double throttle) { + m_throttle = m_isInverted ? -throttle : throttle; } - public double getDutyCycle() { - return m_dutyCycle; + public double getThrottle() { + return m_throttle; } public void setInverted(boolean isInverted) { @@ -25,7 +25,7 @@ public class MockPWMMotorController { } public void disable() { - m_dutyCycle = 0; + m_throttle = 0; } public void stopMotor() { diff --git a/wpilibj/src/test/java/org/wpilib/simulation/DCMotorSimTest.java b/wpilibj/src/test/java/org/wpilib/simulation/DCMotorSimTest.java index 4c18e83474..f71a2a1120 100644 --- a/wpilibj/src/test/java/org/wpilib/simulation/DCMotorSimTest.java +++ b/wpilibj/src/test/java/org/wpilib/simulation/DCMotorSimTest.java @@ -38,7 +38,7 @@ class DCMotorSimTest { // ------ SimulationPeriodic() happens after user code ------- RoboRioSim.setVInVoltage( BatterySim.calculateDefaultBatteryLoadedVoltage(sim.getCurrentDraw())); - sim.setInputVoltage(motor.getDutyCycle() * RobotController.getBatteryVoltage()); + sim.setInputVoltage(motor.getThrottle() * RobotController.getBatteryVoltage()); sim.update(0.020); encoderSim.setRate(sim.getAngularVelocity()); } @@ -51,7 +51,7 @@ class DCMotorSimTest { // ------ SimulationPeriodic() happens after user code ------- RoboRioSim.setVInVoltage( BatterySim.calculateDefaultBatteryLoadedVoltage(sim.getCurrentDraw())); - sim.setInputVoltage(motor.getDutyCycle() * RobotController.getBatteryVoltage()); + sim.setInputVoltage(motor.getThrottle() * RobotController.getBatteryVoltage()); sim.update(0.020); encoderSim.setRate(sim.getAngularVelocity()); } @@ -76,12 +76,12 @@ class DCMotorSimTest { encoderSim.resetData(); for (int i = 0; i < 140; i++) { - motor.setDutyCycle(controller.calculate(encoder.getDistance(), 750)); + motor.setThrottle(controller.calculate(encoder.getDistance(), 750)); // ------ SimulationPeriodic() happens after user code ------- RoboRioSim.setVInVoltage( BatterySim.calculateDefaultBatteryLoadedVoltage(sim.getCurrentDraw())); - sim.setInputVoltage(motor.getDutyCycle() * RobotController.getBatteryVoltage()); + sim.setInputVoltage(motor.getThrottle() * RobotController.getBatteryVoltage()); sim.update(0.020); encoderSim.setDistance(sim.getAngularPosition()); encoderSim.setRate(sim.getAngularVelocity()); diff --git a/wpilibj/src/test/java/org/wpilib/simulation/ElevatorSimTest.java b/wpilibj/src/test/java/org/wpilib/simulation/ElevatorSimTest.java index b06e3ba4d2..7b079d753f 100644 --- a/wpilibj/src/test/java/org/wpilib/simulation/ElevatorSimTest.java +++ b/wpilibj/src/test/java/org/wpilib/simulation/ElevatorSimTest.java @@ -48,11 +48,11 @@ class ElevatorSimTest { double nextVoltage = controller.calculate(encoderSim.getDistance()); double currentBatteryVoltage = RobotController.getBatteryVoltage(); - motor.setDutyCycle(nextVoltage / currentBatteryVoltage); + motor.setThrottle(nextVoltage / currentBatteryVoltage); // ------ SimulationPeriodic() happens after user code ------- - var u = VecBuilder.fill(motor.getDutyCycle() * currentBatteryVoltage); + var u = VecBuilder.fill(motor.getThrottle() * currentBatteryVoltage); sim.setInput(u); sim.update(0.020); var y = sim.getOutput(); diff --git a/wpilibj/src/test/java/org/wpilib/simulation/PWMMotorControllerSimTest.java b/wpilibj/src/test/java/org/wpilib/simulation/PWMMotorControllerSimTest.java index 14a852df25..5d4f998f48 100644 --- a/wpilibj/src/test/java/org/wpilib/simulation/PWMMotorControllerSimTest.java +++ b/wpilibj/src/test/java/org/wpilib/simulation/PWMMotorControllerSimTest.java @@ -18,14 +18,14 @@ class PWMMotorControllerSimTest { try (Spark spark = new Spark(0)) { PWMMotorControllerSim sim = new PWMMotorControllerSim(spark); - spark.setDutyCycle(0); - assertEquals(0, sim.getDutyCycle()); + spark.setThrottle(0); + assertEquals(0, sim.getThrottle()); - spark.setDutyCycle(0.354); - assertEquals(0.354, sim.getDutyCycle()); + spark.setThrottle(0.354); + assertEquals(0.354, sim.getThrottle()); - spark.setDutyCycle(-0.785); - assertEquals(-0.785, sim.getDutyCycle()); + spark.setThrottle(-0.785); + assertEquals(-0.785, sim.getThrottle()); } } } diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/arcadedrivegamepad/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/examples/arcadedrivegamepad/Robot.java index d3f440d46f..a7fe831b9c 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/arcadedrivegamepad/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/arcadedrivegamepad/Robot.java @@ -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. */ diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/armsimulation/subsystems/Arm.java b/wpilibjExamples/src/main/java/org/wpilib/examples/armsimulation/subsystems/Arm.java index 8306277e9e..fda913c301 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/armsimulation/subsystems/Arm.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/armsimulation/subsystems/Arm.java @@ -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 diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/differentialdriveposeestimator/Drivetrain.java b/wpilibjExamples/src/main/java/org/wpilib/examples/differentialdriveposeestimator/Drivetrain.java index 3c875525d2..6aa067264d 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/differentialdriveposeestimator/Drivetrain.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/differentialdriveposeestimator/Drivetrain.java @@ -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()); diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/drivedistanceoffboard/ExampleSmartMotorController.java b/wpilibjExamples/src/main/java/org/wpilib/examples/drivedistanceoffboard/ExampleSmartMotorController.java index ee1b9217e1..9f26abc84d 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/drivedistanceoffboard/ExampleSmartMotorController.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/drivedistanceoffboard/ExampleSmartMotorController.java @@ -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; } diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/drivedistanceoffboard/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/org/wpilib/examples/drivedistanceoffboard/subsystems/DriveSubsystem.java index 72a23456a2..7604dfd0cd 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/drivedistanceoffboard/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/drivedistanceoffboard/subsystems/DriveSubsystem.java @@ -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 = diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/elevatorexponentialprofile/ExampleSmartMotorController.java b/wpilibjExamples/src/main/java/org/wpilib/examples/elevatorexponentialprofile/ExampleSmartMotorController.java index c87b5ae953..fa564ea88d 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/elevatorexponentialprofile/ExampleSmartMotorController.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/elevatorexponentialprofile/ExampleSmartMotorController.java @@ -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; } diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/elevatorexponentialsimulation/subsystems/Elevator.java b/wpilibjExamples/src/main/java/org/wpilib/examples/elevatorexponentialsimulation/subsystems/Elevator.java index 13609f099f..33dabafae8 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/elevatorexponentialsimulation/subsystems/Elevator.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/elevatorexponentialsimulation/subsystems/Elevator.java @@ -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. */ diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/elevatorsimulation/subsystems/Elevator.java b/wpilibjExamples/src/main/java/org/wpilib/examples/elevatorsimulation/subsystems/Elevator.java index 7194ee62d9..dc2cd935db 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/elevatorsimulation/subsystems/Elevator.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/elevatorsimulation/subsystems/Elevator.java @@ -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. */ diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/elevatortrapezoidprofile/ExampleSmartMotorController.java b/wpilibjExamples/src/main/java/org/wpilib/examples/elevatortrapezoidprofile/ExampleSmartMotorController.java index 59294f4391..9eb8acd5f2 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/elevatortrapezoidprofile/ExampleSmartMotorController.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/elevatortrapezoidprofile/ExampleSmartMotorController.java @@ -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; } diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/gettingstarted/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/examples/gettingstarted/Robot.java index 6f66aeba96..52ad3f2935 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/gettingstarted/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/gettingstarted/Robot.java @@ -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(); diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/gyro/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/examples/gyro/Robot.java index 141091f907..5dffe8d44d 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/gyro/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/gyro/Robot.java @@ -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); diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbotinlined/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbotinlined/subsystems/DriveSubsystem.java index a6c4b4faef..e59465c92f 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbotinlined/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbotinlined/subsystems/DriveSubsystem.java @@ -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 = diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbottraditional/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbottraditional/subsystems/DriveSubsystem.java index a79e47f2ab..d7f7795ded 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbottraditional/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbottraditional/subsystems/DriveSubsystem.java @@ -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 = diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/mecanumdrive/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/examples/mecanumdrive/Robot.java index ef5dedd299..d03d9e421a 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/mecanumdrive/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/mecanumdrive/Robot.java @@ -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); diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/mechanism2d/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/examples/mechanism2d/Robot.java index d045a9c9eb..ad7197b907 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/mechanism2d/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/mechanism2d/Robot.java @@ -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)); } } diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/rapidreactcommandbot/subsystems/Drive.java b/wpilibjExamples/src/main/java/org/wpilib/examples/rapidreactcommandbot/subsystems/Drive.java index 37f0abe202..b6655c8e04 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/rapidreactcommandbot/subsystems/Drive.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/rapidreactcommandbot/subsystems/Drive.java @@ -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 = diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/rapidreactcommandbot/subsystems/Intake.java b/wpilibjExamples/src/main/java/org/wpilib/examples/rapidreactcommandbot/subsystems/Intake.java index 5710e9c0df..6c9dce7bfe 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/rapidreactcommandbot/subsystems/Intake.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/rapidreactcommandbot/subsystems/Intake.java @@ -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"); } diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/rapidreactcommandbot/subsystems/Shooter.java b/wpilibjExamples/src/main/java/org/wpilib/examples/rapidreactcommandbot/subsystems/Shooter.java index 47d93afa20..58582d1d17 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/rapidreactcommandbot/subsystems/Shooter.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/rapidreactcommandbot/subsystems/Shooter.java @@ -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"); } } diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/rapidreactcommandbot/subsystems/Storage.java b/wpilibjExamples/src/main/java/org/wpilib/examples/rapidreactcommandbot/subsystems/Storage.java index 2b2d61c988..17e197f28e 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/rapidreactcommandbot/subsystems/Storage.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/rapidreactcommandbot/subsystems/Storage.java @@ -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"); } } diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/romireference/subsystems/Drivetrain.java b/wpilibjExamples/src/main/java/org/wpilib/examples/romireference/subsystems/Drivetrain.java index 48a732b042..26c5940af4 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/romireference/subsystems/Drivetrain.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/romireference/subsystems/Drivetrain.java @@ -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(); diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/simpledifferentialdrivesimulation/Drivetrain.java b/wpilibjExamples/src/main/java/org/wpilib/examples/simpledifferentialdrivesimulation/Drivetrain.java index 53c894295c..f138ba2646 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/simpledifferentialdrivesimulation/Drivetrain.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/simpledifferentialdrivesimulation/Drivetrain.java @@ -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()); diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/sysidroutine/subsystems/Drive.java b/wpilibjExamples/src/main/java/org/wpilib/examples/sysidroutine/subsystems/Drive.java index 0af3ffa879..58804fc6f7 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/sysidroutine/subsystems/Drive.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/sysidroutine/subsystems/Drive.java @@ -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())); }, diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/sysidroutine/subsystems/Shooter.java b/wpilibjExamples/src/main/java/org/wpilib/examples/sysidroutine/subsystems/Shooter.java index e864953b4b..1c62532ece 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/sysidroutine/subsystems/Shooter.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/sysidroutine/subsystems/Shooter.java @@ -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( () -> { diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/tankdrivegamepad/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/examples/tankdrivegamepad/Robot.java index 057ac39fd5..ccb50c6079 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/tankdrivegamepad/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/tankdrivegamepad/Robot.java @@ -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. */ diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/unittest/subsystems/Intake.java b/wpilibjExamples/src/main/java/org/wpilib/examples/unittest/subsystems/Intake.java index 063663d6ed..5bb8bfcf58 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/unittest/subsystems/Intake.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/unittest/subsystems/Intake.java @@ -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); } } diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/xrpreference/subsystems/Drivetrain.java b/wpilibjExamples/src/main/java/org/wpilib/examples/xrpreference/subsystems/Drivetrain.java index cf78719711..289fcd0b08 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/xrpreference/subsystems/Drivetrain.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/xrpreference/subsystems/Drivetrain.java @@ -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(); diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/xrptimed/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/examples/xrptimed/Robot.java index e4d100d5df..8a6d8feff0 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/examples/xrptimed/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/examples/xrptimed/Robot.java @@ -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(); diff --git a/wpilibjExamples/src/main/java/org/wpilib/snippets/encoderdrive/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/snippets/encoderdrive/Robot.java index 0aa1e613d5..02dfa40ba9 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/snippets/encoderdrive/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/snippets/encoderdrive/Robot.java @@ -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() { diff --git a/wpilibjExamples/src/main/java/org/wpilib/snippets/encoderhoming/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/snippets/encoderhoming/Robot.java index ffb8db7c5d..24c42dcfc0 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/snippets/encoderhoming/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/snippets/encoderhoming/Robot.java @@ -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(); } } diff --git a/wpilibjExamples/src/main/java/org/wpilib/snippets/eventloop/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/snippets/eventloop/Robot.java index 014caf2b72..1c180083dc 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/snippets/eventloop/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/snippets/eventloop/Robot.java @@ -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 diff --git a/wpilibjExamples/src/main/java/org/wpilib/snippets/flywheelbangbangcontroller/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/snippets/flywheelbangbangcontroller/Robot.java index ffc33defc7..2deb9e0bee 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/snippets/flywheelbangbangcontroller/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/snippets/flywheelbangbangcontroller/Robot.java @@ -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()); } diff --git a/wpilibjExamples/src/main/java/org/wpilib/snippets/limitswitch/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/snippets/limitswitch/Robot.java index 93faa490bb..e4faff1b98 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/snippets/limitswitch/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/snippets/limitswitch/Robot.java @@ -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); } } } diff --git a/wpilibjExamples/src/main/java/org/wpilib/snippets/motorcontrol/Robot.java b/wpilibjExamples/src/main/java/org/wpilib/snippets/motorcontrol/Robot.java index 9b5de7cc04..5119bfdd07 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/snippets/motorcontrol/Robot.java +++ b/wpilibjExamples/src/main/java/org/wpilib/snippets/motorcontrol/Robot.java @@ -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()); } } diff --git a/wpilibjExamples/src/main/java/org/wpilib/templates/romicommandv2/subsystems/RomiDrivetrain.java b/wpilibjExamples/src/main/java/org/wpilib/templates/romicommandv2/subsystems/RomiDrivetrain.java index a0a41017e4..60f8c5e15e 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/templates/romicommandv2/subsystems/RomiDrivetrain.java +++ b/wpilibjExamples/src/main/java/org/wpilib/templates/romicommandv2/subsystems/RomiDrivetrain.java @@ -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() { diff --git a/wpilibjExamples/src/main/java/org/wpilib/templates/romieducational/RomiDrivetrain.java b/wpilibjExamples/src/main/java/org/wpilib/templates/romieducational/RomiDrivetrain.java index ac70e09802..3bcf03dda9 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/templates/romieducational/RomiDrivetrain.java +++ b/wpilibjExamples/src/main/java/org/wpilib/templates/romieducational/RomiDrivetrain.java @@ -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() { diff --git a/wpilibjExamples/src/main/java/org/wpilib/templates/romitimed/RomiDrivetrain.java b/wpilibjExamples/src/main/java/org/wpilib/templates/romitimed/RomiDrivetrain.java index f17420a144..f0bd81d763 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/templates/romitimed/RomiDrivetrain.java +++ b/wpilibjExamples/src/main/java/org/wpilib/templates/romitimed/RomiDrivetrain.java @@ -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() { diff --git a/wpilibjExamples/src/main/java/org/wpilib/templates/xrpcommandv2/subsystems/XRPDrivetrain.java b/wpilibjExamples/src/main/java/org/wpilib/templates/xrpcommandv2/subsystems/XRPDrivetrain.java index be877dca7c..daa425c040 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/templates/xrpcommandv2/subsystems/XRPDrivetrain.java +++ b/wpilibjExamples/src/main/java/org/wpilib/templates/xrpcommandv2/subsystems/XRPDrivetrain.java @@ -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() { diff --git a/wpilibjExamples/src/main/java/org/wpilib/templates/xrpeducational/XRPDrivetrain.java b/wpilibjExamples/src/main/java/org/wpilib/templates/xrpeducational/XRPDrivetrain.java index f9f00592b8..7192bea520 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/templates/xrpeducational/XRPDrivetrain.java +++ b/wpilibjExamples/src/main/java/org/wpilib/templates/xrpeducational/XRPDrivetrain.java @@ -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() { diff --git a/wpilibjExamples/src/main/java/org/wpilib/templates/xrptimed/XRPDrivetrain.java b/wpilibjExamples/src/main/java/org/wpilib/templates/xrptimed/XRPDrivetrain.java index c2a9b90de4..21f86df29b 100644 --- a/wpilibjExamples/src/main/java/org/wpilib/templates/xrptimed/XRPDrivetrain.java +++ b/wpilibjExamples/src/main/java/org/wpilib/templates/xrptimed/XRPDrivetrain.java @@ -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() { diff --git a/wpilibjExamples/src/test/java/org/wpilib/examples/armsimulation/ArmSimulationTest.java b/wpilibjExamples/src/test/java/org/wpilib/examples/armsimulation/ArmSimulationTest.java index 49e29d6066..db3e45e30d 100644 --- a/wpilibjExamples/src/test/java/org/wpilib/examples/armsimulation/ArmSimulationTest.java +++ b/wpilibjExamples/src/test/java/org/wpilib/examples/armsimulation/ArmSimulationTest.java @@ -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); } } diff --git a/wpilibjExamples/src/test/java/org/wpilib/examples/elevatorsimulation/ElevatorSimulationTest.java b/wpilibjExamples/src/test/java/org/wpilib/examples/elevatorsimulation/ElevatorSimulationTest.java index 674bd7048b..ec9b775004 100644 --- a/wpilibjExamples/src/test/java/org/wpilib/examples/elevatorsimulation/ElevatorSimulationTest.java +++ b/wpilibjExamples/src/test/java/org/wpilib/examples/elevatorsimulation/ElevatorSimulationTest.java @@ -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); } } diff --git a/wpilibjExamples/src/test/java/org/wpilib/examples/unittest/subsystems/IntakeTest.java b/wpilibjExamples/src/test/java/org/wpilib/examples/unittest/subsystems/IntakeTest.java index aada8fef21..dbe57359ca 100644 --- a/wpilibjExamples/src/test/java/org/wpilib/examples/unittest/subsystems/IntakeTest.java +++ b/wpilibjExamples/src/test/java/org/wpilib/examples/unittest/subsystems/IntakeTest.java @@ -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 diff --git a/xrpVendordep/src/main/java/org/wpilib/xrp/XRPMotor.java b/xrpVendordep/src/main/java/org/wpilib/xrp/XRPMotor.java index 5f632237c3..0c7b0796ec 100644 --- a/xrpVendordep/src/main/java/org/wpilib/xrp/XRPMotor.java +++ b/xrpVendordep/src/main/java/org/wpilib/xrp/XRPMotor.java @@ -41,7 +41,7 @@ public class XRPMotor implements MotorController { s_simDeviceNameMap.put(3, "motor4"); } - private final SimDouble m_simVelocity; + private final SimDouble m_simThrottle; private final SimBoolean m_simInverted; /** @@ -59,29 +59,29 @@ public class XRPMotor implements MotorController { if (xrpMotorSimDevice != null) { xrpMotorSimDevice.createBoolean("init", Direction.OUTPUT, true); m_simInverted = xrpMotorSimDevice.createBoolean("inverted", Direction.INPUT, false); - m_simVelocity = xrpMotorSimDevice.createDouble("velocity", Direction.OUTPUT, 0.0); + m_simThrottle = xrpMotorSimDevice.createDouble("throttle", Direction.OUTPUT, 0.0); } else { m_simInverted = null; - m_simVelocity = null; + m_simThrottle = null; } } @Override - public void setDutyCycle(double velocity) { - if (m_simVelocity != null) { + public void setThrottle(double throttle) { + if (m_simThrottle != null) { boolean invert = false; if (m_simInverted != null) { invert = m_simInverted.get(); } - m_simVelocity.set(invert ? -velocity : velocity); + m_simThrottle.set(invert ? -throttle : throttle); } } @Override - public double getDutyCycle() { - if (m_simVelocity != null) { - return m_simVelocity.get(); + public double getThrottle() { + if (m_simThrottle != null) { + return m_simThrottle.get(); } return 0.0; @@ -101,6 +101,6 @@ public class XRPMotor implements MotorController { @Override public void disable() { - setDutyCycle(0.0); + setThrottle(0.0); } } diff --git a/xrpVendordep/src/main/native/cpp/xrp/XRPMotor.cpp b/xrpVendordep/src/main/native/cpp/xrp/XRPMotor.cpp index f61374327f..c1dc97d9c7 100644 --- a/xrpVendordep/src/main/native/cpp/xrp/XRPMotor.cpp +++ b/xrpVendordep/src/main/native/cpp/xrp/XRPMotor.cpp @@ -31,8 +31,6 @@ void XRPMotor::CheckDeviceAllocation(int deviceNum) { s_registeredDevices.insert(deviceNum); } -WPI_IGNORE_DEPRECATED - XRPMotor::XRPMotor(int deviceNum) { CheckDeviceAllocation(deviceNum); @@ -43,27 +41,25 @@ XRPMotor::XRPMotor(int deviceNum) { m_simDevice.CreateBoolean("init", hal::SimDevice::Direction::OUTPUT, true); m_simInverted = m_simDevice.CreateBoolean( "inverted", hal::SimDevice::Direction::INPUT, false); - m_simVelocity = m_simDevice.CreateDouble( - "velocity", hal::SimDevice::Direction::OUTPUT, 0.0); + m_simThrottle = m_simDevice.CreateDouble( + "throttle", hal::SimDevice::Direction::OUTPUT, 0.0); } } -WPI_UNIGNORE_DEPRECATED - -void XRPMotor::SetDutyCycle(double velocity) { - if (m_simVelocity) { +void XRPMotor::SetThrottle(double throttle) { + if (m_simThrottle) { bool invert = false; if (m_simInverted) { invert = m_simInverted.Get(); } - m_simVelocity.Set(invert ? -velocity : velocity); + m_simThrottle.Set(invert ? -throttle : throttle); } } -double XRPMotor::GetDutyCycle() const { - if (m_simVelocity) { - return m_simVelocity.Get(); +double XRPMotor::GetThrottle() const { + if (m_simThrottle) { + return m_simThrottle.Get(); } return 0.0; @@ -84,11 +80,11 @@ bool XRPMotor::GetInverted() const { } void XRPMotor::Disable() { - SetDutyCycle(0.0); + SetThrottle(0.0); } void XRPMotor::StopMotor() { - SetDutyCycle(0.0); + SetThrottle(0.0); } std::string XRPMotor::GetDescription() const { diff --git a/xrpVendordep/src/main/native/include/wpi/xrp/XRPMotor.hpp b/xrpVendordep/src/main/native/include/wpi/xrp/XRPMotor.hpp index c8f6d7bfe2..6a4d6bb292 100644 --- a/xrpVendordep/src/main/native/include/wpi/xrp/XRPMotor.hpp +++ b/xrpVendordep/src/main/native/include/wpi/xrp/XRPMotor.hpp @@ -11,12 +11,9 @@ #include "wpi/hal/SimDevice.hpp" #include "wpi/hardware/motor/MotorController.hpp" #include "wpi/hardware/motor/MotorSafety.hpp" -#include "wpi/util/deprecated.hpp" namespace wpi::xrp { -WPI_IGNORE_DEPRECATED - /** * @defgroup xrp_api XRP Hardware API * @{ @@ -36,8 +33,8 @@ class XRPMotor : public wpi::MotorController, public wpi::MotorSafety { */ explicit XRPMotor(int deviceNum); - void SetDutyCycle(double value) override; - double GetDutyCycle() const override; + void SetThrottle(double throttle) override; + double GetThrottle() const override; void SetInverted(bool isInverted) override; bool GetInverted() const override; @@ -49,7 +46,7 @@ class XRPMotor : public wpi::MotorController, public wpi::MotorSafety { private: hal::SimDevice m_simDevice; - hal::SimDouble m_simVelocity; + hal::SimDouble m_simThrottle; hal::SimBoolean m_simInverted; std::string m_deviceName; @@ -62,6 +59,4 @@ class XRPMotor : public wpi::MotorController, public wpi::MotorSafety { /** @} */ -WPI_UNIGNORE_DEPRECATED - } // namespace wpi::xrp diff --git a/xrpVendordep/src/main/python/semiwrap/XRPMotor.yml b/xrpVendordep/src/main/python/semiwrap/XRPMotor.yml index da2abd2a86..bbf868d94b 100644 --- a/xrpVendordep/src/main/python/semiwrap/XRPMotor.yml +++ b/xrpVendordep/src/main/python/semiwrap/XRPMotor.yml @@ -2,8 +2,8 @@ classes: wpi::xrp::XRPMotor: methods: XRPMotor: - SetDutyCycle: - GetDutyCycle: + SetThrottle: + GetThrottle: SetInverted: GetInverted: Disable: