WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
MecanumDrive.hpp
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
13#include "wpi/units/angle.hpp"
17
18namespace wpi {
19
20class MotorController;
21
22/**
23 * A class for driving Mecanum drive platforms.
24 *
25 * Mecanum drives are rectangular with one wheel on each corner. Each wheel has
26 * rollers toed in 45 degrees toward the front or back. When looking at the
27 * wheels from the top, the roller axles should form an X across the robot.
28 *
29 * Drive base diagram:
30 * <pre>
31 * \\_______/
32 * \\ | | /
33 * | |
34 * /_|___|_\\
35 * / \\
36 * </pre>
37 *
38 * Each Drive() function provides different inverse kinematic relations for a
39 * Mecanum drive robot.
40 *
41 * This library uses the NWU axes convention (North-West-Up as external
42 * reference in the world frame). The positive X axis points ahead, the positive
43 * Y axis points to the left, and the positive Z axis points up. Rotations
44 * follow the right-hand rule, so counterclockwise rotation around the Z axis is
45 * positive.
46 *
47 * Inputs smaller then 0.02 will be set to 0, and larger values will be scaled
48 * so that the full range is still used. This deadband value can be changed
49 * with SetDeadband().
50 *
51 * MotorSafety is enabled by default. The DriveCartesian or DrivePolar
52 * methods should be called periodically to avoid Motor Safety timeouts.
53 */
56 public wpi::util::SendableHelper<MecanumDrive> {
57 public:
58 /**
59 * Wheel velocities for a mecanum drive.
60 *
61 * Uses normalized voltage [-1.0..1.0].
62 */
64 /// Front-left wheel velocity.
65 double frontLeft = 0.0;
66 /// Front-right wheel velocity.
67 double frontRight = 0.0;
68 /// Rear-left wheel velocity.
69 double rearLeft = 0.0;
70 /// Rear-right wheel velocity.
71 double rearRight = 0.0;
72 };
73
75
76 /**
77 * Construct a MecanumDrive.
78 *
79 * If a motor needs to be inverted, do so before passing it in.
80 *
81 * @param frontLeftMotor Front-left motor.
82 * @param rearLeftMotor Rear-left motor.
83 * @param frontRightMotor Front-right motor.
84 * @param rearRightMotor Rear-right motor.
85 */
86 MecanumDrive(MotorController& frontLeftMotor, MotorController& rearLeftMotor,
87 MotorController& frontRightMotor,
88 MotorController& rearRightMotor);
89
91
92 /**
93 * Construct a MecanumDrive.
94 *
95 * If a motor needs to be inverted, do so before passing it in.
96 *
97 * @param frontLeftMotor Front-left motor setter.
98 * @param rearLeftMotor Rear-left motor setter.
99 * @param frontRightMotor Front-right motor setter.
100 * @param rearRightMotor Rear-right motor setter.
101 */
102 MecanumDrive(std::function<void(double)> frontLeftMotor,
103 std::function<void(double)> rearLeftMotor,
104 std::function<void(double)> frontRightMotor,
105 std::function<void(double)> rearRightMotor);
106
107 ~MecanumDrive() override = default;
108
111
112 /**
113 * Drive method for Mecanum platform.
114 *
115 * Angles are measured counterclockwise from the positive X axis. The robot's
116 * velocity is independent from its angle or rotation rate.
117 *
118 * @param xVelocity The robot's velocity along the X axis [-1.0..1.0]. Forward
119 * is positive.
120 * @param yVelocity The robot's velocity along the Y axis [-1.0..1.0]. Left is
121 * positive.
122 * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
123 * Counterclockwise is positive.
124 * @param gyroAngle The gyro heading around the Z axis. Use this to implement
125 * field-oriented controls.
126 */
127 void DriveCartesian(double xVelocity, double yVelocity, double zRotation,
128 wpi::math::Rotation2d gyroAngle = 0_rad);
129
130 /**
131 * Drive method for Mecanum platform.
132 *
133 * Angles are measured counterclockwise from the positive X axis. The robot's
134 * velocity is independent from its angle or rotation rate.
135 *
136 * @param magnitude The robot's velocity at a given angle [-1.0..1.0]. Forward
137 * is positive.
138 * @param angle The angle around the Z axis at which the robot drives.
139 * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
140 * Counterclockwise is positive.
141 */
142 void DrivePolar(double magnitude, wpi::math::Rotation2d angle,
143 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 * velocity is independent from its angle or rotation rate.
150 *
151 * @param xVelocity The robot's velocity along the X axis [-1.0..1.0]. Forward
152 * is positive.
153 * @param yVelocity The robot's velocity 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 velocities [-1.0..1.0].
160 */
162 double xVelocity, double yVelocity, double zRotation,
163 wpi::math::Rotation2d gyroAngle = 0_rad);
164
165 void StopMotor() override;
166 std::string GetDescription() const override;
167
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 wpi
void DrivePolar(double magnitude, wpi::math::Rotation2d angle, double zRotation)
Drive method for Mecanum platform.
std::string GetDescription() const override
Returns a description to print when an error occurs.
void StopMotor() override
Called to stop the motor when the timeout expires.
~MecanumDrive() override=default
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(MecanumDrive &&)=default
static WheelVelocities DriveCartesianIK(double xVelocity, double yVelocity, double zRotation, wpi::math::Rotation2d gyroAngle=0_rad)
Cartesian inverse kinematics for Mecanum platform.
void DriveCartesian(double xVelocity, double yVelocity, double zRotation, wpi::math::Rotation2d gyroAngle=0_rad)
Drive method for Mecanum platform.
void InitSendable(wpi::util::SendableBuilder &builder) override
Initializes this Sendable object.
MecanumDrive & operator=(MecanumDrive &&)=default
Interface for motor controlling devices.
Definition MotorController.hpp:14
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.hpp:26
Helper class for building Sendable dashboard representations.
Definition SendableBuilder.hpp:21
A helper class for use with objects that add themselves to SendableRegistry.
Definition SendableHelper.hpp:21
Interface for Sendable objects.
Definition Sendable.hpp:16
#define WPI_IGNORE_DEPRECATED
Definition deprecated.hpp:15
#define WPI_UNIGNORE_DEPRECATED
Definition deprecated.hpp:26
Definition CvSource.hpp:15
Wheel velocities for a mecanum drive.
Definition MecanumDrive.hpp:63
double frontRight
Front-right wheel velocity.
Definition MecanumDrive.hpp:67
double rearLeft
Rear-left wheel velocity.
Definition MecanumDrive.hpp:69
double frontLeft
Front-left wheel velocity.
Definition MecanumDrive.hpp:65
double rearRight
Rear-right wheel velocity.
Definition MecanumDrive.hpp:71