WPILibC++ 2025.3.1
Loading...
Searching...
No Matches
TrapezoidProfile.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 <type_traits>
8
9#include "units/math.h"
10#include "units/time.h"
11#include "wpimath/MathShared.h"
12
13namespace frc {
14
15/**
16 * A trapezoid-shaped velocity profile.
17 *
18 * While this class can be used for a profiled movement from start to finish,
19 * the intended usage is to filter a reference's dynamics based on trapezoidal
20 * velocity constraints. To compute the reference obeying this constraint, do
21 * the following.
22 *
23 * Initialization:
24 * @code{.cpp}
25 * TrapezoidProfile::Constraints constraints{kMaxV, kMaxA};
26 * double previousProfiledReference = initialReference;
27 * TrapezoidProfile profile{constraints};
28 * @endcode
29 *
30 * Run on update:
31 * @code{.cpp}
32 * previousProfiledReference = profile.Calculate(timeSincePreviousUpdate,
33 * previousProfiledReference,
34 * unprofiledReference);
35 * @endcode
36 *
37 * where `unprofiledReference` is free to change between calls. Note that when
38 * the unprofiled reference is within the constraints, `Calculate()` returns the
39 * unprofiled reference unchanged.
40 *
41 * Otherwise, a timer can be started to provide monotonic values for
42 * `Calculate()` and to determine when the profile has completed via
43 * `IsFinished()`.
44 */
45template <class Distance>
47 public:
49 using Velocity =
55
56 /**
57 * Profile constraints.
58 */
60 public:
61 /// Maximum velocity.
63
64 /// Maximum acceleration.
66
67 /**
68 * Default constructor.
69 */
70 constexpr Constraints() {
71 if (!std::is_constant_evaluated()) {
74 }
75 }
76
77 /**
78 * Constructs constraints for a Trapezoid Profile.
79 *
80 * @param maxVelocity Maximum velocity.
81 * @param maxAcceleration Maximum acceleration.
82 */
91 };
92
93 /**
94 * Profile state.
95 */
96 class State {
97 public:
98 /// The position at this state.
100
101 /// The velocity at this state.
103
104 constexpr bool operator==(const State&) const = default;
105 };
106
107 /**
108 * Constructs a TrapezoidProfile.
109 *
110 * @param constraints The constraints on the profile, like maximum velocity.
111 */
112 constexpr TrapezoidProfile(Constraints constraints) // NOLINT
113 : m_constraints(constraints) {}
114
115 constexpr TrapezoidProfile(const TrapezoidProfile&) = default;
116 constexpr TrapezoidProfile& operator=(const TrapezoidProfile&) = default;
117 constexpr TrapezoidProfile(TrapezoidProfile&&) = default;
119
120 /**
121 * Calculates the position and velocity for the profile at a time t where the
122 * current state is at time t = 0.
123 *
124 * @param t How long to advance from the current state toward the desired
125 * state.
126 * @param current The current state.
127 * @param goal The desired state when the profile is complete.
128 * @return The position and velocity of the profile at time t.
129 */
130 constexpr State Calculate(units::second_t t, State current, State goal) {
131 m_direction = ShouldFlipAcceleration(current, goal) ? -1 : 1;
132 m_current = Direct(current);
133 goal = Direct(goal);
134 if (m_current.velocity > m_constraints.maxVelocity) {
135 m_current.velocity = m_constraints.maxVelocity;
136 }
137
138 // Deal with a possibly truncated motion profile (with nonzero initial or
139 // final velocity) by calculating the parameters as if the profile began and
140 // ended at zero velocity
141 units::second_t cutoffBegin =
142 m_current.velocity / m_constraints.maxAcceleration;
143 Distance_t cutoffDistBegin =
144 cutoffBegin * cutoffBegin * m_constraints.maxAcceleration / 2.0;
145
146 units::second_t cutoffEnd = goal.velocity / m_constraints.maxAcceleration;
147 Distance_t cutoffDistEnd =
148 cutoffEnd * cutoffEnd * m_constraints.maxAcceleration / 2.0;
149
150 // Now we can calculate the parameters as if it was a full trapezoid instead
151 // of a truncated one
152
153 Distance_t fullTrapezoidDist =
154 cutoffDistBegin + (goal.position - m_current.position) + cutoffDistEnd;
155 units::second_t accelerationTime =
156 m_constraints.maxVelocity / m_constraints.maxAcceleration;
157
158 Distance_t fullSpeedDist =
159 fullTrapezoidDist -
160 accelerationTime * accelerationTime * m_constraints.maxAcceleration;
161
162 // Handle the case where the profile never reaches full speed
163 if (fullSpeedDist < Distance_t{0}) {
164 accelerationTime =
165 units::math::sqrt(fullTrapezoidDist / m_constraints.maxAcceleration);
166 fullSpeedDist = Distance_t{0};
167 }
168
169 m_endAccel = accelerationTime - cutoffBegin;
170 m_endFullSpeed = m_endAccel + fullSpeedDist / m_constraints.maxVelocity;
171 m_endDecel = m_endFullSpeed + accelerationTime - cutoffEnd;
172 State result = m_current;
173
174 if (t < m_endAccel) {
175 result.velocity += t * m_constraints.maxAcceleration;
176 result.position +=
177 (m_current.velocity + t * m_constraints.maxAcceleration / 2.0) * t;
178 } else if (t < m_endFullSpeed) {
179 result.velocity = m_constraints.maxVelocity;
180 result.position += (m_current.velocity +
181 m_endAccel * m_constraints.maxAcceleration / 2.0) *
182 m_endAccel +
183 m_constraints.maxVelocity * (t - m_endAccel);
184 } else if (t <= m_endDecel) {
185 result.velocity =
186 goal.velocity + (m_endDecel - t) * m_constraints.maxAcceleration;
187 units::second_t timeLeft = m_endDecel - t;
188 result.position =
189 goal.position -
190 (goal.velocity + timeLeft * m_constraints.maxAcceleration / 2.0) *
191 timeLeft;
192 } else {
193 result = goal;
194 }
195
196 return Direct(result);
197 }
198
199 /**
200 * Returns the time left until a target distance in the profile is reached.
201 *
202 * @param target The target distance.
203 * @return The time left until a target distance in the profile is reached.
204 */
205 constexpr units::second_t TimeLeftUntil(Distance_t target) const {
206 Distance_t position = m_current.position * m_direction;
207 Velocity_t velocity = m_current.velocity * m_direction;
208
209 units::second_t endAccel = m_endAccel * m_direction;
210 units::second_t endFullSpeed = m_endFullSpeed * m_direction - endAccel;
211
212 if (target < position) {
213 endAccel *= -1.0;
214 endFullSpeed *= -1.0;
215 velocity *= -1.0;
216 }
217
218 endAccel = units::math::max(endAccel, 0_s);
219 endFullSpeed = units::math::max(endFullSpeed, 0_s);
220
221 const Acceleration_t acceleration = m_constraints.maxAcceleration;
222 const Acceleration_t deceleration = -m_constraints.maxAcceleration;
223
224 Distance_t distToTarget = units::math::abs(target - position);
225
226 if (distToTarget < Distance_t{1e-6}) {
227 return 0_s;
228 }
229
230 Distance_t accelDist =
231 velocity * endAccel + 0.5 * acceleration * endAccel * endAccel;
232
233 Velocity_t decelVelocity;
234 if (endAccel > 0_s) {
235 decelVelocity = units::math::sqrt(
236 units::math::abs(velocity * velocity + 2 * acceleration * accelDist));
237 } else {
238 decelVelocity = velocity;
239 }
240
241 Distance_t fullSpeedDist = m_constraints.maxVelocity * endFullSpeed;
242 Distance_t decelDist;
243
244 if (accelDist > distToTarget) {
245 accelDist = distToTarget;
246 fullSpeedDist = Distance_t{0};
247 decelDist = Distance_t{0};
248 } else if (accelDist + fullSpeedDist > distToTarget) {
249 fullSpeedDist = distToTarget - accelDist;
250 decelDist = Distance_t{0};
251 } else {
252 decelDist = distToTarget - fullSpeedDist - accelDist;
253 }
254
255 units::second_t accelTime =
257 velocity * velocity + 2 * acceleration * accelDist))) /
258 acceleration;
259
260 units::second_t decelTime =
261 (-decelVelocity +
262 units::math::sqrt(units::math::abs(decelVelocity * decelVelocity +
263 2 * deceleration * decelDist))) /
264 deceleration;
265
266 units::second_t fullSpeedTime = fullSpeedDist / m_constraints.maxVelocity;
267
268 return accelTime + fullSpeedTime + decelTime;
269 }
270
271 /**
272 * Returns the total time the profile takes to reach the goal.
273 *
274 * @return The total time the profile takes to reach the goal.
275 */
276 constexpr units::second_t TotalTime() const { return m_endDecel; }
277
278 /**
279 * Returns true if the profile has reached the goal.
280 *
281 * The profile has reached the goal if the time since the profile started has
282 * exceeded the profile's total time.
283 *
284 * @param t The time since the beginning of the profile.
285 * @return True if the profile has reached the goal.
286 */
287 constexpr bool IsFinished(units::second_t t) const {
288 return t >= TotalTime();
289 }
290
291 private:
292 /**
293 * Returns true if the profile inverted.
294 *
295 * The profile is inverted if goal position is less than the initial position.
296 *
297 * @param initial The initial state (usually the current state).
298 * @param goal The desired state when the profile is complete.
299 */
300 static constexpr bool ShouldFlipAcceleration(const State& initial,
301 const State& goal) {
302 return initial.position > goal.position;
303 }
304
305 // Flip the sign of the velocity and position if the profile is inverted
306 constexpr State Direct(const State& in) const {
307 State result = in;
308 result.position *= m_direction;
309 result.velocity *= m_direction;
310 return result;
311 }
312
313 // The direction of the profile, either 1 for forwards or -1 for inverted
314 int m_direction;
315
316 Constraints m_constraints;
317 State m_current;
318
319 units::second_t m_endAccel;
320 units::second_t m_endFullSpeed;
321 units::second_t m_endDecel;
322};
323
324} // namespace frc
Profile constraints.
Definition TrapezoidProfile.h:59
constexpr Constraints(Velocity_t maxVelocity, Acceleration_t maxAcceleration)
Constructs constraints for a Trapezoid Profile.
Definition TrapezoidProfile.h:83
Velocity_t maxVelocity
Maximum velocity.
Definition TrapezoidProfile.h:62
constexpr Constraints()
Default constructor.
Definition TrapezoidProfile.h:70
Acceleration_t maxAcceleration
Maximum acceleration.
Definition TrapezoidProfile.h:65
Profile state.
Definition TrapezoidProfile.h:96
constexpr bool operator==(const State &) const =default
Velocity_t velocity
The velocity at this state.
Definition TrapezoidProfile.h:102
Distance_t position
The position at this state.
Definition TrapezoidProfile.h:99
A trapezoid-shaped velocity profile.
Definition TrapezoidProfile.h:46
constexpr TrapezoidProfile & operator=(const TrapezoidProfile &)=default
constexpr TrapezoidProfile(Constraints constraints)
Constructs a TrapezoidProfile.
Definition TrapezoidProfile.h:112
constexpr TrapezoidProfile & operator=(TrapezoidProfile &&)=default
constexpr TrapezoidProfile(const TrapezoidProfile &)=default
constexpr units::second_t TotalTime() const
Returns the total time the profile takes to reach the goal.
Definition TrapezoidProfile.h:276
units::compound_unit< Distance, units::inverse< units::seconds > > Velocity
Definition TrapezoidProfile.h:49
constexpr bool IsFinished(units::second_t t) const
Returns true if the profile has reached the goal.
Definition TrapezoidProfile.h:287
constexpr units::second_t TimeLeftUntil(Distance_t target) const
Returns the time left until a target distance in the profile is reached.
Definition TrapezoidProfile.h:205
constexpr TrapezoidProfile(TrapezoidProfile &&)=default
constexpr State Calculate(units::second_t t, State current, State goal)
Calculates the position and velocity for the profile at a time t where the current state is at time t...
Definition TrapezoidProfile.h:130
units::compound_unit< Velocity, units::inverse< units::seconds > > Acceleration
Definition TrapezoidProfile.h:52
static void ReportUsage(MathUsageId id, int count)
Definition MathShared.h:75
constexpr UnitType abs(const UnitType x) noexcept
Compute absolute value.
Definition math.h:726
constexpr auto sqrt(const UnitType &value) noexcept -> unit_t< square_root< typename units::traits::unit_t_traits< UnitType >::unit_type >, typename units::traits::unit_t_traits< UnitType >::underlying_type, linear_scale >
computes the square root of value
Definition math.h:485
typename units::detail::compound_impl< U, Us... >::type compound_unit
Represents a unit type made up from other units.
Definition base.h:1438
State
Possible state of a SysId routine.
Definition SysIdRoutineLog.h:25
Definition CAN.h:11
constexpr UnitTypeLhs max(const UnitTypeLhs &lhs, const UnitTypeRhs &rhs)
Definition base.h:3422