[command] Rename trigger methods (#4210)

Motivation

Feedback from 2022 showed that the Trigger API is rather confusing, mostly due to the following:
- duplicate Trigger and Button APIs were available; users were confused searching for a nonexistent difference between them.
- the when terminology was ambiguous and unclear whether it refers to the high state or specifically the rising edge.
- the Active terminology didn't unambiguously refer to the high state; it wasn't unintuitive to understand it as "when the binding is active/polled".
- whileHeld vs whenHeld was very confusing, and the difference between them wasn't obvious. The parallel Trigger verbs, whileActiveContinuously and whileActiveOnce are much less confusing.

Solution

Deprecating Button and its binding methods. The rationale for deprecating Button (and not Trigger) is because Button uses terminology that is needlessly more specific and restricting to the button use case, making the use case of arbitrary trigger conditions unintuitive.

After consideration, deprecation of Button's subclasses was decided against:

- NetworkButton (a trigger condition based on a boolean NT entry/topic) is a use case that is not necessarily intuitive for teams to implement themselves, so it is an abstraction that should be provided in the library. A parallel class for the BooleanEvent level, NetworkBooleanEvent, was also added as part of NT4. NT listeners were considered as a alternative solution, but they require attention to thread safety, and aren't interoperable with the EventLoop API.
- JoystickButton/POVButton provide abstractions around HID buttons. The new Trigger-returning factories on the HID classes are an equal (if not more concise) alternative, but there is no reason not to keep them for those who find their use preferable.

At a later date in the deprecation cycle (perhaps for 2024), when Button is removed, these subclasses should be changed to inherit directly from Trigger.

Trigger's bindings are changed to use True/False terminology, as it should be unambiguous. Each binding type has both True and False variants; for brevity, only the True variants are listed here:

- onTrue (replaces whenActive): schedule on rising edge.
- whileTrue (replaces whileActiveOnce): schedule on rising edge, cancel on falling edge.
- toggleOnTrue (replaces toggleWhenActive): on rising edge, schedule if unscheduled and cancel if scheduled.

Two binding types are completely deprecated:

- cancelWhenActive: this is a fairly niche use case which is better described as having the trigger's rising edge (Trigger.rising()) as an end condition for the command (using Command.until()).
- whileActiveContinuously: however common, this relied on the no-op behavior of scheduling an already-scheduled command. The more correct way to repeat the command if it ends before the falling edge is using Command.repeatedly/RepeatCommand or a RunCommand -- the only difference is if the command is interrupted, but that is more likely to result in two commands perpetually canceling each other than achieve the desired behavior. Manually implementing a blindly-scheduling binding like whileActiveContinuously is still possible, though might not be intuitive.

Notes

It was considered to share BooleanEvent's digital signal terminology; however, once it was decided that Trigger should not inherit from BooleanEvent (due to overload incompatibility) the common terminology was not worth the unintuitiveness stemming from users' unfamiliarity with the signal processing terms.
This commit is contained in:
Starlight220
2022-10-28 08:03:28 +03:00
committed by GitHub
parent 66157397c1
commit dcda09f90a
50 changed files with 1090 additions and 645 deletions

View File

@@ -5,6 +5,9 @@
#include "RobotContainer.h"
#include <frc/shuffleboard/Shuffleboard.h>
#include <frc2/command/Commands.h>
#include <frc2/command/InstantCommand.h>
#include <frc2/command/RunCommand.h>
#include <frc2/command/button/JoystickButton.h>
#include <units/angle.h>
@@ -28,31 +31,31 @@ void RobotContainer::ConfigureButtonBindings() {
// Move the arm to 2 radians above horizontal when the 'A' button is pressed.
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)
.WhenPressed(
.OnTrue(frc2::cmd::RunOnce(
[this] {
m_arm.SetGoal(2_rad);
m_arm.Enable();
},
{&m_arm});
{&m_arm}));
// Move the arm to neutral position when the 'B' button is pressed.
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kB)
.WhenPressed(
.OnTrue(frc2::cmd::RunOnce(
[this] {
m_arm.SetGoal(ArmConstants::kArmOffset);
m_arm.Enable();
},
{&m_arm});
{&m_arm}));
// Disable the arm controller when Y is pressed.
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kY)
.WhenPressed([this] { m_arm.Disable(); }, {&m_arm});
.OnTrue(frc2::cmd::RunOnce([this] { m_arm.Disable(); }, {&m_arm}));
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController,
frc::XboxController::Button::kRightBumper)
.WhenPressed([this] { m_drive.SetMaxOutput(0.5); })
.WhenReleased([this] { m_drive.SetMaxOutput(1); });
.OnTrue(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(0.5); }))
.OnFalse(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(1); }));
}
void RobotContainer::DisablePIDSubsystems() {

View File

@@ -7,13 +7,6 @@
#include <frc/XboxController.h>
#include <frc/smartdashboard/SendableChooser.h>
#include <frc2/command/Command.h>
#include <frc2/command/ConditionalCommand.h>
#include <frc2/command/InstantCommand.h>
#include <frc2/command/ParallelRaceGroup.h>
#include <frc2/command/RunCommand.h>
#include <frc2/command/SequentialCommandGroup.h>
#include <frc2/command/WaitCommand.h>
#include <frc2/command/WaitUntilCommand.h>
#include "Constants.h"
#include "subsystems/ArmSubsystem.h"

View File

@@ -5,6 +5,9 @@
#include "RobotContainer.h"
#include <frc/shuffleboard/Shuffleboard.h>
#include <frc2/command/Commands.h>
#include <frc2/command/InstantCommand.h>
#include <frc2/command/RunCommand.h>
#include <frc2/command/button/JoystickButton.h>
#include <units/angle.h>
@@ -28,18 +31,18 @@ void RobotContainer::ConfigureButtonBindings() {
// Move the arm to 2 radians above horizontal when the 'A' button is pressed.
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)
.WhenPressed([this] { m_arm.SetGoal(2_rad); }, {&m_arm});
.OnTrue(frc2::cmd::RunOnce([this] { m_arm.SetGoal(2_rad); }, {&m_arm}));
// Move the arm to neutral position when the 'B' button is pressed.
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kB)
.WhenPressed([this] { m_arm.SetGoal(ArmConstants::kArmOffset); },
{&m_arm});
.OnTrue(frc2::cmd::RunOnce(
[this] { m_arm.SetGoal(ArmConstants::kArmOffset); }, {&m_arm}));
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController,
frc::XboxController::Button::kRightBumper)
.WhenPressed([this] { m_drive.SetMaxOutput(0.5); })
.WhenReleased([this] { m_drive.SetMaxOutput(1); });
.OnTrue(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(0.5); }))
.OnFalse(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(1); }));
}
frc2::Command* RobotContainer::GetAutonomousCommand() {

View File

@@ -7,13 +7,6 @@
#include <frc/XboxController.h>
#include <frc/smartdashboard/SendableChooser.h>
#include <frc2/command/Command.h>
#include <frc2/command/ConditionalCommand.h>
#include <frc2/command/InstantCommand.h>
#include <frc2/command/ParallelRaceGroup.h>
#include <frc2/command/RunCommand.h>
#include <frc2/command/SequentialCommandGroup.h>
#include <frc2/command/WaitCommand.h>
#include <frc2/command/WaitUntilCommand.h>
#include "Constants.h"
#include "subsystems/ArmSubsystem.h"

View File

@@ -5,6 +5,7 @@
#include "RobotContainer.h"
#include <frc/shuffleboard/Shuffleboard.h>
#include <frc2/command/Commands.h>
#include <frc2/command/button/JoystickButton.h>
#include "commands/DriveDistanceProfiled.h"
@@ -16,7 +17,7 @@ RobotContainer::RobotContainer() {
ConfigureButtonBindings();
// Set up default drive command
m_drive.SetDefaultCommand(frc2::RunCommand(
m_drive.SetDefaultCommand(frc2::cmd::Run(
[this] {
m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
m_driverController.GetRightX());
@@ -30,18 +31,18 @@ void RobotContainer::ConfigureButtonBindings() {
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController,
frc::XboxController::Button::kRightBumper)
.WhenPressed(&m_driveHalfSpeed)
.WhenReleased(&m_driveFullSpeed);
.OnTrue(&m_driveHalfSpeed)
.OnFalse(&m_driveFullSpeed);
// Drive forward by 3 meters when the 'A' button is pressed, with a timeout of
// 10 seconds
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)
.WhenPressed(DriveDistanceProfiled(3_m, &m_drive).WithTimeout(10_s));
.OnTrue(DriveDistanceProfiled(3_m, &m_drive).WithTimeout(10_s));
// Do the same thing as above when the 'B' button is pressed, but defined
// inline
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kB)
.WhenPressed(
.OnTrue(
frc2::TrapezoidProfileCommand<units::meters>(
frc::TrapezoidProfile<units::meters>(
// Limit the max acceleration and velocity
@@ -54,7 +55,9 @@ void RobotContainer::ConfigureButtonBindings() {
},
// Require the drive
{&m_drive})
.BeforeStarting([this]() { m_drive.ResetEncoders(); })
.ToPtr()
.BeforeStarting(
frc2::cmd::RunOnce([this]() { m_drive.ResetEncoders(); }, {}))
.WithTimeout(10_s));
}

View File

@@ -27,22 +27,22 @@ void RobotContainer::ConfigureButtonBindings() {
// Spin up the shooter when the 'A' button is pressed
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)
.WhenPressed(&m_spinUpShooter);
.OnTrue(&m_spinUpShooter);
// Turn off the shooter when the 'B' button is pressed
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kB)
.WhenPressed(&m_stopShooter);
.OnTrue(&m_stopShooter);
// Shoot when the 'X' button is held
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kX)
.WhenPressed(&m_shoot)
.WhenReleased(&m_stopFeeder);
.OnTrue(&m_shoot)
.OnFalse(&m_stopFeeder);
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController,
frc::XboxController::Button::kRightBumper)
.WhenPressed(&m_driveHalfSpeed)
.WhenReleased(&m_driveFullSpeed);
.OnTrue(&m_driveHalfSpeed)
.OnFalse(&m_driveFullSpeed);
}
frc2::Command* RobotContainer::GetAutonomousCommand() {

View File

@@ -32,20 +32,20 @@ RobotContainer::RobotContainer()
void RobotContainer::ConfigureButtonBindings() {
// Configure your button bindings here
frc2::JoystickButton(&m_joy, 5).WhenPressed(
SetElevatorSetpoint(0.25, m_elevator));
frc2::JoystickButton(&m_joy, 6).WhenPressed(CloseClaw(m_claw));
frc2::JoystickButton(&m_joy, 7).WhenPressed(
SetElevatorSetpoint(0.0, m_elevator));
frc2::JoystickButton(&m_joy, 8).WhenPressed(OpenClaw(m_claw));
frc2::JoystickButton(&m_joy, 9).WhenPressed(
Autonomous(m_claw, m_wrist, m_elevator, m_drivetrain));
frc2::JoystickButton(&m_joy, 5).OnTrue(
SetElevatorSetpoint(0.25, m_elevator).ToPtr());
frc2::JoystickButton(&m_joy, 6).OnTrue(CloseClaw(m_claw).ToPtr());
frc2::JoystickButton(&m_joy, 7).OnTrue(
SetElevatorSetpoint(0.0, m_elevator).ToPtr());
frc2::JoystickButton(&m_joy, 8).OnTrue(OpenClaw(m_claw).ToPtr());
frc2::JoystickButton(&m_joy, 9).OnTrue(
Autonomous(m_claw, m_wrist, m_elevator, m_drivetrain).ToPtr());
frc2::JoystickButton(&m_joy, 10)
.WhenPressed(Pickup(m_claw, m_wrist, m_elevator));
.OnTrue(Pickup(m_claw, m_wrist, m_elevator).ToPtr());
frc2::JoystickButton(&m_joy, 11)
.WhenPressed(Place(m_claw, m_wrist, m_elevator));
.OnTrue(Place(m_claw, m_wrist, m_elevator).ToPtr());
frc2::JoystickButton(&m_joy, 12)
.WhenPressed(PrepareToPickup(m_claw, m_wrist, m_elevator));
.OnTrue(PrepareToPickup(m_claw, m_wrist, m_elevator).ToPtr());
}
frc2::Command* RobotContainer::GetAutonomousCommand() {

View File

@@ -5,6 +5,7 @@
#include "RobotContainer.h"
#include <frc/shuffleboard/Shuffleboard.h>
#include <frc2/command/Commands.h>
#include <frc2/command/PIDCommand.h>
#include <frc2/command/ParallelRaceGroup.h>
#include <frc2/command/RunCommand.h>
@@ -32,33 +33,35 @@ void RobotContainer::ConfigureButtonBindings() {
// Stabilize robot to drive straight with gyro when L1 is held
frc2::JoystickButton(&m_driverController, frc::PS4Controller::Button::kL1)
.WhenHeld(frc2::PIDCommand{
frc2::PIDController{dc::kStabilizationP, dc::kStabilizationI,
dc::kStabilizationD},
// Close the loop on the turn rate
[this] { return m_drive.GetTurnRate(); },
// Setpoint is 0
0,
// Pipe the output to the turning controls
[this](double output) {
m_drive.ArcadeDrive(m_driverController.GetLeftY(), output);
},
// Require the robot drive
{&m_drive}});
.WhileTrue(
frc2::PIDCommand(
frc2::PIDController{dc::kStabilizationP, dc::kStabilizationI,
dc::kStabilizationD},
// Close the loop on the turn rate
[this] { return m_drive.GetTurnRate(); },
// Setpoint is 0
0,
// Pipe the output to the turning controls
[this](double output) {
m_drive.ArcadeDrive(m_driverController.GetLeftY(), output);
},
// Require the robot drive
{&m_drive})
.ToPtr());
// Turn to 90 degrees when the 'Cross' button is pressed
frc2::JoystickButton(&m_driverController, frc::PS4Controller::Button::kCross)
.WhenPressed(TurnToAngle{90_deg, &m_drive}.WithTimeout(5_s));
.OnTrue(TurnToAngle{90_deg, &m_drive}.WithTimeout(5_s));
// Turn to -90 degrees with a profile when the 'Square' button is pressed,
// with a 5 second timeout
frc2::JoystickButton(&m_driverController, frc::PS4Controller::Button::kSquare)
.WhenPressed(TurnToAngle{90_deg, &m_drive}.WithTimeout(5_s));
.OnTrue(TurnToAngle{90_deg, &m_drive}.WithTimeout(5_s));
// While holding R1, drive at half speed
frc2::JoystickButton(&m_driverController, frc::PS4Controller::Button::kR1)
.WhenPressed(frc2::InstantCommand{[this] { m_drive.SetMaxOutput(0.5); }})
.WhenReleased(frc2::InstantCommand{[this] { m_drive.SetMaxOutput(1); }});
.OnTrue(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(0.5); }, {}))
.OnFalse(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(1); }, {}));
}
frc2::Command* RobotContainer::GetAutonomousCommand() {

View File

@@ -34,14 +34,14 @@ void RobotContainer::ConfigureButtonBindings() {
// Grab the hatch when the 'Circle' button is pressed.
frc2::JoystickButton(&m_driverController, frc::PS4Controller::Button::kCircle)
.WhenPressed(&m_grabHatch);
.OnTrue(&m_grabHatch);
// Release the hatch when the 'Square' button is pressed.
frc2::JoystickButton(&m_driverController, frc::PS4Controller::Button::kSquare)
.WhenPressed(&m_releaseHatch);
.OnTrue(&m_releaseHatch);
// While holding R1, drive at half speed
frc2::JoystickButton(&m_driverController, frc::PS4Controller::Button::kR1)
.WhenPressed(&m_driveHalfSpeed)
.WhenReleased(&m_driveFullSpeed);
.OnTrue(&m_driveHalfSpeed)
.OnFalse(&m_driveFullSpeed);
}
frc2::Command* RobotContainer::GetAutonomousCommand() {

View File

@@ -41,14 +41,14 @@ void RobotContainer::ConfigureButtonBindings() {
// Grab the hatch when the 'A' button is pressed.
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)
.WhenPressed(new GrabHatch(&m_hatch));
.OnTrue(GrabHatch(&m_hatch).ToPtr());
// Release the hatch when the 'B' button is pressed.
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kB)
.WhenPressed(new ReleaseHatch(&m_hatch));
.OnTrue(ReleaseHatch(&m_hatch).ToPtr());
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController,
frc::XboxController::Button::kRightBumper)
.WhenHeld(new HalveDriveSpeed(&m_drive));
.WhileTrue(HalveDriveSpeed(&m_drive).ToPtr());
}
frc2::Command* RobotContainer::GetAutonomousCommand() {

View File

@@ -43,8 +43,8 @@ void RobotContainer::ConfigureButtonBindings() {
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController,
frc::XboxController::Button::kRightBumper)
.WhenPressed(&m_driveHalfSpeed)
.WhenReleased(&m_driveFullSpeed);
.OnTrue(&m_driveHalfSpeed)
.OnFalse(&m_driveFullSpeed);
}
frc2::Command* RobotContainer::GetAutonomousCommand() {

View File

@@ -39,8 +39,8 @@ void RobotContainer::ConfigureButtonBindings() {
// While holding the shoulder button, drive at half speed
frc2::JoystickButton{&m_driverController, 6}
.WhenPressed(&m_driveHalfSpeed)
.WhenReleased(&m_driveFullSpeed);
.OnTrue(&m_driveHalfSpeed)
.OnFalse(&m_driveFullSpeed);
}
frc2::Command* RobotContainer::GetAutonomousCommand() {

View File

@@ -5,7 +5,7 @@
#include "RobotContainer.h"
#include <frc/smartdashboard/SmartDashboard.h>
#include <frc2/command/PrintCommand.h>
#include <frc2/command/Commands.h>
#include <frc2/command/button/Button.h>
#include "commands/TeleopArcadeDrive.h"
@@ -22,8 +22,8 @@ void RobotContainer::ConfigureButtonBindings() {
[this] { return m_controller.GetRawAxis(2); }));
// Example of how to use the onboard IO
m_onboardButtonA.WhenPressed(frc2::PrintCommand("Button A Pressed"))
.WhenReleased(frc2::PrintCommand("Button A Released"));
m_onboardButtonA.OnTrue(frc2::cmd::Print("Button A Pressed"))
.OnFalse(frc2::cmd::Print("Button A Released"));
// Setup SmartDashboard options.
m_chooser.SetDefaultOption("Auto Routine Distance", &m_autoDistance);

View File

@@ -7,6 +7,7 @@
#include <frc/Joystick.h>
#include <frc/smartdashboard/SendableChooser.h>
#include <frc2/command/Command.h>
#include <frc2/command/CommandPtr.h>
#include <frc2/command/button/Button.h>
#include "Constants.h"

View File

@@ -46,14 +46,14 @@ void RobotContainer::ConfigureButtonBindings() {
// Run instant command 1 when the 'A' button is pressed
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)
.WhenPressed(&m_instantCommand1);
.OnTrue(&m_instantCommand1);
// Run instant command 2 when the 'X' button is pressed
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kX)
.WhenPressed(&m_instantCommand2);
.OnTrue(&m_instantCommand2);
// Run instant command 3 when the 'Y' button is held; release early to
// interrupt
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kY)
.WhenHeld(&m_waitCommand);
.OnTrue(&m_waitCommand);
}
frc2::Command* RobotContainer::GetAutonomousCommand() {

View File

@@ -53,8 +53,8 @@ void RobotContainer::ConfigureButtonBindings() {
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController,
frc::XboxController::Button::kRightBumper)
.WhenPressed(&m_driveHalfSpeed)
.WhenReleased(&m_driveFullSpeed);
.OnTrue(&m_driveHalfSpeed)
.OnFalse(&m_driveFullSpeed);
}
frc2::Command* RobotContainer::GetAutonomousCommand() {