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