Class DifferentialDrive
- All Implemented Interfaces:
Sendable,AutoCloseable
These drive bases typically have drop-center / skid-steer with two or more wheels per side
(e.g., 6WD or 8WD). This class takes a setter per side. For four and six motor drivetrains, use
CAN motor controller followers or PWMMotorController.addFollower(PWMMotorController).
A differential drive robot has left and right wheels separated by an arbitrary width.
Drive base diagram:
|_______| | | | | | | |_|___|_| | |
Each drive function provides different inverse kinematic relations for a differential drive robot.
This library uses the NWU axes convention (North-West-Up as external reference in the world frame). The positive X axis points ahead, the positive Y axis points to the left, and the positive Z axis points up. Rotations follow the right-hand rule, so counterclockwise rotation around the Z axis is positive.
Inputs smaller then 0.02 will
be set to 0, and larger values will be scaled so that the full range is still used. This deadband
value can be changed with RobotDriveBase.setDeadband(double).
MotorSafety is enabled by default. The tankDrive, arcadeDrive,
or curvatureDrive methods should be called periodically to avoid Motor Safety timeouts.
-
Nested Class Summary
Nested ClassesModifier and TypeClassDescriptionstatic classWheel speeds for a differential drive.Nested classes/interfaces inherited from class edu.wpi.first.wpilibj.drive.RobotDriveBase
RobotDriveBase.MotorType -
Field Summary
Fields inherited from class edu.wpi.first.wpilibj.drive.RobotDriveBase
kDefaultDeadband, kDefaultMaxOutput, m_deadband, m_maxOutput -
Constructor Summary
ConstructorsConstructorDescriptionDifferentialDrive(MotorController leftMotor, MotorController rightMotor) Construct a DifferentialDrive.DifferentialDrive(DoubleConsumer leftMotor, DoubleConsumer rightMotor) Construct a DifferentialDrive. -
Method Summary
Modifier and TypeMethodDescriptionvoidarcadeDrive(double xSpeed, double zRotation) Arcade drive method for differential drive platform.voidarcadeDrive(double xSpeed, double zRotation, boolean squareInputs) Arcade drive method for differential drive platform.arcadeDriveIK(double xSpeed, double zRotation, boolean squareInputs) Arcade drive inverse kinematics for differential drive platform.voidclose()voidcurvatureDrive(double xSpeed, double zRotation, boolean allowTurnInPlace) Curvature drive method for differential drive platform.curvatureDriveIK(double xSpeed, double zRotation, boolean allowTurnInPlace) Curvature drive inverse kinematics for differential drive platform.Returns a description to print when an error occurs.voidinitSendable(SendableBuilder builder) Initializes thisSendableobject.voidCalled to stop the motor when the timeout expires.voidtankDrive(double leftSpeed, double rightSpeed) Tank drive method for differential drive platform.voidtankDrive(double leftSpeed, double rightSpeed, boolean squareInputs) Tank drive method for differential drive platform.tankDriveIK(double leftSpeed, double rightSpeed, boolean squareInputs) Tank drive inverse kinematics for differential drive platform.Methods inherited from class edu.wpi.first.wpilibj.drive.RobotDriveBase
feedWatchdog, normalize, setDeadband, setMaxOutputMethods inherited from class edu.wpi.first.wpilibj.MotorSafety
check, checkMotors, feed, getExpiration, isAlive, isSafetyEnabled, setExpiration, setSafetyEnabled
-
Constructor Details
-
DifferentialDrive
Construct a DifferentialDrive.To pass multiple motors per side, use CAN motor controller followers or
PWMMotorController.addFollower(PWMMotorController). If a motor needs to be inverted, do so before passing it in.- Parameters:
leftMotor- Left motor.rightMotor- Right motor.
-
DifferentialDrive
Construct a DifferentialDrive.To pass multiple motors per side, use CAN motor controller followers or
PWMMotorController.addFollower(PWMMotorController). If a motor needs to be inverted, do so before passing it in.- Parameters:
leftMotor- Left motor setter.rightMotor- Right motor setter.
-
-
Method Details
-
close
- Specified by:
closein interfaceAutoCloseable
-
arcadeDrive
Arcade drive method for differential drive platform. The calculated values will be squared to decrease sensitivity at low speeds.- Parameters:
xSpeed- The robot's speed along the X axis [-1.0..1.0]. Forward is positive.zRotation- The robot's rotation rate around the Z axis [-1.0..1.0]. Counterclockwise is positive.
-
arcadeDrive
Arcade drive method for differential drive platform.- Parameters:
xSpeed- The robot's speed along the X axis [-1.0..1.0]. Forward is positive.zRotation- The robot's rotation rate around the Z axis [-1.0..1.0]. Counterclockwise is positive.squareInputs- If set, decreases the input sensitivity at low speeds.
-
curvatureDrive
Curvature drive method for differential drive platform.The rotation argument controls the curvature of the robot's path rather than its rate of heading change. This makes the robot more controllable at high speeds.
- Parameters:
xSpeed- The robot's speed along the X axis [-1.0..1.0]. Forward is positive.zRotation- The normalized curvature [-1.0..1.0]. Counterclockwise is positive.allowTurnInPlace- If set, overrides constant-curvature turning for turn-in-place maneuvers. zRotation will control turning rate instead of curvature.
-
tankDrive
Tank drive method for differential drive platform. The calculated values will be squared to decrease sensitivity at low speeds.- Parameters:
leftSpeed- The robot's left side speed along the X axis [-1.0..1.0]. Forward is positive.rightSpeed- The robot's right side speed along the X axis [-1.0..1.0]. Forward is positive.
-
tankDrive
Tank drive method for differential drive platform.- Parameters:
leftSpeed- The robot left side's speed along the X axis [-1.0..1.0]. Forward is positive.rightSpeed- The robot right side's speed along the X axis [-1.0..1.0]. Forward is positive.squareInputs- If set, decreases the input sensitivity at low speeds.
-
arcadeDriveIK
public static DifferentialDrive.WheelSpeeds arcadeDriveIK(double xSpeed, double zRotation, boolean squareInputs) Arcade drive inverse kinematics for differential drive platform.- Parameters:
xSpeed- The robot's speed along the X axis [-1.0..1.0]. Forward is positive.zRotation- The robot's rotation rate around the Z axis [-1.0..1.0]. Counterclockwise is positive.squareInputs- If set, decreases the input sensitivity at low speeds.- Returns:
- Wheel speeds [-1.0..1.0].
-
curvatureDriveIK
public static DifferentialDrive.WheelSpeeds curvatureDriveIK(double xSpeed, double zRotation, boolean allowTurnInPlace) Curvature drive inverse kinematics for differential drive platform.The rotation argument controls the curvature of the robot's path rather than its rate of heading change. This makes the robot more controllable at high speeds.
- Parameters:
xSpeed- The robot's speed along the X axis [-1.0..1.0]. Forward is positive.zRotation- The normalized curvature [-1.0..1.0]. Counterclockwise is positive.allowTurnInPlace- If set, overrides constant-curvature turning for turn-in-place maneuvers. zRotation will control rotation rate around the Z axis instead of curvature.- Returns:
- Wheel speeds [-1.0..1.0].
-
tankDriveIK
public static DifferentialDrive.WheelSpeeds tankDriveIK(double leftSpeed, double rightSpeed, boolean squareInputs) Tank drive inverse kinematics for differential drive platform.- Parameters:
leftSpeed- The robot left side's speed along the X axis [-1.0..1.0]. Forward is positive.rightSpeed- The robot right side's speed along the X axis [-1.0..1.0]. Forward is positive.squareInputs- If set, decreases the input sensitivity at low speeds.- Returns:
- Wheel speeds [-1.0..1.0].
-
stopMotor
Description copied from class:MotorSafetyCalled to stop the motor when the timeout expires.- Specified by:
stopMotorin classRobotDriveBase
-
getDescription
Description copied from class:MotorSafetyReturns a description to print when an error occurs.- Specified by:
getDescriptionin classRobotDriveBase- Returns:
- Description to print when an error occurs.
-
initSendable
Description copied from interface:SendableInitializes thisSendableobject.- Specified by:
initSendablein interfaceSendable- Parameters:
builder- sendable builder
-