WPILibC++ 2027.0.0-alpha-2
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()) {
72 wpi::math::MathSharedStore::ReportUsage("TrapezoidProfile", "");
73 }
74 }
75
76 /**
77 * Constructs constraints for a Trapezoid Profile.
78 *
79 * @param maxVelocity Maximum velocity, must be non-negative.
80 * @param maxAcceleration Maximum acceleration, must be non-negative.
81 */
85 if (!std::is_constant_evaluated()) {
86 wpi::math::MathSharedStore::ReportUsage("TrapezoidProfile", "");
87 }
88
90 throw std::domain_error("Constraints must be non-negative");
91 }
92 }
93 };
94
95 /**
96 * Profile state.
97 */
98 class State {
99 public:
100 /// The position at this state.
102
103 /// The velocity at this state.
105
106 constexpr bool operator==(const State&) const = default;
107 };
108
109 /**
110 * Constructs a TrapezoidProfile.
111 *
112 * @param constraints The constraints on the profile, like maximum velocity.
113 */
114 constexpr TrapezoidProfile(Constraints constraints) // NOLINT
115 : m_constraints(constraints) {}
116
117 constexpr TrapezoidProfile(const TrapezoidProfile&) = default;
118 constexpr TrapezoidProfile& operator=(const TrapezoidProfile&) = default;
119 constexpr TrapezoidProfile(TrapezoidProfile&&) = default;
121
122 /**
123 * Calculates the position and velocity for the profile at a time t where the
124 * current state is at time t = 0.
125 *
126 * @param t How long to advance from the current state toward the desired
127 * state.
128 * @param current The current state.
129 * @param goal The desired state when the profile is complete.
130 * @return The position and velocity of the profile at time t.
131 */
132 constexpr State Calculate(units::second_t t, State current, State goal) {
133 m_direction = ShouldFlipAcceleration(current, goal) ? -1 : 1;
134 m_current = Direct(current);
135 goal = Direct(goal);
136 if (units::math::abs(m_current.velocity) > m_constraints.maxVelocity) {
137 m_current.velocity =
138 units::math::copysign(m_constraints.maxVelocity, m_current.velocity);
139 }
140
141 // Deal with a possibly truncated motion profile (with nonzero initial or
142 // final velocity) by calculating the parameters as if the profile began and
143 // ended at zero velocity
144 units::second_t cutoffBegin =
145 m_current.velocity / m_constraints.maxAcceleration;
146 Distance_t cutoffDistBegin =
147 cutoffBegin * cutoffBegin * m_constraints.maxAcceleration / 2.0;
148
149 units::second_t cutoffEnd = goal.velocity / m_constraints.maxAcceleration;
150 Distance_t cutoffDistEnd =
151 cutoffEnd * cutoffEnd * m_constraints.maxAcceleration / 2.0;
152
153 // Now we can calculate the parameters as if it was a full trapezoid instead
154 // of a truncated one
155
156 Distance_t fullTrapezoidDist =
157 cutoffDistBegin + (goal.position - m_current.position) + cutoffDistEnd;
158 units::second_t accelerationTime =
159 m_constraints.maxVelocity / m_constraints.maxAcceleration;
160
161 Distance_t fullSpeedDist =
162 fullTrapezoidDist -
163 accelerationTime * accelerationTime * m_constraints.maxAcceleration;
164
165 // Handle the case where the profile never reaches full speed
166 if (fullSpeedDist < Distance_t{0}) {
167 accelerationTime =
168 units::math::sqrt(fullTrapezoidDist / m_constraints.maxAcceleration);
169 fullSpeedDist = Distance_t{0};
170 }
171
172 m_endAccel = accelerationTime - cutoffBegin;
173 m_endFullSpeed = m_endAccel + fullSpeedDist / m_constraints.maxVelocity;
174 m_endDecel = m_endFullSpeed + accelerationTime - cutoffEnd;
175 State result = m_current;
176
177 if (t < m_endAccel) {
178 result.velocity += t * m_constraints.maxAcceleration;
179 result.position +=
180 (m_current.velocity + t * m_constraints.maxAcceleration / 2.0) * t;
181 } else if (t < m_endFullSpeed) {
182 result.velocity = m_constraints.maxVelocity;
183 result.position += (m_current.velocity +
184 m_endAccel * m_constraints.maxAcceleration / 2.0) *
185 m_endAccel +
186 m_constraints.maxVelocity * (t - m_endAccel);
187 } else if (t <= m_endDecel) {
188 result.velocity =
189 goal.velocity + (m_endDecel - t) * m_constraints.maxAcceleration;
190 units::second_t timeLeft = m_endDecel - t;
191 result.position =
192 goal.position -
193 (goal.velocity + timeLeft * m_constraints.maxAcceleration / 2.0) *
194 timeLeft;
195 } else {
196 result = goal;
197 }
198
199 return Direct(result);
200 }
201
202 /**
203 * Returns the time left until a target distance in the profile is reached.
204 *
205 * @param target The target distance.
206 * @return The time left until a target distance in the profile is reached, or
207 * zero if no goal was set.
208 */
209 constexpr units::second_t TimeLeftUntil(Distance_t target) const {
210 Distance_t position = m_current.position * m_direction;
211 Velocity_t velocity = m_current.velocity * m_direction;
212
213 units::second_t endAccel = m_endAccel * m_direction;
214 units::second_t endFullSpeed = m_endFullSpeed * m_direction - endAccel;
215
216 if (target < position) {
217 endAccel *= -1.0;
218 endFullSpeed *= -1.0;
219 velocity *= -1.0;
220 }
221
222 endAccel = units::math::max(endAccel, 0_s);
223 endFullSpeed = units::math::max(endFullSpeed, 0_s);
224
225 const Acceleration_t acceleration = m_constraints.maxAcceleration;
226 const Acceleration_t deceleration = -m_constraints.maxAcceleration;
227
228 Distance_t distToTarget = units::math::abs(target - position);
229
230 if (distToTarget < Distance_t{1e-6}) {
231 return 0_s;
232 }
233
234 Distance_t accelDist =
235 velocity * endAccel + 0.5 * acceleration * endAccel * endAccel;
236
237 Velocity_t decelVelocity;
238 if (endAccel > 0_s) {
239 decelVelocity = units::math::sqrt(
240 units::math::abs(velocity * velocity + 2 * acceleration * accelDist));
241 } else {
242 decelVelocity = velocity;
243 }
244
245 Distance_t fullSpeedDist = m_constraints.maxVelocity * endFullSpeed;
246 Distance_t decelDist;
247
248 if (accelDist > distToTarget) {
249 accelDist = distToTarget;
250 fullSpeedDist = Distance_t{0};
251 decelDist = Distance_t{0};
252 } else if (accelDist + fullSpeedDist > distToTarget) {
253 fullSpeedDist = distToTarget - accelDist;
254 decelDist = Distance_t{0};
255 } else {
256 decelDist = distToTarget - fullSpeedDist - accelDist;
257 }
258
259 units::second_t accelTime =
261 velocity * velocity + 2 * acceleration * accelDist))) /
262 acceleration;
263
264 units::second_t decelTime =
265 (-decelVelocity +
266 units::math::sqrt(units::math::abs(decelVelocity * decelVelocity +
267 2 * deceleration * decelDist))) /
268 deceleration;
269
270 units::second_t fullSpeedTime = fullSpeedDist / m_constraints.maxVelocity;
271
272 return accelTime + fullSpeedTime + decelTime;
273 }
274
275 /**
276 * Returns the total time the profile takes to reach the goal.
277 *
278 * @return The total time the profile takes to reach the goal, or zero if no
279 * goal was set.
280 */
281 constexpr units::second_t TotalTime() const { return m_endDecel; }
282
283 /**
284 * Returns true if the profile has reached the goal.
285 *
286 * The profile has reached the goal if the time since the profile started has
287 * exceeded the profile's total time.
288 *
289 * @param t The time since the beginning of the profile.
290 * @return True if the profile has reached the goal.
291 */
292 constexpr bool IsFinished(units::second_t t) const {
293 return t >= TotalTime();
294 }
295
296 private:
297 /**
298 * Returns true if the profile inverted.
299 *
300 * The profile is inverted if goal position is less than the initial position.
301 *
302 * @param initial The initial state (usually the current state).
303 * @param goal The desired state when the profile is complete.
304 */
305 static constexpr bool ShouldFlipAcceleration(const State& initial,
306 const State& goal) {
307 return initial.position > goal.position;
308 }
309
310 // Flip the sign of the velocity and position if the profile is inverted
311 constexpr State Direct(const State& in) const {
312 State result = in;
313 result.position *= m_direction;
314 result.velocity *= m_direction;
315 return result;
316 }
317
318 // The direction of the profile, either 1 for forwards or -1 for inverted
319 int m_direction = 1;
320
321 Constraints m_constraints;
322 State m_current;
323
324 units::second_t m_endAccel = 0_s;
325 units::second_t m_endFullSpeed = 0_s;
326 units::second_t m_endDecel = 0_s;
327};
328
329} // 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:82
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:98
constexpr bool operator==(const State &) const =default
Velocity_t velocity
The velocity at this state.
Definition TrapezoidProfile.h:104
Distance_t position
The position at this state.
Definition TrapezoidProfile.h:101
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:114
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:281
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:292
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:209
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:132
units::compound_unit< Velocity, units::inverse< units::seconds > > Acceleration
Definition TrapezoidProfile.h:52
static void ReportUsage(std::string_view resource, std::string_view data)
Definition MathShared.h:61
constexpr UnitType abs(const UnitType x) noexcept
Compute absolute value.
Definition math.h:726
constexpr UnitTypeLhs copysign(const UnitTypeLhs x, const UnitTypeRhs y) noexcept
Copy sign.
Definition math.h:615
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 SystemServer.h:9
constexpr UnitTypeLhs max(const UnitTypeLhs &lhs, const UnitTypeRhs &rhs)
Definition base.h:3422