#include <trajectory_path.h>
TrajectoryPath represents a list of 2D trajectories that are connected end-to-end to form a path. A TrajectoryPathNode is a 2D trajectory and the time at which it ends and the next TrajectoryPathNode begins.
◆ TrajectoryPath()
Constructor
- Parameters
-
| initial_trajectory | The initial trajectory of this trajectory path |
| traj_generator | A function used to generate new trajectories given the kinematic constraints, initial position, final position, and initial velocity. |
◆ append()
Generate and append a new trajectory to the end of this trajectory path
- Parameters
-
| constraints | Constraints of the new generated trajectory |
| connection_time_sec | The time where the last existing trajectory should connect to the newly generated trajectory |
| destination | Destination of the newly generated trajectory |
◆ getAcceleration()
| Vector getAcceleration |
( |
double |
t_sec | ) |
const |
|
overridevirtual |
Get the acceleration at time t of this trajectory path
- Parameters
-
| t_sec | The time elapsed since the start of the trajectory path |
- Returns
- The acceleration at time t
Implements Trajectory< Point, Vector, Vector >.
◆ getBoundingBoxes()
| std::vector< Rectangle > getBoundingBoxes |
( |
| ) |
const |
|
overridevirtual |
Get the bounding boxes of the trajectory path
- Returns
- A list of bounding boxes which wrap this trajectory path
Implements Trajectory2D.
◆ getPosition()
| Point getPosition |
( |
double |
t_sec | ) |
const |
|
overridevirtual |
Get the position at time t of this trajectory path
- Parameters
-
| t_sec | The time elapsed since the start of the trajectory path |
- Returns
- The position at time t
Implements Trajectory< Point, Vector, Vector >.
◆ getTotalTime()
| double getTotalTime |
( |
| ) |
const |
|
overridevirtual |
◆ getTrajectoryPathNodes()
Get the list of TrajectoryPathNodes that make up this trajectory path
- Returns
- The list of TrajectoryPathNodes that make up this trajectory path
◆ getVelocity()
| Vector getVelocity |
( |
double |
t_sec | ) |
const |
|
overridevirtual |
Get the velocity at time t of this trajectory path
- Parameters
-
| t_sec | The time elapsed since the start of the trajectory path |
- Returns
- The velocity at time t
Implements Trajectory< Point, Vector, Vector >.
The documentation for this class was generated from the following files:
- src/software/ai/navigator/trajectory/trajectory_path.h
- src/software/ai/navigator/trajectory/trajectory_path.cpp