WPILibC++ 2024.1.1-beta-4
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 <memory>
8#include <string>
9
10#include <units/angle.h>
13
16
17namespace frc {
18
19class MotorController;
20
21/**
22 * A class for driving Mecanum drive platforms.
23 *
24 * Mecanum drives are rectangular with one wheel on each corner. Each wheel has
25 * rollers toed in 45 degrees toward the front or back. When looking at the
26 * wheels from the top, the roller axles should form an X across the robot.
27 *
28 * Drive base diagram:
29 * <pre>
30 * \\_______/
31 * \\ | | /
32 * | |
33 * /_|___|_\\
34 * / \\
35 * </pre>
36 *
37 * Each Drive() function provides different inverse kinematic relations for a
38 * Mecanum drive robot.
39 *
40 * This library uses the NWU axes convention (North-West-Up as external
41 * reference in the world frame). The positive X axis points ahead, the positive
42 * Y axis points to the left, and the positive Z axis points up. Rotations
43 * follow the right-hand rule, so counterclockwise rotation around the Z axis is
44 * positive.
45 *
46 * Note: the axis conventions used in this class differ from DifferentialDrive.
47 * This may change in a future year's WPILib release.
48 *
49 * Inputs smaller then 0.02 will be set to 0, and larger values will be scaled
50 * so that the full range is still used. This deadband value can be changed
51 * with SetDeadband().
52 *
53 * MotorSafety is enabled by default. The DriveCartesian or DrivePolar
54 * methods should be called periodically to avoid Motor Safety timeouts.
55 */
57 public wpi::Sendable,
58 public wpi::SendableHelper<MecanumDrive> {
59 public:
60 /**
61 * Wheel speeds for a mecanum drive.
62 *
63 * Uses normalized voltage [-1.0..1.0].
64 */
65 struct WheelSpeeds {
66 double frontLeft = 0.0;
67 double frontRight = 0.0;
68 double rearLeft = 0.0;
69 double rearRight = 0.0;
70 };
71
72 /**
73 * Construct a MecanumDrive.
74 *
75 * If a motor needs to be inverted, do so before passing it in.
76 */
77 MecanumDrive(MotorController& frontLeftMotor, MotorController& rearLeftMotor,
78 MotorController& frontRightMotor,
79 MotorController& rearRightMotor);
80
81 ~MecanumDrive() override = default;
82
85
86 /**
87 * Drive method for Mecanum platform.
88 *
89 * Angles are measured counterclockwise from the positive X axis. The robot's
90 * speed is independent from its angle or rotation rate.
91 *
92 * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is
93 * positive.
94 * @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Left is
95 * positive.
96 * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
97 * Counterclockwise is positive.
98 * @param gyroAngle The gyro heading around the Z axis. Use this to implement
99 * field-oriented controls.
100 */
101 void DriveCartesian(double xSpeed, double ySpeed, double zRotation,
102 Rotation2d gyroAngle = 0_rad);
103
104 /**
105 * Drive method for Mecanum platform.
106 *
107 * Angles are measured counterclockwise from the positive X axis. The robot's
108 * speed is independent from its angle or rotation rate.
109 *
110 * @param magnitude The robot's speed at a given angle [-1.0..1.0]. Forward is
111 * positive.
112 * @param angle The angle around the Z axis at which the robot drives.
113 * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
114 * Counterclockwise is positive.
115 */
116 void DrivePolar(double magnitude, Rotation2d angle, double zRotation);
117
118 /**
119 * Cartesian inverse kinematics for Mecanum platform.
120 *
121 * Angles are measured counterclockwise from the positive X axis. The robot's
122 * speed is independent from its angle or rotation rate.
123 *
124 * @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is
125 * positive.
126 * @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Left is
127 * positive.
128 * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
129 * Counterclockwise is positive.
130 * @param gyroAngle The gyro heading around the Z axis. Use this to implement
131 * field-oriented controls.
132 * @return Wheel speeds [-1.0..1.0].
133 */
134 static WheelSpeeds DriveCartesianIK(double xSpeed, double ySpeed,
135 double zRotation,
136 Rotation2d gyroAngle = 0_rad);
137
138 void StopMotor() override;
139 std::string GetDescription() const override;
140
141 void InitSendable(wpi::SendableBuilder& builder) override;
142
143 private:
144 MotorController* m_frontLeftMotor;
145 MotorController* m_rearLeftMotor;
146 MotorController* m_frontRightMotor;
147 MotorController* m_rearRightMotor;
148
149 bool reported = false;
150};
151
152} // namespace frc
A class for driving Mecanum drive platforms.
Definition: MecanumDrive.h:58
MecanumDrive(MotorController &frontLeftMotor, MotorController &rearLeftMotor, MotorController &frontRightMotor, MotorController &rearRightMotor)
Construct a MecanumDrive.
MecanumDrive & operator=(MecanumDrive &&)=default
void StopMotor() override
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.
std::string GetDescription() const override
The return value from this method is printed out 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
Definition: SendableBuilder.h:18
A helper class for use with objects that add themselves to SendableRegistry.
Definition: SendableHelper.h:19
Interface for Sendable objects.
Definition: Sendable.h:16
Definition: AprilTagPoseEstimator.h:15
Wheel speeds for a mecanum drive.
Definition: MecanumDrive.h:65
double rearRight
Definition: MecanumDrive.h:69
double frontRight
Definition: MecanumDrive.h:67
double frontLeft
Definition: MecanumDrive.h:66
double rearLeft
Definition: MecanumDrive.h:68