001// Copyright (c) FIRST and other WPILib contributors.
002// Open Source Software; you can modify and/or share it under the terms of
003// the WPILib BSD license file in the root directory of this project.
004
005package edu.wpi.first.wpilibj2.command.sysid;
006
007import static edu.wpi.first.units.MutableMeasure.mutable;
008import static edu.wpi.first.units.Units.Second;
009import static edu.wpi.first.units.Units.Seconds;
010import static edu.wpi.first.units.Units.Volts;
011import static java.util.Map.entry;
012
013import edu.wpi.first.units.Measure;
014import edu.wpi.first.units.MutableMeasure;
015import edu.wpi.first.units.Time;
016import edu.wpi.first.units.Velocity;
017import edu.wpi.first.units.Voltage;
018import edu.wpi.first.wpilibj.Timer;
019import edu.wpi.first.wpilibj.sysid.SysIdRoutineLog;
020import edu.wpi.first.wpilibj2.command.Command;
021import edu.wpi.first.wpilibj2.command.Subsystem;
022import java.util.Map;
023import java.util.function.Consumer;
024
025/**
026 * A SysId characterization routine for a single mechanism. Mechanisms may have multiple motors.
027 *
028 * <p>A single subsystem may have multiple mechanisms, but mechanisms should not share test
029 * routines. Each complete test of a mechanism should have its own SysIdRoutine instance, since the
030 * log name of the recorded data is determined by the mechanism name.
031 *
032 * <p>The test state (e.g. "quasistatic-forward") is logged once per iteration during test
033 * execution, and once with state "none" when a test ends. Motor frames are logged every iteration
034 * during test execution.
035 *
036 * <p>Timestamps are not coordinated across data, so motor frames and test state tags may be
037 * recorded on different log frames. Because frame alignment is not guaranteed, SysId parses the log
038 * by using the test state flag to determine the timestamp range for each section of the test, and
039 * then extracts the motor frames within the valid timestamp ranges. If a given test was run
040 * multiple times in a single logfile, the user will need to select which of the tests to use for
041 * the fit in the analysis tool.
042 */
043public class SysIdRoutine extends SysIdRoutineLog {
044  private final Config m_config;
045  private final Mechanism m_mechanism;
046  private final MutableMeasure<Voltage> m_outputVolts = mutable(Volts.of(0));
047  private final Consumer<State> m_recordState;
048
049  /**
050   * Create a new SysId characterization routine.
051   *
052   * @param config Hardware-independent parameters for the SysId routine.
053   * @param mechanism Hardware interface for the SysId routine.
054   */
055  public SysIdRoutine(Config config, Mechanism mechanism) {
056    super(mechanism.m_name);
057    m_config = config;
058    m_mechanism = mechanism;
059    m_recordState = config.m_recordState != null ? config.m_recordState : this::recordState;
060  }
061
062  /** Hardware-independent configuration for a SysId test routine. */
063  public static class Config {
064    /** The voltage ramp rate used for quasistatic test routines. */
065    public final Measure<Velocity<Voltage>> m_rampRate;
066
067    /** The step voltage output used for dynamic test routines. */
068    public final Measure<Voltage> m_stepVoltage;
069
070    /** Safety timeout for the test routine commands. */
071    public final Measure<Time> m_timeout;
072
073    /** Optional handle for recording test state in a third-party logging solution. */
074    public final Consumer<State> m_recordState;
075
076    /**
077     * Create a new configuration for a SysId test routine.
078     *
079     * @param rampRate The voltage ramp rate used for quasistatic test routines. Defaults to 1 volt
080     *     per second if left null.
081     * @param stepVoltage The step voltage output used for dynamic test routines. Defaults to 7
082     *     volts if left null.
083     * @param timeout Safety timeout for the test routine commands. Defaults to 10 seconds if left
084     *     null.
085     * @param recordState Optional handle for recording test state in a third-party logging
086     *     solution. If provided, the test routine state will be passed to this callback instead of
087     *     logged in WPILog.
088     */
089    public Config(
090        Measure<Velocity<Voltage>> rampRate,
091        Measure<Voltage> stepVoltage,
092        Measure<Time> timeout,
093        Consumer<State> recordState) {
094      m_rampRate = rampRate != null ? rampRate : Volts.of(1).per(Seconds.of(1));
095      m_stepVoltage = stepVoltage != null ? stepVoltage : Volts.of(7);
096      m_timeout = timeout != null ? timeout : Seconds.of(10);
097      m_recordState = recordState;
098    }
099
100    /**
101     * Create a new configuration for a SysId test routine.
102     *
103     * @param rampRate The voltage ramp rate used for quasistatic test routines. Defaults to 1 volt
104     *     per second if left null.
105     * @param stepVoltage The step voltage output used for dynamic test routines. Defaults to 7
106     *     volts if left null.
107     * @param timeout Safety timeout for the test routine commands. Defaults to 10 seconds if left
108     *     null.
109     */
110    public Config(
111        Measure<Velocity<Voltage>> rampRate, Measure<Voltage> stepVoltage, Measure<Time> timeout) {
112      this(rampRate, stepVoltage, timeout, null);
113    }
114
115    /**
116     * Create a default configuration for a SysId test routine with all default settings.
117     *
118     * <p>rampRate: 1 volt/sec
119     *
120     * <p>stepVoltage: 7 volts
121     *
122     * <p>timeout: 10 seconds
123     */
124    public Config() {
125      this(null, null, null, null);
126    }
127  }
128
129  /**
130   * A mechanism to be characterized by a SysId routine. Defines callbacks needed for the SysId test
131   * routine to control and record data from the mechanism.
132   */
133  public static class Mechanism {
134    /** Sends the SysId-specified drive signal to the mechanism motors during test routines. */
135    public final Consumer<Measure<Voltage>> m_drive;
136
137    /**
138     * Returns measured data (voltages, positions, velocities) of the mechanism motors during test
139     * routines.
140     */
141    public final Consumer<SysIdRoutineLog> m_log;
142
143    /** The subsystem containing the motor(s) that is (or are) being characterized. */
144    public final Subsystem m_subsystem;
145
146    /** The name of the mechanism being tested. */
147    public final String m_name;
148
149    /**
150     * Create a new mechanism specification for a SysId routine.
151     *
152     * @param drive Sends the SysId-specified drive signal to the mechanism motors during test
153     *     routines.
154     * @param log Returns measured data of the mechanism motors during test routines. To return
155     *     data, call `motor(string motorName)` on the supplied `SysIdRoutineLog` instance, and then
156     *     call one or more of the chainable logging handles (e.g. `voltage`) on the returned
157     *     `MotorLog`. Multiple motors can be logged in a single callback by calling `motor`
158     *     multiple times.
159     * @param subsystem The subsystem containing the motor(s) that is (or are) being characterized.
160     *     Will be declared as a requirement for the returned test commands.
161     * @param name The name of the mechanism being tested. Will be appended to the log entry title
162     *     for the routine's test state, e.g. "sysid-test-state-mechanism". Defaults to the name of
163     *     the subsystem if left null.
164     */
165    public Mechanism(
166        Consumer<Measure<Voltage>> drive,
167        Consumer<SysIdRoutineLog> log,
168        Subsystem subsystem,
169        String name) {
170      m_drive = drive;
171      m_log = log != null ? log : l -> {};
172      m_subsystem = subsystem;
173      m_name = name != null ? name : subsystem.getName();
174    }
175
176    /**
177     * Create a new mechanism specification for a SysId routine. Defaults the mechanism name to the
178     * subsystem name.
179     *
180     * @param drive Sends the SysId-specified drive signal to the mechanism motors during test
181     *     routines.
182     * @param log Returns measured data of the mechanism motors during test routines. To return
183     *     data, call `motor(string motorName)` on the supplied `SysIdRoutineLog` instance, and then
184     *     call one or more of the chainable logging handles (e.g. `voltage`) on the returned
185     *     `MotorLog`. Multiple motors can be logged in a single callback by calling `motor`
186     *     multiple times.
187     * @param subsystem The subsystem containing the motor(s) that is (or are) being characterized.
188     *     Will be declared as a requirement for the returned test commands. The subsystem's `name`
189     *     will be appended to the log entry title for the routine's test state, e.g.
190     *     "sysid-test-state-subsystem".
191     */
192    public Mechanism(
193        Consumer<Measure<Voltage>> drive, Consumer<SysIdRoutineLog> log, Subsystem subsystem) {
194      this(drive, log, subsystem, null);
195    }
196  }
197
198  /** Motor direction for a SysId test. */
199  public enum Direction {
200    /** Forward. */
201    kForward,
202    /** Reverse. */
203    kReverse
204  }
205
206  /**
207   * Returns a command to run a quasistatic test in the specified direction.
208   *
209   * <p>The command will call the `drive` and `log` callbacks supplied at routine construction once
210   * per iteration. Upon command end or interruption, the `drive` callback is called with a value of
211   * 0 volts.
212   *
213   * @param direction The direction in which to run the test.
214   * @return A command to run the test.
215   */
216  public Command quasistatic(Direction direction) {
217    State state;
218    if (direction == Direction.kForward) {
219      state = State.kQuasistaticForward;
220    } else { // if (direction == Direction.kReverse) {
221      state = State.kQuasistaticReverse;
222    }
223
224    double outputSign = direction == Direction.kForward ? 1.0 : -1.0;
225
226    Timer timer = new Timer();
227    return m_mechanism
228        .m_subsystem
229        .runOnce(timer::restart)
230        .andThen(
231            m_mechanism.m_subsystem.run(
232                () -> {
233                  m_mechanism.m_drive.accept(
234                      m_outputVolts.mut_replace(
235                          outputSign * timer.get() * m_config.m_rampRate.in(Volts.per(Second)),
236                          Volts));
237                  m_mechanism.m_log.accept(this);
238                  m_recordState.accept(state);
239                }))
240        .finallyDo(
241            () -> {
242              m_mechanism.m_drive.accept(Volts.of(0));
243              m_recordState.accept(State.kNone);
244              timer.stop();
245            })
246        .withName("sysid-" + state.toString() + "-" + m_mechanism.m_name)
247        .withTimeout(m_config.m_timeout.in(Seconds));
248  }
249
250  /**
251   * Returns a command to run a dynamic test in the specified direction.
252   *
253   * <p>The command will call the `drive` and `log` callbacks supplied at routine construction once
254   * per iteration. Upon command end or interruption, the `drive` callback is called with a value of
255   * 0 volts.
256   *
257   * @param direction The direction in which to run the test.
258   * @return A command to run the test.
259   */
260  public Command dynamic(Direction direction) {
261    double outputSign = direction == Direction.kForward ? 1.0 : -1.0;
262    State state =
263        Map.ofEntries(
264                entry(Direction.kForward, State.kDynamicForward),
265                entry(Direction.kReverse, State.kDynamicReverse))
266            .get(direction);
267
268    return m_mechanism
269        .m_subsystem
270        .runOnce(
271            () -> m_outputVolts.mut_replace(m_config.m_stepVoltage.in(Volts) * outputSign, Volts))
272        .andThen(
273            m_mechanism.m_subsystem.run(
274                () -> {
275                  m_mechanism.m_drive.accept(m_outputVolts);
276                  m_mechanism.m_log.accept(this);
277                  m_recordState.accept(state);
278                }))
279        .finallyDo(
280            () -> {
281              m_mechanism.m_drive.accept(Volts.of(0));
282              m_recordState.accept(State.kNone);
283            })
284        .withName("sysid-" + state.toString() + "-" + m_mechanism.m_name)
285        .withTimeout(m_config.m_timeout.in(Seconds));
286  }
287}