WPILib Subsystems and Commands Pattern Questions

Hi - We are trying this year to buy in whole hog to the “new” way of programming the robot, and I am having some fundamental problems that maybe someone can quickly and easily get me past my blockage. I have read the documentation several times, and still haven’t found the answers to what I am struggling with. Thanks in advance (even pointing me at something here or on-line to read is fine; I have tried searching topics and can’t quite find the answer, or figure out the answer from what I see). Part of the problem is we have an existing framework that we’ve used several years and it’s become less compatible, and no doubt less capable than the existing WPILib command framework - which is why we want to switch over. Thanks in advance for any help!

(1) Number of Motors in a Single Subsystem - Is the general design pattern to have a single active (commanded) thing in a subsystem? We have an arm, with two speed controllers & PIDs - one to rotate and one to extend. Because commands want to have exclusive access to the subsystem, trying to interact with both seems problematic - because of how existing commands to rotate interrupt the running command to extend. I think I see how you can “coordinate” subsystems via command groups - is that the pattern to use?

(2) Triggers (Buttons) vs. Joysticks (Axes) - Why is there not equivalent Trigger functions that work for Joysticks? As an example of what we are trying to do - we have three commands that rotate the arm based on setting the set point on the PID that are tied to buttons. We also want to be able to “tweak” the height by using the joysticks to update current set point. I implemented a command for this that takes inputs from the axes, but as soon as one of the Triggers run, it interrupts the tweak command, and so we loose that functionality. I would make it the default command for the Arm subsystem (so it’s always running when one of the buttons isn’t firing), but I can’t have that for both the rotate and the extension (see question #1) above. The code snippet is as follows:

   private void configureTeleopButtonBindings() {
      logger.info("configure");

      // Rotate to set point when button is pressed
      rotateHighButton.onTrue(new ArmRotateToHighPosition());
      rotateMidButton.onTrue(new ArmRotateToMidPosition());
      rotateLowButton.onTrue(new ArmRotateToLowPosition());
      // Nudge rotation when joystick is moved
      new ArmRotateToTarget(() -> deadBand(-getRightYAxis(), 0.10)).schedule();

      gripperButton
            // Open the gripper when the button is pressed
            .onTrue(new GripperOpen())
            // Close thre gripper when that same button is released
            .onFalse(new GripperClose());

      logger.info("configured");
   }

1 - yes. For example our arm is broken into LowerArm arm and UpperArm and then we have and additional Arm subsystem that combines them, but basically has convenience factories and methods.

2 - We use the subsystem periodic to maintain the set points (run the PID) for the joints. The commands basically just alter the set points and enable/disable the arm from actively maintaining/converging on the set point.

1 Like

Do you combine fixed set points and manual adjustment? I can get either to work by themselves; it’s when I try to add the “manual” tweak off the joystick that it breaks (the manual only runs until one of the button Triggers have run).

Each independently controlled mechanism should have its own Subsystem to model that mechanism. The number of motors that control that mechanism is irrelevant as long as they are bound together (e.g. two motors in one gearbox, or motors for a drive train are all controlling the same mechanism). If your robot’s arm is built as an extending linear slide mounted to a rotating arm, the extension and the rotation should generally be separate subsystems in code. You can build distinct commands to control the extension and rotation - just keep in mind that they’ll need to know the rotation and extension states to avoid collisions (e.g. a theoretical Extend command will need to know the current rotation of the arm, to avoid extending too far and slamming your end effector into the floor)

If you want to get fancy, you could encapsulate both in a single subsystem and have it do the IK under the hood to get to a particular position, but that can make it difficult to separate control for the different mechanisms and can be harder to reason about - it’s usually better to compose commands together into command groups to build complex actions out of simple ones.

(2) Triggers (Buttons) vs. Joysticks (Axes) - Why is there not equivalent Trigger functions that work for Joysticks?

You can build your own Trigger to fire whenever you want - use the Trigger(BooleanSupplier) constructor to pass in a lambda that will determine if the trigger is on or off. You can bind commands to that trigger just like a JoystickButton.

I implemented a command for this that takes inputs from the axes, but as soon as one of the Triggers run, it interrupts the tweak command, and so we loose that functionality

This is likely because your commands are set up to go to a hardcoded position. That’s generally the correct way to do things, because your setpoints should be tuned to be known good positions. If you want to tune those setpoints with manual control, then it’d be better to note the final position after manual control and then use that as the new hardcoded setpoint.

2 Likes

I think you want your subsystem to maintain the last set point it was given. You can do that via default command or in the periodic method of the subsystem. It shouldn’t matter if the last set point was sent by a button or an axis. Perhaps you are using the Joystick to run the motors rather than adjust the set point?

The subsystem does maintain the PID set point - and it works regardless of whether it is set by the button or axes as a source. My problem was getting the joystick axes to act like the button triggers and not get unscheduled and never rescheduled. I think Sam’s suggestion on how to create my own Trigger that “fires” when the axes comes out of the deadzone will work. (Although when I break my arm into two separate subsystems, I can make the default command the joystick one, and I’m pretty sure that will also work). Thank you for your help.

There’s a range of views about how fine-grained subsystems should be.

The atomic approach says that you should have a separate subsystem for every motor or actuator that might possibly be commanded separately. Any co-ordination between motors has to be done in commands that require both subsystems.

With this approach, it is possible to have separate commands that operate related robot functions (e.g. intake deployment and intake motors) without their requirements interfering. It also makes it possible to take advantage of convenience classes like PIDSubsystem.

The other approach is to group related motors together (e.g. everything on the intake, everything on the arm). This means you have fewer classes, but each class becomes more complex because it has multiple concerns. Even just naming the methods and member variables becomes more complex.

An advantage of this approach is that it provides somewhere to manage the interaction between two motors: Should the intake only run when it is deployed? Should we avoid extending the arm when it is pointing straight down? Putting that logic into commands is error prone because every command has to worry about it. Putting that logic into an atomic subsystem means that one subsystem is dependent on another.

3 Likes

I have a couple of recommendations here:

  1. Have the button triggers be instant commands that only change the setpoint for the subsystem. Service the PID controller within the subsystem periodic.
m_joystick.button(1).onTrue(
    new InstantCommand(
        () -> m_mySubsystem.setPosition(k_myPosition1), 
        m_mySubsystem));
  1. Have the joystick tweak be a mode that is engaged by a toggle button. E.g.
m_joystick.button(2).toggleOnTrue(
    new RunCommand(
        () -> m_mySubsystem.setPosition(m_joystick.getX())), 
        m_mySubsystem);
1 Like

The second method is the one we use- it also means that the subsystem can do all the kinematics and unit conversions, so commands can say something like “drive forward at 3 m/s”, rather than having to deal with native units everywhere.

Thank you. If I can solve the command interaction at the subsystem level, I prefer having a subsystem be a more logical group of potentially interacting active components (e.g., speed controllers / motors). But I can see both approaches (or creating a subsystem of subsystems to manage the interactions of the two lower level pieces).

This is ultimately the most important concern imo; the others are minor ergonomics warts, but this will sink you at scale if you get it wrong. There are too many possible interactions if you try to keep everything atomic.

5 Likes

Thank you - I can see invoking it from a button (we were just trying to avoid that extra complexity for the operators during a match - but it makes sense as an approach that would work).

Thank you - I agree (and in the old days before trying to deal with the Command framework) it was easier …

Unit conversions should be done as early as possible. Only the internals of a subsystem should know about encoder ticks. The subsystem APIs (and hence the commands) should only know about real-world units and how things affect robot behaviour. For example, suppose (purely hypothetically) that your gyro is mounted upside-down and sideways, but only on the practice robot, the subsystem API should hide all that.

Kinematics is another good example of subsystem inter-dependence. If you have an arm with a shoulder and a wrist, you may want to say “Hold the hand horizontal”. Solving the inverse kinematics for the wrist requires you to know the shoulder position. Similarly if you want to implement a trigonometric feedforward model for the wrist.

1 Like

Yeah - I’ve got all that … we actually maintain 4 configurations of robots / code, that hide the details inside the actual implementation of the subsystem class (using dynamic class loading from a text properties file that is unique for each robot at boot time). The commands and everything else just talks to the subsystems from an interface class that is at the “functional” level.

2 Likes

We could possibly help the ergonomics here by adding Parallel command group factories to Subsystem that relax the “cannot require the same subsystem from parallel commands” restriction. This would encourage uses to write multipart commands within the subsystem, keeping the sharing of state to a minimum.

1 Like

Opened the issue, with some open questions: Add an `allowedSharedRequirement` parameter for parallel command compositions · Issue #5144 · wpilibsuite/allwpilib · GitHub

1 Like