Command Compositions
Individual commands are capable of accomplishing a large variety of robot tasks, but the simple three-state format can quickly become cumbersome when more advanced functionality requiring extended sequences of robot tasks or coordination of multiple robot subsystems is required. In order to accomplish this, users are encouraged to use the powerful command composition functionality included in the command-based library.
As the name suggests, a command composition is a composition of one or more commands. This allows code to be kept much cleaner and simpler, as the individual component commands may be written independently of the code that combines them, greatly reducing the amount of complexity at any given step of the process.
Most importantly, however, command compositions are themselves commands - they extend the Command
class. This allows command compositions to be further composed as a recursive composition - that is, a command composition may contain other command compositions as components. This allows very powerful and concise inline expressions:
// Will run fooCommand, and then a race between barCommand and bazCommand
button.onTrue(fooCommand.andThen(barCommand.raceWith(bazCommand)));
// Will run fooCommand, and then a race between barCommand and bazCommand
button.OnTrue(std::move(fooCommand).AndThen(std::move(barCommand).RaceWith(std::move(bazCommand))));
# Will run fooCommand, and then a race between barCommand and bazCommand
button.onTrue(fooCommand.andThen(barCommand.raceWith(bazCommand)))
As a rule, command compositions require all subsystems their components require, may run when disabled if all their component set runsWhenDisabled
as true
, and are kCancelIncoming
if all their components are kCancelIncoming
as well.
Command instances that have been passed to a command composition cannot be independently scheduled or passed to a second command composition. Attempting to do so will throw an exception and crash the user program. This is because composition members are run through their encapsulating command composition, and errors could occur if those same command instances were independently scheduled at the same time as the composition - the command would be being run from multiple places at once, and thus could end up with inconsistent internal state, causing unexpected and hard-to-diagnose behavior. The C++ command-based library uses CommandPtr
, a class with move-only semantics, so this type of mistake is easier to avoid.
Composition Types
The command-based library includes various composition types. All of them can be constructed using factories that accept the member commands, and some can also be constructed using decorators: methods that can be called on a command object, which is transformed into a new object that is returned.
Important
After calling a decorator or being passed to a composition, the command object cannot be reused! Use only the command object returned from the decorator.
Repeating
The repeatedly()
decorator (Java, C++, Python
>`, backed by the RepeatCommand
class (Java, C++, Python
) restarts the command each time it ends, so that it runs until interrupted.
// Will run forever unless externally interrupted, restarting every time command.isFinished() returns true
Command repeats = command.repeatedly();
// Will run forever unless externally interrupted, restarting every time command.IsFinished() returns true
frc2::CommandPtr repeats = std::move(command).Repeatedly();
# Will run forever unless externally interrupted, restarting every time command.IsFinished() returns true
repeats = commands2.cmd.repeatedly()
Sequence
The Sequence
factory (Java, C++, Python
>`, backed by the SequentialCommandGroup
class (Java, C++, Python
), runs a list of commands in sequence: the first command will be executed, then the second, then the third, and so on until the list finishes. The sequential group finishes after the last command in the sequence finishes. It is therefore usually important to ensure that each command in the sequence does actually finish (if a given command does not finish, the next command will never start!).
The andThen()
(Java, C++, Python
>` and beforeStarting()
(Java, C++, Python
) decorators can be used to construct a sequence composition with infix syntax.
fooCommand.andThen(barCommand)
std::move(fooCommand).AndThen(std::move(barCommand))
fooCommand.andThen(barCommand)
Repeating Sequence
As it’s a fairly common combination, the RepeatingSequence
factory (Java, C++, Python
) creates a Repeating Sequence that runs until interrupted, restarting from the first command each time the last command finishes.
Parallel
There are three types of parallel compositions, differing based on when the composition finishes:
The
Parallel
factory (Java, C++,Python
>`, backed by theParallelCommandGroup
class (Java, C++,Python
>`, constructs a parallel composition that finishes when all members finish. ThealongWith
decorator (Java, C++,Python
) does the same in infix notation.The
Race
factory (Java, C++,Python
>`, backed by theParallelRaceGroup
class (Java, C++,Python
>`, constructs a parallel composition that finishes as soon as any member finishes; all other members are interrupted at that point. TheraceWith
decorator (Java, C++,Python
) does the same in infix notation.The
Deadline
factory (Java, C++,Python
>`,ParallelDeadlineGroup
(Java, C++,Python
>` finishes when a specific command (the “deadline”) ends; all other members still running at that point are interrupted. ThedeadlineWith
decorator (Java <https://github.wpilib.org/allwpilib/docs/development/java/edu/wpi/first/wpilibj2/command/Command.html#deadlineWith(edu.wpi.first.wpilibj2.command.Command…)), `C++,Python
) does the same in infix notation; the command the decorator was called on is the deadline.
// Will be a parallel command composition that ends after three seconds with all three commands running their full duration.
button.onTrue(Commands.parallel(twoSecCommand, oneSecCommand, threeSecCommand));
// Will be a parallel race composition that ends after one second with the two and three second commands getting interrupted.
button.onTrue(Commands.race(twoSecCommand, oneSecCommand, threeSecCommand));
// Will be a parallel deadline composition that ends after two seconds (the deadline) with the three second command getting interrupted (one second command already finished).
button.onTrue(Commands.deadline(twoSecCommand, oneSecCommand, threeSecCommand));
// Will be a parallel command composition that ends after three seconds with all three commands running their full duration.
button.OnTrue(frc2::cmd::Parallel(std::move(twoSecCommand), std::move(oneSecCommand), std::move(threeSecCommand)));
// Will be a parallel race composition that ends after one second with the two and three second commands getting interrupted.
button.OnTrue(frc2::cmd::Race(std::move(twoSecCommand), std::move(oneSecCommand), std::move(threeSecCommand)));
// Will be a parallel deadline composition that ends after two seconds (the deadline) with the three second command getting interrupted (one second command already finished).
button.OnTrue(frc2::cmd::Deadline(std::move(twoSecCommand), std::move(oneSecCommand), std::move(threeSecCommand)));
# Will be a parallel command composition that ends after three seconds with all three commands running their full duration.
button.onTrue(commands2.cmd.parallel(twoSecCommand, oneSecCommand, threeSecCommand))
# Will be a parallel race composition that ends after one second with the two and three second commands getting interrupted.
button.onTrue(commands2.cmd.race(twoSecCommand, oneSecCommand, threeSecCommand))
# Will be a parallel deadline composition that ends after two seconds (the deadline) with the three second command getting interrupted (one second command already finished).
button.onTrue(commands2.cmd.deadline(twoSecCommand, oneSecCommand, threeSecCommand))
Adding Command End Conditions
The until()
(Java, C++, Python
) decorator composes the command with an additional end condition. Note that the command the decorator was called on will see this end condition as an interruption.
// Will be interrupted if m_limitSwitch.get() returns true
button.onTrue(command.until(m_limitSwitch::get));
// Will be interrupted if m_limitSwitch.get() returns true
button.OnTrue(command.Until([&m_limitSwitch] { return m_limitSwitch.Get(); }));
# Will be interrupted if limitSwitch.get() returns true
button.onTrue(commands2.cmd.until(limitSwitch.get))
The withTimeout()
decorator (Java, C++, Python
) is a specialization of until
that uses a timeout as the additional end condition.
// Will time out 5 seconds after being scheduled, and be interrupted
button.onTrue(command.withTimeout(5));
// Will time out 5 seconds after being scheduled, and be interrupted
button.OnTrue(command.WithTimeout(5.0_s));
# Will time out 5 seconds after being scheduled, and be interrupted
button.onTrue(commands2.cmd.withTimeout(5.0))
Adding End Behavior
The finallyDo()
(Java, C++, Python
) decorator composes the command with an a lambda that will be called after the command’s end()
method, with the same boolean parameter indicating whether the command finished or was interrupted.
The handleInterrupt()
(Java, C++, Python
) decorator composes the command with an a lambda that will be called only when the command is interrupted.
Selecting Compositions
Sometimes it’s desired to run a command out of a few options based on sensor feedback or other data known only at runtime. This can be useful for determining an auto routine, or running a different command based on whether a game piece is present or not, and so on.
The Select
factory (Java, C++, Python
>`, backed by the SelectCommand
class (Java, C++, Python
), executes one command from a map, based on a selector function called when scheduled.
20public class RobotContainer {
21 // The enum used as keys for selecting the command to run.
22 private enum CommandSelector {
23 ONE,
24 TWO,
25 THREE
26 }
27
28 // An example selector method for the selectcommand. Returns the selector that will select
29 // which command to run. Can base this choice on logical conditions evaluated at runtime.
30 private CommandSelector select() {
31 return CommandSelector.ONE;
32 }
33
34 // An example selectcommand. Will select from the three commands based on the value returned
35 // by the selector method at runtime. Note that selectcommand works on Object(), so the
36 // selector does not have to be an enum; it could be any desired type (string, integer,
37 // boolean, double...)
38 private final Command m_exampleSelectCommand =
39 new SelectCommand<>(
40 // Maps selector values to commands
41 Map.ofEntries(
42 Map.entry(CommandSelector.ONE, new PrintCommand("Command one was selected!")),
43 Map.entry(CommandSelector.TWO, new PrintCommand("Command two was selected!")),
44 Map.entry(CommandSelector.THREE, new PrintCommand("Command three was selected!"))),
45 this::select);
26 // The enum used as keys for selecting the command to run.
27 enum CommandSelector { ONE, TWO, THREE };
28
29 // An example of how command selector may be used with SendableChooser
30 frc::SendableChooser<CommandSelector> m_chooser;
31
32 // The robot's subsystems and commands are defined here...
33
34 // An example selectcommand. Will select from the three commands based on the
35 // value returned by the selector method at runtime. Note that selectcommand
36 // takes a generic type, so the selector does not have to be an enum; it could
37 // be any desired type (string, integer, boolean, double...)
38 frc2::CommandPtr m_exampleSelectCommand = frc2::cmd::Select<CommandSelector>(
39 [this] { return m_chooser.GetSelected(); },
40 // Maps selector values to commands
41 std::pair{ONE, frc2::cmd::Print("Command one was selected!")},
42 std::pair{TWO, frc2::cmd::Print("Command two was selected!")},
43 std::pair{THREE, frc2::cmd::Print("Command three was selected!")});
The Either
factory (Java, C++, Python
>`, backed by the ConditionalCommand
class (Java, C++, Python
), is a specialization accepting two commands and a boolean selector function.
// Runs either commandOnTrue or commandOnFalse depending on the value of m_limitSwitch.get()
new ConditionalCommand(commandOnTrue, commandOnFalse, m_limitSwitch::get)
// Runs either commandOnTrue or commandOnFalse depending on the value of m_limitSwitch.get()
frc2::ConditionalCommand(commandOnTrue, commandOnFalse, [&m_limitSwitch] { return m_limitSwitch.Get(); })
# Runs either commandOnTrue or commandOnFalse depending on the value of limitSwitch.get()
ConditionalCommand(commandOnTrue, commandOnFalse, limitSwitch.get)
The unless()
decorator (Java, C++, Python
) composes a command with a condition that will prevent it from running.
// Command will only run if the intake is deployed. If the intake gets deployed while the command is running, the command will not stop running
button.onTrue(command.unless(() -> !intake.isDeployed()));
// Command will only run if the intake is deployed. If the intake gets deployed while the command is running, the command will not stop running
button.OnTrue(command.Unless([&intake] { return !intake.IsDeployed(); }));
# Command will only run if the intake is deployed. If the intake gets deployed while the command is running, the command will not stop running
button.onTrue(command.unless(lambda: not intake.isDeployed()))
ProxyCommand
described below also has a constructor overload (Java, C++, Python
) that calls a command-returning lambda at schedule-time and runs the returned command by proxy.
Scheduling Other Commands
By default, composition members are run through the command composition, and are never themselves seen by the scheduler. Accordingly, their requirements are added to the composition’s requirements. While this is usually fine, sometimes it is undesirable for the entire command composition to gain the requirements of a single command. A good solution is to “fork off” from the command composition and schedule that command separately. However, this requires synchronization between the composition and the individually-scheduled command.
ProxyCommand
(Java, C++, Python
>`, also creatable using the .asProxy()
decorator (Java, C++, Python
), schedules a command “by proxy”: the command is scheduled when the proxy is scheduled, and the proxy finishes when the command finishes. In the case of “forking off” from a command composition, this allows the composition to track the command’s progress without it being in the composition.
Command compositions inherit the union of their compoments’ requirements and requirements are immutable. Therefore, a SequentialCommandGroup
(Java, C++, Python
) that intakes a game piece, indexes it, aims a shooter, and shoots it would reserve all three subsystems (the intake, indexer, and shooter), precluding any of those subsystems from performing other operations in their “downtime”. If this is not desired, the subsystems that should only be reserved for the composition while they are actively being used by it should have their commands proxied.
Warning
Do not use ProxyCommand
unless you are sure of what you are doing and there is no other way to accomplish your need! Proxying is only intended for use as an escape hatch from command composition requirement unions.
Note
Because proxied commands still require their subsystem, despite not leaking that requirement to the composition, all of the commands that require a given subsystem must be proxied if one of them is. Otherwise, when the proxied command is scheduled its requirement will conflict with that of the composition, canceling the composition.
// composition requirements are indexer and shooter, intake still reserved during its command but not afterwards
Commands.sequence(
intake.intakeGamePiece().asProxy(), // we want to let the intake intake another game piece while we are processing this one
indexer.processGamePiece(),
shooter.aimAndShoot()
);
// composition requirements are indexer and shooter, intake still reserved during its command but not afterwards
frc2::cmd::Sequence(
intake.IntakeGamePiece().AsProxy(), // we want to let the intake intake another game piece while we are processing this one
indexer.ProcessGamePiece(),
shooter.AimAndShoot()
);
# composition requirements are indexer and shooter, intake still reserved during its command but not afterwards
commands2.cmd.sequence(
intake.intakeGamePiece().asProxy(), # we want to let the intake intake another game piece while we are processing this one
indexer.processGamePiece(),
shooter.aimAndShoot()
)
For cases that don’t need to track the proxied command, ScheduleCommand
(Java, C++, Python
) schedules a specified command and ends instantly.
// ScheduleCommand ends immediately, so the sequence continues
new ScheduleCommand(Commands.waitSeconds(5.0))
.andThen(Commands.print("This will be printed immediately!"))
// ScheduleCommand ends immediately, so the sequence continues
frc2::ScheduleCommand(frc2::cmd::Wait(5.0_s))
.AndThen(frc2::cmd::Print("This will be printed immediately!"))
# ScheduleCommand ends immediately, so the sequence continues
ScheduleCommand(commands2.cmd.waitSeconds(5.0))
.andThen(commands2.cmd.print("This will be printed immediately!"))
Subclassing Compositions
Command compositions can also be written as a constructor-only subclass of the most exterior composition type, passing the composition members to the superclass constructor. Consider the following from the Hatch Bot example project (Java, C++):
5package edu.wpi.first.wpilibj.examples.hatchbottraditional.commands;
6
7import edu.wpi.first.wpilibj.examples.hatchbottraditional.Constants.AutoConstants;
8import edu.wpi.first.wpilibj.examples.hatchbottraditional.subsystems.DriveSubsystem;
9import edu.wpi.first.wpilibj.examples.hatchbottraditional.subsystems.HatchSubsystem;
10import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
11
12/** A complex auto command that drives forward, releases a hatch, and then drives backward. */
13public class ComplexAuto extends SequentialCommandGroup {
14 /**
15 * Creates a new ComplexAuto.
16 *
17 * @param drive The drive subsystem this command will run on
18 * @param hatch The hatch subsystem this command will run on
19 */
20 public ComplexAuto(DriveSubsystem drive, HatchSubsystem hatch) {
21 addCommands(
22 // Drive forward the specified distance
23 new DriveDistance(
24 AutoConstants.kAutoDriveDistanceInches, AutoConstants.kAutoDriveSpeed, drive),
25
26 // Release the hatch
27 new ReleaseHatch(hatch),
28
29 // Drive backward the specified distance
30 new DriveDistance(
31 AutoConstants.kAutoBackupDistanceInches, -AutoConstants.kAutoDriveSpeed, drive));
32 }
33}
5#pragma once
6
7#include <frc2/command/CommandHelper.h>
8#include <frc2/command/SequentialCommandGroup.h>
9
10#include "Constants.h"
11#include "commands/DriveDistance.h"
12#include "commands/ReleaseHatch.h"
13
14/**
15 * A complex auto command that drives forward, releases a hatch, and then drives
16 * backward.
17 */
18class ComplexAuto
19 : public frc2::CommandHelper<frc2::SequentialCommandGroup, ComplexAuto> {
20 public:
21 /**
22 * Creates a new ComplexAuto.
23 *
24 * @param drive The drive subsystem this command will run on
25 * @param hatch The hatch subsystem this command will run on
26 */
27 ComplexAuto(DriveSubsystem* drive, HatchSubsystem* hatch);
28};
5#include "commands/ComplexAuto.h"
6
7using namespace AutoConstants;
8
9ComplexAuto::ComplexAuto(DriveSubsystem* drive, HatchSubsystem* hatch) {
10 AddCommands(
11 // Drive forward the specified distance
12 DriveDistance(kAutoDriveDistanceInches, kAutoDriveSpeed, drive),
13 // Release the hatch
14 ReleaseHatch(hatch),
15 // Drive backward the specified distance
16 DriveDistance(kAutoBackupDistanceInches, -kAutoDriveSpeed, drive));
17}
5import commands2
6
7import constants
8
9from .drivedistance import DriveDistance
10from .releasehatch import ReleaseHatch
11
12from subsystems.drivesubsystem import DriveSubsystem
13from subsystems.hatchsubsystem import HatchSubsystem
14
15
16class ComplexAuto(commands2.SequentialCommandGroup):
17 """
18 A complex auto command that drives forward, releases a hatch, and then drives backward.
19 """
20
21 def __init__(self, drive: DriveSubsystem, hatch: HatchSubsystem):
22 super().__init__(
23 # Drive forward the specified distance
24 DriveDistance(
25 constants.kAutoDriveDistanceInches, constants.kAutoDriveSpeed, drive
26 ),
27 # Release the hatch
28 ReleaseHatch(hatch),
29 # Drive backward the specified distance
30 DriveDistance(
31 constants.kAutoBackupDistanceInches, -constants.kAutoDriveSpeed, drive
32 ),
33 )
The advantages and disadvantages of this subclassing approach in comparison to others are discussed in Subclassing Command Groups.