WPILibC++ 2023.4.3-108-ge5452e3
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 "units/time.h"
9
10namespace frc {
11
12/**
13 * A trapezoid-shaped velocity profile.
14 *
15 * While this class can be used for a profiled movement from start to finish,
16 * the intended usage is to filter a reference's dynamics based on trapezoidal
17 * velocity constraints. To compute the reference obeying this constraint, do
18 * the following.
19 *
20 * Initialization:
21 * @code{.cpp}
22 * TrapezoidProfile::Constraints constraints{kMaxV, kMaxA};
23 * double previousProfiledReference = initialReference;
24 * @endcode
25 *
26 * Run on update:
27 * @code{.cpp}
28 * TrapezoidProfile profile{constraints, unprofiledReference,
29 * previousProfiledReference};
30 * previousProfiledReference = profile.Calculate(timeSincePreviousUpdate);
31 * @endcode
32 *
33 * where `unprofiledReference` is free to change between calls. Note that when
34 * the unprofiled reference is within the constraints, `Calculate()` returns the
35 * unprofiled reference unchanged.
36 *
37 * Otherwise, a timer can be started to provide monotonic values for
38 * `Calculate()` and to determine when the profile has completed via
39 * `IsFinished()`.
40 */
41template <class Distance>
43 public:
45 using Velocity =
51
53 public:
57 }
58 Constraints(Velocity_t maxVelocity_, Acceleration_t maxAcceleration_)
59 : maxVelocity{maxVelocity_}, maxAcceleration{maxAcceleration_} {
62 }
65 };
66
67 class State {
68 public:
71 bool operator==(const State&) const = default;
72 };
73
74 /**
75 * Construct a TrapezoidProfile.
76 *
77 * @param constraints The constraints on the profile, like maximum velocity.
78 * @param goal The desired state when the profile is complete.
79 * @param initial The initial state (usually the current state).
80 */
81 TrapezoidProfile(Constraints constraints, State goal,
82 State initial = State{Distance_t{0}, Velocity_t{0}});
83
88
89 /**
90 * Calculate the correct position and velocity for the profile at a time t
91 * where the beginning of the profile was at time t = 0.
92 *
93 * @param t The time since the beginning of the profile.
94 */
95 State Calculate(units::second_t t) const;
96
97 /**
98 * Returns the time left until a target distance in the profile is reached.
99 *
100 * @param target The target distance.
101 */
102 units::second_t TimeLeftUntil(Distance_t target) const;
103
104 /**
105 * Returns the total time the profile takes to reach the goal.
106 */
107 units::second_t TotalTime() const { return m_endDeccel; }
108
109 /**
110 * Returns true if the profile has reached the goal.
111 *
112 * The profile has reached the goal if the time since the profile started
113 * has exceeded the profile's total time.
114 *
115 * @param t The time since the beginning of the profile.
116 */
117 bool IsFinished(units::second_t t) const { return t >= TotalTime(); }
118
119 private:
120 /**
121 * Returns true if the profile inverted.
122 *
123 * The profile is inverted if goal position is less than the initial position.
124 *
125 * @param initial The initial state (usually the current state).
126 * @param goal The desired state when the profile is complete.
127 */
128 static bool ShouldFlipAcceleration(const State& initial, const State& goal) {
129 return initial.position > goal.position;
130 }
131
132 // Flip the sign of the velocity and position if the profile is inverted
133 State Direct(const State& in) const {
134 State result = in;
135 result.position *= m_direction;
136 result.velocity *= m_direction;
137 return result;
138 }
139
140 // The direction of the profile, either 1 for forwards or -1 for inverted
141 int m_direction;
142
143 Constraints m_constraints;
144 State m_initial;
145 State m_goal;
146
147 units::second_t m_endAccel;
148 units::second_t m_endFullSpeed;
149 units::second_t m_endDeccel;
150};
151} // namespace frc
152
153#include "TrapezoidProfile.inc"
Definition: TrapezoidProfile.h:52
Constraints()
Definition: TrapezoidProfile.h:54
Velocity_t maxVelocity
Definition: TrapezoidProfile.h:63
Constraints(Velocity_t maxVelocity_, Acceleration_t maxAcceleration_)
Definition: TrapezoidProfile.h:58
Acceleration_t maxAcceleration
Definition: TrapezoidProfile.h:64
Definition: TrapezoidProfile.h:67
Velocity_t velocity
Definition: TrapezoidProfile.h:70
bool operator==(const State &) const =default
Distance_t position
Definition: TrapezoidProfile.h:69
A trapezoid-shaped velocity profile.
Definition: TrapezoidProfile.h:42
TrapezoidProfile & operator=(const TrapezoidProfile &)=default
units::compound_unit< Velocity, units::inverse< units::seconds > > Acceleration
Definition: TrapezoidProfile.h:49
units::compound_unit< Distance, units::inverse< units::seconds > > Velocity
Definition: TrapezoidProfile.h:46
TrapezoidProfile(const TrapezoidProfile &)=default
State Calculate(units::second_t t) const
Calculate the correct position and velocity for the profile at a time t where the beginning of the pr...
Definition: TrapezoidProfile.inc:62
TrapezoidProfile(Constraints constraints, State goal, State initial=State{Distance_t{0}, Velocity_t{0}})
Construct a TrapezoidProfile.
Definition: TrapezoidProfile.inc:14
units::second_t TimeLeftUntil(Distance_t target) const
Returns the time left until a target distance in the profile is reached.
Definition: TrapezoidProfile.inc:91
units::second_t TotalTime() const
Returns the total time the profile takes to reach the goal.
Definition: TrapezoidProfile.h:107
bool IsFinished(units::second_t t) const
Returns true if the profile has reached the goal.
Definition: TrapezoidProfile.h:117
TrapezoidProfile & operator=(TrapezoidProfile &&)=default
units::unit_t< Velocity > Velocity_t
Definition: TrapezoidProfile.h:47
TrapezoidProfile(TrapezoidProfile &&)=default
static void ReportUsage(MathUsageId id, int count)
Definition: MathShared.h:73
typename units::detail::compound_impl< U, Us... >::type compound_unit
Represents a unit type made up from other units.
Definition: base.h:1445
result
Definition: format.h:2564
Definition: AprilTagPoseEstimator.h:15