![]() |
WPILibC++ 2027.0.0-alpha-4
|
A class for driving Mecanum drive platforms. More...
#include <wpi/drive/MecanumDrive.hpp>
Classes | |
| struct | WheelVelocities |
| Wheel velocities for a mecanum drive. More... | |
Public Member Functions | |
| WPI_IGNORE_DEPRECATED | MecanumDrive (MotorController &frontLeftMotor, MotorController &rearLeftMotor, MotorController &frontRightMotor, MotorController &rearRightMotor) |
| Construct a MecanumDrive. | |
| 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. | |
| ~MecanumDrive () override=default | |
| MecanumDrive (MecanumDrive &&)=default | |
| MecanumDrive & | operator= (MecanumDrive &&)=default |
| void | DriveCartesian (double xVelocity, double yVelocity, double zRotation, wpi::math::Rotation2d gyroAngle=0_rad) |
| Drive method for Mecanum platform. | |
| void | DrivePolar (double magnitude, wpi::math::Rotation2d angle, double zRotation) |
| Drive method for Mecanum 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< MecanumDrive > | |
| constexpr | SendableHelper (const SendableHelper &rhs)=default |
| constexpr SendableHelper & | operator= (const SendableHelper &rhs)=default |
Static Public Member Functions | |
| static WheelVelocities | DriveCartesianIK (double xVelocity, double yVelocity, double zRotation, wpi::math::Rotation2d gyroAngle=0_rad) |
| Cartesian inverse kinematics for Mecanum 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< MecanumDrive > | |
| 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 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.
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 wpi::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 wpi::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 wpi::MecanumDrive::DriveCartesian | ( | double | xVelocity, |
| double | yVelocity, | ||
| double | zRotation, | ||
| wpi::math::Rotation2d | gyroAngle = 0_rad ) |
Drive method for Mecanum platform.
Angles are measured counterclockwise from the positive X axis. The robot's velocity is independent from its angle or rotation rate.
| xVelocity | The robot's velocity along the X axis [-1.0..1.0]. Forward is positive. |
| yVelocity | The robot's velocity 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 velocity is independent from its angle or rotation rate.
| xVelocity | The robot's velocity along the X axis [-1.0..1.0]. Forward is positive. |
| yVelocity | The robot's velocity 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 wpi::MecanumDrive::DrivePolar | ( | double | magnitude, |
| wpi::math::Rotation2d | angle, | ||
| double | zRotation ) |
Drive method for Mecanum platform.
Angles are measured counterclockwise from the positive X axis. The robot's velocity is independent from its angle or rotation rate.
| magnitude | The robot's velocity 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 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.