Weird exception with Command Groups-Please Help

Error at java.base/jdk.internal.util.Preconditions.outOfBounds(Unknown Source): Unhandled exception: java.lang.IndexOutOfBoundsException: Index 2 out of bounds for length 2
Robots should not quit, but yours did!
The startCompetition() method (or methods called by it) should have handled the exception above.
at java.base/jdk.internal.util.Preconditions.outOfBounds(Unknown Source)
at java.base/jdk.internal.util.Preconditions.outOfBoundsCheckIndex(Unknown Source)
at java.base/jdk.internal.util.Preconditions.checkIndex(Unknown Source)
at java.base/java.util.Objects.checkIndex(Unknown Source)
at java.base/java.util.ArrayList.get(Unknown Source)
at edu.wpi.first.wpilibj2.command.SequentialCommandGroup.execute(SequentialCommandGroup.java:66)
at edu.wpi.first.wpilibj2.command.PerpetualCommand.execute(PerpetualCommand.java:44)
at edu.wpi.first.wpilibj2.command.ParallelDeadlineGroup.execute(ParallelDeadlineGroup.java:94)
at edu.wpi.first.wpilibj2.command.SequentialCommandGroup.execute(SequentialCommandGroup.java:68)
at edu.wpi.first.wpilibj2.command.CommandScheduler.run(CommandScheduler.java:263)
at frc.robot.Robot.robotPeriodic(Robot.java:55)
at edu.wpi.first.wpilibj.IterativeRobotBase.loopFunc(IterativeRobotBase.java:285)
at edu.wpi.first.wpilibj.TimedRobot.startCompetition(TimedRobot.java:86)
at edu.wpi.first.wpilibj.RobotBase.runRobot(RobotBase.java:276)
at edu.wpi.first.wpilibj.RobotBase.startRobot(RobotBase.java:348)
at frc.robot.Main.main(Main.java:29)

^ Error occurs when running my shoot command group, generally after firing one ball, but also sometimes before even firing.

Code:

public MultipleAutoShootCG(ShooterS shooterS, HopperS hopperS, int ballsToFire) {
    super(
      new InstantCommand(() -> shooterS.spinUp(), shooterS), //spinup
      new ParallelDeadlineGroup(
        new ShooterWaitUntilFireC(shooterS, ballsToFire <= 5 ? ballsToFire : 5), //until we have fired the right amount of balls, or 5
        new ShooterFireOneCG(shooterS, hopperS).perpetually() //repeatedly fire balls.
      )
    );
  }

Relevant WPILIB snippet (comments by me):

public class SequentialCommandGroup extends CommandGroupBase {
  private final List<Command> m_commands = new ArrayList<>();
  private int m_currentCommandIndex = -1;
  private boolean m_runWhenDisabled = true;

  /**
   * Creates a new SequentialCommandGroup.  The given commands will be run sequentially, with
   * the CommandGroup finishing when the last command finishes.
   *
   * @param commands the commands to include in this group.
   */
  public SequentialCommandGroup(Command... commands) {
    addCommands(commands);
  }

  @Override
  public final void addCommands(Command... commands) {
    requireUngrouped(commands);

    if (m_currentCommandIndex != -1) {
      throw new IllegalStateException(
          "Commands cannot be added to a CommandGroup while the group is running");
    }

    registerGroupedCommands(commands);

    for (Command command : commands) {
      m_commands.add(command);
      m_requirements.addAll(command.getRequirements());
      m_runWhenDisabled &= command.runsWhenDisabled();
    }
  }

  @Override
  public void initialize() {
    m_currentCommandIndex = 0;

    if (!m_commands.isEmpty()) {
      m_commands.get(0).initialize();
    }
  }

  @Override
  public void execute() {
    if (m_commands.isEmpty()) {
      return;
    }

    Command currentCommand = m_commands.get(m_currentCommandIndex); //line 66

    currentCommand.execute();
    if (currentCommand.isFinished()) {
      currentCommand.end(false);
      m_currentCommandIndex++; //line 71, probably where the index gets incremented to two.
      if (m_currentCommandIndex < m_commands.size()) { // I think the error shows up here due to one being 0 indexed and one being 1 indexed. 
        m_commands.get(m_currentCommandIndex).initialize();
      }
    }
  }

  @Override
  public void end(boolean interrupted) {
    if (interrupted && !m_commands.isEmpty() && m_currentCommandIndex > -1
        && m_currentCommandIndex < m_commands.size()
    ) {
      m_commands.get(m_currentCommandIndex).end(true);
    }
    m_currentCommandIndex = -1;
  }

  @Override
  public boolean isFinished() {
    return m_currentCommandIndex == m_commands.size();
  }
}

Your code ends up placing a command sequence (SequentialCommandGroup) inside a perpetual command (PerpetualCommand), as shown in the stack trace.
The PerpetualCommand simply keeps executing a command, ignoring the isFinished result.
That doesn’t work with a SequentialCommandGroup, which needs to be re-initialized after it finishes. See error report on https://github.com/wpilibsuite/allwpilib/issues/2302, which shows some more examples of what doesn’t work.

1 Like

Okay so what is the best way to do what I need to do (hopefully it’s obvious but I’m trying to perpetually repeat a command group until another command finishes.)?

Well, you can’t place a SequentialCommandGroup inside a PerpetualCommand.
But in your teleopPeriodic or autonomousPeriodic you can simply ‘schedule’ a SequentialCommandGroup to keep it running. While the sequence is already running, the added schedule call is ignored, and as soon as it finishes, it’s right away re-scheduled.

Unfortunately I don’t think that is going to work. I’m trying to create a command group that a) waits until the shooter is ready, then b)runs the hopper motors until the shooter detects a ball going through, then waits for it to be ready, etc. Until the specified number of balls have been fired, preferably as passed in through a parameter to a command group.

This may be a good thing to use a builder function for. We ran into some odd constraints with the command sequencing (specifically with trying to re-use complicated parallel subgroups), and this helped us out a lot. I’d start with your basic shot function, setup however it is (quick example here):

Command buildSingleShootSequence(){
  return new 
    RunCommand( ()->{}).withInterrupt( ()-> shooter.isAtTargetRPM() )
    .andThen( InstantCommand( ()->hopper.fireOneBall() ) )
    .andThen( ()->{}).withInterrupt( ()-> hopper.isDone() )
  ;
}

That part I know works great, and lets you do stuff like

auto = buildShootSequence()
.andThen(buildshootsequence())
.andThen(buildShootSequence));

If you wanted to parameterize this further, you should be able to iterate on an object via a loop like this. We don’t loop quite like this, so while it should work, I can’t promise anything about this part.

Command buildMultipleShotSequence(int numshots){
  Command sequence = buildSingleShootSequence();
  for(int i=0; i++ i<numShots){
    sequence = sequence.andThen(buildSingleShootSequence);
  }
}
2 Likes

Would that go in the shooter subsystem?

We’re putting our autos in RobotContainer. Since commands need scope access to all subsystems, trying to put them elsewhere just adds a lot of dependency injection, without making our code notably cleaner. With the exception of our actual shooting process, all our autos are pretty streamlined, and easy to run with the command decorators.

Generally, it’s a bad idea to try to reference other subsystems from another subsystem. This can trap you into circular references, making your code really hard to follow, and likely to lead to null references and crashing. Commands should be the links between subsystems, aided by RobotContainer.

If it helps, our RobotContainer and setup looks something like this.

class RobotContainer{

  SendableChooser<Command> autoChooser = new SendableChooser<>();
  Command fireCenteredAndDriveForward;

  /* Subsystems were actually declared here but aren't meaningful in the context of this example */

  public RobotContainer() {
    configureDefaultCommands();
    configureButtonBindings();
    buildAutoCommands();
    configAutoSelector();
  }

   //We build generate this using a function since it's both parameterized, 
  //and reused multiple times in different autos
  public ParallelDeadlineGroup buildSpinupAndShoot(double targetDistance){
    return    
    new ParallelDeadlineGroup(
      new SequentialCommandGroup(
        new WaitCommand(0.02),
        new RunCommand(()->{}).withInterrupt(()->shooter.isOnTarget()).withTimeout(3),
        new InstantCommand(()->passthrough.shoot()),
        new WaitCommand(0.1),
        new RunCommand(()->{}).withInterrupt(()->passthrough.isOnTarget(1))
      ),
      new ShooterSetRPM(()->Constants.distanceToRPM.getOutputAt(targetDistance),shooter)
    );
  }

  public void configAutoSelector(){
    autoChooser.setDefaultOption("Basic", fireCenteredAndDriveForward);
  }

  public Command getAutonomousCommand() {
    //get values from dashboard
    return autoChooser.getSelected();
  }


  public void buildAutos(){
    fireCenteredAndDriveForward = 
    new ChassisDriveToHeadingBasic(0, ()->0, 3, 0.05, navX, chassis)
    .andThen(buildSpinupAndShoot(110))//Estimated Guess of distance
    .andThen(()->shooter.setRPM(0))
    .andThen(new ChassisDriveToHeadingBasic(1.2, ()->0, 3, 0.05, navX, chassis))
    ;
  }

}

We found that making heavy use of the new convenience commands, command decorators, and lambdas made things pretty straightforward when trying to put together autos. It can cut down on a lot of overly-simple or minor variant Command/CommandGroup files, but make sure you don’t leave stuff in an unwanted state or try to conflict with running DefaultCommands.

If your RobotContainer is getting too lengthy for you, it’s totally reasonable to create a new AutoContainer class just to hold the autos. Just inject all your dependencies to ensure you have proper access within that file, and you can do a very similar process as is shown here.

This topic was automatically closed 365 days after the last reply. New replies are no longer allowed.