|
WPILibC++
2020.3.2
|
Represents a time-parameterized trajectory. More...
#include <Trajectory.h>
Classes | |
| struct | State |
| Represents one point on the trajectory. More... | |
Public Member Functions | |
| Trajectory (const std::vector< State > &states) | |
| Constructs a trajectory from a vector of states. | |
| 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... | |
| Pose2d | InitialPose () const |
| Returns the initial pose of the trajectory. 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.
|
inline |
Returns the initial pose of the trajectory.
| 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. |