001/*----------------------------------------------------------------------------*/
002/* Copyright (c) FIRST 2008-2017. All Rights Reserved.                        */
003/* Open Source Software - may be modified and shared by FRC teams. The code   */
004/* must be accompanied by the FIRST BSD license file in the root directory of */
005/* the project.                                                               */
006/*----------------------------------------------------------------------------*/
007
008package edu.wpi.first.wpilibj.command;
009
010import java.util.Enumeration;
011import java.util.Vector;
012
013/**
014 * A {@link CommandGroup} is a list of commands which are executed in sequence.
015 *
016 * <p> Commands in a {@link CommandGroup} are added using the {@link
017 * CommandGroup#addSequential(Command) addSequential(...)} method and are called sequentially.
018 * {@link CommandGroup CommandGroups} are themselves {@link Command commands} and can be given to
019 * other {@link CommandGroup CommandGroups}. </p>
020 *
021 * <p> {@link CommandGroup CommandGroups} will carry all of the requirements of their {@link Command
022 * subcommands}. Additional requirements can be specified by calling {@link
023 * CommandGroup#requires(Subsystem) requires(...)} normally in the constructor. </P>
024 *
025 * <p> CommandGroups can also execute commands in parallel, simply by adding them using {@link
026 * CommandGroup#addParallel(Command) addParallel(...)}. </p>
027 *
028 * @see Command
029 * @see Subsystem
030 * @see IllegalUseOfCommandException
031 */
032public class CommandGroup extends Command {
033
034  /**
035   * The commands in this group (stored in entries).
036   */
037  private final Vector m_commands = new Vector();
038  /*
039   * Intentionally package private
040   */
041  /**
042   * The active children in this group (stored in entries).
043   */
044  final Vector m_children = new Vector();
045  /**
046   * The current command, -1 signifies that none have been run.
047   */
048  private int m_currentCommandIndex = -1;
049
050  /**
051   * Creates a new {@link CommandGroup CommandGroup}. The name of this command will be set to its
052   * class name.
053   */
054  public CommandGroup() {
055  }
056
057  /**
058   * Creates a new {@link CommandGroup CommandGroup} with the given name.
059   *
060   * @param name the name for this command group
061   * @throws IllegalArgumentException if name is null
062   */
063  public CommandGroup(String name) {
064    super(name);
065  }
066
067  /**
068   * Adds a new {@link Command Command} to the group. The {@link Command Command} will be started
069   * after all the previously added {@link Command Commands}.
070   *
071   * <p> Note that any requirements the given {@link Command Command} has will be added to the
072   * group. For this reason, a {@link Command Command's} requirements can not be changed after being
073   * added to a group. </p>
074   *
075   * <p> It is recommended that this method be called in the constructor. </p>
076   *
077   * @param command The {@link Command Command} to be added
078   * @throws IllegalUseOfCommandException if the group has been started before or been given to
079   *                                      another group
080   * @throws IllegalArgumentException     if command is null
081   */
082  public final synchronized void addSequential(Command command) {
083    validate("Can not add new command to command group");
084    if (command == null) {
085      throw new IllegalArgumentException("Given null command");
086    }
087
088    command.setParent(this);
089
090    m_commands.addElement(new Entry(command, Entry.IN_SEQUENCE));
091    for (Enumeration e = command.getRequirements(); e.hasMoreElements(); ) {
092      requires((Subsystem) e.nextElement());
093    }
094  }
095
096  /**
097   * Adds a new {@link Command Command} to the group with a given timeout. The {@link Command
098   * Command} will be started after all the previously added commands.
099   *
100   * <p> Once the {@link Command Command} is started, it will be run until it finishes or the time
101   * expires, whichever is sooner. Note that the given {@link Command Command} will have no
102   * knowledge that it is on a timer. </p>
103   *
104   * <p> Note that any requirements the given {@link Command Command} has will be added to the
105   * group. For this reason, a {@link Command Command's} requirements can not be changed after being
106   * added to a group. </p>
107   *
108   * <p> It is recommended that this method be called in the constructor. </p>
109   *
110   * @param command The {@link Command Command} to be added
111   * @param timeout The timeout (in seconds)
112   * @throws IllegalUseOfCommandException if the group has been started before or been given to
113   *                                      another group or if the {@link Command Command} has been
114   *                                      started before or been given to another group
115   * @throws IllegalArgumentException     if command is null or timeout is negative
116   */
117  public final synchronized void addSequential(Command command, double timeout) {
118    validate("Can not add new command to command group");
119    if (command == null) {
120      throw new IllegalArgumentException("Given null command");
121    }
122    if (timeout < 0) {
123      throw new IllegalArgumentException("Can not be given a negative timeout");
124    }
125
126    command.setParent(this);
127
128    m_commands.addElement(new Entry(command, Entry.IN_SEQUENCE, timeout));
129    for (Enumeration e = command.getRequirements(); e.hasMoreElements(); ) {
130      requires((Subsystem) e.nextElement());
131    }
132  }
133
134  /**
135   * Adds a new child {@link Command} to the group. The {@link Command} will be started after all
136   * the previously added {@link Command Commands}.
137   *
138   * <p> Instead of waiting for the child to finish, a {@link CommandGroup} will have it run at the
139   * same time as the subsequent {@link Command Commands}. The child will run until either it
140   * finishes, a new child with conflicting requirements is started, or the main sequence runs a
141   * {@link Command} with conflicting requirements. In the latter two cases, the child will be
142   * canceled even if it says it can't be interrupted. </p>
143   *
144   * <p> Note that any requirements the given {@link Command Command} has will be added to the
145   * group. For this reason, a {@link Command Command's} requirements can not be changed after being
146   * added to a group. </p>
147   *
148   * <p> It is recommended that this method be called in the constructor. </p>
149   *
150   * @param command The command to be added
151   * @throws IllegalUseOfCommandException if the group has been started before or been given to
152   *                                      another command group
153   * @throws IllegalArgumentException     if command is null
154   */
155  public final synchronized void addParallel(Command command) {
156    validate("Can not add new command to command group");
157    if (command == null) {
158      throw new NullPointerException("Given null command");
159    }
160
161    command.setParent(this);
162
163    m_commands.addElement(new Entry(command, Entry.BRANCH_CHILD));
164    for (Enumeration e = command.getRequirements(); e.hasMoreElements(); ) {
165      requires((Subsystem) e.nextElement());
166    }
167  }
168
169  /**
170   * Adds a new child {@link Command} to the group with the given timeout. The {@link Command} will
171   * be started after all the previously added {@link Command Commands}.
172   *
173   * <p> Once the {@link Command Command} is started, it will run until it finishes, is interrupted,
174   * or the time expires, whichever is sooner. Note that the given {@link Command Command} will have
175   * no knowledge that it is on a timer. </p>
176   *
177   * <p> Instead of waiting for the child to finish, a {@link CommandGroup} will have it run at the
178   * same time as the subsequent {@link Command Commands}. The child will run until either it
179   * finishes, the timeout expires, a new child with conflicting requirements is started, or the
180   * main sequence runs a {@link Command} with conflicting requirements. In the latter two cases,
181   * the child will be canceled even if it says it can't be interrupted. </p>
182   *
183   * <p> Note that any requirements the given {@link Command Command} has will be added to the
184   * group. For this reason, a {@link Command Command's} requirements can not be changed after being
185   * added to a group. </p>
186   *
187   * <p> It is recommended that this method be called in the constructor. </p>
188   *
189   * @param command The command to be added
190   * @param timeout The timeout (in seconds)
191   * @throws IllegalUseOfCommandException if the group has been started before or been given to
192   *                                      another command group
193   * @throws IllegalArgumentException     if command is null
194   */
195  public final synchronized void addParallel(Command command, double timeout) {
196    validate("Can not add new command to command group");
197    if (command == null) {
198      throw new NullPointerException("Given null command");
199    }
200    if (timeout < 0) {
201      throw new IllegalArgumentException("Can not be given a negative timeout");
202    }
203
204    command.setParent(this);
205
206    m_commands.addElement(new Entry(command, Entry.BRANCH_CHILD, timeout));
207    for (Enumeration e = command.getRequirements(); e.hasMoreElements(); ) {
208      requires((Subsystem) e.nextElement());
209    }
210  }
211
212  @SuppressWarnings("MethodName")
213  void _initialize() {
214    m_currentCommandIndex = -1;
215  }
216
217  @SuppressWarnings("MethodName")
218  void _execute() {
219    Entry entry = null;
220    Command cmd = null;
221    boolean firstRun = false;
222    if (m_currentCommandIndex == -1) {
223      firstRun = true;
224      m_currentCommandIndex = 0;
225    }
226
227    while (m_currentCommandIndex < m_commands.size()) {
228
229      if (cmd != null) {
230        if (entry.isTimedOut()) {
231          cmd._cancel();
232        }
233        if (cmd.run()) {
234          break;
235        } else {
236          cmd.removed();
237          m_currentCommandIndex++;
238          firstRun = true;
239          cmd = null;
240          continue;
241        }
242      }
243
244      entry = (Entry) m_commands.elementAt(m_currentCommandIndex);
245      cmd = null;
246
247      switch (entry.m_state) {
248        case Entry.IN_SEQUENCE:
249          cmd = entry.m_command;
250          if (firstRun) {
251            cmd.startRunning();
252            cancelConflicts(cmd);
253          }
254          firstRun = false;
255          break;
256        case Entry.BRANCH_PEER:
257          m_currentCommandIndex++;
258          entry.m_command.start();
259          break;
260        case Entry.BRANCH_CHILD:
261          m_currentCommandIndex++;
262          cancelConflicts(entry.m_command);
263          entry.m_command.startRunning();
264          m_children.addElement(entry);
265          break;
266        default:
267          break;
268      }
269    }
270
271    // Run Children
272    for (int i = 0; i < m_children.size(); i++) {
273      entry = (Entry) m_children.elementAt(i);
274      Command child = entry.m_command;
275      if (entry.isTimedOut()) {
276        child._cancel();
277      }
278      if (!child.run()) {
279        child.removed();
280        m_children.removeElementAt(i--);
281      }
282    }
283  }
284
285  @SuppressWarnings("MethodName")
286  void _end() {
287    // Theoretically, we don't have to check this, but we do if teams override
288    // the isFinished method
289    if (m_currentCommandIndex != -1 && m_currentCommandIndex < m_commands.size()) {
290      Command cmd = ((Entry) m_commands.elementAt(m_currentCommandIndex)).m_command;
291      cmd._cancel();
292      cmd.removed();
293    }
294
295    Enumeration children = m_children.elements();
296    while (children.hasMoreElements()) {
297      Command cmd = ((Entry) children.nextElement()).m_command;
298      cmd._cancel();
299      cmd.removed();
300    }
301    m_children.removeAllElements();
302  }
303
304  @SuppressWarnings("MethodName")
305  void _interrupted() {
306    _end();
307  }
308
309  /**
310   * Returns true if all the {@link Command Commands} in this group have been started and have
311   * finished.
312   *
313   * <p> Teams may override this method, although they should probably reference super.isFinished()
314   * if they do. </p>
315   *
316   * @return whether this {@link CommandGroup} is finished
317   */
318  protected boolean isFinished() {
319    return m_currentCommandIndex >= m_commands.size() && m_children.isEmpty();
320  }
321
322  // Can be overwritten by teams
323  protected void initialize() {
324  }
325
326  // Can be overwritten by teams
327  protected void execute() {
328  }
329
330  // Can be overwritten by teams
331  protected void end() {
332  }
333
334  // Can be overwritten by teams
335  protected void interrupted() {
336  }
337
338  /**
339   * Returns whether or not this group is interruptible. A command group will be uninterruptible if
340   * {@link CommandGroup#setInterruptible(boolean) setInterruptable(false)} was called or if it is
341   * currently running an uninterruptible command or child.
342   *
343   * @return whether or not this {@link CommandGroup} is interruptible.
344   */
345  public synchronized boolean isInterruptible() {
346    if (!super.isInterruptible()) {
347      return false;
348    }
349
350    if (m_currentCommandIndex != -1 && m_currentCommandIndex < m_commands.size()) {
351      Command cmd = ((Entry) m_commands.elementAt(m_currentCommandIndex)).m_command;
352      if (!cmd.isInterruptible()) {
353        return false;
354      }
355    }
356
357    for (int i = 0; i < m_children.size(); i++) {
358      if (!((Entry) m_children.elementAt(i)).m_command.isInterruptible()) {
359        return false;
360      }
361    }
362
363    return true;
364  }
365
366  private void cancelConflicts(Command command) {
367    for (int i = 0; i < m_children.size(); i++) {
368      Command child = ((Entry) m_children.elementAt(i)).m_command;
369
370      Enumeration requirements = command.getRequirements();
371
372      while (requirements.hasMoreElements()) {
373        Object requirement = requirements.nextElement();
374        if (child.doesRequire((Subsystem) requirement)) {
375          child._cancel();
376          child.removed();
377          m_children.removeElementAt(i--);
378          break;
379        }
380      }
381    }
382  }
383
384  private static class Entry {
385
386    private static final int IN_SEQUENCE = 0;
387    private static final int BRANCH_PEER = 1;
388    private static final int BRANCH_CHILD = 2;
389    private final Command m_command;
390    private final int m_state;
391    private final double m_timeout;
392
393    Entry(Command command, int state) {
394      m_command = command;
395      m_state = state;
396      m_timeout = -1;
397    }
398
399    Entry(Command command, int state, double timeout) {
400      m_command = command;
401      m_state = state;
402      m_timeout = timeout;
403    }
404
405    boolean isTimedOut() {
406      if (m_timeout == -1) {
407        return false;
408      } else {
409        double time = m_command.timeSinceInitialized();
410        return time != 0 && time >= m_timeout;
411      }
412    }
413  }
414}