WPILibC++ 2024.1.1-beta-4
DifferentialDrive.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 <string>
8
11
13
14namespace frc {
15
16class MotorController;
17
18/**
19 * A class for driving differential drive/skid-steer drive platforms such as
20 * the Kit of Parts drive base, "tank drive", or West Coast Drive.
21 *
22 * These drive bases typically have drop-center / skid-steer with two or more
23 * wheels per side (e.g., 6WD or 8WD). This class takes a MotorController per
24 * side. For four and six motor drivetrains, construct and pass in
25 * MotorControllerGroup instances as follows.
26 *
27 * Four motor drivetrain:
28 * @code{.cpp}
29 * class Robot {
30 * public:
31 * frc::PWMVictorSPX m_frontLeft{1};
32 * frc::PWMVictorSPX m_rearLeft{2};
33 * frc::MotorControllerGroup m_left{m_frontLeft, m_rearLeft};
34 *
35 * frc::PWMVictorSPX m_frontRight{3};
36 * frc::PWMVictorSPX m_rearRight{4};
37 * frc::MotorControllerGroup m_right{m_frontRight, m_rearRight};
38 *
39 * frc::DifferentialDrive m_drive{m_left, m_right};
40 * };
41 * @endcode
42 *
43 * Six motor drivetrain:
44 * @code{.cpp}
45 * class Robot {
46 * public:
47 * frc::PWMVictorSPX m_frontLeft{1};
48 * frc::PWMVictorSPX m_midLeft{2};
49 * frc::PWMVictorSPX m_rearLeft{3};
50 * frc::MotorControllerGroup m_left{m_frontLeft, m_midLeft, m_rearLeft};
51 *
52 * frc::PWMVictorSPX m_frontRight{4};
53 * frc::PWMVictorSPX m_midRight{5};
54 * frc::PWMVictorSPX m_rearRight{6};
55 * frc::MotorControllerGroup m_right{m_frontRight, m_midRight, m_rearRight};
56 *
57 * frc::DifferentialDrive m_drive{m_left, m_right};
58 * };
59 * @endcode
60 *
61 * A differential drive robot has left and right wheels separated by an
62 * arbitrary width.
63 *
64 * Drive base diagram:
65 * <pre>
66 * |_______|
67 * | | | |
68 * | |
69 * |_|___|_|
70 * | |
71 * </pre>
72 *
73 * Each drive function provides different inverse kinematic relations for a
74 * differential drive robot.
75 *
76 * This library uses the NWU axes convention (North-West-Up as external
77 * reference in the world frame). The positive X axis points ahead, the positive
78 * Y axis points to the left, and the positive Z axis points up. Rotations
79 * follow the right-hand rule, so counterclockwise rotation around the Z axis is
80 * positive.
81 *
82 * Inputs smaller then 0.02 will be set to 0, and larger values will be scaled
83 * so that the full range is still used. This deadband value can be changed
84 * with SetDeadband().
85 *
86 * MotorSafety is enabled by default. The tankDrive, arcadeDrive,
87 * or curvatureDrive methods should be called periodically to avoid Motor
88 * Safety timeouts.
89 */
91 public wpi::Sendable,
92 public wpi::SendableHelper<DifferentialDrive> {
93 public:
94 /**
95 * Wheel speeds for a differential drive.
96 *
97 * Uses normalized voltage [-1.0..1.0].
98 */
99 struct WheelSpeeds {
100 double left = 0.0;
101 double right = 0.0;
102 };
103
104 /**
105 * Construct a DifferentialDrive.
106 *
107 * To pass multiple motors per side, use a MotorControllerGroup. If a motor
108 * needs to be inverted, do so before passing it in.
109 */
111
112 ~DifferentialDrive() override = default;
113
116
117 /**
118 * Arcade drive method for differential drive platform.
119 *
120 * Note: Some drivers may prefer inverted rotation controls. This can be done
121 * by negating the value passed for rotation.
122 *
123 * @param xSpeed The speed at which the robot should drive along the X
124 * axis [-1.0..1.0]. Forward is positive.
125 * @param zRotation The rotation rate of the robot around the Z axis
126 * [-1.0..1.0]. Counterclockwise is positive.
127 * @param squareInputs If set, decreases the input sensitivity at low speeds.
128 */
129 void ArcadeDrive(double xSpeed, double zRotation, bool squareInputs = true);
130
131 /**
132 * Curvature drive method for differential drive platform.
133 *
134 * The rotation argument controls the curvature of the robot's path rather
135 * than its rate of heading change. This makes the robot more controllable at
136 * high speeds.
137 *
138 * @param xSpeed The robot's speed along the X axis [-1.0..1.0].
139 * Forward is positive.
140 * @param zRotation The normalized curvature [-1.0..1.0].
141 * Counterclockwise is positive.
142 * @param allowTurnInPlace If set, overrides constant-curvature turning for
143 * turn-in-place maneuvers. zRotation will control
144 * turning rate instead of curvature.
145 */
146 void CurvatureDrive(double xSpeed, double zRotation, bool allowTurnInPlace);
147
148 /**
149 * Tank drive method for differential drive platform.
150 *
151 * @param leftSpeed The robot left side's speed along the X axis
152 * [-1.0..1.0]. Forward is positive.
153 * @param rightSpeed The robot right side's speed along the X axis
154 * [-1.0..1.0]. Forward is positive.
155 * @param squareInputs If set, decreases the input sensitivity at low speeds.
156 */
157 void TankDrive(double leftSpeed, double rightSpeed, bool squareInputs = true);
158
159 /**
160 * Arcade drive inverse kinematics for differential drive platform.
161 *
162 * Note: Some drivers may prefer inverted rotation controls. This can be done
163 * by negating the value passed for rotation.
164 *
165 * @param xSpeed The speed at which the robot should drive along the X
166 * axis [-1.0..1.0]. Forward is positive.
167 * @param zRotation The rotation rate of the robot around the Z axis
168 * [-1.0..1.0]. Clockwise is positive.
169 * @param squareInputs If set, decreases the input sensitivity at low speeds.
170 * @return Wheel speeds [-1.0..1.0].
171 */
172 static WheelSpeeds ArcadeDriveIK(double xSpeed, double zRotation,
173 bool squareInputs = true);
174
175 /**
176 * Curvature drive inverse kinematics for differential drive platform.
177 *
178 * The rotation argument controls the curvature of the robot's path rather
179 * than its rate of heading change. This makes the robot more controllable at
180 * high speeds.
181 *
182 * @param xSpeed The robot's speed along the X axis [-1.0..1.0].
183 * Forward is positive.
184 * @param zRotation The normalized curvature [-1.0..1.0]. Clockwise is
185 * positive.
186 * @param allowTurnInPlace If set, overrides constant-curvature turning for
187 * turn-in-place maneuvers. zRotation will control
188 * turning rate instead of curvature.
189 * @return Wheel speeds [-1.0..1.0].
190 */
191 static WheelSpeeds CurvatureDriveIK(double xSpeed, double zRotation,
192 bool allowTurnInPlace);
193
194 /**
195 * Tank drive inverse kinematics for differential drive platform.
196 *
197 * @param leftSpeed The robot left side's speed along the X axis
198 * [-1.0..1.0]. Forward is positive.
199 * @param rightSpeed The robot right side's speed along the X axis
200 * [-1.0..1.0]. Forward is positive.
201 * @param squareInputs If set, decreases the input sensitivity at low speeds.
202 * @return Wheel speeds [-1.0..1.0].
203 */
204 static WheelSpeeds TankDriveIK(double leftSpeed, double rightSpeed,
205 bool squareInputs = true);
206
207 void StopMotor() override;
208 std::string GetDescription() const override;
209
210 void InitSendable(wpi::SendableBuilder& builder) override;
211
212 private:
213 MotorController* m_leftMotor;
214 MotorController* m_rightMotor;
215};
216
217} // namespace frc
A class for driving differential drive/skid-steer drive platforms such as the Kit of Parts drive base...
Definition: DifferentialDrive.h:92
void ArcadeDrive(double xSpeed, double zRotation, bool squareInputs=true)
Arcade drive method for differential drive platform.
DifferentialDrive(DifferentialDrive &&)=default
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
std::string GetDescription() const override
The return value from this method is printed out when an error occurs.
DifferentialDrive & operator=(DifferentialDrive &&)=default
static WheelSpeeds CurvatureDriveIK(double xSpeed, double zRotation, bool allowTurnInPlace)
Curvature drive inverse kinematics for differential drive platform.
~DifferentialDrive() override=default
DifferentialDrive(MotorController &leftMotor, MotorController &rightMotor)
Construct a DifferentialDrive.
static WheelSpeeds ArcadeDriveIK(double xSpeed, double zRotation, bool squareInputs=true)
Arcade drive inverse kinematics for differential drive platform.
void TankDrive(double leftSpeed, double rightSpeed, bool squareInputs=true)
Tank drive method for differential drive platform.
void StopMotor() override
void CurvatureDrive(double xSpeed, double zRotation, bool allowTurnInPlace)
Curvature drive method for differential drive platform.
static WheelSpeeds TankDriveIK(double leftSpeed, double rightSpeed, bool squareInputs=true)
Tank drive inverse kinematics for differential drive platform.
Interface for motor controlling devices.
Definition: MotorController.h:14
Common base class for drive platforms.
Definition: RobotDriveBase.h:20
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 differential drive.
Definition: DifferentialDrive.h:99
double left
Definition: DifferentialDrive.h:100
double right
Definition: DifferentialDrive.h:101