[wpilib,cmd] Rename gamepad shoulder to bumper (#8573)

Both programs used bumper, so we shouldn't rename it. There's no reason
to change it, and we don't need to match SDL.
This commit is contained in:
Thad House
2026-02-07 10:39:22 -08:00
committed by GitHub
parent 19c61cc419
commit 4aa21e947d
24 changed files with 179 additions and 182 deletions

View File

@@ -24,8 +24,8 @@ RobotContainer::RobotContainer() {
void RobotContainer::ConfigureButtonBindings() {
// Configure your button bindings here
// While holding the shoulder button, drive at half speed
m_driverController.RightShoulder()
// While holding the bumper button, drive at half speed
m_driverController.RightBumper()
.OnTrue(m_driveHalfSpeed.get())
.OnFalse(m_driveFullSpeed.get());

View File

@@ -40,7 +40,7 @@ void RobotContainer::ConfigureButtonBindings() {
// Release the hatch when the 'West Face' button is pressed.
m_driverController.WestFace().OnTrue(m_hatch.ReleaseHatchCommand());
// While holding Right Bumper, drive at half speed
m_driverController.RightShoulder()
m_driverController.RightBumper()
.OnTrue(wpi::cmd::cmd::RunOnce([this] { m_drive.SetMaxOutput(0.5); }, {}))
.OnFalse(
wpi::cmd::cmd::RunOnce([this] { m_drive.SetMaxOutput(1.0); }, {}));

View File

@@ -46,9 +46,9 @@ void RobotContainer::ConfigureButtonBindings() {
// Release the hatch when the 'East Face' button is pressed.
wpi::cmd::JoystickButton(&m_driverController, wpi::Gamepad::Button::kEastFace)
.OnTrue(ReleaseHatch(&m_hatch).ToPtr());
// While holding the shoulder button, drive at half speed
// While holding the bumper button, drive at half speed
wpi::cmd::JoystickButton(&m_driverController,
wpi::Gamepad::Button::kRightShoulder)
wpi::Gamepad::Button::kRightBumper)
.WhileTrue(HalveDriveSpeed(&m_drive).ToPtr());
}

View File

@@ -112,7 +112,7 @@ class Robot : public wpi::TimedRobot {
// Sets the target position of our arm. This is similar to setting the
// setpoint of a PID controller.
wpi::math::TrapezoidProfile<wpi::units::radians>::State goal;
if (m_joystick.GetRightShoulderButton()) {
if (m_joystick.GetRightBumperButton()) {
// We pressed the bumper, so let's set our next reference
goal = {kRaisedPosition, 0_rad_per_s};
} else {

View File

@@ -112,7 +112,7 @@ class Robot : public wpi::TimedRobot {
// Sets the target height of our elevator. This is similar to setting the
// setpoint of a PID controller.
wpi::math::TrapezoidProfile<wpi::units::meters>::State goal;
if (m_joystick.GetRightShoulderButton()) {
if (m_joystick.GetRightBumperButton()) {
// We pressed the bumper, so let's set our next reference
goal = {kRaisedPosition, 0_fps};
} else {

View File

@@ -91,7 +91,7 @@ class Robot : public wpi::TimedRobot {
void TeleopPeriodic() override {
// Sets the target speed of our flywheel. This is similar to setting the
// setpoint of a PID controller.
if (m_joystick.GetRightShoulderButton()) {
if (m_joystick.GetRightBumperButton()) {
// We pressed the bumper, so let's set our next reference
m_loop.SetNextR(wpi::math::Vectord<1>{kSpinup.value()});
} else {

View File

@@ -88,7 +88,7 @@ class Robot : public wpi::TimedRobot {
void TeleopPeriodic() override {
// Sets the target speed of our flywheel. This is similar to setting the
// setpoint of a PID controller.
if (m_joystick.GetRightShoulderButton()) {
if (m_joystick.GetRightBumperButton()) {
// We pressed the bumper, so let's set our next reference
m_loop.SetNextR(wpi::math::Vectord<1>{kSpinup.value()});
} else {

View File

@@ -17,29 +17,29 @@ void SysIdRoutineBot::ConfigureBindings() {
// Using bumpers as a modifier and combining it with the buttons so that we
// can have both sets of bindings at once
(m_driverController.SouthFace() && m_driverController.RightShoulder())
(m_driverController.SouthFace() && m_driverController.RightBumper())
.WhileTrue(
m_drive.SysIdQuasistatic(wpi::cmd::sysid::Direction::kForward));
(m_driverController.EastFace() && m_driverController.RightShoulder())
(m_driverController.EastFace() && m_driverController.RightBumper())
.WhileTrue(
m_drive.SysIdQuasistatic(wpi::cmd::sysid::Direction::kReverse));
(m_driverController.WestFace() && m_driverController.RightShoulder())
(m_driverController.WestFace() && m_driverController.RightBumper())
.WhileTrue(m_drive.SysIdDynamic(wpi::cmd::sysid::Direction::kForward));
(m_driverController.NorthFace() && m_driverController.RightShoulder())
(m_driverController.NorthFace() && m_driverController.RightBumper())
.WhileTrue(m_drive.SysIdDynamic(wpi::cmd::sysid::Direction::kReverse));
m_shooter.SetDefaultCommand(m_shooter.RunShooterCommand(
[this] { return m_driverController.GetLeftTriggerAxis(); }));
(m_driverController.SouthFace() && m_driverController.LeftShoulder())
(m_driverController.SouthFace() && m_driverController.LeftBumper())
.WhileTrue(
m_shooter.SysIdQuasistatic(wpi::cmd::sysid::Direction::kForward));
(m_driverController.EastFace() && m_driverController.LeftShoulder())
(m_driverController.EastFace() && m_driverController.LeftBumper())
.WhileTrue(
m_shooter.SysIdQuasistatic(wpi::cmd::sysid::Direction::kReverse));
(m_driverController.WestFace() && m_driverController.LeftShoulder())
(m_driverController.WestFace() && m_driverController.LeftBumper())
.WhileTrue(m_shooter.SysIdDynamic(wpi::cmd::sysid::Direction::kForward));
(m_driverController.NorthFace() && m_driverController.LeftShoulder())
(m_driverController.NorthFace() && m_driverController.LeftBumper())
.WhileTrue(m_shooter.SysIdDynamic(wpi::cmd::sysid::Direction::kReverse));
}