Class RobotDrive
- java.lang.Object
-
- edu.wpi.first.wpilibj.MotorSafety
-
- edu.wpi.first.wpilibj.RobotDrive
-
- All Implemented Interfaces:
AutoCloseable
@Deprecated public class RobotDrive extends MotorSafety implements AutoCloseable
Deprecated.UseDifferentialDrive
orMecanumDrive
classes instead.Utility class for handling Robot drive based on a definition of the motor configuration. The robot drive class handles basic driving for a robot. Currently, 2 and 4 motor tank and mecanum drive trains are supported. In the future other drive types like swerve might be implemented. Motor channel numbers are supplied on creation of the class. Those are used for either the drive function (intended for hand created drive code, such as autonomous) or with the Tank/Arcade functions intended to be used for Operator Control driving.
-
-
Nested Class Summary
Nested Classes Modifier and Type Class Description static class
RobotDrive.MotorType
Deprecated.The location of a motor on the robot for the purpose of driving.
-
Field Summary
Fields Modifier and Type Field Description protected static boolean
kArcadeRatioCurve_Reported
Deprecated.protected static boolean
kArcadeStandard_Reported
Deprecated.static double
kDefaultExpirationTime
Deprecated.static double
kDefaultMaxOutput
Deprecated.static double
kDefaultSensitivity
Deprecated.protected static int
kMaxNumberOfMotors
Deprecated.protected static boolean
kMecanumCartesian_Reported
Deprecated.protected static boolean
kMecanumPolar_Reported
Deprecated.protected static boolean
kTank_Reported
Deprecated.protected boolean
m_allocatedSpeedControllers
Deprecated.protected SpeedController
m_frontLeftMotor
Deprecated.protected SpeedController
m_frontRightMotor
Deprecated.protected double
m_maxOutput
Deprecated.protected SpeedController
m_rearLeftMotor
Deprecated.protected SpeedController
m_rearRightMotor
Deprecated.protected double
m_sensitivity
Deprecated.
-
Constructor Summary
Constructors Constructor Description RobotDrive(int leftMotorChannel, int rightMotorChannel)
Deprecated.Constructor for RobotDrive with 2 motors specified with channel numbers.RobotDrive(int frontLeftMotor, int rearLeftMotor, int frontRightMotor, int rearRightMotor)
Deprecated.Constructor for RobotDrive with 4 motors specified with channel numbers.RobotDrive(SpeedController leftMotor, SpeedController rightMotor)
Deprecated.Constructor for RobotDrive with 2 motors specified as SpeedController objects.RobotDrive(SpeedController frontLeftMotor, SpeedController rearLeftMotor, SpeedController frontRightMotor, SpeedController rearRightMotor)
Deprecated.Constructor for RobotDrive with 4 motors specified as SpeedController objects.
-
Method Summary
All Methods Static Methods Instance Methods Concrete Methods Deprecated Methods Modifier and Type Method Description void
arcadeDrive(double moveValue, double rotateValue)
Deprecated.Arcade drive implements single stick driving.void
arcadeDrive(double moveValue, double rotateValue, boolean squaredInputs)
Deprecated.Arcade drive implements single stick driving.void
arcadeDrive(GenericHID stick)
Deprecated.Arcade drive implements single stick driving.void
arcadeDrive(GenericHID stick, boolean squaredInputs)
Deprecated.Arcade drive implements single stick driving.void
arcadeDrive(GenericHID moveStick, int moveAxis, GenericHID rotateStick, int rotateAxis)
Deprecated.Arcade drive implements single stick driving.void
arcadeDrive(GenericHID moveStick, int moveAxis, GenericHID rotateStick, int rotateAxis, boolean squaredInputs)
Deprecated.Arcade drive implements single stick driving.void
close()
Deprecated.Free the speed controllers if they were allocated locally.void
drive(double outputMagnitude, double curve)
Deprecated.Drive the motors at "outputMagnitude" and "curve".void
free()
Deprecated.String
getDescription()
Deprecated.protected int
getNumMotors()
Deprecated.protected static double
limit(double number)
Deprecated.Limit motor values to the -1.0 to +1.0 range.void
mecanumDrive_Cartesian(double x, double y, double rotation, double gyroAngle)
Deprecated.Drive method for Mecanum wheeled robots.void
mecanumDrive_Polar(double magnitude, double direction, double rotation)
Deprecated.Drive method for Mecanum wheeled robots.protected static void
normalize(double[] wheelSpeeds)
Deprecated.Normalize all wheel speeds if the magnitude of any wheel is greater than 1.0.protected static double[]
rotateVector(double x, double y, double angle)
Deprecated.Rotate a vector in Cartesian space.void
setInvertedMotor(RobotDrive.MotorType motor, boolean isInverted)
Deprecated.Invert a motor direction.void
setLeftRightMotorOutputs(double leftOutput, double rightOutput)
Deprecated.Set the speed of the right and left motors.void
setMaxOutput(double maxOutput)
Deprecated.Configure the scaling factor for using RobotDrive with motor controllers in a mode other than PercentVbus.void
setSensitivity(double sensitivity)
Deprecated.Set the turning sensitivity.void
stopMotor()
Deprecated.void
tankDrive(double leftValue, double rightValue)
Deprecated.Provide tank steering using the stored robot configuration.void
tankDrive(double leftValue, double rightValue, boolean squaredInputs)
Deprecated.Provide tank steering using the stored robot configuration.void
tankDrive(GenericHID leftStick, int leftAxis, GenericHID rightStick, int rightAxis)
Deprecated.Provide tank steering using the stored robot configuration.void
tankDrive(GenericHID leftStick, int leftAxis, GenericHID rightStick, int rightAxis, boolean squaredInputs)
Deprecated.Provide tank steering using the stored robot configuration.void
tankDrive(GenericHID leftStick, GenericHID rightStick)
Deprecated.Provide tank steering using the stored robot configuration.void
tankDrive(GenericHID leftStick, GenericHID rightStick, boolean squaredInputs)
Deprecated.Provide tank steering using the stored robot configuration.-
Methods inherited from class edu.wpi.first.wpilibj.MotorSafety
check, checkMotors, feed, getExpiration, isAlive, isSafetyEnabled, setExpiration, setSafetyEnabled
-
-
-
-
Field Detail
-
kDefaultExpirationTime
public static final double kDefaultExpirationTime
Deprecated.- See Also:
- Constant Field Values
-
kDefaultSensitivity
public static final double kDefaultSensitivity
Deprecated.- See Also:
- Constant Field Values
-
kDefaultMaxOutput
public static final double kDefaultMaxOutput
Deprecated.- See Also:
- Constant Field Values
-
kMaxNumberOfMotors
protected static final int kMaxNumberOfMotors
Deprecated.- See Also:
- Constant Field Values
-
m_sensitivity
protected double m_sensitivity
Deprecated.
-
m_maxOutput
protected double m_maxOutput
Deprecated.
-
m_frontLeftMotor
protected SpeedController m_frontLeftMotor
Deprecated.
-
m_frontRightMotor
protected SpeedController m_frontRightMotor
Deprecated.
-
m_rearLeftMotor
protected SpeedController m_rearLeftMotor
Deprecated.
-
m_rearRightMotor
protected SpeedController m_rearRightMotor
Deprecated.
-
m_allocatedSpeedControllers
protected boolean m_allocatedSpeedControllers
Deprecated.
-
kArcadeRatioCurve_Reported
protected static boolean kArcadeRatioCurve_Reported
Deprecated.
-
kTank_Reported
protected static boolean kTank_Reported
Deprecated.
-
kArcadeStandard_Reported
protected static boolean kArcadeStandard_Reported
Deprecated.
-
kMecanumCartesian_Reported
protected static boolean kMecanumCartesian_Reported
Deprecated.
-
kMecanumPolar_Reported
protected static boolean kMecanumPolar_Reported
Deprecated.
-
-
Constructor Detail
-
RobotDrive
public RobotDrive(int leftMotorChannel, int rightMotorChannel)
Deprecated.Constructor for RobotDrive with 2 motors specified with channel numbers. Set up parameters for a two wheel drive system where the left and right motor pwm channels are specified in the call. This call assumes Talons for controlling the motors.- Parameters:
leftMotorChannel
- The PWM channel number that drives the left motor.rightMotorChannel
- The PWM channel number that drives the right motor.
-
RobotDrive
public RobotDrive(int frontLeftMotor, int rearLeftMotor, int frontRightMotor, int rearRightMotor)
Deprecated.Constructor for RobotDrive with 4 motors specified with channel numbers. Set up parameters for a four wheel drive system where all four motor pwm channels are specified in the call. This call assumes Talons for controlling the motors.- Parameters:
frontLeftMotor
- Front left motor channel numberrearLeftMotor
- Rear Left motor channel numberfrontRightMotor
- Front right motor channel numberrearRightMotor
- Rear Right motor channel number
-
RobotDrive
public RobotDrive(SpeedController leftMotor, SpeedController rightMotor)
Deprecated.Constructor for RobotDrive with 2 motors specified as SpeedController objects. The SpeedController version of the constructor enables programs to use the RobotDrive classes with subclasses of the SpeedController objects, for example, versions with ramping or reshaping of the curve to suit motor bias or dead-band elimination.- Parameters:
leftMotor
- The left SpeedController object used to drive the robot.rightMotor
- the right SpeedController object used to drive the robot.
-
RobotDrive
public RobotDrive(SpeedController frontLeftMotor, SpeedController rearLeftMotor, SpeedController frontRightMotor, SpeedController rearRightMotor)
Deprecated.Constructor for RobotDrive with 4 motors specified as SpeedController objects. Speed controller input version of RobotDrive (see previous comments).- Parameters:
frontLeftMotor
- The front left SpeedController object used to drive the robotrearLeftMotor
- The back left SpeedController object used to drive the robot.frontRightMotor
- The front right SpeedController object used to drive the robot.rearRightMotor
- The back right SpeedController object used to drive the robot.
-
-
Method Detail
-
drive
public void drive(double outputMagnitude, double curve)
Deprecated.Drive the motors at "outputMagnitude" and "curve". Both outputMagnitude and curve are -1.0 to +1.0 values, where 0.0 represents stopped and not turning. curve < 0 will turn left and curve > 0 will turn right.The algorithm for steering provides a constant turn radius for any normal speed range, both forward and backward. Increasing sensitivity causes sharper turns for fixed values of curve.
This function will most likely be used in an autonomous routine.
- Parameters:
outputMagnitude
- The speed setting for the outside wheel in a turn, forward or backwards, +1 to -1.curve
- The rate of turn, constant for different forward speeds. Set curve < 0 for left turn or curve > 0 for right turn. Set curve = e^(-r/w) to get a turn radius r for wheelbase w of your robot. Conversely, turn radius r = -ln(curve)*w for a given value of curve and wheelbase w.
-
tankDrive
public void tankDrive(GenericHID leftStick, GenericHID rightStick)
Deprecated.Provide tank steering using the stored robot configuration. drive the robot using two joystick inputs. The Y-axis will be selected from each Joystick object. The calculated values will be squared to decrease sensitivity at low speeds.- Parameters:
leftStick
- The joystick to control the left side of the robot.rightStick
- The joystick to control the right side of the robot.
-
tankDrive
public void tankDrive(GenericHID leftStick, GenericHID rightStick, boolean squaredInputs)
Deprecated.Provide tank steering using the stored robot configuration. drive the robot using two joystick inputs. The Y-axis will be selected from each Joystick object.- Parameters:
leftStick
- The joystick to control the left side of the robot.rightStick
- The joystick to control the right side of the robot.squaredInputs
- Setting this parameter to true decreases the sensitivity at lower speeds
-
tankDrive
public void tankDrive(GenericHID leftStick, int leftAxis, GenericHID rightStick, int rightAxis)
Deprecated.Provide tank steering using the stored robot configuration. This function lets you pick the axis to be used on each Joystick object for the left and right sides of the robot. The calculated values will be squared to decrease sensitivity at low speeds.- Parameters:
leftStick
- The Joystick object to use for the left side of the robot.leftAxis
- The axis to select on the left side Joystick object.rightStick
- The Joystick object to use for the right side of the robot.rightAxis
- The axis to select on the right side Joystick object.
-
tankDrive
public void tankDrive(GenericHID leftStick, int leftAxis, GenericHID rightStick, int rightAxis, boolean squaredInputs)
Deprecated.Provide tank steering using the stored robot configuration. This function lets you pick the axis to be used on each Joystick object for the left and right sides of the robot.- Parameters:
leftStick
- The Joystick object to use for the left side of the robot.leftAxis
- The axis to select on the left side Joystick object.rightStick
- The Joystick object to use for the right side of the robot.rightAxis
- The axis to select on the right side Joystick object.squaredInputs
- Setting this parameter to true decreases the sensitivity at lower speeds
-
tankDrive
public void tankDrive(double leftValue, double rightValue, boolean squaredInputs)
Deprecated.Provide tank steering using the stored robot configuration. This function lets you directly provide joystick values from any source.- Parameters:
leftValue
- The value of the left stick.rightValue
- The value of the right stick.squaredInputs
- Setting this parameter to true decreases the sensitivity at lower speeds
-
tankDrive
public void tankDrive(double leftValue, double rightValue)
Deprecated.Provide tank steering using the stored robot configuration. This function lets you directly provide joystick values from any source. The calculated values will be squared to decrease sensitivity at low speeds.- Parameters:
leftValue
- The value of the left stick.rightValue
- The value of the right stick.
-
arcadeDrive
public void arcadeDrive(GenericHID stick, boolean squaredInputs)
Deprecated.Arcade drive implements single stick driving. Given a single Joystick, the class assumes the Y axis for the move value and the X axis for the rotate value. (Should add more information here regarding the way that arcade drive works.)- Parameters:
stick
- The joystick to use for Arcade single-stick driving. The Y-axis will be selected for forwards/backwards and the X-axis will be selected for rotation rate.squaredInputs
- If true, the sensitivity will be decreased for small values
-
arcadeDrive
public void arcadeDrive(GenericHID stick)
Deprecated.Arcade drive implements single stick driving. Given a single Joystick, the class assumes the Y axis for the move value and the X axis for the rotate value. (Should add more information here regarding the way that arcade drive works.) The calculated values will be squared to decrease sensitivity at low speeds.- Parameters:
stick
- The joystick to use for Arcade single-stick driving. The Y-axis will be selected for forwards/backwards and the X-axis will be selected for rotation rate.
-
arcadeDrive
public void arcadeDrive(GenericHID moveStick, int moveAxis, GenericHID rotateStick, int rotateAxis, boolean squaredInputs)
Deprecated.Arcade drive implements single stick driving. Given two joystick instances and two axis, compute the values to send to either two or four motors.- Parameters:
moveStick
- The Joystick object that represents the forward/backward directionmoveAxis
- The axis on the moveStick object to use for forwards/backwards (typically Y_AXIS)rotateStick
- The Joystick object that represents the rotation valuerotateAxis
- The axis on the rotation object to use for the rotate right/left (typically X_AXIS)squaredInputs
- Setting this parameter to true decreases the sensitivity at lower speeds
-
arcadeDrive
public void arcadeDrive(GenericHID moveStick, int moveAxis, GenericHID rotateStick, int rotateAxis)
Deprecated.Arcade drive implements single stick driving. Given two joystick instances and two axis, compute the values to send to either two or four motors. The calculated values will be squared to decrease sensitivity at low speeds.- Parameters:
moveStick
- The Joystick object that represents the forward/backward directionmoveAxis
- The axis on the moveStick object to use for forwards/backwards (typically Y_AXIS)rotateStick
- The Joystick object that represents the rotation valuerotateAxis
- The axis on the rotation object to use for the rotate right/left (typically X_AXIS)
-
arcadeDrive
public void arcadeDrive(double moveValue, double rotateValue, boolean squaredInputs)
Deprecated.Arcade drive implements single stick driving. This function lets you directly provide joystick values from any source.- Parameters:
moveValue
- The value to use for forwards/backwardsrotateValue
- The value to use for the rotate right/leftsquaredInputs
- If set, decreases the sensitivity at low speeds
-
arcadeDrive
public void arcadeDrive(double moveValue, double rotateValue)
Deprecated.Arcade drive implements single stick driving. This function lets you directly provide joystick values from any source. The calculated values will be squared to decrease sensitivity at low speeds.- Parameters:
moveValue
- The value to use for forwards/backwardsrotateValue
- The value to use for the rotate right/left
-
mecanumDrive_Cartesian
public void mecanumDrive_Cartesian(double x, double y, double rotation, double gyroAngle)
Deprecated.Drive method for Mecanum wheeled robots.A method for driving with Mecanum wheeled robots. There are 4 wheels on the robot, arranged so that the front and back wheels are toed in 45 degrees. When looking at the wheels from the top, the roller axles should form an X across the robot.
This is designed to be directly driven by joystick axes.
- Parameters:
x
- The speed that the robot should drive in the X direction. [-1.0..1.0]y
- The speed that the robot should drive in the Y direction. This input is inverted to match the forward == -1.0 that joysticks produce. [-1.0..1.0]rotation
- The rate of rotation for the robot that is completely independent of the translation. [-1.0..1.0]gyroAngle
- The current angle reading from the gyro. Use this to implement field-oriented controls.
-
mecanumDrive_Polar
public void mecanumDrive_Polar(double magnitude, double direction, double rotation)
Deprecated.Drive method for Mecanum wheeled robots.A method for driving with Mecanum wheeled robots. There are 4 wheels on the robot, arranged so that the front and back wheels are toed in 45 degrees. When looking at the wheels from the top, the roller axles should form an X across the robot.
- Parameters:
magnitude
- The speed that the robot should drive in a given direction. [-1.0..1.0]direction
- The angle the robot should drive in degrees. The direction and magnitude are independent of the rotation rate. [-180.0..180.0]rotation
- The rate of rotation for the robot that is completely independent of the magnitude or direction. [-1.0..1.0]
-
setLeftRightMotorOutputs
public void setLeftRightMotorOutputs(double leftOutput, double rightOutput)
Deprecated.Set the speed of the right and left motors. This is used once an appropriate drive setup function is called such as twoWheelDrive(). The motors are set to "leftSpeed" and "rightSpeed" and includes flipping the direction of one side for opposing motors.- Parameters:
leftOutput
- The speed to send to the left side of the robot.rightOutput
- The speed to send to the right side of the robot.
-
limit
protected static double limit(double number)
Deprecated.Limit motor values to the -1.0 to +1.0 range.
-
normalize
protected static void normalize(double[] wheelSpeeds)
Deprecated.Normalize all wheel speeds if the magnitude of any wheel is greater than 1.0.
-
rotateVector
protected static double[] rotateVector(double x, double y, double angle)
Deprecated.Rotate a vector in Cartesian space.
-
setInvertedMotor
public void setInvertedMotor(RobotDrive.MotorType motor, boolean isInverted)
Deprecated.Invert a motor direction. This is used when a motor should run in the opposite direction as the drive code would normally run it. Motors that are direct drive would be inverted, the drive code assumes that the motors are geared with one reversal.- Parameters:
motor
- The motor index to invert.isInverted
- True if the motor should be inverted when operated.
-
setSensitivity
public void setSensitivity(double sensitivity)
Deprecated.Set the turning sensitivity.This only impacts the drive() entry-point.
- Parameters:
sensitivity
- Effectively sets the turning sensitivity (or turn radius for a given value)
-
setMaxOutput
public void setMaxOutput(double maxOutput)
Deprecated.Configure the scaling factor for using RobotDrive with motor controllers in a mode other than PercentVbus.- Parameters:
maxOutput
- Multiplied with the output percentage computed by the drive functions.
-
free
@Deprecated public void free()
Deprecated.
-
close
public void close()
Deprecated.Free the speed controllers if they were allocated locally.- Specified by:
close
in interfaceAutoCloseable
-
getDescription
public String getDescription()
Deprecated.- Specified by:
getDescription
in classMotorSafety
-
stopMotor
public void stopMotor()
Deprecated.- Specified by:
stopMotor
in classMotorSafety
-
getNumMotors
protected int getNumMotors()
Deprecated.
-
-