|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |
java.lang.Objectedu.wpi.first.wpilibj.RobotDrive
public class RobotDrive
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 standard drive trains are supported. In the future other drive types like swerve and meccanum might be implemented. Motor channel numbers are passed 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 | |
---|---|
static class |
RobotDrive.MotorType
The location of a motor on the robot for the purpose of driving |
Field Summary | |
---|---|
protected static boolean |
kArcadeRatioCurve_Reported
|
protected static boolean |
kArcadeStandard_Reported
|
static double |
kDefaultExpirationTime
|
static double |
kDefaultMaxOutput
|
static double |
kDefaultSensitivity
|
protected static int |
kMaxNumberOfMotors
|
protected static boolean |
kMecanumCartesian_Reported
|
protected static boolean |
kMecanumPolar_Reported
|
protected static boolean |
kTank_Reported
|
protected boolean |
m_allocatedSpeedControllers
|
protected SpeedController |
m_frontLeftMotor
|
protected SpeedController |
m_frontRightMotor
|
protected int[] |
m_invertedMotors
|
protected boolean |
m_isCANInitialized
|
protected double |
m_maxOutput
|
protected SpeedController |
m_rearLeftMotor
|
protected SpeedController |
m_rearRightMotor
|
protected MotorSafetyHelper |
m_safetyHelper
|
protected double |
m_sensitivity
|
Fields inherited from interface edu.wpi.first.wpilibj.MotorSafety |
---|
DEFAULT_SAFETY_EXPIRATION |
Constructor Summary | |
---|---|
RobotDrive(int leftMotorChannel,
int rightMotorChannel)
Constructor for RobotDrive with 2 motors specified with channel numbers. |
|
RobotDrive(int frontLeftMotor,
int rearLeftMotor,
int frontRightMotor,
int rearRightMotor)
Constructor for RobotDrive with 4 motors specified with channel numbers. |
|
RobotDrive(SpeedController leftMotor,
SpeedController rightMotor)
Constructor for RobotDrive with 2 motors specified as SpeedController objects. |
|
RobotDrive(SpeedController frontLeftMotor,
SpeedController rearLeftMotor,
SpeedController frontRightMotor,
SpeedController rearRightMotor)
Constructor for RobotDrive with 4 motors specified as SpeedController objects. |
Method Summary | |
---|---|
void |
arcadeDrive(double moveValue,
double rotateValue)
Arcade drive implements single stick driving. |
void |
arcadeDrive(double moveValue,
double rotateValue,
boolean squaredInputs)
Arcade drive implements single stick driving. |
void |
arcadeDrive(GenericHID stick)
Arcade drive implements single stick driving. |
void |
arcadeDrive(GenericHID stick,
boolean squaredInputs)
Arcade drive implements single stick driving. |
void |
arcadeDrive(GenericHID moveStick,
int moveAxis,
GenericHID rotateStick,
int rotateAxis)
Arcade drive implements single stick driving. |
void |
arcadeDrive(GenericHID moveStick,
int moveAxis,
GenericHID rotateStick,
int rotateAxis,
boolean squaredInputs)
Arcade drive implements single stick driving. |
void |
drive(double outputMagnitude,
double curve)
Drive the motors at "speed" and "curve". |
void |
free()
Free the speed controllers if they were allocated locally |
java.lang.String |
getDescription()
|
double |
getExpiration()
|
protected int |
getNumMotors()
|
boolean |
isAlive()
|
boolean |
isSafetyEnabled()
|
protected static double |
limit(double num)
Limit motor values to the -1.0 to +1.0 range. |
void |
mecanumDrive_Cartesian(double x,
double y,
double rotation,
double gyroAngle)
Drive method for Mecanum wheeled robots. |
void |
mecanumDrive_Polar(double magnitude,
double direction,
double rotation)
Drive method for Mecanum wheeled robots. |
protected static void |
normalize(double[] wheelSpeeds)
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)
Rotate a vector in Cartesian space. |
void |
setExpiration(double timeout)
|
void |
setInvertedMotor(RobotDrive.MotorType motor,
boolean isInverted)
Invert a motor direction. |
void |
setLeftRightMotorOutputs(double leftOutput,
double rightOutput)
Set the speed of the right and left motors. |
void |
setMaxOutput(double maxOutput)
Configure the scaling factor for using RobotDrive with motor controllers in a mode other than PercentVbus. |
void |
setSafetyEnabled(boolean enabled)
|
void |
setSensitivity(double sensitivity)
Set the turning sensitivity. |
void |
stopMotor()
|
void |
tankDrive(double leftValue,
double rightValue)
Provide tank steering using the stored robot configuration. |
void |
tankDrive(double leftValue,
double rightValue,
boolean squaredInputs)
Provide tank steering using the stored robot configuration. |
void |
tankDrive(GenericHID leftStick,
GenericHID rightStick)
Provide tank steering using the stored robot configuration. |
void |
tankDrive(GenericHID leftStick,
GenericHID rightStick,
boolean squaredInputs)
Provide tank steering using the stored robot configuration. |
void |
tankDrive(GenericHID leftStick,
int leftAxis,
GenericHID rightStick,
int rightAxis)
Provide tank steering using the stored robot configuration. |
void |
tankDrive(GenericHID leftStick,
int leftAxis,
GenericHID rightStick,
int rightAxis,
boolean squaredInputs)
Provide tank steering using the stored robot configuration. |
Methods inherited from class java.lang.Object |
---|
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait |
Field Detail |
---|
protected MotorSafetyHelper m_safetyHelper
public static final double kDefaultExpirationTime
public static final double kDefaultSensitivity
public static final double kDefaultMaxOutput
protected static final int kMaxNumberOfMotors
protected final int[] m_invertedMotors
protected double m_sensitivity
protected double m_maxOutput
protected SpeedController m_frontLeftMotor
protected SpeedController m_frontRightMotor
protected SpeedController m_rearLeftMotor
protected SpeedController m_rearRightMotor
protected boolean m_allocatedSpeedControllers
protected boolean m_isCANInitialized
protected static boolean kArcadeRatioCurve_Reported
protected static boolean kTank_Reported
protected static boolean kArcadeStandard_Reported
protected static boolean kMecanumCartesian_Reported
protected static boolean kMecanumPolar_Reported
Constructor Detail |
---|
public RobotDrive(int leftMotorChannel, int rightMotorChannel)
leftMotorChannel
- The PWM channel number on the default digital module that drives the left motor.rightMotorChannel
- The PWM channel number on the default digital module that drives the right motor.public RobotDrive(int frontLeftMotor, int rearLeftMotor, int frontRightMotor, int rearRightMotor)
frontLeftMotor
- Front left motor channel number on the default digital modulerearLeftMotor
- Rear Left motor channel number on the default digital modulefrontRightMotor
- Front right motor channel number on the default digital modulerearRightMotor
- Rear Right motor channel number on the default digital modulepublic RobotDrive(SpeedController leftMotor, SpeedController rightMotor)
leftMotor
- The left SpeedController object used to drive the robot.rightMotor
- the right SpeedController object used to drive the robot.public RobotDrive(SpeedController frontLeftMotor, SpeedController rearLeftMotor, SpeedController frontRightMotor, SpeedController rearRightMotor)
rearLeftMotor
- The back left SpeedController object used to drive the robot.frontLeftMotor
- The front left SpeedController object used to drive the robotrearRightMotor
- The back right SpeedController object used to drive the robot.frontRightMotor
- The front right SpeedController object used to drive the robot.Method Detail |
---|
public void drive(double outputMagnitude, double curve)
outputMagnitude
- The forward component of the output magnitude to send to the motors.curve
- The rate of turn, constant for different forward speeds.public void tankDrive(GenericHID leftStick, GenericHID rightStick)
leftStick
- The joystick to control the left side of the robot.rightStick
- The joystick to control the right side of the robot.public void tankDrive(GenericHID leftStick, GenericHID rightStick, boolean squaredInputs)
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 speedspublic void tankDrive(GenericHID leftStick, int leftAxis, GenericHID rightStick, int rightAxis)
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.public void tankDrive(GenericHID leftStick, int leftAxis, GenericHID rightStick, int rightAxis, boolean squaredInputs)
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 speedspublic void tankDrive(double leftValue, double rightValue, boolean squaredInputs)
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 speedspublic void tankDrive(double leftValue, double rightValue)
leftValue
- The value of the left stick.rightValue
- The value of the right stick.public void arcadeDrive(GenericHID stick, boolean squaredInputs)
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 valuespublic void arcadeDrive(GenericHID stick)
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.public void arcadeDrive(GenericHID moveStick, int moveAxis, GenericHID rotateStick, int rotateAxis, boolean squaredInputs)
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 speedspublic void arcadeDrive(GenericHID moveStick, int moveAxis, GenericHID rotateStick, int rotateAxis)
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)public void arcadeDrive(double moveValue, double rotateValue, boolean squaredInputs)
moveValue
- The value to use for forwards/backwardsrotateValue
- The value to use for the rotate right/leftsquaredInputs
- If set, decreases the sensitivity at low speedspublic void arcadeDrive(double moveValue, double rotateValue)
moveValue
- The value to use for fowards/backwardsrotateValue
- The value to use for the rotate right/leftpublic void mecanumDrive_Cartesian(double x, double y, double rotation, double gyroAngle)
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.public void mecanumDrive_Polar(double magnitude, double direction, double rotation)
magnitude
- The speed that the robot should drive in a given direction.direction
- The direction the robot should drive in degrees. The direction and maginitute are
independent of the rotation rate.rotation
- The rate of rotation for the robot that is completely independent of
the magnitute or direction. [-1.0..1.0]public void setLeftRightMotorOutputs(double leftOutput, double rightOutput)
leftOutput
- The speed to send to the left side of the robot.rightOutput
- The speed to send to the right side of the robot.protected static double limit(double num)
protected static void normalize(double[] wheelSpeeds)
protected static double[] rotateVector(double x, double y, double angle)
public void setInvertedMotor(RobotDrive.MotorType motor, boolean isInverted)
motor
- The motor index to invert.isInverted
- True if the motor should be inverted when operated.public void setSensitivity(double sensitivity)
sensitivity
- Effectively sets the turning sensitivity (or turn radius for a given value)public void setMaxOutput(double maxOutput)
maxOutput
- Multiplied with the output percentage computed by the drive functions.public void free()
public void setExpiration(double timeout)
setExpiration
in interface MotorSafety
public double getExpiration()
getExpiration
in interface MotorSafety
public boolean isAlive()
isAlive
in interface MotorSafety
public boolean isSafetyEnabled()
isSafetyEnabled
in interface MotorSafety
public void setSafetyEnabled(boolean enabled)
setSafetyEnabled
in interface MotorSafety
public java.lang.String getDescription()
getDescription
in interface MotorSafety
public void stopMotor()
stopMotor
in interface MotorSafety
protected int getNumMotors()
|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |