DifferentialDrive
- class wpilib.DifferentialDrive(*args, **kwargs)
Bases:
RobotDriveBase,SendableA class for driving differential drive/skid-steer drive platforms such as the Kit of Parts drive base, “tank drive”, or West Coast Drive.
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 MotorController per side. For four and six motor drivetrains, construct and pass in
MotorControllerGroupinstances as follows.Four motor drivetrain:
import wpilib.drive class Robot(wpilib.TimedRobot): def robotInit(self): self.front_left = wpilib.PWMVictorSPX(1) self.rear_left = wpilib.PWMVictorSPX(2) self.left = wpilib.MotorControllerGroup(self.front_left, self.rear_left) self.front_right = wpilib.PWMVictorSPX(3) self.rear_right = wpilib.PWMVictorSPX(4) self.right = wpilib.MotorControllerGroup(self.front_right, self.rear_right) self.drive = wpilib.drive.DifferentialDrive(self.left, self.right)
Six motor drivetrain:
import wpilib.drive class Robot(wpilib.TimedRobot): def robotInit(self): self.front_left = wpilib.PWMVictorSPX(1) self.mid_left = wpilib.PWMVictorSPX(2) self.rear_left = wpilib.PWMVictorSPX(3) self.left = wpilib.MotorControllerGroup(self.front_left, self.mid_left, self.rear_left) self.front_right = wpilib.PWMVictorSPX(4) self.mid_right = wpilib.PWMVictorSPX(5) self.rear_right = wpilib.PWMVictorSPX(6) self.right = wpilib.MotorControllerGroup(self.front_right, self.mid_right, self.rear_right) self.drive = wpilib.drive.DifferentialDrive(self.left, self.right)
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. Motor outputs for the right side are negated, so motor direction inversion by the user is usually unnecessary.
This library uses the NED axes convention (North-East-Down as external reference in the world frame): http://www.nuclearprojects.com/ins/images/axis_big.png.
The positive X axis points ahead, the positive Y axis points to the right, and the positive Z axis points down. Rotations follow the right-hand rule, so clockwise 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 SetDeadband().
RobotDrive porting guide:
tankDrive()is equivalent toRobotDrive.tankDriveif a deadband of 0 is used.arcadeDrive()is equivalent toRobotDrive.arcadeDriveif a deadband of 0 is used and the the rotation input is inverted, e.g.arcadeDrive(y, -rotation, squareInputs=False)curvatureDrive()is similar in concept toRobotDrive.drivewith the addition of a quick turn mode. However, it is not designed to give exactly the same response.
Overloaded function.
__init__(self: wpilib._wpilib.DifferentialDrive, leftMotor: wpilib._wpilib.MotorController, rightMotor: wpilib._wpilib.MotorController) -> None
Construct a DifferentialDrive.
To pass multiple motors per side, use CAN motor controller followers or PWMMotorController::AddFollower(). If a motor needs to be inverted, do so before passing it in.
- Parameters:
leftMotor – Left motor.
rightMotor – Right motor.
__init__(self: wpilib._wpilib.DifferentialDrive, leftMotor: collections.abc.Callable[[typing.SupportsFloat | typing.SupportsIndex], None], rightMotor: collections.abc.Callable[[typing.SupportsFloat | typing.SupportsIndex], None]) -> None
Construct a DifferentialDrive.
To pass multiple motors per side, use CAN motor controller followers or PWMMotorController::AddFollower(). If a motor needs to be inverted, do so before passing it in.
- Parameters:
leftMotor – Left motor setter.
rightMotor – Right motor setter.
- class WheelVelocities
Bases:
pybind11_objectWheel velocities for a differential drive.
Uses normalized voltage [-1.0..1.0].
- arcadeDrive(xVelocity: SupportsFloat | SupportsIndex, zRotation: SupportsFloat | SupportsIndex, squareInputs: bool = True) None
Arcade drive method for differential drive platform.
Note: Some drivers may prefer inverted rotation controls. This can be done by negating the value passed for rotation.
- Parameters:
xVelocity – The velocity at which the robot should drive along the X axis [-1.0..1.0]. Forward is positive.
zRotation – The rotation rate of the robot around the Z axis [-1.0..1.0]. Counterclockwise is positive.
squareInputs – If set, decreases the input sensitivity at low velocities.
- static arcadeDriveIK(xVelocity: SupportsFloat | SupportsIndex, zRotation: SupportsFloat | SupportsIndex, squareInputs: bool = True) wpilib._wpilib.DifferentialDrive.WheelVelocities
Arcade drive inverse kinematics for differential drive platform.
Note: Some drivers may prefer inverted rotation controls. This can be done by negating the value passed for rotation.
- Parameters:
xVelocity – The velocity at which the robot should drive along the X axis [-1.0..1.0]. Forward is positive.
zRotation – The rotation rate of the robot around the Z axis [-1.0..1.0]. Clockwise is positive.
squareInputs – If set, decreases the input sensitivity at low velocities.
- Returns:
Wheel velocities [-1.0..1.0].
- curvatureDrive(xVelocity: SupportsFloat | SupportsIndex, zRotation: SupportsFloat | SupportsIndex, allowTurnInPlace: bool) None
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 velocities.
- Parameters:
xVelocity – The robot’s velocity 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.
- static curvatureDriveIK(xVelocity: SupportsFloat | SupportsIndex, zRotation: SupportsFloat | SupportsIndex, allowTurnInPlace: bool) wpilib._wpilib.DifferentialDrive.WheelVelocities
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 velocities.
- Parameters:
xVelocity – The robot’s velocity along the X axis [-1.0..1.0]. Forward is positive.
zRotation – The normalized curvature [-1.0..1.0]. Clockwise is positive.
allowTurnInPlace – If set, overrides constant-curvature turning for turn-in-place maneuvers. zRotation will control turning rate instead of curvature.
- Returns:
Wheel velocities [-1.0..1.0].
- getDescription() str
- initSendable(builder: wpiutil._wpiutil.SendableBuilder) None
- stopMotor() None
- tankDrive(leftVelocity: SupportsFloat | SupportsIndex, rightVelocity: SupportsFloat | SupportsIndex, squareInputs: bool = True) None
Tank drive method for differential drive platform.
- Parameters:
leftVelocity – The robot left side’s velocity along the X axis [-1.0..1.0]. Forward is positive.
rightVelocity – The robot right side’s velocity along the X axis [-1.0..1.0]. Forward is positive.
squareInputs – If set, decreases the input sensitivity at low velocities.
- static tankDriveIK(leftVelocity: SupportsFloat | SupportsIndex, rightVelocity: SupportsFloat | SupportsIndex, squareInputs: bool = True) wpilib._wpilib.DifferentialDrive.WheelVelocities
Tank drive inverse kinematics for differential drive platform.
- Parameters:
leftVelocity – The robot left side’s velocity along the X axis [-1.0..1.0]. Forward is positive.
rightVelocity – The robot right side’s velocity along the X axis [-1.0..1.0]. Forward is positive.
squareInputs – If set, decreases the input sensitivity at low velocities.
- Returns:
Wheel velocities [-1.0..1.0].