001/*----------------------------------------------------------------------------*/
002/* Copyright (c) 2008-2018 FIRST. 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;
009
010import edu.wpi.first.wpilibj.hal.FRCNetComm.tInstances;
011import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
012import edu.wpi.first.wpilibj.hal.HAL;
013
014import static java.util.Objects.requireNonNull;
015
016/**
017 * Utility class for handling Robot drive based on a definition of the motor configuration. The
018 * robot drive class handles basic driving for a robot. Currently, 2 and 4 motor tank and mecanum
019 * drive trains are supported. In the future other drive types like swerve might be implemented.
020 * Motor channel numbers are supplied on creation of the class. Those are used for either the drive
021 * function (intended for hand created drive code, such as autonomous) or with the Tank/Arcade
022 * functions intended to be used for Operator Control driving.
023 *
024 * @deprecated Use {@link edu.wpi.first.wpilibj.drive.DifferentialDrive}
025 *             or {@link edu.wpi.first.wpilibj.drive.MecanumDrive} classes instead.
026 */
027@Deprecated
028public class RobotDrive implements MotorSafety {
029  protected MotorSafetyHelper m_safetyHelper;
030
031  /**
032   * The location of a motor on the robot for the purpose of driving.
033   */
034  public enum MotorType {
035    kFrontLeft(0), kFrontRight(1), kRearLeft(2), kRearRight(3);
036
037    @SuppressWarnings("MemberName")
038    public final int value;
039
040    MotorType(int value) {
041      this.value = value;
042    }
043  }
044
045  public static final double kDefaultExpirationTime = 0.1;
046  public static final double kDefaultSensitivity = 0.5;
047  public static final double kDefaultMaxOutput = 1.0;
048  protected static final int kMaxNumberOfMotors = 4;
049  protected double m_sensitivity;
050  protected double m_maxOutput;
051  protected SpeedController m_frontLeftMotor;
052  protected SpeedController m_frontRightMotor;
053  protected SpeedController m_rearLeftMotor;
054  protected SpeedController m_rearRightMotor;
055  protected boolean m_allocatedSpeedControllers;
056  protected static boolean kArcadeRatioCurve_Reported = false;
057  protected static boolean kTank_Reported = false;
058  protected static boolean kArcadeStandard_Reported = false;
059  protected static boolean kMecanumCartesian_Reported = false;
060  protected static boolean kMecanumPolar_Reported = false;
061
062  /**
063   * Constructor for RobotDrive with 2 motors specified with channel numbers. Set up parameters for
064   * a two wheel drive system where the left and right motor pwm channels are specified in the call.
065   * This call assumes Talons for controlling the motors.
066   *
067   * @param leftMotorChannel  The PWM channel number that drives the left motor.
068   * @param rightMotorChannel The PWM channel number that drives the right motor.
069   */
070  public RobotDrive(final int leftMotorChannel, final int rightMotorChannel) {
071    m_sensitivity = kDefaultSensitivity;
072    m_maxOutput = kDefaultMaxOutput;
073    m_frontLeftMotor = null;
074    m_rearLeftMotor = new Talon(leftMotorChannel);
075    m_frontRightMotor = null;
076    m_rearRightMotor = new Talon(rightMotorChannel);
077    m_allocatedSpeedControllers = true;
078    setupMotorSafety();
079    drive(0, 0);
080  }
081
082  /**
083   * Constructor for RobotDrive with 4 motors specified with channel numbers. Set up parameters for
084   * a four wheel drive system where all four motor pwm channels are specified in the call. This
085   * call assumes Talons for controlling the motors.
086   *
087   * @param frontLeftMotor  Front left motor channel number
088   * @param rearLeftMotor   Rear Left motor channel number
089   * @param frontRightMotor Front right motor channel number
090   * @param rearRightMotor  Rear Right motor channel number
091   */
092  public RobotDrive(final int frontLeftMotor, final int rearLeftMotor, final int frontRightMotor,
093                    final int rearRightMotor) {
094    m_sensitivity = kDefaultSensitivity;
095    m_maxOutput = kDefaultMaxOutput;
096    m_rearLeftMotor = new Talon(rearLeftMotor);
097    m_rearRightMotor = new Talon(rearRightMotor);
098    m_frontLeftMotor = new Talon(frontLeftMotor);
099    m_frontRightMotor = new Talon(frontRightMotor);
100    m_allocatedSpeedControllers = true;
101    setupMotorSafety();
102    drive(0, 0);
103  }
104
105  /**
106   * Constructor for RobotDrive with 2 motors specified as SpeedController objects. The
107   * SpeedController version of the constructor enables programs to use the RobotDrive classes with
108   * subclasses of the SpeedController objects, for example, versions with ramping or reshaping of
109   * the curve to suit motor bias or dead-band elimination.
110   *
111   * @param leftMotor  The left SpeedController object used to drive the robot.
112   * @param rightMotor the right SpeedController object used to drive the robot.
113   */
114  public RobotDrive(SpeedController leftMotor, SpeedController rightMotor) {
115    requireNonNull(leftMotor, "Provided left motor was null");
116    requireNonNull(rightMotor, "Provided right motor was null");
117
118    m_frontLeftMotor = null;
119    m_rearLeftMotor = leftMotor;
120    m_frontRightMotor = null;
121    m_rearRightMotor = rightMotor;
122    m_sensitivity = kDefaultSensitivity;
123    m_maxOutput = kDefaultMaxOutput;
124    m_allocatedSpeedControllers = false;
125    setupMotorSafety();
126    drive(0, 0);
127  }
128
129  /**
130   * Constructor for RobotDrive with 4 motors specified as SpeedController objects. Speed controller
131   * input version of RobotDrive (see previous comments).
132   *
133   * @param frontLeftMotor  The front left SpeedController object used to drive the robot
134   * @param rearLeftMotor   The back left SpeedController object used to drive the robot.
135   * @param frontRightMotor The front right SpeedController object used to drive the robot.
136   * @param rearRightMotor  The back right SpeedController object used to drive the robot.
137   */
138  public RobotDrive(SpeedController frontLeftMotor, SpeedController rearLeftMotor,
139                    SpeedController frontRightMotor, SpeedController rearRightMotor) {
140    m_frontLeftMotor = requireNonNull(frontLeftMotor, "frontLeftMotor cannot be null");
141    m_rearLeftMotor = requireNonNull(rearLeftMotor, "rearLeftMotor cannot be null");
142    m_frontRightMotor = requireNonNull(frontRightMotor, "frontRightMotor cannot be null");
143    m_rearRightMotor = requireNonNull(rearRightMotor, "rearRightMotor cannot be null");
144    m_sensitivity = kDefaultSensitivity;
145    m_maxOutput = kDefaultMaxOutput;
146    m_allocatedSpeedControllers = false;
147    setupMotorSafety();
148    drive(0, 0);
149  }
150
151  /**
152   * Drive the motors at "outputMagnitude" and "curve". Both outputMagnitude and curve are -1.0 to
153   * +1.0 values, where 0.0 represents stopped and not turning. {@literal curve < 0 will turn left
154   * and curve > 0} will turn right.
155   *
156   * <p>The algorithm for steering provides a constant turn radius for any normal speed range, both
157   * forward and backward. Increasing sensitivity causes sharper turns for fixed values of curve.
158   *
159   * <p>This function will most likely be used in an autonomous routine.
160   *
161   * @param outputMagnitude The speed setting for the outside wheel in a turn, forward or backwards,
162   *                        +1 to -1.
163   * @param curve           The rate of turn, constant for different forward speeds. Set {@literal
164   *                        curve < 0 for left turn or curve > 0 for right turn.} Set curve =
165   *                        e^(-r/w) to get a turn radius r for wheelbase w of your robot.
166   *                        Conversely, turn radius r = -ln(curve)*w for a given value of curve and
167   *                        wheelbase w.
168   */
169  public void drive(double outputMagnitude, double curve) {
170    final double leftOutput;
171    final double rightOutput;
172
173    if (!kArcadeRatioCurve_Reported) {
174      HAL.report(tResourceType.kResourceType_RobotDrive, getNumMotors(),
175          tInstances.kRobotDrive_ArcadeRatioCurve);
176      kArcadeRatioCurve_Reported = true;
177    }
178    if (curve < 0) {
179      double value = Math.log(-curve);
180      double ratio = (value - m_sensitivity) / (value + m_sensitivity);
181      if (ratio == 0) {
182        ratio = .0000000001;
183      }
184      leftOutput = outputMagnitude / ratio;
185      rightOutput = outputMagnitude;
186    } else if (curve > 0) {
187      double value = Math.log(curve);
188      double ratio = (value - m_sensitivity) / (value + m_sensitivity);
189      if (ratio == 0) {
190        ratio = .0000000001;
191      }
192      leftOutput = outputMagnitude;
193      rightOutput = outputMagnitude / ratio;
194    } else {
195      leftOutput = outputMagnitude;
196      rightOutput = outputMagnitude;
197    }
198    setLeftRightMotorOutputs(leftOutput, rightOutput);
199  }
200
201  /**
202   * Provide tank steering using the stored robot configuration. drive the robot using two joystick
203   * inputs. The Y-axis will be selected from each Joystick object. The calculated values will be
204   * squared to decrease sensitivity at low speeds.
205   *
206   * @param leftStick  The joystick to control the left side of the robot.
207   * @param rightStick The joystick to control the right side of the robot.
208   */
209  public void tankDrive(GenericHID leftStick, GenericHID rightStick) {
210    requireNonNull(leftStick, "Provided left stick was null");
211    requireNonNull(rightStick, "Provided right stick was null");
212
213    tankDrive(leftStick.getY(), rightStick.getY(), true);
214  }
215
216  /**
217   * Provide tank steering using the stored robot configuration. drive the robot using two joystick
218   * inputs. The Y-axis will be selected from each Joystick object.
219   *
220   * @param leftStick     The joystick to control the left side of the robot.
221   * @param rightStick    The joystick to control the right side of the robot.
222   * @param squaredInputs Setting this parameter to true decreases the sensitivity at lower speeds
223   */
224  public void tankDrive(GenericHID leftStick, GenericHID rightStick, boolean squaredInputs) {
225    requireNonNull(leftStick, "Provided left stick was null");
226    requireNonNull(rightStick, "Provided right stick was null");
227
228    tankDrive(leftStick.getY(), rightStick.getY(), squaredInputs);
229  }
230
231  /**
232   * Provide tank steering using the stored robot configuration. This function lets you pick the
233   * axis to be used on each Joystick object for the left and right sides of the robot. The
234   * calculated values will be squared to decrease sensitivity at low speeds.
235   *
236   * @param leftStick  The Joystick object to use for the left side of the robot.
237   * @param leftAxis   The axis to select on the left side Joystick object.
238   * @param rightStick The Joystick object to use for the right side of the robot.
239   * @param rightAxis  The axis to select on the right side Joystick object.
240   */
241  public void tankDrive(GenericHID leftStick, final int leftAxis, GenericHID rightStick,
242                        final int rightAxis) {
243    requireNonNull(leftStick, "Provided left stick was null");
244    requireNonNull(rightStick, "Provided right stick was null");
245
246    tankDrive(leftStick.getRawAxis(leftAxis), rightStick.getRawAxis(rightAxis), true);
247  }
248
249  /**
250   * Provide tank steering using the stored robot configuration. This function lets you pick the
251   * axis to be used on each Joystick object for the left and right sides of the robot.
252   *
253   * @param leftStick     The Joystick object to use for the left side of the robot.
254   * @param leftAxis      The axis to select on the left side Joystick object.
255   * @param rightStick    The Joystick object to use for the right side of the robot.
256   * @param rightAxis     The axis to select on the right side Joystick object.
257   * @param squaredInputs Setting this parameter to true decreases the sensitivity at lower speeds
258   */
259  public void tankDrive(GenericHID leftStick, final int leftAxis, GenericHID rightStick,
260                        final int rightAxis, boolean squaredInputs) {
261    requireNonNull(leftStick, "Provided left stick was null");
262    requireNonNull(rightStick, "Provided right stick was null");
263
264    tankDrive(leftStick.getRawAxis(leftAxis), rightStick.getRawAxis(rightAxis), squaredInputs);
265  }
266
267  /**
268   * Provide tank steering using the stored robot configuration. This function lets you directly
269   * provide joystick values from any source.
270   *
271   * @param leftValue     The value of the left stick.
272   * @param rightValue    The value of the right stick.
273   * @param squaredInputs Setting this parameter to true decreases the sensitivity at lower speeds
274   */
275  public void tankDrive(double leftValue, double rightValue, boolean squaredInputs) {
276
277    if (!kTank_Reported) {
278      HAL.report(tResourceType.kResourceType_RobotDrive, getNumMotors(),
279          tInstances.kRobotDrive_Tank);
280      kTank_Reported = true;
281    }
282
283    leftValue = limit(leftValue);
284    rightValue = limit(rightValue);
285
286    // square the inputs (while preserving the sign) to increase fine control
287    // while permitting full power
288    if (squaredInputs) {
289      leftValue = Math.copySign(leftValue * leftValue, leftValue);
290      rightValue = Math.copySign(rightValue * rightValue, rightValue);
291    }
292    setLeftRightMotorOutputs(leftValue, rightValue);
293  }
294
295  /**
296   * Provide tank steering using the stored robot configuration. This function lets you directly
297   * provide joystick values from any source. The calculated values will be squared to decrease
298   * sensitivity at low speeds.
299   *
300   * @param leftValue  The value of the left stick.
301   * @param rightValue The value of the right stick.
302   */
303  public void tankDrive(double leftValue, double rightValue) {
304    tankDrive(leftValue, rightValue, true);
305  }
306
307  /**
308   * Arcade drive implements single stick driving. Given a single Joystick, the class assumes the Y
309   * axis for the move value and the X axis for the rotate value. (Should add more information here
310   * regarding the way that arcade drive works.)
311   *
312   * @param stick         The joystick to use for Arcade single-stick driving. The Y-axis will be
313   *                      selected for forwards/backwards and the X-axis will be selected for
314   *                      rotation rate.
315   * @param squaredInputs If true, the sensitivity will be decreased for small values
316   */
317  public void arcadeDrive(GenericHID stick, boolean squaredInputs) {
318    // simply call the full-featured arcadeDrive with the appropriate values
319    arcadeDrive(stick.getY(), stick.getX(), squaredInputs);
320  }
321
322  /**
323   * Arcade drive implements single stick driving. Given a single Joystick, the class assumes the Y
324   * axis for the move value and the X axis for the rotate value. (Should add more information here
325   * regarding the way that arcade drive works.) The calculated values will be squared to decrease
326   * sensitivity at low speeds.
327   *
328   * @param stick The joystick to use for Arcade single-stick driving. The Y-axis will be selected
329   *              for forwards/backwards and the X-axis will be selected for rotation rate.
330   */
331  public void arcadeDrive(GenericHID stick) {
332    arcadeDrive(stick, true);
333  }
334
335  /**
336   * Arcade drive implements single stick driving. Given two joystick instances and two axis,
337   * compute the values to send to either two or four motors.
338   *
339   * @param moveStick     The Joystick object that represents the forward/backward direction
340   * @param moveAxis      The axis on the moveStick object to use for forwards/backwards (typically
341   *                      Y_AXIS)
342   * @param rotateStick   The Joystick object that represents the rotation value
343   * @param rotateAxis    The axis on the rotation object to use for the rotate right/left
344   *                      (typically X_AXIS)
345   * @param squaredInputs Setting this parameter to true decreases the sensitivity at lower speeds
346   */
347  public void arcadeDrive(GenericHID moveStick, final int moveAxis, GenericHID rotateStick,
348                          final int rotateAxis, boolean squaredInputs) {
349    double moveValue = moveStick.getRawAxis(moveAxis);
350    double rotateValue = rotateStick.getRawAxis(rotateAxis);
351
352    arcadeDrive(moveValue, rotateValue, squaredInputs);
353  }
354
355  /**
356   * Arcade drive implements single stick driving. Given two joystick instances and two axis,
357   * compute the values to send to either two or four motors. The calculated values will be
358   * squared to decrease sensitivity at low speeds.
359   *
360   * @param moveStick   The Joystick object that represents the forward/backward direction
361   * @param moveAxis    The axis on the moveStick object to use for forwards/backwards (typically
362   *                    Y_AXIS)
363   * @param rotateStick The Joystick object that represents the rotation value
364   * @param rotateAxis  The axis on the rotation object to use for the rotate right/left (typically
365   *                    X_AXIS)
366   */
367  public void arcadeDrive(GenericHID moveStick, final int moveAxis, GenericHID rotateStick,
368                          final int rotateAxis) {
369    arcadeDrive(moveStick, moveAxis, rotateStick, rotateAxis, true);
370  }
371
372  /**
373   * Arcade drive implements single stick driving. This function lets you directly provide
374   * joystick values from any source.
375   *
376   * @param moveValue     The value to use for forwards/backwards
377   * @param rotateValue   The value to use for the rotate right/left
378   * @param squaredInputs If set, decreases the sensitivity at low speeds
379   */
380  public void arcadeDrive(double moveValue, double rotateValue, boolean squaredInputs) {
381    // local variables to hold the computed PWM values for the motors
382    if (!kArcadeStandard_Reported) {
383      HAL.report(tResourceType.kResourceType_RobotDrive, getNumMotors(),
384          tInstances.kRobotDrive_ArcadeStandard);
385      kArcadeStandard_Reported = true;
386    }
387
388    double leftMotorSpeed;
389    double rightMotorSpeed;
390
391    moveValue = limit(moveValue);
392    rotateValue = limit(rotateValue);
393
394    // square the inputs (while preserving the sign) to increase fine control
395    // while permitting full power
396    if (squaredInputs) {
397      // square the inputs (while preserving the sign) to increase fine control
398      // while permitting full power
399      moveValue = Math.copySign(moveValue * moveValue, moveValue);
400      rotateValue = Math.copySign(rotateValue * rotateValue, rotateValue);
401    }
402
403    if (moveValue > 0.0) {
404      if (rotateValue > 0.0) {
405        leftMotorSpeed = moveValue - rotateValue;
406        rightMotorSpeed = Math.max(moveValue, rotateValue);
407      } else {
408        leftMotorSpeed = Math.max(moveValue, -rotateValue);
409        rightMotorSpeed = moveValue + rotateValue;
410      }
411    } else {
412      if (rotateValue > 0.0) {
413        leftMotorSpeed = -Math.max(-moveValue, rotateValue);
414        rightMotorSpeed = moveValue + rotateValue;
415      } else {
416        leftMotorSpeed = moveValue - rotateValue;
417        rightMotorSpeed = -Math.max(-moveValue, -rotateValue);
418      }
419    }
420
421    setLeftRightMotorOutputs(leftMotorSpeed, rightMotorSpeed);
422  }
423
424  /**
425   * Arcade drive implements single stick driving. This function lets you directly provide
426   * joystick values from any source. The calculated values will be squared to decrease
427   * sensitivity at low speeds.
428   *
429   * @param moveValue   The value to use for forwards/backwards
430   * @param rotateValue The value to use for the rotate right/left
431   */
432  public void arcadeDrive(double moveValue, double rotateValue) {
433    arcadeDrive(moveValue, rotateValue, true);
434  }
435
436  /**
437   * Drive method for Mecanum wheeled robots.
438   *
439   * <p>A method for driving with Mecanum wheeled robots. There are 4 wheels on the robot, arranged
440   * so that the front and back wheels are toed in 45 degrees. When looking at the wheels from the
441   * top, the roller axles should form an X across the robot.
442   *
443   * <p>This is designed to be directly driven by joystick axes.
444   *
445   * @param x         The speed that the robot should drive in the X direction. [-1.0..1.0]
446   * @param y         The speed that the robot should drive in the Y direction. This input is
447   *                  inverted to match the forward == -1.0 that joysticks produce. [-1.0..1.0]
448   * @param rotation  The rate of rotation for the robot that is completely independent of the
449   *                  translation. [-1.0..1.0]
450   * @param gyroAngle The current angle reading from the gyro. Use this to implement field-oriented
451   *                  controls.
452   */
453  @SuppressWarnings("ParameterName")
454  public void mecanumDrive_Cartesian(double x, double y, double rotation, double gyroAngle) {
455    if (!kMecanumCartesian_Reported) {
456      HAL.report(tResourceType.kResourceType_RobotDrive, getNumMotors(),
457          tInstances.kRobotDrive_MecanumCartesian);
458      kMecanumCartesian_Reported = true;
459    }
460    @SuppressWarnings("LocalVariableName")
461    double xIn = x;
462    @SuppressWarnings("LocalVariableName")
463    double yIn = y;
464    // Negate y for the joystick.
465    yIn = -yIn;
466    // Compensate for gyro angle.
467    double[] rotated = rotateVector(xIn, yIn, gyroAngle);
468    xIn = rotated[0];
469    yIn = rotated[1];
470
471    double[] wheelSpeeds = new double[kMaxNumberOfMotors];
472    wheelSpeeds[MotorType.kFrontLeft.value] = xIn + yIn + rotation;
473    wheelSpeeds[MotorType.kFrontRight.value] = -xIn + yIn - rotation;
474    wheelSpeeds[MotorType.kRearLeft.value] = -xIn + yIn + rotation;
475    wheelSpeeds[MotorType.kRearRight.value] = xIn + yIn - rotation;
476
477    normalize(wheelSpeeds);
478    m_frontLeftMotor.set(wheelSpeeds[MotorType.kFrontLeft.value] * m_maxOutput);
479    m_frontRightMotor.set(wheelSpeeds[MotorType.kFrontRight.value] * m_maxOutput);
480    m_rearLeftMotor.set(wheelSpeeds[MotorType.kRearLeft.value] * m_maxOutput);
481    m_rearRightMotor.set(wheelSpeeds[MotorType.kRearRight.value] * m_maxOutput);
482
483    if (m_safetyHelper != null) {
484      m_safetyHelper.feed();
485    }
486  }
487
488  /**
489   * Drive method for Mecanum wheeled robots.
490   *
491   * <p>A method for driving with Mecanum wheeled robots. There are 4 wheels on the robot, arranged
492   * so that the front and back wheels are toed in 45 degrees. When looking at the wheels from the
493   * top, the roller axles should form an X across the robot.
494   *
495   * @param magnitude The speed that the robot should drive in a given direction. [-1.0..1.0]
496   * @param direction The angle the robot should drive in degrees. The direction and magnitude
497   *                  are independent of the rotation rate. [-180.0..180.0]
498   * @param rotation  The rate of rotation for the robot that is completely independent of the
499   *                  magnitude or direction. [-1.0..1.0]
500   */
501  public void mecanumDrive_Polar(double magnitude, double direction, double rotation) {
502    if (!kMecanumPolar_Reported) {
503      HAL.report(tResourceType.kResourceType_RobotDrive, getNumMotors(),
504          tInstances.kRobotDrive_MecanumPolar);
505      kMecanumPolar_Reported = true;
506    }
507    // Normalized for full power along the Cartesian axes.
508    magnitude = limit(magnitude) * Math.sqrt(2.0);
509    // The rollers are at 45 degree angles.
510    double dirInRad = (direction + 45.0) * Math.PI / 180.0;
511    double cosD = Math.cos(dirInRad);
512    double sinD = Math.sin(dirInRad);
513
514    double[] wheelSpeeds = new double[kMaxNumberOfMotors];
515    wheelSpeeds[MotorType.kFrontLeft.value] = sinD * magnitude + rotation;
516    wheelSpeeds[MotorType.kFrontRight.value] = cosD * magnitude - rotation;
517    wheelSpeeds[MotorType.kRearLeft.value] = cosD * magnitude + rotation;
518    wheelSpeeds[MotorType.kRearRight.value] = sinD * magnitude - rotation;
519
520    normalize(wheelSpeeds);
521
522    m_frontLeftMotor.set(wheelSpeeds[MotorType.kFrontLeft.value] * m_maxOutput);
523    m_frontRightMotor.set(wheelSpeeds[MotorType.kFrontRight.value] * m_maxOutput);
524    m_rearLeftMotor.set(wheelSpeeds[MotorType.kRearLeft.value] * m_maxOutput);
525    m_rearRightMotor.set(wheelSpeeds[MotorType.kRearRight.value] * m_maxOutput);
526
527    if (m_safetyHelper != null) {
528      m_safetyHelper.feed();
529    }
530  }
531
532  /**
533   * Holonomic Drive method for Mecanum wheeled robots.
534   *
535   * <p>This is an alias to mecanumDrive_Polar() for backward compatibility
536   *
537   * @param magnitude The speed that the robot should drive in a given direction. [-1.0..1.0]
538   * @param direction The direction the robot should drive. The direction and maginitude are
539   *                  independent of the rotation rate.
540   * @param rotation  The rate of rotation for the robot that is completely independent of the
541   *                  magnitute or direction. [-1.0..1.0]
542   */
543  void holonomicDrive(double magnitude, double direction, double rotation) {
544    mecanumDrive_Polar(magnitude, direction, rotation);
545  }
546
547  /**
548   * Set the speed of the right and left motors. This is used once an appropriate drive setup
549   * function is called such as twoWheelDrive(). The motors are set to "leftSpeed" and
550   * "rightSpeed" and includes flipping the direction of one side for opposing motors.
551   *
552   * @param leftOutput  The speed to send to the left side of the robot.
553   * @param rightOutput The speed to send to the right side of the robot.
554   */
555  public void setLeftRightMotorOutputs(double leftOutput, double rightOutput) {
556    requireNonNull(m_rearLeftMotor, "Provided left motor was null");
557    requireNonNull(m_rearRightMotor, "Provided right motor was null");
558
559    if (m_frontLeftMotor != null) {
560      m_frontLeftMotor.set(limit(leftOutput) * m_maxOutput);
561    }
562    m_rearLeftMotor.set(limit(leftOutput) * m_maxOutput);
563
564    if (m_frontRightMotor != null) {
565      m_frontRightMotor.set(-limit(rightOutput) * m_maxOutput);
566    }
567    m_rearRightMotor.set(-limit(rightOutput) * m_maxOutput);
568
569    if (m_safetyHelper != null) {
570      m_safetyHelper.feed();
571    }
572  }
573
574  /**
575   * Limit motor values to the -1.0 to +1.0 range.
576   */
577  protected static double limit(double number) {
578    if (number > 1.0) {
579      return 1.0;
580    }
581    if (number < -1.0) {
582      return -1.0;
583    }
584    return number;
585  }
586
587  /**
588   * Normalize all wheel speeds if the magnitude of any wheel is greater than 1.0.
589   */
590  protected static void normalize(double[] wheelSpeeds) {
591    double maxMagnitude = Math.abs(wheelSpeeds[0]);
592    for (int i = 1; i < kMaxNumberOfMotors; i++) {
593      double temp = Math.abs(wheelSpeeds[i]);
594      if (maxMagnitude < temp) {
595        maxMagnitude = temp;
596      }
597    }
598    if (maxMagnitude > 1.0) {
599      for (int i = 0; i < kMaxNumberOfMotors; i++) {
600        wheelSpeeds[i] = wheelSpeeds[i] / maxMagnitude;
601      }
602    }
603  }
604
605  /**
606   * Rotate a vector in Cartesian space.
607   */
608  @SuppressWarnings("ParameterName")
609  protected static double[] rotateVector(double x, double y, double angle) {
610    double cosA = Math.cos(angle * (Math.PI / 180.0));
611    double sinA = Math.sin(angle * (Math.PI / 180.0));
612    double[] out = new double[2];
613    out[0] = x * cosA - y * sinA;
614    out[1] = x * sinA + y * cosA;
615    return out;
616  }
617
618  /**
619   * Invert a motor direction. This is used when a motor should run in the opposite direction as the
620   * drive code would normally run it. Motors that are direct drive would be inverted, the drive
621   * code assumes that the motors are geared with one reversal.
622   *
623   * @param motor      The motor index to invert.
624   * @param isInverted True if the motor should be inverted when operated.
625   */
626  public void setInvertedMotor(MotorType motor, boolean isInverted) {
627    switch (motor) {
628      case kFrontLeft:
629        m_frontLeftMotor.setInverted(isInverted);
630        break;
631      case kFrontRight:
632        m_frontRightMotor.setInverted(isInverted);
633        break;
634      case kRearLeft:
635        m_rearLeftMotor.setInverted(isInverted);
636        break;
637      case kRearRight:
638        m_rearRightMotor.setInverted(isInverted);
639        break;
640      default:
641        throw new IllegalArgumentException("Illegal motor type: " + motor);
642    }
643  }
644
645  /**
646   * Set the turning sensitivity.
647   *
648   * <p>This only impacts the drive() entry-point.
649   *
650   * @param sensitivity Effectively sets the turning sensitivity (or turn radius for a given value)
651   */
652  public void setSensitivity(double sensitivity) {
653    m_sensitivity = sensitivity;
654  }
655
656  /**
657   * Configure the scaling factor for using RobotDrive with motor controllers in a mode other than
658   * PercentVbus.
659   *
660   * @param maxOutput Multiplied with the output percentage computed by the drive functions.
661   */
662  public void setMaxOutput(double maxOutput) {
663    m_maxOutput = maxOutput;
664  }
665
666  /**
667   * Free the speed controllers if they were allocated locally.
668   */
669  public void free() {
670    if (m_allocatedSpeedControllers) {
671      if (m_frontLeftMotor != null) {
672        ((PWM) m_frontLeftMotor).free();
673      }
674      if (m_frontRightMotor != null) {
675        ((PWM) m_frontRightMotor).free();
676      }
677      if (m_rearLeftMotor != null) {
678        ((PWM) m_rearLeftMotor).free();
679      }
680      if (m_rearRightMotor != null) {
681        ((PWM) m_rearRightMotor).free();
682      }
683    }
684  }
685
686  @Override
687  public void setExpiration(double timeout) {
688    m_safetyHelper.setExpiration(timeout);
689  }
690
691  @Override
692  public double getExpiration() {
693    return m_safetyHelper.getExpiration();
694  }
695
696  @Override
697  public boolean isAlive() {
698    return m_safetyHelper.isAlive();
699  }
700
701  @Override
702  public boolean isSafetyEnabled() {
703    return m_safetyHelper.isSafetyEnabled();
704  }
705
706  @Override
707  public void setSafetyEnabled(boolean enabled) {
708    m_safetyHelper.setSafetyEnabled(enabled);
709  }
710
711  @Override
712  public String getDescription() {
713    return "Robot Drive";
714  }
715
716  @Override
717  public void stopMotor() {
718    if (m_frontLeftMotor != null) {
719      m_frontLeftMotor.stopMotor();
720    }
721    if (m_frontRightMotor != null) {
722      m_frontRightMotor.stopMotor();
723    }
724    if (m_rearLeftMotor != null) {
725      m_rearLeftMotor.stopMotor();
726    }
727    if (m_rearRightMotor != null) {
728      m_rearRightMotor.stopMotor();
729    }
730    if (m_safetyHelper != null) {
731      m_safetyHelper.feed();
732    }
733  }
734
735  private void setupMotorSafety() {
736    m_safetyHelper = new MotorSafetyHelper(this);
737    m_safetyHelper.setExpiration(kDefaultExpirationTime);
738    m_safetyHelper.setSafetyEnabled(true);
739  }
740
741  protected int getNumMotors() {
742    int motors = 0;
743    if (m_frontLeftMotor != null) {
744      motors++;
745    }
746    if (m_frontRightMotor != null) {
747      motors++;
748    }
749    if (m_rearLeftMotor != null) {
750      motors++;
751    }
752    if (m_rearRightMotor != null) {
753      motors++;
754    }
755    return motors;
756  }
757}