2010 FRC Java API


edu.wpi.first.wpilibj
Class RobotDrive

java.lang.Object
  extended by edu.wpi.first.wpilibj.RobotDrive

public class RobotDrive
extends Object

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

kDefaultSensitivity

public static final double kDefaultSensitivity
default sensitivity to use when not specified

See Also:
Constant Field Values
Constructor Detail

RobotDrive

public RobotDrive(int leftMotorChannel,
                  int rightMotorChannel,
                  double sensitivity)
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 Jaguars for controlling the motors.

Parameters:
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).

RobotDrive

public RobotDrive(int leftMotorChannel,
                  int rightMotorChannel)
RobotDrive constructor that uses a default sensitivity

Parameters:
leftMotorChannel - Left motor channel
rightMotorChannel - Right motor channel

RobotDrive

public RobotDrive(int frontLeftMotor,
                  int rearLeftMotor,
                  int frontRightMotor,
                  int rearRightMotor,
                  double sensitivity)
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 Jaguars for controlling the motors.

Parameters:
frontLeftMotor - Front left motor channel number on the default digital module
rearLeftMotor - Rear Left motor channel number on the default digital module
frontRightMotor - Front right motor channel number on the default digital module
rearRightMotor - Rear Right motor channel number on the default digital module
sensitivity - Effectively sets the turning sensitivity (or turn radius for a given value)

RobotDrive

public RobotDrive(int frontLeftMotor,
                  int rearLeftMotor,
                  int frontRightMotor,
                  int rearRightMotor)
Constructor for RobotDrive with a default sensitivity

Parameters:
frontLeftMotor - Front left motor port
rearLeftMotor - Rear left motor port
frontRightMotor - Front right motor port
rearRightMotor - Rear right motor port

RobotDrive

public RobotDrive(SpeedController leftMotor,
                  SpeedController rightMotor,
                  double sensitivity)
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 deadband elimination.

Parameters:
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)

RobotDrive

public RobotDrive(SpeedController leftMotor,
                  SpeedController rightMotor)
RobotDrive constructor with SpeedControllers as parameters. Use this method if the speed controllers are not plugged into the default digital sidecar

Parameters:
leftMotor - Left motor port
rightMotor - Right motor port

RobotDrive

public RobotDrive(SpeedController frontLeftMotor,
                  SpeedController rearLeftMotor,
                  SpeedController frontRightMotor,
                  SpeedController rearRightMotor,
                  double sensitivity)
Constructor for RobotDrive with 4 motors specified as SpeedController objects. Speed controller input version of RobotDrive (see previous comments).

Parameters:
rearLeftMotor - The back left SpeedController object used to drive the robot.
frontLeftMotor - The front left SpeedController object used to drive the robot
rearRightMotor - 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)

RobotDrive

public RobotDrive(SpeedController frontLeftMotor,
                  SpeedController rearLeftMotor,
                  SpeedController frontRightMotor,
                  SpeedController rearRightMotor)
Constructor for RobotDrive with 4 motors specified as SpeedController objects. Speed controller input version of RobotDrive (see previous comments).

Parameters:
rearLeftMotor - The back left SpeedController object used to drive the robot.
frontLeftMotor - The front left SpeedController object used to drive the robot
rearRightMotor - The back right SpeedController object used to drive the robot.
frontRightMotor - The front right SpeedController object used to drive the robot.
Method Detail

drive

public void drive(double speed,
                  double curve)
drive the motors at "speed" and "curve". The speed and curve are -1.0 to +1.0 values where 0.0 represents stopped and not turning. The algorithm for adding in the direction attempts to provide a constant turn radius for differing speeds. This function sill most likely be used in an autonomous routine.

Parameters:
speed - The forward component of the speed to send to the motors.
curve - The rate of turn, constant for different forward speeds.

tankDrive

public void tankDrive(GenericHID leftStick,
                      GenericHID rightStick)
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.

tankDrive

public void tankDrive(GenericHID leftStick,
                      int leftAxis,
                      GenericHID rightStick,
                      int rightAxis)
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.

tankDrive

public void tankDrive(double leftValue,
                      double rightValue)
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.

arcadeDrive

public void arcadeDrive(GenericHID stick,
                        boolean squaredInputs)
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 increased for small values

arcadeDrive

public void arcadeDrive(GenericHID stick)
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.

arcadeDrive

public void arcadeDrive(GenericHID moveStick,
                        int moveAxis,
                        GenericHID rotateStick,
                        int rotateAxis,
                        boolean squaredInputs)
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 direction
moveAxis - The axis on the moveStick object to use for fowards/backwards (typically Y_AXIS)
rotateStick - The Joystick object that represents the rotation value
rotateAxis - 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 speeds

arcadeDrive

public void arcadeDrive(GenericHID moveStick,
                        int moveAxis,
                        GenericHID rotateStick,
                        int rotateAxis)
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 direction
moveAxis - The axis on the moveStick object to use for fowards/backwards (typically Y_AXIS)
rotateStick - The Joystick object that represents the rotation value
rotateAxis - 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)
Arcade drive implements single stick driving. This function lets you directly provide joystick values from any source.

Parameters:
moveValue - The value to use for fowards/backwards
rotateValue - The value to use for the rotate right/left
squaredInputs - If set, increases the sensitivity at low speeds

arcadeDrive

public void arcadeDrive(double moveValue,
                        double rotateValue)
Arcade drive implements single stick driving. This function lets you directly provide joystick values from any source.

Parameters:
moveValue - The value to use for fowards/backwards
rotateValue - The value to use for the rotate right/left

holonomicDrive

public void holonomicDrive(double magnitude,
                           double direction,
                           double rotation)
Holonomic drive class for Mecanum wheeled robots. Experimental class 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. For holonomic drive with omni-wheels, the rotation value will need to be offset based on the drive configuration.

Parameters:
magnitude - The speed that the robot should drive in a given direction.
direction - The direction the robot should drive. 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.

setLeftRightMotorSpeeds

public void setLeftRightMotorSpeeds(double leftSpeed,
                                    double rightSpeed)
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:
leftSpeed - The speed to send to the left side of the robot.
rightSpeed - The speed to send to the right side of the robot.

setInvertedMotor

public void setInvertedMotor(RobotDrive.MotorType motor,
                             boolean isInverted)
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.

free

protected void free()
Free the speed controllers if they were allocated locally


2010 FRC Java API


Copyright © 2006-2009 Sun Microsystems, Inc. All Rights Reserved.