WPILibC++ 2027.0.0-alpha-5
Loading...
Searching...
No Matches
Trajectory.hpp
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 <algorithm>
8#include <stdexcept>
9#include <vector>
10
13#include "wpi/units/acceleration.hpp"
14#include "wpi/units/curvature.hpp"
15#include "wpi/units/math.hpp"
16#include "wpi/units/time.hpp"
17#include "wpi/units/velocity.hpp"
20
21namespace wpi::util {
22class json;
23} // namespace wpi::util
24
25namespace wpi::math {
26/**
27 * Represents a time-parameterized trajectory. The trajectory contains of
28 * various States that represent the pose, curvature, time elapsed, velocity,
29 * and acceleration at that point.
30 */
32 public:
33 /**
34 * Represents one point on the trajectory.
35 */
37 /// The time elapsed since the beginning of the trajectory.
38 wpi::units::second_t t = 0_s;
39
40 /// The velocity at that point of the trajectory.
41 wpi::units::meters_per_second_t velocity = 0_mps;
42
43 /// The acceleration at that point of the trajectory.
44 wpi::units::meters_per_second_squared_t acceleration = 0_mps_sq;
45
46 /// The pose at that point of the trajectory.
48
49 /// The curvature at that point of the trajectory.
50 wpi::units::curvature_t curvature{0.0};
51
52 /**
53 * Checks equality between this State and another object.
54 */
55 constexpr bool operator==(const State&) const = default;
56
57 /**
58 * Interpolates between two States.
59 *
60 * @param endValue The end value for the interpolation.
61 * @param i The interpolant (fraction).
62 *
63 * @return The interpolated state.
64 */
65 constexpr State Interpolate(State endValue, double i) const {
66 // Find the new [t] value.
67 const auto newT = wpi::util::Lerp(t, endValue.t, i);
68
69 // Find the delta time between the current state and the interpolated
70 // state.
71 const auto deltaT = newT - t;
72
73 // If delta time is negative, flip the order of interpolation.
74 if (deltaT < 0_s) {
75 return endValue.Interpolate(*this, 1.0 - i);
76 }
77
78 // Check whether the robot is reversing at this stage.
79 const auto reversing =
80 velocity < 0_mps || (wpi::units::math::abs(velocity) < 1E-9_mps &&
81 acceleration < 0_mps_sq);
82
83 // Calculate the new velocity.
84 // v = v_0 + at
85 const wpi::units::meters_per_second_t newV =
86 velocity + (acceleration * deltaT);
87
88 // Calculate the change in position.
89 // delta_s = v_0 t + 0.5at²
90 const wpi::units::meter_t newS =
91 (velocity * deltaT + 0.5 * acceleration * deltaT * deltaT) *
92 (reversing ? -1.0 : 1.0);
93
94 // Return the new state. To find the new position for the new state, we
95 // need to interpolate between the two endpoint poses. The fraction for
96 // interpolation is the change in position (delta s) divided by the total
97 // distance between the two endpoints.
98 const double interpolationFrac =
99 // NOLINTNEXTLINE (bugprone-integer-division)
100 newS / endValue.pose.Translation().Distance(pose.Translation());
101
102 return {
103 newT, newV, acceleration,
104 wpi::util::Lerp(pose, endValue.pose, interpolationFrac),
105 wpi::util::Lerp(curvature, endValue.curvature, interpolationFrac)};
106 }
107 };
108
109 Trajectory() = default;
110
111 /**
112 * Constructs a trajectory from a vector of states.
113 *
114 * @throws std::invalid_argument if the vector of states is empty.
115 */
116 explicit Trajectory(const std::vector<State>& states) : m_states(states) {
117 if (m_states.empty()) {
118 throw std::invalid_argument(
119 "Trajectory manually initialized with no states.");
120 }
121
122 m_totalTime = states.back().t;
123 }
124
125 /**
126 * Returns the overall duration of the trajectory.
127 * @return The duration of the trajectory.
128 */
129 wpi::units::second_t TotalTime() const { return m_totalTime; }
130
131 /**
132 * Return the states of the trajectory.
133 *
134 * @return The states of the trajectory.
135 */
136 const std::vector<State>& States() const { return m_states; }
137
138 /**
139 * Sample the trajectory at a point in time.
140 *
141 * @param t The point in time since the beginning of the trajectory to sample.
142 * @return The state at that point in time.
143 * @throws std::runtime_error if the trajectory has no states.
144 */
145 State Sample(wpi::units::second_t t) const {
146 if (m_states.empty()) {
147 throw std::runtime_error(
148 "Trajectory cannot be sampled if it has no states.");
149 }
150
151 if (t <= m_states.front().t) {
152 return m_states.front();
153 }
154 if (t >= m_totalTime) {
155 return m_states.back();
156 }
157
158 // Use binary search to get the element with a timestamp no less than the
159 // requested timestamp. This starts at 1 because we use the previous state
160 // later on for interpolation.
161 auto sample =
162 std::lower_bound(m_states.cbegin() + 1, m_states.cend(), t,
163 [](const auto& a, const auto& b) { return a.t < b; });
164
165 auto prevSample = sample - 1;
166
167 // The sample's timestamp is now greater than or equal to the requested
168 // timestamp. If it is greater, we need to interpolate between the
169 // previous state and the current state to get the exact state that we
170 // want.
171
172 // If the difference in states is negligible, then we are spot on!
173 if (wpi::units::math::abs(sample->t - prevSample->t) < 1E-9_s) {
174 return *sample;
175 }
176 // Interpolate between the two states for the state that we want.
177 return prevSample->Interpolate(
178 *sample, (t - prevSample->t) / (sample->t - prevSample->t));
179 }
180
181 /**
182 * Transforms all poses in the trajectory by the given transform. This is
183 * useful for converting a robot-relative trajectory into a field-relative
184 * trajectory. This works with respect to the first pose in the trajectory.
185 *
186 * @param transform The transform to transform the trajectory by.
187 * @return The transformed trajectory.
188 */
190 auto& firstState = m_states[0];
191 auto& firstPose = firstState.pose;
192
193 // Calculate the transformed first pose.
194 auto newFirstPose = firstPose + transform;
195 auto newStates = m_states;
196 newStates[0].pose = newFirstPose;
197
198 for (unsigned int i = 1; i < newStates.size(); i++) {
199 auto& state = newStates[i];
200 // We are transforming relative to the coordinate frame of the new initial
201 // pose.
202 state.pose = newFirstPose + (state.pose - firstPose);
203 }
204
205 return Trajectory(newStates);
206 }
207
208 /**
209 * Transforms all poses in the trajectory so that they are relative to the
210 * given pose. This is useful for converting a field-relative trajectory
211 * into a robot-relative trajectory.
212 *
213 * @param pose The pose that is the origin of the coordinate frame that
214 * the current trajectory will be transformed into.
215 * @return The transformed trajectory.
216 */
218 auto newStates = m_states;
219 for (auto& state : newStates) {
220 state.pose = state.pose.RelativeTo(pose);
221 }
222 return Trajectory(newStates);
223 }
224
225 /**
226 * Concatenates another trajectory to the current trajectory. The user is
227 * responsible for making sure that the end pose of this trajectory and the
228 * start pose of the other trajectory match (if that is the desired behavior).
229 *
230 * @param other The trajectory to concatenate.
231 * @return The concatenated trajectory.
232 */
233 Trajectory operator+(const Trajectory& other) const {
234 // If this is a default constructed trajectory with no states, then we can
235 // simply return the rhs trajectory.
236 if (m_states.empty()) {
237 return other;
238 }
239
240 auto states = m_states;
241 auto otherStates = other.States();
242 for (auto& otherState : otherStates) {
243 otherState.t += m_totalTime;
244 }
245
246 // Here we omit the first state of the other trajectory because we don't
247 // want two time points with different states. Sample() will automatically
248 // interpolate between the end of this trajectory and the second state of
249 // the other trajectory.
250 states.insert(states.end(), otherStates.begin() + 1, otherStates.end());
251 return Trajectory(states);
252 }
253
254 /**
255 * Returns the initial pose of the trajectory.
256 *
257 * @return The initial pose of the trajectory.
258 */
259 Pose2d InitialPose() const { return Sample(0_s).pose; }
260
261 /**
262 * Checks equality between this Trajectory and another object.
263 */
264 bool operator==(const Trajectory&) const = default;
265
266 private:
267 std::vector<State> m_states;
268 wpi::units::second_t m_totalTime = 0_s;
269};
270
272void to_json(wpi::util::json& json, const Trajectory::State& state);
273
276
277} // namespace wpi::math
278
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.hpp:30
constexpr const Translation2d & Translation() const
Returns the underlying translation.
Definition Pose2d.hpp:110
Pose2d InitialPose() const
Returns the initial pose of the trajectory.
Definition Trajectory.hpp:259
wpi::units::second_t TotalTime() const
Returns the overall duration of the trajectory.
Definition Trajectory.hpp:129
Trajectory RelativeTo(const Pose2d &pose)
Transforms all poses in the trajectory so that they are relative to the given pose.
Definition Trajectory.hpp:217
bool operator==(const Trajectory &) const =default
Checks equality between this Trajectory and another object.
State Sample(wpi::units::second_t t) const
Sample the trajectory at a point in time.
Definition Trajectory.hpp:145
const std::vector< State > & States() const
Return the states of the trajectory.
Definition Trajectory.hpp:136
Trajectory operator+(const Trajectory &other) const
Concatenates another trajectory to the current trajectory.
Definition Trajectory.hpp:233
Trajectory(const std::vector< State > &states)
Constructs a trajectory from a vector of states.
Definition Trajectory.hpp:116
Trajectory TransformBy(const Transform2d &transform)
Transforms all poses in the trajectory by the given transform.
Definition Trajectory.hpp:189
Represents a transformation for a Pose2d in the pose's frame.
Definition Transform2d.hpp:21
constexpr wpi::units::meter_t Distance(const Translation2d &other) const
Calculates the distance between two translations in 2D space.
Definition Translation2d.hpp:79
Definition json.hpp:85
Definition LinearSystem.hpp:20
WPILIB_DLLEXPORT void to_json(wpi::util::json &json, const Translation2d &state)
WPILIB_DLLEXPORT void from_json(const wpi::util::json &json, Translation2d &state)
Definition raw_os_ostream.hpp:19
constexpr T Lerp(const T &startValue, const T &endValue, double t)
Linearly interpolates between two values.
Definition MathExtras.hpp:780
Represents one point on the trajectory.
Definition Trajectory.hpp:36
wpi::units::second_t t
The time elapsed since the beginning of the trajectory.
Definition Trajectory.hpp:38
constexpr State Interpolate(State endValue, double i) const
Interpolates between two States.
Definition Trajectory.hpp:65
constexpr bool operator==(const State &) const =default
Checks equality between this State and another object.
Pose2d pose
The pose at that point of the trajectory.
Definition Trajectory.hpp:47
wpi::units::meters_per_second_squared_t acceleration
The acceleration at that point of the trajectory.
Definition Trajectory.hpp:44
wpi::units::meters_per_second_t velocity
The velocity at that point of the trajectory.
Definition Trajectory.hpp:41
wpi::units::curvature_t curvature
The curvature at that point of the trajectory.
Definition Trajectory.hpp:50