WPILibC++ 2024.3.2
|
A class for driving Mecanum drive platforms. More...
#include <frc/drive/MecanumDrive.h>
Classes | |
struct | WheelSpeeds |
Wheel speeds for a mecanum drive. More... | |
Public Member Functions | |
WPI_IGNORE_DEPRECATED | MecanumDrive (MotorController &frontLeftMotor, MotorController &rearLeftMotor, MotorController &frontRightMotor, MotorController &rearRightMotor) |
Construct a MecanumDrive. More... | |
WPI_UNIGNORE_DEPRECATED | MecanumDrive (std::function< void(double)> frontLeftMotor, std::function< void(double)> rearLeftMotor, std::function< void(double)> frontRightMotor, std::function< void(double)> rearRightMotor) |
Construct a MecanumDrive. More... | |
~MecanumDrive () override=default | |
MecanumDrive (MecanumDrive &&)=default | |
MecanumDrive & | operator= (MecanumDrive &&)=default |
void | DriveCartesian (double xSpeed, double ySpeed, double zRotation, Rotation2d gyroAngle=0_rad) |
Drive method for Mecanum platform. More... | |
void | DrivePolar (double magnitude, Rotation2d angle, double zRotation) |
Drive method for Mecanum platform. More... | |
void | StopMotor () override |
Called to stop the motor when the timeout expires. More... | |
std::string | GetDescription () const override |
Returns a description to print when an error occurs. More... | |
void | InitSendable (wpi::SendableBuilder &builder) override |
Initializes this Sendable object. More... | |
Public Member Functions inherited from frc::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). 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 | StopMotor () override=0 |
Called to stop the motor when the timeout expires. More... | |
std::string | GetDescription () const override=0 |
Returns a description to print when an error occurs. More... | |
Public Member Functions inherited from frc::MotorSafety | |
MotorSafety () | |
virtual | ~MotorSafety () |
MotorSafety (MotorSafety &&rhs) | |
MotorSafety & | operator= (MotorSafety &&rhs) |
void | Feed () |
Feed the motor safety object. More... | |
void | SetExpiration (units::second_t expirationTime) |
Set the expiration time for the corresponding motor safety object. More... | |
units::second_t | GetExpiration () const |
Retrieve the timeout value for the corresponding motor safety object. More... | |
bool | IsAlive () const |
Determine if the motor is still operating or has timed out. More... | |
void | SetSafetyEnabled (bool enabled) |
Enable/disable motor safety for this device. More... | |
bool | IsSafetyEnabled () const |
Return the state of the motor safety enabled flag. More... | |
void | Check () |
Check if this motor has exceeded its timeout. More... | |
virtual void | StopMotor ()=0 |
Called to stop the motor when the timeout expires. More... | |
virtual std::string | GetDescription () const =0 |
Returns a description to print when an error occurs. More... | |
Public Member Functions inherited from wpi::Sendable | |
virtual | ~Sendable ()=default |
virtual void | InitSendable (SendableBuilder &builder)=0 |
Initializes this Sendable object. More... | |
Public Member Functions inherited from wpi::SendableHelper< MecanumDrive > | |
SendableHelper (const SendableHelper &rhs)=default | |
SendableHelper (SendableHelper &&rhs) | |
SendableHelper & | operator= (const SendableHelper &rhs)=default |
SendableHelper & | operator= (SendableHelper &&rhs) |
Static Public Member Functions | |
static WheelSpeeds | DriveCartesianIK (double xSpeed, double ySpeed, double zRotation, Rotation2d gyroAngle=0_rad) |
Cartesian inverse kinematics for Mecanum platform. More... | |
Static Public Member Functions inherited from frc::MotorSafety | |
static void | CheckMotors () |
Check the motors to see if any have timed out. More... | |
Additional Inherited Members | |
Public Types inherited from frc::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::SendableHelper< MecanumDrive > | |
SendableHelper ()=default | |
~SendableHelper () | |
Static Protected Member Functions inherited from frc::RobotDriveBase | |
static void | Desaturate (std::span< double > wheelSpeeds) |
Renormalize all wheel speeds if the magnitude of any wheel is greater than 1.0. More... | |
Protected Attributes inherited from frc::RobotDriveBase | |
double | m_deadband = kDefaultDeadband |
Input deadband. More... | |
double | m_maxOutput = kDefaultMaxOutput |
Maximum output. More... | |
Static Protected Attributes inherited from frc::RobotDriveBase | |
static constexpr double | kDefaultDeadband = 0.02 |
Default input deadband. More... | |
static constexpr double | kDefaultMaxOutput = 1.0 |
Default maximum output. More... | |
A class for driving Mecanum drive platforms.
Mecanum drives are rectangular with one wheel on each corner. Each wheel has rollers toed in 45 degrees toward the front or back. When looking at the wheels from the top, the roller axles should form an X across the robot.
Drive base diagram:
\_______/ \ | | / | | /_|___|_\ / \
Each Drive() function provides different inverse kinematic relations for a Mecanum 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.
Note: the axis conventions used in this class differ from DifferentialDrive. This may change in a future year's WPILib release.
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 DriveCartesian or DrivePolar methods should be called periodically to avoid Motor Safety timeouts.
WPI_IGNORE_DEPRECATED frc::MecanumDrive::MecanumDrive | ( | MotorController & | frontLeftMotor, |
MotorController & | rearLeftMotor, | ||
MotorController & | frontRightMotor, | ||
MotorController & | rearRightMotor | ||
) |
Construct a MecanumDrive.
If a motor needs to be inverted, do so before passing it in.
frontLeftMotor | Front-left motor. |
rearLeftMotor | Rear-left motor. |
frontRightMotor | Front-right motor. |
rearRightMotor | Rear-right motor. |
WPI_UNIGNORE_DEPRECATED frc::MecanumDrive::MecanumDrive | ( | std::function< void(double)> | frontLeftMotor, |
std::function< void(double)> | rearLeftMotor, | ||
std::function< void(double)> | frontRightMotor, | ||
std::function< void(double)> | rearRightMotor | ||
) |
Construct a MecanumDrive.
If a motor needs to be inverted, do so before passing it in.
frontLeftMotor | Front-left motor setter. |
rearLeftMotor | Rear-left motor setter. |
frontRightMotor | Front-right motor setter. |
rearRightMotor | Rear-right motor setter. |
|
overridedefault |
|
default |
void frc::MecanumDrive::DriveCartesian | ( | double | xSpeed, |
double | ySpeed, | ||
double | zRotation, | ||
Rotation2d | gyroAngle = 0_rad |
||
) |
Drive method for Mecanum platform.
Angles are measured counterclockwise from the positive X axis. The robot's speed is independent from its angle or rotation rate.
xSpeed | The robot's speed along the X axis [-1.0..1.0]. Forward is positive. |
ySpeed | The robot's speed along the Y axis [-1.0..1.0]. Left is positive. |
zRotation | The robot's rotation rate around the Z axis [-1.0..1.0]. Counterclockwise is positive. |
gyroAngle | The gyro heading around the Z axis. Use this to implement field-oriented controls. |
|
static |
Cartesian inverse kinematics for Mecanum platform.
Angles are measured counterclockwise from the positive X axis. The robot's speed is independent from its angle or rotation rate.
xSpeed | The robot's speed along the X axis [-1.0..1.0]. Forward is positive. |
ySpeed | The robot's speed along the Y axis [-1.0..1.0]. Left is positive. |
zRotation | The robot's rotation rate around the Z axis [-1.0..1.0]. Counterclockwise is positive. |
gyroAngle | The gyro heading around the Z axis. Use this to implement field-oriented controls. |
void frc::MecanumDrive::DrivePolar | ( | double | magnitude, |
Rotation2d | angle, | ||
double | zRotation | ||
) |
Drive method for Mecanum platform.
Angles are measured counterclockwise from the positive X axis. The robot's speed is independent from its angle or rotation rate.
magnitude | The robot's speed at a given angle [-1.0..1.0]. Forward is positive. |
angle | The angle around the Z axis at which the robot drives. |
zRotation | The robot's rotation rate around the Z axis [-1.0..1.0]. Counterclockwise is positive. |
|
overridevirtual |
Returns a description to print when an error occurs.
Implements frc::RobotDriveBase.
|
overridevirtual |
|
default |
|
overridevirtual |
Called to stop the motor when the timeout expires.
Implements frc::RobotDriveBase.