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