![]() |
WPILibC++ 2027.0.0-alpha-4
|
A class for driving differential drive/skid-steer drive platforms such as the Kit of Parts drive base, "tank drive", or West Coast Drive. More...
#include <wpi/drive/DifferentialDrive.hpp>
Classes | |
| struct | WheelVelocities |
| Wheel velocities for a differential drive. More... | |
Public Member Functions | |
| WPI_IGNORE_DEPRECATED | DifferentialDrive (MotorController &leftMotor, MotorController &rightMotor) |
| Construct a DifferentialDrive. | |
| WPI_UNIGNORE_DEPRECATED | DifferentialDrive (std::function< void(double)> leftMotor, std::function< void(double)> rightMotor) |
| Construct a DifferentialDrive. | |
| ~DifferentialDrive () override=default | |
| DifferentialDrive (DifferentialDrive &&)=default | |
| DifferentialDrive & | operator= (DifferentialDrive &&)=default |
| void | ArcadeDrive (double xVelocity, double zRotation, bool squareInputs=true) |
| Arcade drive method for differential drive platform. | |
| void | CurvatureDrive (double xVelocity, double zRotation, bool allowTurnInPlace) |
| Curvature drive method for differential drive platform. | |
| void | TankDrive (double leftVelocity, double rightVelocity, bool squareInputs=true) |
| Tank drive method for differential drive platform. | |
| void | StopMotor () override |
| Called to stop the motor when the timeout expires. | |
| std::string | GetDescription () const override |
| Returns a description to print when an error occurs. | |
| void | InitSendable (wpi::util::SendableBuilder &builder) override |
| Initializes this Sendable object. | |
| Public Member Functions inherited from wpi::RobotDriveBase | |
| RobotDriveBase () | |
| ~RobotDriveBase () override=default | |
| RobotDriveBase (RobotDriveBase &&)=default | |
| RobotDriveBase & | operator= (RobotDriveBase &&)=default |
| void | SetDeadband (double deadband) |
| Sets the deadband applied to the drive inputs (e.g., joystick values). | |
| void | SetMaxOutput (double maxOutput) |
| Configure the scaling factor for using RobotDrive with motor controllers in a mode other than PercentVbus or to limit the maximum output. | |
| void | FeedWatchdog () |
| Feed the motor safety object. | |
| Public Member Functions inherited from wpi::MotorSafety | |
| MotorSafety () | |
| virtual | ~MotorSafety () |
| MotorSafety (MotorSafety &&rhs) | |
| MotorSafety & | operator= (MotorSafety &&rhs) |
| void | Feed () |
| Feed the motor safety object. | |
| void | SetExpiration (wpi::units::second_t expirationTime) |
| Set the expiration time for the corresponding motor safety object. | |
| wpi::units::second_t | GetExpiration () const |
| Retrieve the timeout value for the corresponding motor safety object. | |
| bool | IsAlive () const |
| Determine if the motor is still operating or has timed out. | |
| void | SetSafetyEnabled (bool enabled) |
| Enable/disable motor safety for this device. | |
| bool | IsSafetyEnabled () const |
| Return the state of the motor safety enabled flag. | |
| void | Check () |
| Check if this motor has exceeded its timeout. | |
| Public Member Functions inherited from wpi::util::Sendable | |
| virtual constexpr | ~Sendable ()=default |
| Public Member Functions inherited from wpi::util::SendableHelper< DifferentialDrive > | |
| constexpr | SendableHelper (const SendableHelper &rhs)=default |
| constexpr SendableHelper & | operator= (const SendableHelper &rhs)=default |
Static Public Member Functions | |
| static WheelVelocities | ArcadeDriveIK (double xVelocity, double zRotation, bool squareInputs=true) |
| Arcade drive inverse kinematics for differential drive platform. | |
| static WheelVelocities | CurvatureDriveIK (double xVelocity, double zRotation, bool allowTurnInPlace) |
| Curvature drive inverse kinematics for differential drive platform. | |
| static WheelVelocities | TankDriveIK (double leftVelocity, double rightVelocity, bool squareInputs=true) |
| Tank drive inverse kinematics for differential drive platform. | |
| Static Public Member Functions inherited from wpi::MotorSafety | |
| static void | CheckMotors () |
| Check the motors to see if any have timed out. | |
Additional Inherited Members | |
| Public Types inherited from wpi::RobotDriveBase | |
| enum | MotorType { kFrontLeft = 0 , kFrontRight = 1 , kRearLeft = 2 , kRearRight = 3 , kLeft = 0 , kRight = 1 , kBack = 2 } |
| The location of a motor on the robot for the purpose of driving. More... | |
| Protected Member Functions inherited from wpi::util::SendableHelper< DifferentialDrive > | |
| constexpr | ~SendableHelper () |
| Static Protected Member Functions inherited from wpi::RobotDriveBase | |
| static void | Desaturate (std::span< double > wheelVelocities) |
| Renormalize all wheel velocities if the magnitude of any wheel is greater than 1.0. | |
| Protected Attributes inherited from wpi::RobotDriveBase | |
| double | m_deadband = kDefaultDeadband |
| Input deadband. | |
| double | m_maxOutput = kDefaultMaxOutput |
| Maximum output. | |
| Static Protected Attributes inherited from wpi::RobotDriveBase | |
| static constexpr double | kDefaultDeadband = 0.02 |
| Default input deadband. | |
| static constexpr double | kDefaultMaxOutput = 1.0 |
| Default maximum output. | |
A 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 setter per side. For four and six motor drivetrains, use CAN motor controller followers or PWMMotorController::AddFollower().
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 SetDeadband().
MotorSafety is enabled by default. The tankDrive, arcadeDrive, or curvatureDrive methods should be called periodically to avoid Motor Safety timeouts.
| WPI_IGNORE_DEPRECATED wpi::DifferentialDrive::DifferentialDrive | ( | MotorController & | leftMotor, |
| MotorController & | rightMotor ) |
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.
| leftMotor | Left motor. |
| rightMotor | Right motor. |
| WPI_UNIGNORE_DEPRECATED wpi::DifferentialDrive::DifferentialDrive | ( | std::function< void(double)> | leftMotor, |
| std::function< void(double)> | rightMotor ) |
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.
| leftMotor | Left motor setter. |
| rightMotor | Right motor setter. |
|
overridedefault |
|
default |
| void wpi::DifferentialDrive::ArcadeDrive | ( | double | xVelocity, |
| double | zRotation, | ||
| bool | squareInputs = true ) |
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.
| 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 |
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.
| 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. |
| void wpi::DifferentialDrive::CurvatureDrive | ( | double | xVelocity, |
| double | zRotation, | ||
| bool | allowTurnInPlace ) |
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.
| 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 |
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.
| 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. |
|
overridevirtual |
Returns a description to print when an error occurs.
Implements wpi::RobotDriveBase.
|
overridevirtual |
Initializes this Sendable object.
| builder | sendable builder |
Implements wpi::util::Sendable.
|
default |
|
overridevirtual |
Called to stop the motor when the timeout expires.
Implements wpi::RobotDriveBase.
| void wpi::DifferentialDrive::TankDrive | ( | double | leftVelocity, |
| double | rightVelocity, | ||
| bool | squareInputs = true ) |
Tank drive method for differential drive platform.
| 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 |
Tank drive inverse kinematics for differential drive platform.
| 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. |