Drake
Drake C++ Documentation
Trajectory< T > Class Template Referenceabstract

Detailed Description

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

A Trajectory represents a time-varying matrix, indexed by a single scalar time.

Template Parameters
TThe scalar type, which must be one of the default scalars.

#include <drake/common/trajectories/trajectory.h>

Public Member Functions

virtual ~Trajectory ()
 
virtual std::unique_ptr< Trajectory< T > > Clone () const =0
 
virtual MatrixX< T > value (const T &t) const =0
 Evaluates the trajectory at the given time t. More...
 
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 =0
 
virtual Eigen::Index cols () const =0
 
virtual T start_time () const =0
 
virtual T end_time () const =0
 

Protected Member Functions

 Trajectory ()=default
 
virtual bool do_has_derivative () const
 
virtual MatrixX< T > DoEvalDerivative (const T &t, int derivative_order) const
 
virtual std::unique_ptr< Trajectory< T > > DoMakeDerivative (int derivative_order) const
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 Trajectory (const Trajectory &)=default
 
Trajectoryoperator= (const Trajectory &)=default
 
 Trajectory (Trajectory &&)=default
 
Trajectoryoperator= (Trajectory &&)=default
 

Constructor & Destructor Documentation

◆ ~Trajectory()

virtual ~Trajectory ( )
virtual

◆ Trajectory() [1/3]

Trajectory ( const Trajectory< T > &  )
protecteddefault

◆ Trajectory() [2/3]

Trajectory ( Trajectory< T > &&  )
protecteddefault

◆ Trajectory() [3/3]

Trajectory ( )
protecteddefault

Member Function Documentation

◆ Clone()

◆ cols()

◆ do_has_derivative()

virtual bool do_has_derivative ( ) const
protectedvirtual

◆ DoEvalDerivative()

virtual MatrixX<T> DoEvalDerivative ( const T &  t,
int  derivative_order 
) const
protectedvirtual

◆ DoMakeDerivative()

virtual std::unique_ptr<Trajectory<T> > DoMakeDerivative ( int  derivative_order) const
protectedvirtual

◆ end_time()

◆ EvalDerivative()

MatrixX<T> EvalDerivative ( const T &  t,
int  derivative_order = 1 
) const

Evaluates the derivative of this at the given time t.

Returns the nth derivative, where n is the value of derivative_order.

Exceptions
std::exceptionif derivative_order is negative.

◆ has_derivative()

bool has_derivative ( ) const

Returns true iff the Trajectory provides and implementation for EvalDerivative() and MakeDerivative().

The derivative need not be continuous, but should return a result for all t for which value(t) returns a result.

◆ MakeDerivative()

std::unique_ptr<Trajectory<T> > MakeDerivative ( int  derivative_order = 1) const

Takes the derivative of this Trajectory.

Parameters
derivative_orderThe number of times to take the derivative before returning.
Returns
The nth derivative of this object.
Exceptions
std::exceptionif derivative_order is negative.

◆ operator=() [1/2]

Trajectory& operator= ( Trajectory< T > &&  )
protecteddefault

◆ operator=() [2/2]

Trajectory& operator= ( const Trajectory< T > &  )
protecteddefault

◆ rows()

◆ start_time()

◆ value()

◆ vector_values() [1/2]

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.

Otherwise, if rows()==1, then evaluates the trajectory at each time t, and returns the results as a Matrix with the ith row corresponding to the ith time.

Exceptions
std::exceptionif both cols and rows are not equal to 1.

◆ vector_values() [2/2]

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.

Otherwise, if rows()==1, then evaluates the trajectory at each time t, and returns the results as a Matrix with the ith row corresponding to the ith time.

Exceptions
std::exceptionif both cols and rows are not equal to 1.

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