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