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 org.wpilib.drive;
006
007import static org.wpilib.util.ErrorMessages.requireNonNullParam;
008
009import java.util.function.DoubleConsumer;
010import org.wpilib.hardware.hal.HAL;
011import org.wpilib.hardware.motor.MotorController;
012import org.wpilib.math.util.MathUtil;
013import org.wpilib.util.sendable.Sendable;
014import org.wpilib.util.sendable.SendableBuilder;
015import org.wpilib.util.sendable.SendableRegistry;
016
017/**
018 * A class for driving differential drive/skid-steer drive platforms such as the Kit of Parts drive
019 * base, "tank drive", or West Coast Drive.
020 *
021 * <p>These drive bases typically have drop-center / skid-steer with two or more wheels per side
022 * (e.g., 6WD or 8WD). This class takes a setter per side. For four and six motor drivetrains, use
023 * CAN motor controller followers or {@link
024 * org.wpilib.hardware.motor.PWMMotorController#addFollower(PWMMotorController)}.
025 *
026 * <p>A differential drive robot has left and right wheels separated by an arbitrary width.
027 *
028 * <p>Drive base diagram:
029 *
030 * <pre>
031 * |_______|
032 * | |   | |
033 *   |   |
034 * |_|___|_|
035 * |       |
036 * </pre>
037 *
038 * <p>Each drive function provides different inverse kinematic relations for a differential drive
039 * robot.
040 *
041 * <p>This library uses the NWU axes convention (North-West-Up as external reference in the world
042 * frame). The positive X axis points ahead, the positive Y axis points to the left, and the
043 * positive Z axis points up. Rotations follow the right-hand rule, so counterclockwise rotation
044 * around the Z axis is positive.
045 *
046 * <p>Inputs smaller then {@value org.wpilib.drive.RobotDriveBase#DEFAULT_DEADBAND} will be set to
047 * 0, and larger values will be scaled so that the full range is still used. This deadband value can
048 * be changed with {@link #setDeadband}.
049 *
050 * <p>{@link org.wpilib.hardware.motor.MotorSafety} is enabled by default. The tankDrive,
051 * arcadeDrive, or curvatureDrive methods should be called periodically to avoid Motor Safety
052 * timeouts.
053 */
054public class DifferentialDrive extends RobotDriveBase implements Sendable, AutoCloseable {
055  private static int instances;
056
057  private final DoubleConsumer m_leftMotor;
058  private final DoubleConsumer m_rightMotor;
059
060  // Used for Sendable property getters
061  private double m_leftOutput;
062  private double m_rightOutput;
063
064  private boolean m_reported;
065
066  /**
067   * Wheel velocities for a differential drive.
068   *
069   * <p>Uses normalized voltage [-1.0..1.0].
070   */
071  public static class WheelVelocities {
072    /** Left wheel velocity. */
073    public double left;
074
075    /** Right wheel velocity. */
076    public double right;
077
078    /** Constructs a WheelVelocities with zeroes for left and right velocities. */
079    public WheelVelocities() {}
080
081    /**
082     * Constructs a WheelVelocities.
083     *
084     * @param left The left velocity [-1.0..1.0].
085     * @param right The right velocity [-1.0..1.0].
086     */
087    public WheelVelocities(double left, double right) {
088      this.left = left;
089      this.right = right;
090    }
091  }
092
093  /**
094   * Construct a DifferentialDrive.
095   *
096   * <p>To pass multiple motors per side, use CAN motor controller followers or {@link
097   * org.wpilib.hardware.motor.PWMMotorController#addFollower(PWMMotorController)}. If a motor needs
098   * to be inverted, do so before passing it in.
099   *
100   * @param leftMotor Left motor.
101   * @param rightMotor Right motor.
102   */
103  @SuppressWarnings({"removal", "this-escape"})
104  public DifferentialDrive(MotorController leftMotor, MotorController rightMotor) {
105    this(
106        (double output) -> leftMotor.setThrottle(output),
107        (double output) -> rightMotor.setThrottle(output));
108    SendableRegistry.addChild(this, leftMotor);
109    SendableRegistry.addChild(this, rightMotor);
110  }
111
112  /**
113   * Construct a DifferentialDrive.
114   *
115   * <p>To pass multiple motors per side, use CAN motor controller followers or {@link
116   * org.wpilib.hardware.motor.PWMMotorController#addFollower(PWMMotorController)}. If a motor needs
117   * to be inverted, do so before passing it in.
118   *
119   * @param leftMotor Left motor setter.
120   * @param rightMotor Right motor setter.
121   */
122  @SuppressWarnings("this-escape")
123  public DifferentialDrive(DoubleConsumer leftMotor, DoubleConsumer rightMotor) {
124    requireNonNullParam(leftMotor, "leftMotor", "DifferentialDrive");
125    requireNonNullParam(rightMotor, "rightMotor", "DifferentialDrive");
126
127    m_leftMotor = leftMotor;
128    m_rightMotor = rightMotor;
129    instances++;
130    SendableRegistry.add(this, "DifferentialDrive", instances);
131  }
132
133  @Override
134  public void close() {
135    SendableRegistry.remove(this);
136  }
137
138  /**
139   * Arcade drive method for differential drive platform. The calculated values will be squared to
140   * decrease sensitivity at low velocities.
141   *
142   * @param xVelocity The robot's velocity along the X axis [-1.0..1.0]. Forward is positive.
143   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Counterclockwise is
144   *     positive.
145   */
146  public void arcadeDrive(double xVelocity, double zRotation) {
147    arcadeDrive(xVelocity, zRotation, true);
148  }
149
150  /**
151   * Arcade drive method for differential drive platform.
152   *
153   * @param xVelocity The robot's velocity along the X axis [-1.0..1.0]. Forward is positive.
154   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Counterclockwise is
155   *     positive.
156   * @param squareInputs If set, decreases the input sensitivity at low velocities.
157   */
158  public void arcadeDrive(double xVelocity, double zRotation, boolean squareInputs) {
159    if (!m_reported) {
160      HAL.reportUsage("RobotDrive", "DifferentialArcade");
161      m_reported = true;
162    }
163
164    xVelocity = MathUtil.applyDeadband(xVelocity, m_deadband);
165    zRotation = MathUtil.applyDeadband(zRotation, m_deadband);
166
167    var velocities = arcadeDriveIK(xVelocity, zRotation, squareInputs);
168
169    m_leftOutput = velocities.left * m_maxOutput;
170    m_rightOutput = velocities.right * m_maxOutput;
171
172    m_leftMotor.accept(m_leftOutput);
173    m_rightMotor.accept(m_rightOutput);
174
175    feed();
176  }
177
178  /**
179   * Curvature drive method for differential drive platform.
180   *
181   * <p>The rotation argument controls the curvature of the robot's path rather than its rate of
182   * heading change. This makes the robot more controllable at high velocities.
183   *
184   * @param xVelocity The robot's velocity along the X axis [-1.0..1.0]. Forward is positive.
185   * @param zRotation The normalized curvature [-1.0..1.0]. Counterclockwise is positive.
186   * @param allowTurnInPlace If set, overrides constant-curvature turning for turn-in-place
187   *     maneuvers. zRotation will control turning rate instead of curvature.
188   */
189  public void curvatureDrive(double xVelocity, double zRotation, boolean allowTurnInPlace) {
190    if (!m_reported) {
191      HAL.reportUsage("RobotDrive", "DifferentialCurvature");
192      m_reported = true;
193    }
194
195    xVelocity = MathUtil.applyDeadband(xVelocity, m_deadband);
196    zRotation = MathUtil.applyDeadband(zRotation, m_deadband);
197
198    var velocities = curvatureDriveIK(xVelocity, zRotation, allowTurnInPlace);
199
200    m_leftOutput = velocities.left * m_maxOutput;
201    m_rightOutput = velocities.right * m_maxOutput;
202
203    m_leftMotor.accept(m_leftOutput);
204    m_rightMotor.accept(m_rightOutput);
205
206    feed();
207  }
208
209  /**
210   * Tank drive method for differential drive platform. The calculated values will be squared to
211   * decrease sensitivity at low velocities.
212   *
213   * @param leftVelocity The robot's left side velocity along the X axis [-1.0..1.0]. Forward is
214   *     positive.
215   * @param rightVelocity The robot's right side velocity along the X axis [-1.0..1.0]. Forward is
216   *     positive.
217   */
218  public void tankDrive(double leftVelocity, double rightVelocity) {
219    tankDrive(leftVelocity, rightVelocity, true);
220  }
221
222  /**
223   * Tank drive method for differential drive platform.
224   *
225   * @param leftVelocity The robot left side's velocity along the X axis [-1.0..1.0]. Forward is
226   *     positive.
227   * @param rightVelocity The robot right side's velocity along the X axis [-1.0..1.0]. Forward is
228   *     positive.
229   * @param squareInputs If set, decreases the input sensitivity at low velocities.
230   */
231  public void tankDrive(double leftVelocity, double rightVelocity, boolean squareInputs) {
232    if (!m_reported) {
233      HAL.reportUsage("RobotDrive", "DifferentialTank");
234      m_reported = true;
235    }
236
237    leftVelocity = MathUtil.applyDeadband(leftVelocity, m_deadband);
238    rightVelocity = MathUtil.applyDeadband(rightVelocity, m_deadband);
239
240    var velocities = tankDriveIK(leftVelocity, rightVelocity, squareInputs);
241
242    m_leftOutput = velocities.left * m_maxOutput;
243    m_rightOutput = velocities.right * m_maxOutput;
244
245    m_leftMotor.accept(m_leftOutput);
246    m_rightMotor.accept(m_rightOutput);
247
248    feed();
249  }
250
251  /**
252   * Arcade drive inverse kinematics for differential drive platform.
253   *
254   * @param xVelocity The robot's velocity along the X axis [-1.0..1.0]. Forward is positive.
255   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Counterclockwise is
256   *     positive.
257   * @param squareInputs If set, decreases the input sensitivity at low velocities.
258   * @return Wheel velocities [-1.0..1.0].
259   */
260  public static WheelVelocities arcadeDriveIK(
261      double xVelocity, double zRotation, boolean squareInputs) {
262    xVelocity = Math.clamp(xVelocity, -1.0, 1.0);
263    zRotation = Math.clamp(zRotation, -1.0, 1.0);
264
265    // Square the inputs (while preserving the sign) to increase fine control
266    // while permitting full power.
267    if (squareInputs) {
268      xVelocity = MathUtil.copyDirectionPow(xVelocity, 2);
269      zRotation = MathUtil.copyDirectionPow(zRotation, 2);
270    }
271
272    double leftVelocity = xVelocity - zRotation;
273    double rightVelocity = xVelocity + zRotation;
274
275    // Find the maximum possible value of (throttle + turn) along the vector
276    // that the joystick is pointing, then desaturate the wheel velocities
277    double greaterInput = Math.max(Math.abs(xVelocity), Math.abs(zRotation));
278    double lesserInput = Math.min(Math.abs(xVelocity), Math.abs(zRotation));
279    if (greaterInput == 0.0) {
280      return new WheelVelocities(0.0, 0.0);
281    }
282    double saturatedInput = (greaterInput + lesserInput) / greaterInput;
283    leftVelocity /= saturatedInput;
284    rightVelocity /= saturatedInput;
285
286    return new WheelVelocities(leftVelocity, rightVelocity);
287  }
288
289  /**
290   * Curvature drive inverse kinematics for differential drive platform.
291   *
292   * <p>The rotation argument controls the curvature of the robot's path rather than its rate of
293   * heading change. This makes the robot more controllable at high velocities.
294   *
295   * @param xVelocity The robot's velocity along the X axis [-1.0..1.0]. Forward is positive.
296   * @param zRotation The normalized curvature [-1.0..1.0]. Counterclockwise is positive.
297   * @param allowTurnInPlace If set, overrides constant-curvature turning for turn-in-place
298   *     maneuvers. zRotation will control rotation rate around the Z axis instead of curvature.
299   * @return Wheel velocities [-1.0..1.0].
300   */
301  public static WheelVelocities curvatureDriveIK(
302      double xVelocity, double zRotation, boolean allowTurnInPlace) {
303    xVelocity = Math.clamp(xVelocity, -1.0, 1.0);
304    zRotation = Math.clamp(zRotation, -1.0, 1.0);
305
306    double leftVelocity;
307    double rightVelocity;
308
309    if (allowTurnInPlace) {
310      leftVelocity = xVelocity - zRotation;
311      rightVelocity = xVelocity + zRotation;
312    } else {
313      leftVelocity = xVelocity - Math.abs(xVelocity) * zRotation;
314      rightVelocity = xVelocity + Math.abs(xVelocity) * zRotation;
315    }
316
317    // Desaturate wheel velocities
318    double maxMagnitude = Math.max(Math.abs(leftVelocity), Math.abs(rightVelocity));
319    if (maxMagnitude > 1.0) {
320      leftVelocity /= maxMagnitude;
321      rightVelocity /= maxMagnitude;
322    }
323
324    return new WheelVelocities(leftVelocity, rightVelocity);
325  }
326
327  /**
328   * Tank drive inverse kinematics for differential drive platform.
329   *
330   * @param leftVelocity The robot left side's velocity along the X axis [-1.0..1.0]. Forward is
331   *     positive.
332   * @param rightVelocity The robot right side's velocity along the X axis [-1.0..1.0]. Forward is
333   *     positive.
334   * @param squareInputs If set, decreases the input sensitivity at low velocities.
335   * @return Wheel velocities [-1.0..1.0].
336   */
337  public static WheelVelocities tankDriveIK(
338      double leftVelocity, double rightVelocity, boolean squareInputs) {
339    leftVelocity = Math.clamp(leftVelocity, -1.0, 1.0);
340    rightVelocity = Math.clamp(rightVelocity, -1.0, 1.0);
341
342    // Square the inputs (while preserving the sign) to increase fine control
343    // while permitting full power.
344    if (squareInputs) {
345      leftVelocity = MathUtil.copyDirectionPow(leftVelocity, 2);
346      rightVelocity = MathUtil.copyDirectionPow(rightVelocity, 2);
347    }
348
349    return new WheelVelocities(leftVelocity, rightVelocity);
350  }
351
352  @Override
353  public void stopMotor() {
354    m_leftOutput = 0.0;
355    m_rightOutput = 0.0;
356
357    m_leftMotor.accept(0.0);
358    m_rightMotor.accept(0.0);
359
360    feed();
361  }
362
363  @Override
364  public String getDescription() {
365    return "DifferentialDrive";
366  }
367
368  @Override
369  public void initSendable(SendableBuilder builder) {
370    builder.setSmartDashboardType("DifferentialDrive");
371    builder.setActuator(true);
372    builder.addDoubleProperty("Left Motor Velocity", () -> m_leftOutput, m_leftMotor);
373    builder.addDoubleProperty("Right Motor Velocity", () -> m_rightOutput, m_rightMotor);
374  }
375}