WPILibC++ 2024.3.2
MecanumDrive.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <functional>
8#include <memory>
9#include <string>
10
11#include <units/angle.h>
12#include <wpi/deprecated.h>
15
18
19namespace frc {
20
21class MotorController;
22
23/**
24 * A class for driving Mecanum drive platforms.
25 *
26 * Mecanum drives are rectangular with one wheel on each corner. Each wheel has
27 * rollers toed in 45 degrees toward the front or back. When looking at the
28 * wheels from the top, the roller axles should form an X across the robot.
29 *
30 * Drive base diagram:
31 * <pre>
32 * \\_______/
33 * \\ | | /
34 * | |
35 * /_|___|_\\
36 * / \\
37 * </pre>
38 *
39 * Each Drive() function provides different inverse kinematic relations for a
40 * Mecanum drive robot.
41 *
42 * This library uses the NWU axes convention (North-West-Up as external
43 * reference in the world frame). The positive X axis points ahead, the positive
44 * Y axis points to the left, and the positive Z axis points up. Rotations
45 * follow the right-hand rule, so counterclockwise rotation around the Z axis is
46 * positive.
47 *
48 * Note: the axis conventions used in this class differ from DifferentialDrive.
49 * This may change in a future year's WPILib release.
50 *
51 * Inputs smaller then 0.02 will be set to 0, and larger values will be scaled
52 * so that the full range is still used. This deadband value can be changed
53 * with SetDeadband().
54 *
55 * MotorSafety is enabled by default. The DriveCartesian or DrivePolar
56 * methods should be called periodically to avoid Motor Safety timeouts.
57 */
59 public wpi::Sendable,
60 public wpi::SendableHelper<MecanumDrive> {
61 public:
62 /**
63 * Wheel speeds for a mecanum drive.
64 *
65 * Uses normalized voltage [-1.0..1.0].
66 */
67 struct WheelSpeeds {
68 /// Front-left wheel speed.
69 double frontLeft = 0.0;
70 /// Front-right wheel speed.
71 double frontRight = 0.0;
72 /// Rear-left wheel speed.
73 double rearLeft = 0.0;
74 /// Rear-right wheel speed.
75 double rearRight = 0.0;
76 };
77
79
80 /**
81 * Construct a MecanumDrive.
82 *
83 * If a motor needs to be inverted, do so before passing it in.
84 *
85 * @param frontLeftMotor Front-left motor.
86 * @param rearLeftMotor Rear-left motor.
87 * @param frontRightMotor Front-right motor.
88 * @param rearRightMotor Rear-right motor.
89 */
90 MecanumDrive(MotorController& frontLeftMotor, MotorController& rearLeftMotor,
91 MotorController& frontRightMotor,
92 MotorController& rearRightMotor);
93
95
96 /**
97 * Construct a MecanumDrive.
98 *
99 * If a motor needs to be inverted, do so before passing it in.
100 *
101 * @param frontLeftMotor Front-left motor setter.
102 * @param rearLeftMotor Rear-left motor setter.
103 * @param frontRightMotor Front-right motor setter.
104 * @param rearRightMotor Rear-right motor setter.
105 */
106 MecanumDrive(std::function<void(double)> frontLeftMotor,
107 std::function<void(double)> rearLeftMotor,
108 std::function<void(double)> frontRightMotor,
109 std::function<void(double)> rearRightMotor);
110
111 ~MecanumDrive() override = default;
112
115
116 /**
117 * Drive method for Mecanum platform.
118 *
119 * Angles are measured counterclockwise from the positive X axis. The robot's
120 * speed is independent from its angle or rotation rate.
121 *
122 * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is
123 * positive.
124 * @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Left is
125 * positive.
126 * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
127 * Counterclockwise is positive.
128 * @param gyroAngle The gyro heading around the Z axis. Use this to implement
129 * field-oriented controls.
130 */
131 void DriveCartesian(double xSpeed, double ySpeed, double zRotation,
132 Rotation2d gyroAngle = 0_rad);
133
134 /**
135 * Drive method for Mecanum platform.
136 *
137 * Angles are measured counterclockwise from the positive X axis. The robot's
138 * speed is independent from its angle or rotation rate.
139 *
140 * @param magnitude The robot's speed at a given angle [-1.0..1.0]. Forward is
141 * positive.
142 * @param angle The angle around the Z axis at which the robot drives.
143 * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
144 * Counterclockwise is positive.
145 */
146 void DrivePolar(double magnitude, Rotation2d angle, double zRotation);
147
148 /**
149 * Cartesian inverse kinematics for Mecanum platform.
150 *
151 * Angles are measured counterclockwise from the positive X axis. The robot's
152 * speed is independent from its angle or rotation rate.
153 *
154 * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is
155 * positive.
156 * @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Left is
157 * positive.
158 * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
159 * Counterclockwise is positive.
160 * @param gyroAngle The gyro heading around the Z axis. Use this to implement
161 * field-oriented controls.
162 * @return Wheel speeds [-1.0..1.0].
163 */
164 static WheelSpeeds DriveCartesianIK(double xSpeed, double ySpeed,
165 double zRotation,
166 Rotation2d gyroAngle = 0_rad);
167
168 void StopMotor() override;
169 std::string GetDescription() const override;
170
171 void InitSendable(wpi::SendableBuilder& builder) override;
172
173 private:
174 std::function<void(double)> m_frontLeftMotor;
175 std::function<void(double)> m_rearLeftMotor;
176 std::function<void(double)> m_frontRightMotor;
177 std::function<void(double)> m_rearRightMotor;
178
179 // Used for Sendable property getters
180 double m_frontLeftOutput = 0.0;
181 double m_rearLeftOutput = 0.0;
182 double m_frontRightOutput = 0.0;
183 double m_rearRightOutput = 0.0;
184
185 bool reported = false;
186};
187
188} // namespace frc
A class for driving Mecanum drive platforms.
Definition: MecanumDrive.h:60
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 & operator=(MecanumDrive &&)=default
void StopMotor() override
Called to stop the motor when the timeout expires.
void DrivePolar(double magnitude, Rotation2d angle, double zRotation)
Drive method for Mecanum platform.
MecanumDrive(MecanumDrive &&)=default
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
static WheelSpeeds DriveCartesianIK(double xSpeed, double ySpeed, double zRotation, Rotation2d gyroAngle=0_rad)
Cartesian inverse kinematics for Mecanum platform.
WPI_IGNORE_DEPRECATED MecanumDrive(MotorController &frontLeftMotor, MotorController &rearLeftMotor, MotorController &frontRightMotor, MotorController &rearRightMotor)
Construct a MecanumDrive.
std::string GetDescription() const override
Returns a description to print when an error occurs.
~MecanumDrive() override=default
void DriveCartesian(double xSpeed, double ySpeed, double zRotation, Rotation2d gyroAngle=0_rad)
Drive method for Mecanum platform.
Interface for motor controlling devices.
Definition: MotorController.h:14
Common base class for drive platforms.
Definition: RobotDriveBase.h:20
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:23
Helper class for building Sendable dashboard representations.
Definition: SendableBuilder.h:21
A helper class for use with objects that add themselves to SendableRegistry.
Definition: SendableHelper.h:19
Interface for Sendable objects.
Definition: Sendable.h:16
#define WPI_IGNORE_DEPRECATED
Definition: deprecated.h:20
#define WPI_UNIGNORE_DEPRECATED
Definition: deprecated.h:31
Definition: AprilTagPoseEstimator.h:15
Wheel speeds for a mecanum drive.
Definition: MecanumDrive.h:67
double rearRight
Rear-right wheel speed.
Definition: MecanumDrive.h:75
double frontRight
Front-right wheel speed.
Definition: MecanumDrive.h:71
double frontLeft
Front-left wheel speed.
Definition: MecanumDrive.h:69
double rearLeft
Rear-left wheel speed.
Definition: MecanumDrive.h:73