WPILibC++
2018.4.1-20180819050225-1157-gb44f27d
|
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 <DifferentialDrive.h>
Public Member Functions | |
DifferentialDrive (SpeedController &leftMotor, SpeedController &rightMotor) | |
Construct a DifferentialDrive. More... | |
DifferentialDrive (const DifferentialDrive &)=delete | |
DifferentialDrive & | operator= (const DifferentialDrive &)=delete |
void | ArcadeDrive (double xSpeed, double zRotation, bool squaredInputs=true) |
Arcade drive method for differential drive platform. More... | |
void | CurvatureDrive (double xSpeed, double zRotation, bool isQuickTurn) |
Curvature drive method for differential drive platform. More... | |
void | TankDrive (double leftSpeed, double rightSpeed, bool squaredInputs=true) |
Tank drive method for differential drive platform. More... | |
void | SetQuickStopThreshold (double threshold) |
Sets the QuickStop speed threshold in curvature drive. More... | |
void | SetQuickStopAlpha (double alpha) |
Sets the low-pass filter gain for QuickStop in curvature drive. More... | |
bool | IsRightSideInverted () const |
Gets if the power sent to the right side of the drivetrain is multipled by -1. More... | |
void | SetRightSideInverted (bool rightSideInverted) |
Sets if the power sent to the right side of the drivetrain should be multipled by -1. More... | |
void | StopMotor () override |
void | GetDescription (wpi::raw_ostream &desc) const override |
void | InitSendable (SendableBuilder &builder) override |
Initializes this Sendable object. More... | |
![]() | |
RobotDriveBase (const RobotDriveBase &)=delete | |
RobotDriveBase & | operator= (const RobotDriveBase &)=delete |
void | SetDeadband (double deadband) |
Sets the deadband applied to the drive inputs (e.g., joystick values). More... | |
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. More... | |
void | FeedWatchdog () |
Feed the motor safety object. More... | |
void | SetExpiration (double timeout) override |
double | GetExpiration () const override |
bool | IsAlive () const override |
bool | IsSafetyEnabled () const override |
void | SetSafetyEnabled (bool enabled) override |
![]() | |
SendableBase (bool addLiveWindow=true) | |
Creates an instance of the sensor base. More... | |
std::string | GetName () const final |
Gets the name of this Sendable object. More... | |
void | SetName (const wpi::Twine &name) final |
Sets the name of this Sendable object. More... | |
std::string | GetSubsystem () const final |
Gets the subsystem name of this Sendable object. More... | |
void | SetSubsystem (const wpi::Twine &subsystem) final |
Sets the subsystem name of this Sendable object. More... | |
![]() | |
void | SetName (const wpi::Twine &subsystem, const wpi::Twine &name) |
Sets both the subsystem name and device name of this Sendable object. More... | |
Static Public Attributes | |
static constexpr double | kDefaultQuickStopThreshold = 0.2 |
static constexpr double | kDefaultQuickStopAlpha = 0.1 |
Additional Inherited Members | |
![]() | |
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. | |
![]() | |
double | Limit (double number) |
Limit motor values to the -1.0 to +1.0 range. | |
double | ApplyDeadband (double number, double deadband) |
Returns 0.0 if the given value is within the specified range around zero. More... | |
void | Normalize (wpi::MutableArrayRef< double > wheelSpeeds) |
Normalize all wheel speeds if the magnitude of any wheel is greater than 1.0. | |
![]() | |
void | AddChild (std::shared_ptr< Sendable > child) |
Add a child component. More... | |
void | AddChild (void *child) |
Add a child component. More... | |
void | SetName (const wpi::Twine &moduleType, int channel) |
Sets the name of the sensor with a channel number. More... | |
void | SetName (const wpi::Twine &moduleType, int moduleNumber, int channel) |
Sets the name of the sensor with a module and channel number. More... | |
![]() | |
double | m_deadband = 0.02 |
double | m_maxOutput = 1.0 |
MotorSafetyHelper | m_safetyHelper {this} |
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 SpeedController per side. For four and six motor drivetrains, construct and pass in SpeedControllerGroup instances as follows.
Four motor drivetrain:
Six motor drivetrain:
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(double, double, bool) is equivalent to RobotDrive::TankDrive(double, double, bool) if a deadband of 0 is used.
ArcadeDrive(double, double, bool) is equivalent to RobotDrive::ArcadeDrive(double, double, bool) if a deadband of 0 is used and the the rotation input is inverted eg ArcadeDrive(y, -rotation, false)
CurvatureDrive(double, double, bool) is similar in concept to RobotDrive::Drive(double, double) with the addition of a quick turn mode. However, it is not designed to give exactly the same response.
frc::DifferentialDrive::DifferentialDrive | ( | SpeedController & | leftMotor, |
SpeedController & | rightMotor | ||
) |
Construct a DifferentialDrive.
To pass multiple motors per side, use a SpeedControllerGroup. If a motor needs to be inverted, do so before passing it in.
void frc::DifferentialDrive::ArcadeDrive | ( | double | xSpeed, |
double | zRotation, | ||
bool | squaredInputs = 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.
xSpeed | The speed at which the robot should drive along the X axis [-1.0..1.0]. Forward is negative. |
zRotation | The rotation rate of the robot around the Z axis [-1.0..1.0]. Clockwise is positive. |
squaredInputs | If set, decreases the input sensitivity at low speeds. |
void frc::DifferentialDrive::CurvatureDrive | ( | double | xSpeed, |
double | zRotation, | ||
bool | isQuickTurn | ||
) |
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. Also handles the robot's quick turn functionality - "quick turn" overrides constant-curvature turning for turn-in-place maneuvers.
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]. Clockwise is positive. |
isQuickTurn | If set, overrides constant-curvature turning for turn-in-place maneuvers. |
|
overridevirtual |
bool frc::DifferentialDrive::IsRightSideInverted | ( | ) | const |
Gets if the power sent to the right side of the drivetrain is multipled by -1.
void frc::DifferentialDrive::SetQuickStopAlpha | ( | double | alpha | ) |
Sets the low-pass filter gain for QuickStop in curvature drive.
The low-pass filter filters incoming rotation rate commands to smooth out high frequency changes.
alpha | Low-pass filter gain [0.0..2.0]. Smaller values result in slower output changes. Values between 1.0 and 2.0 result in output oscillation. Values below 0.0 and above 2.0 are unstable. |
void frc::DifferentialDrive::SetQuickStopThreshold | ( | double | threshold | ) |
Sets the QuickStop speed threshold in curvature drive.
QuickStop compensates for the robot's moment of inertia when stopping after a QuickTurn.
While QuickTurn is enabled, the QuickStop accumulator takes on the rotation rate value outputted by the low-pass filter when the robot's speed along the X axis is below the threshold. When QuickTurn is disabled, the accumulator's value is applied against the computed angular power request to slow the robot's rotation.
threshold | X speed below which quick stop accumulator will receive rotation rate values [0..1.0]. |
void frc::DifferentialDrive::SetRightSideInverted | ( | bool | rightSideInverted | ) |
Sets if the power sent to the right side of the drivetrain should be multipled by -1.
rightSideInverted | true if right side power should be multipled by -1 |
void frc::DifferentialDrive::TankDrive | ( | double | leftSpeed, |
double | rightSpeed, | ||
bool | squaredInputs = true |
||
) |
Tank drive method for differential drive platform.
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. |
squaredInputs | If set, decreases the input sensitivity at low speeds. |