|
2010 FRC Java API |
|||||||||
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 | |
---|---|
static double |
kDefaultSensitivity
default sensitivity to use when not specified |
Constructor Summary | |
---|---|
RobotDrive(int leftMotorChannel,
int rightMotorChannel)
RobotDrive constructor that uses a default sensitivity |
|
RobotDrive(int leftMotorChannel,
int rightMotorChannel,
double sensitivity)
Constructor for RobotDrive with 2 motors specified with channel numbers. |
|
RobotDrive(int frontLeftMotor,
int rearLeftMotor,
int frontRightMotor,
int rearRightMotor)
Constructor for RobotDrive with a default sensitivity |
|
RobotDrive(int frontLeftMotor,
int rearLeftMotor,
int frontRightMotor,
int rearRightMotor,
double sensitivity)
Constructor for RobotDrive with 4 motors specified with channel numbers. |
|
RobotDrive(SpeedController leftMotor,
SpeedController rightMotor)
RobotDrive constructor with SpeedControllers as parameters. |
|
RobotDrive(SpeedController leftMotor,
SpeedController rightMotor,
double sensitivity)
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. |
|
RobotDrive(SpeedController frontLeftMotor,
SpeedController rearLeftMotor,
SpeedController frontRightMotor,
SpeedController rearRightMotor,
double sensitivity)
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 speed,
double curve)
drive the motors at "speed" and "curve". |
protected void |
free()
Free the speed controllers if they were allocated locally |
void |
holonomicDrive(double magnitude,
double direction,
double rotation)
Holonomic drive class for Mecanum wheeled robots. |
void |
setInvertedMotor(RobotDrive.MotorType motor,
boolean isInverted)
Invert a motor direction. |
void |
setLeftRightMotorSpeeds(double leftSpeed,
double rightSpeed)
Set the speed of the right and left motors. |
void |
tankDrive(double leftValue,
double rightValue)
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,
int leftAxis,
GenericHID rightStick,
int rightAxis)
Provide tank steering using the stored robot configuration. |
Methods inherited from class java.lang.Object |
---|
equals, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait |
Field Detail |
---|
public static final double kDefaultSensitivity
Constructor Detail |
---|
public RobotDrive(int leftMotorChannel, int rightMotorChannel, double sensitivity)
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.sensitivity
- Effectively sets the turning sensitivity (or turn radius for a given value).public RobotDrive(int leftMotorChannel, int rightMotorChannel)
leftMotorChannel
- Left motor channelrightMotorChannel
- Right motor channelpublic RobotDrive(int frontLeftMotor, int rearLeftMotor, int frontRightMotor, int rearRightMotor, double sensitivity)
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 modulesensitivity
- Effectively sets the turning sensitivity (or turn radius for a given value)public RobotDrive(int frontLeftMotor, int rearLeftMotor, int frontRightMotor, int rearRightMotor)
frontLeftMotor
- Front left motor portrearLeftMotor
- Rear left motor portfrontRightMotor
- Front right motor portrearRightMotor
- Rear right motor portpublic RobotDrive(SpeedController leftMotor, SpeedController rightMotor, double sensitivity)
leftMotor
- The left SpeedController object used to drive the robot.rightMotor
- the right SpeedController object used to drive the robot.sensitivity
- Effectively sets the turning sensitivity (or turn radius for a given value)public RobotDrive(SpeedController leftMotor, SpeedController rightMotor)
leftMotor
- Left motor portrightMotor
- Right motor portpublic RobotDrive(SpeedController frontLeftMotor, SpeedController rearLeftMotor, SpeedController frontRightMotor, SpeedController rearRightMotor, double sensitivity)
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.sensitivity
- Effectively sets the turning sensitivity (or turn radius for a given value)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 speed, double curve)
speed
- The forward component of the speed 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, 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(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 increased 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 fowards/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 increases 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 fowards/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 fowards/backwardsrotateValue
- The value to use for the rotate right/leftsquaredInputs
- If set, increases 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 holonomicDrive(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.public void setLeftRightMotorSpeeds(double leftSpeed, double rightSpeed)
leftSpeed
- The speed to send to the left side of the robot.rightSpeed
- The speed to send to the right side of the robot.public void setInvertedMotor(RobotDrive.MotorType motor, boolean isInverted)
motor
- The motor index to invert.isInverted
- True if the motor should be inverted when operated.protected void free()
|
2010 FRC Java API |
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | |||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |