WPILibC++ 2024.3.2
ChassisSpeeds.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 <wpi/SymbolExports.h>
8
12#include "units/velocity.h"
13
14namespace frc {
15/**
16 * Represents the speed of a robot chassis. Although this struct contains
17 * similar members compared to a Twist2d, they do NOT represent the same thing.
18 * Whereas a Twist2d represents a change in pose w.r.t to the robot frame of
19 * reference, a ChassisSpeeds struct represents a robot's velocity.
20 *
21 * A strictly non-holonomic drivetrain, such as a differential drive, should
22 * never have a dy component because it can never move sideways. Holonomic
23 * drivetrains such as swerve and mecanum will often have all three components.
24 */
26 /**
27 * Velocity along the x-axis. (Fwd is +)
28 */
29 units::meters_per_second_t vx = 0_mps;
30
31 /**
32 * Velocity along the y-axis. (Left is +)
33 */
34 units::meters_per_second_t vy = 0_mps;
35
36 /**
37 * Represents the angular velocity of the robot frame. (CCW is +)
38 */
39 units::radians_per_second_t omega = 0_rad_per_s;
40
41 /**
42 * Disretizes a continuous-time chassis speed.
43 *
44 * This function converts a continuous-time chassis speed into a discrete-time
45 * one such that when the discrete-time chassis speed is applied for one
46 * timestep, the robot moves as if the velocity components are independent
47 * (i.e., the robot moves v_x * dt along the x-axis, v_y * dt along the
48 * y-axis, and omega * dt around the z-axis).
49 *
50 * This is useful for compensating for translational skew when translating and
51 * rotating a swerve drivetrain.
52 *
53 * @param vx Forward velocity.
54 * @param vy Sideways velocity.
55 * @param omega Angular velocity.
56 * @param dt The duration of the timestep the speeds should be applied for.
57 *
58 * @return Discretized ChassisSpeeds.
59 */
60 static ChassisSpeeds Discretize(units::meters_per_second_t vx,
61 units::meters_per_second_t vy,
62 units::radians_per_second_t omega,
63 units::second_t dt) {
64 Pose2d desiredDeltaPose{vx * dt, vy * dt, omega * dt};
65 auto twist = Pose2d{}.Log(desiredDeltaPose);
66 return {twist.dx / dt, twist.dy / dt, twist.dtheta / dt};
67 }
68
69 /**
70 * Disretizes a continuous-time chassis speed.
71 *
72 * This function converts a continuous-time chassis speed into a discrete-time
73 * one such that when the discrete-time chassis speed is applied for one
74 * timestep, the robot moves as if the velocity components are independent
75 * (i.e., the robot moves v_x * dt along the x-axis, v_y * dt along the
76 * y-axis, and omega * dt around the z-axis).
77 *
78 * This is useful for compensating for translational skew when translating and
79 * rotating a swerve drivetrain.
80 *
81 * @param continuousSpeeds The continuous speeds.
82 * @param dt The duration of the timestep the speeds should be applied for.
83 *
84 * @return Discretized ChassisSpeeds.
85 */
86 static ChassisSpeeds Discretize(const ChassisSpeeds& continuousSpeeds,
87 units::second_t dt) {
88 return Discretize(continuousSpeeds.vx, continuousSpeeds.vy,
89 continuousSpeeds.omega, dt);
90 }
91
92 /**
93 * Converts a user provided field-relative set of speeds into a robot-relative
94 * ChassisSpeeds object.
95 *
96 * @param vx The component of speed in the x direction relative to the field.
97 * Positive x is away from your alliance wall.
98 * @param vy The component of speed in the y direction relative to the field.
99 * Positive y is to your left when standing behind the alliance wall.
100 * @param omega The angular rate of the robot.
101 * @param robotAngle The angle of the robot as measured by a gyroscope. The
102 * robot's angle is considered to be zero when it is facing directly away from
103 * your alliance station wall. Remember that this should be CCW positive.
104 *
105 * @return ChassisSpeeds object representing the speeds in the robot's frame
106 * of reference.
107 */
109 units::meters_per_second_t vx, units::meters_per_second_t vy,
110 units::radians_per_second_t omega, const Rotation2d& robotAngle) {
111 // CW rotation into chassis frame
112 auto rotated =
113 Translation2d{units::meter_t{vx.value()}, units::meter_t{vy.value()}}
114 .RotateBy(-robotAngle);
115 return {units::meters_per_second_t{rotated.X().value()},
116 units::meters_per_second_t{rotated.Y().value()}, omega};
117 }
118
119 /**
120 * Converts a user provided field-relative ChassisSpeeds object into a
121 * robot-relative ChassisSpeeds object.
122 *
123 * @param fieldRelativeSpeeds The ChassisSpeeds object representing the speeds
124 * in the field frame of reference. Positive x is away from your alliance
125 * wall. Positive y is to your left when standing behind the alliance wall.
126 * @param robotAngle The angle of the robot as measured by a gyroscope. The
127 * robot's angle is considered to be zero when it is facing directly away
128 * from your alliance station wall. Remember that this should be CCW
129 * positive.
130 * @return ChassisSpeeds object representing the speeds in the robot's frame
131 * of reference.
132 */
134 const ChassisSpeeds& fieldRelativeSpeeds, const Rotation2d& robotAngle) {
135 return FromFieldRelativeSpeeds(fieldRelativeSpeeds.vx,
136 fieldRelativeSpeeds.vy,
137 fieldRelativeSpeeds.omega, robotAngle);
138 }
139
140 /**
141 * Converts a user provided robot-relative set of speeds into a field-relative
142 * ChassisSpeeds object.
143 *
144 * @param vx The component of speed in the x direction relative to the robot.
145 * Positive x is towards the robot's front.
146 * @param vy The component of speed in the y direction relative to the robot.
147 * Positive y is towards the robot's left.
148 * @param omega The angular rate of the robot.
149 * @param robotAngle The angle of the robot as measured by a gyroscope. The
150 * robot's angle is considered to be zero when it is facing directly away from
151 * your alliance station wall. Remember that this should be CCW positive.
152 *
153 * @return ChassisSpeeds object representing the speeds in the field's frame
154 * of reference.
155 */
157 units::meters_per_second_t vx, units::meters_per_second_t vy,
158 units::radians_per_second_t omega, const Rotation2d& robotAngle) {
159 // CCW rotation out of chassis frame
160 auto rotated =
161 Translation2d{units::meter_t{vx.value()}, units::meter_t{vy.value()}}
162 .RotateBy(robotAngle);
163 return {units::meters_per_second_t{rotated.X().value()},
164 units::meters_per_second_t{rotated.Y().value()}, omega};
165 }
166
167 /**
168 * Converts a user provided robot-relative ChassisSpeeds object into a
169 * field-relative ChassisSpeeds object.
170 *
171 * @param robotRelativeSpeeds The ChassisSpeeds object representing the speeds
172 * in the robot frame of reference. Positive x is the towards robot's
173 * front. Positive y is towards the robot's left.
174 * @param robotAngle The angle of the robot as measured by a gyroscope. The
175 * robot's angle is considered to be zero when it is facing directly away
176 * from your alliance station wall. Remember that this should be CCW
177 * positive.
178 * @return ChassisSpeeds object representing the speeds in the field's frame
179 * of reference.
180 */
182 const ChassisSpeeds& robotRelativeSpeeds, const Rotation2d& robotAngle) {
183 return FromRobotRelativeSpeeds(robotRelativeSpeeds.vx,
184 robotRelativeSpeeds.vy,
185 robotRelativeSpeeds.omega, robotAngle);
186 }
187
188 /**
189 * Adds two ChassisSpeeds and returns the sum.
190 *
191 * <p>For example, ChassisSpeeds{1.0, 0.5, 1.5} + ChassisSpeeds{2.0, 1.5, 0.5}
192 * = ChassisSpeeds{3.0, 2.0, 2.0}
193 *
194 * @param other The ChassisSpeeds to add.
195 *
196 * @return The sum of the ChassisSpeeds.
197 */
198 constexpr ChassisSpeeds operator+(const ChassisSpeeds& other) const {
199 return {vx + other.vx, vy + other.vy, omega + other.omega};
200 }
201
202 /**
203 * Subtracts the other ChassisSpeeds from the current ChassisSpeeds and
204 * returns the difference.
205 *
206 * <p>For example, ChassisSpeeds{5.0, 4.0, 2.0} - ChassisSpeeds{1.0, 2.0, 1.0}
207 * = ChassisSpeeds{4.0, 2.0, 1.0}
208 *
209 * @param other The ChassisSpeeds to subtract.
210 *
211 * @return The difference between the two ChassisSpeeds.
212 */
213 constexpr ChassisSpeeds operator-(const ChassisSpeeds& other) const {
214 return *this + -other;
215 }
216
217 /**
218 * Returns the inverse of the current ChassisSpeeds.
219 * This is equivalent to negating all components of the ChassisSpeeds.
220 *
221 * @return The inverse of the current ChassisSpeeds.
222 */
223 constexpr ChassisSpeeds operator-() const { return {-vx, -vy, -omega}; }
224
225 /**
226 * Multiplies the ChassisSpeeds by a scalar and returns the new ChassisSpeeds.
227 *
228 * <p>For example, ChassisSpeeds{2.0, 2.5, 1.0} * 2
229 * = ChassisSpeeds{4.0, 5.0, 1.0}
230 *
231 * @param scalar The scalar to multiply by.
232 *
233 * @return The scaled ChassisSpeeds.
234 */
235 constexpr ChassisSpeeds operator*(double scalar) const {
236 return {scalar * vx, scalar * vy, scalar * omega};
237 }
238
239 /**
240 * Divides the ChassisSpeeds by a scalar and returns the new ChassisSpeeds.
241 *
242 * <p>For example, ChassisSpeeds{2.0, 2.5, 1.0} / 2
243 * = ChassisSpeeds{1.0, 1.25, 0.5}
244 *
245 * @param scalar The scalar to divide by.
246 *
247 * @return The scaled ChassisSpeeds.
248 */
249 constexpr ChassisSpeeds operator/(double scalar) const {
250 return operator*(1.0 / scalar);
251 }
252};
253} // namespace frc
254
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:23
Twist2d Log(const Pose2d &end) const
Returns a Twist2d that maps this pose to the end pose.
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:23
Represents a translation in 2D space.
Definition: Translation2d.h:27
constexpr units::meter_t X() const
Returns the X component of the translation.
Definition: Translation2d.h:76
constexpr Translation2d RotateBy(const Rotation2d &other) const
Applies a rotation to the translation in 2D space.
Definition: Translation2d.inc:27
Definition: AprilTagPoseEstimator.h:15
unit< std::ratio< 1 >, units::category::scalar_unit > scalar
Definition: base.h:2510
constexpr auto operator*(const UnitTypeLhs &lhs, const UnitTypeRhs &rhs) noexcept -> unit_t< compound_unit< squared< typename units::traits::unit_t_traits< UnitTypeLhs >::unit_type > > >
Multiplication type for convertible unit_t types with a linear scale.
Definition: base.h:2588
Represents the speed of a robot chassis.
Definition: ChassisSpeeds.h:25
units::meters_per_second_t vx
Velocity along the x-axis.
Definition: ChassisSpeeds.h:29
units::meters_per_second_t vy
Velocity along the y-axis.
Definition: ChassisSpeeds.h:34
static ChassisSpeeds FromFieldRelativeSpeeds(const ChassisSpeeds &fieldRelativeSpeeds, const Rotation2d &robotAngle)
Converts a user provided field-relative ChassisSpeeds object into a robot-relative ChassisSpeeds obje...
Definition: ChassisSpeeds.h:133
units::radians_per_second_t omega
Represents the angular velocity of the robot frame.
Definition: ChassisSpeeds.h:39
static ChassisSpeeds Discretize(units::meters_per_second_t vx, units::meters_per_second_t vy, units::radians_per_second_t omega, units::second_t dt)
Disretizes a continuous-time chassis speed.
Definition: ChassisSpeeds.h:60
constexpr ChassisSpeeds operator+(const ChassisSpeeds &other) const
Adds two ChassisSpeeds and returns the sum.
Definition: ChassisSpeeds.h:198
static ChassisSpeeds FromRobotRelativeSpeeds(const ChassisSpeeds &robotRelativeSpeeds, const Rotation2d &robotAngle)
Converts a user provided robot-relative ChassisSpeeds object into a field-relative ChassisSpeeds obje...
Definition: ChassisSpeeds.h:181
static ChassisSpeeds FromRobotRelativeSpeeds(units::meters_per_second_t vx, units::meters_per_second_t vy, units::radians_per_second_t omega, const Rotation2d &robotAngle)
Converts a user provided robot-relative set of speeds into a field-relative ChassisSpeeds object.
Definition: ChassisSpeeds.h:156
constexpr ChassisSpeeds operator-(const ChassisSpeeds &other) const
Subtracts the other ChassisSpeeds from the current ChassisSpeeds and returns the difference.
Definition: ChassisSpeeds.h:213
static ChassisSpeeds Discretize(const ChassisSpeeds &continuousSpeeds, units::second_t dt)
Disretizes a continuous-time chassis speed.
Definition: ChassisSpeeds.h:86
static ChassisSpeeds FromFieldRelativeSpeeds(units::meters_per_second_t vx, units::meters_per_second_t vy, units::radians_per_second_t omega, const Rotation2d &robotAngle)
Converts a user provided field-relative set of speeds into a robot-relative ChassisSpeeds object.
Definition: ChassisSpeeds.h:108
constexpr ChassisSpeeds operator*(double scalar) const
Multiplies the ChassisSpeeds by a scalar and returns the new ChassisSpeeds.
Definition: ChassisSpeeds.h:235
constexpr ChassisSpeeds operator/(double scalar) const
Divides the ChassisSpeeds by a scalar and returns the new ChassisSpeeds.
Definition: ChassisSpeeds.h:249
constexpr ChassisSpeeds operator-() const
Returns the inverse of the current ChassisSpeeds.
Definition: ChassisSpeeds.h:223
units::meter_t dx
Linear "dx" component.
Definition: Twist2d.h:25