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"
35 wpi::units::second_t
t = 0_s;
38 wpi::units::meters_per_second_t
velocity = 0_mps;
68 const auto deltaT = newT -
t;
76 const auto reversing =
82 const wpi::units::meters_per_second_t newV =
87 const wpi::units::meter_t newS =
89 (reversing ? -1.0 : 1.0);
95 const double interpolationFrac =
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.");
119 m_totalTime = states.back().t;
126 wpi::units::second_t
TotalTime()
const {
return m_totalTime; }
133 const std::vector<State>&
States()
const {
return m_states; }
143 if (m_states.empty()) {
144 throw std::runtime_error(
145 "Trajectory cannot be sampled if it has no states.");
148 if (t <= m_states.front().t) {
149 return m_states.front();
151 if (t >= m_totalTime) {
152 return m_states.back();
159 std::lower_bound(m_states.cbegin() + 1, m_states.cend(), t,
160 [](
const auto& a,
const auto& b) { return a.t < b; });
162 auto prevSample = sample - 1;
170 if (wpi::units::math::abs(sample->t - prevSample->t) < 1E-9_s) {
174 return prevSample->Interpolate(
175 *sample, (t - prevSample->t) / (sample->t - prevSample->t));
187 auto& firstState = m_states[0];
188 auto& firstPose = firstState.pose;
191 auto newFirstPose = firstPose + transform;
192 auto newStates = m_states;
193 newStates[0].pose = newFirstPose;
195 for (
unsigned int i = 1; i < newStates.size(); i++) {
196 auto& state = newStates[i];
199 state.pose = newFirstPose + (state.pose - firstPose);
215 auto newStates = m_states;
216 for (
auto& state : newStates) {
217 state.pose = state.pose.RelativeTo(pose);
233 if (m_states.empty()) {
237 auto states = m_states;
238 auto otherStates = other.
States();
239 for (
auto& otherState : otherStates) {
240 otherState.t += m_totalTime;
247 states.insert(states.end(), otherStates.begin() + 1, otherStates.end());
264 std::vector<State> m_states;
265 wpi::units::second_t m_totalTime = 0_s;
#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
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