A trajectory defined by a path and timing trajectory.
Using a path of form r(s) and a time_scaling of the form s(t), a full trajectory of form q(t) = r(s(t)) is modeled.
| T | The scalar type, which must be one of the default scalars. |
#include <drake/common/trajectories/path_parameterized_trajectory.h>
Public Member Functions | |
| PathParameterizedTrajectory (const Trajectory< T > &path, const Trajectory< T > &time_scaling) | |
| Constructs a trajectory with the given path and time_scaling. | |
| ~PathParameterizedTrajectory () final | |
| MatrixX< T > | value (const T &t) const |
| Evaluates the PathParameterizedTrajectory at the given time t. | |
| const trajectories::Trajectory< T > & | path () const |
| Returns the path of this trajectory. | |
| const trajectories::Trajectory< T > & | time_scaling () const |
| Returns the time_scaling of this trajectory. | |
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable | |
| PathParameterizedTrajectory (const PathParameterizedTrajectory &)=default | |
| PathParameterizedTrajectory & | operator= (const PathParameterizedTrajectory &)=default |
| PathParameterizedTrajectory (PathParameterizedTrajectory &&)=default | |
| PathParameterizedTrajectory & | operator= (PathParameterizedTrajectory &&)=default |
| Public Member Functions inherited from Trajectory< T > | |
| virtual | ~Trajectory () |
| std::unique_ptr< Trajectory< T > > | Clone () const |
| MatrixX< T > | value (const T &t) const |
Evaluates the trajectory at the given time t. | |
| MatrixX< T > | vector_values (const std::vector< T > &t) const |
If cols()==1, then evaluates the trajectory at each time t, and returns the results as a Matrix with the ith column corresponding to the ith time. | |
| MatrixX< T > | vector_values (const Eigen::Ref< const VectorX< T > > &t) const |
If cols()==1, then evaluates the trajectory at each time t, and returns the results as a Matrix with the ith column corresponding to the ith time. | |
| bool | has_derivative () const |
| Returns true iff the Trajectory provides and implementation for EvalDerivative() and MakeDerivative(). | |
| MatrixX< T > | EvalDerivative (const T &t, int derivative_order=1) const |
Evaluates the derivative of this at the given time t. | |
| std::unique_ptr< Trajectory< T > > | MakeDerivative (int derivative_order=1) const |
| Takes the derivative of this Trajectory. | |
| Eigen::Index | rows () const |
| Eigen::Index | cols () const |
| T | start_time () const |
| T | end_time () const |
Additional Inherited Members | |
| Protected Member Functions inherited from Trajectory< T > | |
| Trajectory ()=default | |
| Trajectory (const Trajectory &)=default | |
| Trajectory & | operator= (const Trajectory &)=default |
| Trajectory (Trajectory &&)=default | |
| Trajectory & | operator= (Trajectory &&)=default |
|
default |
|
default |
| PathParameterizedTrajectory | ( | const Trajectory< T > & | path, |
| const Trajectory< T > & | time_scaling ) |
Constructs a trajectory with the given path and time_scaling.
|
final |
|
default |
|
default |
| const trajectories::Trajectory< T > & path | ( | ) | const |
Returns the path of this trajectory.
| const trajectories::Trajectory< T > & time_scaling | ( | ) | const |
Returns the time_scaling of this trajectory.
| MatrixX< T > value | ( | const T & | t | ) | const |
Evaluates the PathParameterizedTrajectory at the given time t.
| t | The time at which to evaluate the PathParameterizedTrajectory. |