WPILibC++ 2025.2.1
Loading...
Searching...
No Matches
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 * Inputs smaller then 0.02 will be set to 0, and larger values will be scaled
49 * so that the full range is still used. This deadband value can be changed
50 * with SetDeadband().
51 *
52 * MotorSafety is enabled by default. The DriveCartesian or DrivePolar
53 * methods should be called periodically to avoid Motor Safety timeouts.
54 */
56 public wpi::Sendable,
57 public wpi::SendableHelper<MecanumDrive> {
58 public:
59 /**
60 * Wheel speeds for a mecanum drive.
61 *
62 * Uses normalized voltage [-1.0..1.0].
63 */
64 struct WheelSpeeds {
65 /// Front-left wheel speed.
66 double frontLeft = 0.0;
67 /// Front-right wheel speed.
68 double frontRight = 0.0;
69 /// Rear-left wheel speed.
70 double rearLeft = 0.0;
71 /// Rear-right wheel speed.
72 double rearRight = 0.0;
73 };
74
76
77 /**
78 * Construct a MecanumDrive.
79 *
80 * If a motor needs to be inverted, do so before passing it in.
81 *
82 * @param frontLeftMotor Front-left motor.
83 * @param rearLeftMotor Rear-left motor.
84 * @param frontRightMotor Front-right motor.
85 * @param rearRightMotor Rear-right motor.
86 */
87 MecanumDrive(MotorController& frontLeftMotor, MotorController& rearLeftMotor,
88 MotorController& frontRightMotor,
89 MotorController& rearRightMotor);
90
92
93 /**
94 * Construct a MecanumDrive.
95 *
96 * If a motor needs to be inverted, do so before passing it in.
97 *
98 * @param frontLeftMotor Front-left motor setter.
99 * @param rearLeftMotor Rear-left motor setter.
100 * @param frontRightMotor Front-right motor setter.
101 * @param rearRightMotor Rear-right motor setter.
102 */
103 MecanumDrive(std::function<void(double)> frontLeftMotor,
104 std::function<void(double)> rearLeftMotor,
105 std::function<void(double)> frontRightMotor,
106 std::function<void(double)> rearRightMotor);
107
108 ~MecanumDrive() override = default;
109
112
113 /**
114 * Drive method for Mecanum platform.
115 *
116 * Angles are measured counterclockwise from the positive X axis. The robot's
117 * speed is independent from its angle or rotation rate.
118 *
119 * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is
120 * positive.
121 * @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Left is
122 * positive.
123 * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
124 * Counterclockwise is positive.
125 * @param gyroAngle The gyro heading around the Z axis. Use this to implement
126 * field-oriented controls.
127 */
128 void DriveCartesian(double xSpeed, double ySpeed, double zRotation,
129 Rotation2d gyroAngle = 0_rad);
130
131 /**
132 * Drive method for Mecanum platform.
133 *
134 * Angles are measured counterclockwise from the positive X axis. The robot's
135 * speed is independent from its angle or rotation rate.
136 *
137 * @param magnitude The robot's speed at a given angle [-1.0..1.0]. Forward is
138 * positive.
139 * @param angle The angle around the Z axis at which the robot drives.
140 * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
141 * Counterclockwise is positive.
142 */
143 void DrivePolar(double magnitude, Rotation2d angle, double zRotation);
144
145 /**
146 * Cartesian inverse kinematics for Mecanum platform.
147 *
148 * Angles are measured counterclockwise from the positive X axis. The robot's
149 * speed is independent from its angle or rotation rate.
150 *
151 * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is
152 * positive.
153 * @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Left is
154 * positive.
155 * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
156 * Counterclockwise is positive.
157 * @param gyroAngle The gyro heading around the Z axis. Use this to implement
158 * field-oriented controls.
159 * @return Wheel speeds [-1.0..1.0].
160 */
161 static WheelSpeeds DriveCartesianIK(double xSpeed, double ySpeed,
162 double zRotation,
163 Rotation2d gyroAngle = 0_rad);
164
165 void StopMotor() override;
166 std::string GetDescription() const override;
167
168 void InitSendable(wpi::SendableBuilder& builder) override;
169
170 private:
171 std::function<void(double)> m_frontLeftMotor;
172 std::function<void(double)> m_rearLeftMotor;
173 std::function<void(double)> m_frontRightMotor;
174 std::function<void(double)> m_rearRightMotor;
175
176 // Used for Sendable property getters
177 double m_frontLeftOutput = 0.0;
178 double m_rearLeftOutput = 0.0;
179 double m_frontRightOutput = 0.0;
180 double m_rearRightOutput = 0.0;
181
182 bool reported = false;
183};
184
185} // namespace frc
A class for driving Mecanum drive platforms.
Definition MecanumDrive.h:57
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:31
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:21
Interface for Sendable objects.
Definition Sendable.h:16
#define WPI_IGNORE_DEPRECATED
Definition deprecated.h:16
#define WPI_UNIGNORE_DEPRECATED
Definition deprecated.h:27
Definition CAN.h:11
Wheel speeds for a mecanum drive.
Definition MecanumDrive.h:64
double rearRight
Rear-right wheel speed.
Definition MecanumDrive.h:72
double frontRight
Front-right wheel speed.
Definition MecanumDrive.h:68
double frontLeft
Front-left wheel speed.
Definition MecanumDrive.h:66
double rearLeft
Rear-left wheel speed.
Definition MecanumDrive.h:70