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 . More... | |
~PathParameterizedTrajectory () final | |
MatrixX< T > | value (const T &t) const final |
Evaluates the PathParameterizedTrajectory at the given time t. More... | |
const trajectories::Trajectory< T > & | path () const |
Returns the path of this trajectory. More... | |
const trajectories::Trajectory< T > & | time_scaling () const |
Returns the time_scaling of this trajectory. More... | |
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable | |
PathParameterizedTrajectory (const PathParameterizedTrajectory &)=default | |
PathParameterizedTrajectory & | operator= (const PathParameterizedTrajectory &)=default |
PathParameterizedTrajectory (PathParameterizedTrajectory &&)=default | |
PathParameterizedTrajectory & | operator= (PathParameterizedTrajectory &&)=default |
![]() | |
virtual | ~Trajectory () |
virtual std::unique_ptr< Trajectory< T > > | Clone () const |
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. More... | |
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. More... | |
bool | has_derivative () const |
Returns true iff the Trajectory provides and implementation for EvalDerivative() and MakeDerivative(). More... | |
MatrixX< T > | EvalDerivative (const T &t, int derivative_order=1) const |
Evaluates the derivative of this at the given time t . More... | |
std::unique_ptr< Trajectory< T > > | MakeDerivative (int derivative_order=1) const |
Takes the derivative of this Trajectory. More... | |
virtual Eigen::Index | rows () const |
virtual Eigen::Index | cols () const |
virtual T | start_time () const |
virtual T | end_time () const |
Additional Inherited Members | |
![]() | |
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.
|
finalvirtual |
Evaluates the PathParameterizedTrajectory at the given time t.
t | The time at which to evaluate the PathParameterizedTrajectory. |
t.is_constant()
must be true. value(-1)
will return value(0)
for a trajectory defined over [0, 1]. Reimplemented from Trajectory< T >.