10#include "units/time.h"
45template <
class Distance>
50 units::compound_unit<Distance, units::inverse<units::seconds>>;
53 units::compound_unit<Velocity, units::inverse<units::seconds>>;
71 if (!std::is_constant_evaluated()) {
85 if (!std::is_constant_evaluated()) {
90 throw std::domain_error(
"Constraints must be non-negative");
115 : m_constraints(constraints) {}
133 m_direction = ShouldFlipAcceleration(current, goal) ? -1 : 1;
134 m_current = Direct(current);
144 units::second_t cutoffBegin =
158 units::second_t accelerationTime =
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;
177 if (t < m_endAccel) {
181 }
else if (t < m_endFullSpeed) {
183 result.position += (m_current.
velocity +
187 }
else if (t <= m_endDecel) {
190 units::second_t timeLeft = m_endDecel - t;
199 return Direct(result);
213 units::second_t endAccel = m_endAccel * m_direction;
214 units::second_t endFullSpeed = m_endFullSpeed * m_direction - endAccel;
216 if (target < position) {
218 endFullSpeed *= -1.0;
222 endAccel = units::math::max(endAccel, 0_s);
223 endFullSpeed = units::math::max(endFullSpeed, 0_s);
228 Distance_t distToTarget = units::math::abs(target - position);
235 velocity * endAccel + 0.5 * acceleration * endAccel * endAccel;
238 if (endAccel > 0_s) {
239 decelVelocity = units::math::sqrt(
240 units::math::abs(velocity * velocity + 2 * acceleration * accelDist));
242 decelVelocity = velocity;
248 if (accelDist > distToTarget) {
249 accelDist = distToTarget;
252 }
else if (accelDist + fullSpeedDist > distToTarget) {
253 fullSpeedDist = distToTarget - accelDist;
256 decelDist = distToTarget - fullSpeedDist - accelDist;
259 units::second_t accelTime =
260 (-velocity + units::math::sqrt(units::math::abs(
261 velocity * velocity + 2 * acceleration * accelDist))) /
264 units::second_t decelTime =
266 units::math::sqrt(units::math::abs(decelVelocity * decelVelocity +
267 2 * deceleration * decelDist))) /
270 units::second_t fullSpeedTime = fullSpeedDist / m_constraints.
maxVelocity;
272 return accelTime + fullSpeedTime + decelTime;
281 constexpr units::second_t
TotalTime()
const {
return m_endDecel; }
305 static constexpr bool ShouldFlipAcceleration(
const State& initial,
307 return initial.position > goal.position;
311 constexpr State Direct(
const State& in)
const {
313 result.position *= m_direction;
314 result.velocity *= m_direction;
321 Constraints m_constraints;
324 units::second_t m_endAccel = 0_s;
325 units::second_t m_endFullSpeed = 0_s;
326 units::second_t m_endDecel = 0_s;
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
units::unit_t< Distance > Distance_t
Definition TrapezoidProfile.h:48
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::unit_t< Acceleration > Acceleration_t
Definition TrapezoidProfile.h:54
units::compound_unit< Velocity, units::inverse< units::seconds > > Acceleration
Definition TrapezoidProfile.h:52
units::unit_t< Velocity > Velocity_t
Definition TrapezoidProfile.h:51
static void ReportUsage(std::string_view resource, std::string_view data)
Definition MathShared.h:61
State
Possible state of a SysId routine.
Definition SysIdRoutineLog.h:25
Definition SystemServer.h:9