Drake
Drake C++ Documentation
Loading...
Searching...
No Matches
PathParameterizedTrajectory< T > Class Template Referencefinal

Detailed Description

template<typename T>
class drake::trajectories::PathParameterizedTrajectory< T >

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.

Template Parameters
TThe 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
PathParameterizedTrajectoryoperator= (const PathParameterizedTrajectory &)=default
 PathParameterizedTrajectory (PathParameterizedTrajectory &&)=default
PathParameterizedTrajectoryoperator= (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
start_time () const
end_time () const

Additional Inherited Members

Protected Member Functions inherited from Trajectory< T >
 Trajectory ()=default
 Trajectory (const Trajectory &)=default
Trajectoryoperator= (const Trajectory &)=default
 Trajectory (Trajectory &&)=default
Trajectoryoperator= (Trajectory &&)=default

Constructor & Destructor Documentation

◆ PathParameterizedTrajectory() [1/3]

template<typename T>
PathParameterizedTrajectory ( const PathParameterizedTrajectory< T > & )
default

◆ PathParameterizedTrajectory() [2/3]

template<typename T>
PathParameterizedTrajectory ( PathParameterizedTrajectory< T > && )
default

◆ PathParameterizedTrajectory() [3/3]

template<typename T>
PathParameterizedTrajectory ( const Trajectory< T > & path,
const Trajectory< T > & time_scaling )

Constructs a trajectory with the given path and time_scaling.

Precondition
time_scaling.rows() == time_scaling.cols() == 1

◆ ~PathParameterizedTrajectory()

template<typename T>
~PathParameterizedTrajectory ( )
final

Member Function Documentation

◆ operator=() [1/2]

template<typename T>
PathParameterizedTrajectory & operator= ( const PathParameterizedTrajectory< T > & )
default

◆ operator=() [2/2]

template<typename T>
PathParameterizedTrajectory & operator= ( PathParameterizedTrajectory< T > && )
default

◆ path()

template<typename T>
const trajectories::Trajectory< T > & path ( ) const

Returns the path of this trajectory.

◆ time_scaling()

template<typename T>
const trajectories::Trajectory< T > & time_scaling ( ) const

Returns the time_scaling of this trajectory.

◆ value()

template<typename T>
MatrixX< T > value ( const T & t) const

Evaluates the PathParameterizedTrajectory at the given time t.

Parameters
tThe time at which to evaluate the PathParameterizedTrajectory.
Returns
The matrix of evaluated values.
Precondition
If T == symbolic::Expression, t.is_constant() must be true.
Warning
If t does not lie in the range [start_time(), end_time()], the trajectory will silently be evaluated at the closest valid value of time to t. For example, value(-1) will return value(0) for a trajectory defined over [0, 1].

The documentation for this class was generated from the following file: