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