WPILibC++ 2024.3.2
Trajectory.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 <vector>
8
9#include <wpi/SymbolExports.h>
10#include <wpi/json_fwd.h>
11
12#include "frc/geometry/Pose2d.h"
14#include "units/acceleration.h"
15#include "units/curvature.h"
16#include "units/time.h"
17#include "units/velocity.h"
18
19namespace frc {
20/**
21 * Represents a time-parameterized trajectory. The trajectory contains of
22 * various States that represent the pose, curvature, time elapsed, velocity,
23 * and acceleration at that point.
24 */
26 public:
27 /**
28 * Represents one point on the trajectory.
29 */
31 /// The time elapsed since the beginning of the trajectory.
32 units::second_t t = 0_s;
33
34 /// The speed at that point of the trajectory.
35 units::meters_per_second_t velocity = 0_mps;
36
37 /// The acceleration at that point of the trajectory.
38 units::meters_per_second_squared_t acceleration = 0_mps_sq;
39
40 /// The pose at that point of the trajectory.
42
43 /// The curvature at that point of the trajectory.
44 units::curvature_t curvature{0.0};
45
46 /**
47 * Checks equality between this State and another object.
48 */
49 bool operator==(const State&) const = default;
50
51 /**
52 * Interpolates between two States.
53 *
54 * @param endValue The end value for the interpolation.
55 * @param i The interpolant (fraction).
56 *
57 * @return The interpolated state.
58 */
59 State Interpolate(State endValue, double i) const;
60 };
61
62 Trajectory() = default;
63
64 /**
65 * Constructs a trajectory from a vector of states.
66 *
67 * @throws std::invalid_argument if the vector of states is empty.
68 */
69 explicit Trajectory(const std::vector<State>& states);
70
71 /**
72 * Returns the overall duration of the trajectory.
73 * @return The duration of the trajectory.
74 */
75 units::second_t TotalTime() const { return m_totalTime; }
76
77 /**
78 * Return the states of the trajectory.
79 *
80 * @return The states of the trajectory.
81 */
82 const std::vector<State>& States() const { return m_states; }
83
84 /**
85 * Sample the trajectory at a point in time.
86 *
87 * @param t The point in time since the beginning of the trajectory to sample.
88 * @return The state at that point in time.
89 * @throws std::runtime_error if the trajectory has no states.
90 */
91 State Sample(units::second_t t) const;
92
93 /**
94 * Transforms all poses in the trajectory by the given transform. This is
95 * useful for converting a robot-relative trajectory into a field-relative
96 * trajectory. This works with respect to the first pose in the trajectory.
97 *
98 * @param transform The transform to transform the trajectory by.
99 * @return The transformed trajectory.
100 */
102
103 /**
104 * Transforms all poses in the trajectory so that they are relative to the
105 * given pose. This is useful for converting a field-relative trajectory
106 * into a robot-relative trajectory.
107 *
108 * @param pose The pose that is the origin of the coordinate frame that
109 * the current trajectory will be transformed into.
110 * @return The transformed trajectory.
111 */
113
114 /**
115 * Concatenates another trajectory to the current trajectory. The user is
116 * responsible for making sure that the end pose of this trajectory and the
117 * start pose of the other trajectory match (if that is the desired behavior).
118 *
119 * @param other The trajectory to concatenate.
120 * @return The concatenated trajectory.
121 */
122 Trajectory operator+(const Trajectory& other) const;
123
124 /**
125 * Returns the initial pose of the trajectory.
126 *
127 * @return The initial pose of the trajectory.
128 */
129 Pose2d InitialPose() const { return Sample(0_s).pose; }
130
131 /**
132 * Checks equality between this Trajectory and another object.
133 */
134 bool operator==(const Trajectory&) const = default;
135
136 private:
137 std::vector<State> m_states;
138 units::second_t m_totalTime = 0_s;
139};
140
142void to_json(wpi::json& json, const Trajectory::State& state);
143
145void from_json(const wpi::json& json, Trajectory::State& state);
146
147} // namespace frc
148
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
a class to store JSON values
Definition: json.h:96
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:23
Represents a time-parameterized trajectory.
Definition: Trajectory.h:25
units::second_t TotalTime() const
Returns the overall duration of the trajectory.
Definition: Trajectory.h:75
Trajectory operator+(const Trajectory &other) const
Concatenates another trajectory to the current trajectory.
Trajectory TransformBy(const Transform2d &transform)
Transforms all poses in the trajectory by the given transform.
Trajectory RelativeTo(const Pose2d &pose)
Transforms all poses in the trajectory so that they are relative to the given pose.
Trajectory()=default
bool operator==(const Trajectory &) const =default
Checks equality between this Trajectory and another object.
Trajectory(const std::vector< State > &states)
Constructs a trajectory from a vector of states.
State Sample(units::second_t t) const
Sample the trajectory at a point in time.
Pose2d InitialPose() const
Returns the initial pose of the trajectory.
Definition: Trajectory.h:129
const std::vector< State > & States() const
Return the states of the trajectory.
Definition: Trajectory.h:82
Represents a transformation for a Pose2d in the pose's frame.
Definition: Transform2d.h:18
state
Definition: core.h:2271
Definition: AprilTagPoseEstimator.h:15
WPILIB_DLLEXPORT void from_json(const wpi::json &json, AprilTagFieldLayout &layout)
WPILIB_DLLEXPORT void to_json(wpi::json &json, const AprilTagFieldLayout &layout)
Represents one point on the trajectory.
Definition: Trajectory.h:30
Pose2d pose
The pose at that point of the trajectory.
Definition: Trajectory.h:41
State Interpolate(State endValue, double i) const
Interpolates between two States.
bool operator==(const State &) const =default
Checks equality between this State and another object.