WPILibC++ 2023.4.3
|
Represents a time-parameterized trajectory. More...
#include <frc/trajectory/Trajectory.h>
Classes | |
struct | State |
Represents one point on the trajectory. More... | |
Public Member Functions | |
Trajectory ()=default | |
Trajectory (const std::vector< State > &states) | |
Constructs a trajectory from a vector of states. More... | |
units::second_t | TotalTime () const |
Returns the overall duration of the trajectory. More... | |
const std::vector< State > & | States () const |
Return the states of the trajectory. More... | |
State | Sample (units::second_t t) const |
Sample the trajectory at a point in time. More... | |
Trajectory | TransformBy (const Transform2d &transform) |
Transforms all poses in the trajectory by the given transform. More... | |
Trajectory | RelativeTo (const Pose2d &pose) |
Transforms all poses in the trajectory so that they are relative to the given pose. More... | |
Trajectory | operator+ (const Trajectory &other) const |
Concatenates another trajectory to the current trajectory. More... | |
Pose2d | InitialPose () const |
Returns the initial pose of the trajectory. More... | |
bool | operator== (const Trajectory &) const =default |
Checks equality between this Trajectory and another object. More... | |
Represents a time-parameterized trajectory.
The trajectory contains of various States that represent the pose, curvature, time elapsed, velocity, and acceleration at that point.
|
default |
|
explicit |
Constructs a trajectory from a vector of states.
|
inline |
Returns the initial pose of the trajectory.
Trajectory frc::Trajectory::operator+ | ( | const Trajectory & | other | ) | const |
Concatenates another trajectory to the current trajectory.
The user is responsible for making sure that the end pose of this trajectory and the start pose of the other trajectory match (if that is the desired behavior).
other | The trajectory to concatenate. |
|
default |
Checks equality between this Trajectory and another object.
Trajectory frc::Trajectory::RelativeTo | ( | const Pose2d & | pose | ) |
Transforms all poses in the trajectory so that they are relative to the given pose.
This is useful for converting a field-relative trajectory into a robot-relative trajectory.
pose | The pose that is the origin of the coordinate frame that the current trajectory will be transformed into. |
State frc::Trajectory::Sample | ( | units::second_t | t | ) | const |
Sample the trajectory at a point in time.
t | The point in time since the beginning of the trajectory to sample. |
|
inline |
Return the states of the trajectory.
|
inline |
Returns the overall duration of the trajectory.
Trajectory frc::Trajectory::TransformBy | ( | const Transform2d & | transform | ) |
Transforms all poses in the trajectory by the given transform.
This is useful for converting a robot-relative trajectory into a field-relative trajectory. This works with respect to the first pose in the trajectory.
transform | The transform to transform the trajectory by. |