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

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
 
virtual MatrixX< T > value (const T &t) const
 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
 
virtual Eigen::Index cols () const
 
virtual T start_time () const
 
virtual T end_time () const
 

Protected Member Functions

 Trajectory ()=default
 
virtual std::unique_ptr< Trajectory< T > > DoClone () const
 
virtual MatrixX< T > do_value (const T &t) const
 
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
 
virtual Eigen::Index do_rows () const
 
virtual Eigen::Index do_cols () const
 
virtual T do_start_time () const
 
virtual T do_end_time () 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()

virtual std::unique_ptr<Trajectory<T> > Clone ( ) const
virtual
Returns
A deep copy of this Trajectory.
Warning
Support for overriding this as a virtual function is deprecated and will be removed on or after 2025-08-01. Subclasses should override the protected function DoClone(), instead.

◆ cols()

virtual Eigen::Index cols ( ) const
virtual
Returns
The number of columns in the matrix returned by value().
Warning
Support for overriding this as a virtual function is deprecated and will be removed on or after 2025-08-01. Subclasses should override the protected function do_cols(), instead.

Reimplemented in PiecewisePolynomial< T >, PiecewisePolynomial< double >, PiecewisePolynomial< AutoDiffXd >, and DiscreteTimeTrajectory< T >.

◆ do_cols()

virtual Eigen::Index do_cols ( ) const
protectedvirtual

◆ do_end_time()

virtual T do_end_time ( ) const
protectedvirtual

◆ do_has_derivative()

virtual bool do_has_derivative ( ) const
protectedvirtual

◆ do_rows()

virtual Eigen::Index do_rows ( ) const
protectedvirtual

◆ do_start_time()

virtual T do_start_time ( ) const
protectedvirtual

◆ do_value()

virtual MatrixX<T> do_value ( const T &  t) const
protectedvirtual

◆ DoClone()

virtual std::unique_ptr<Trajectory<T> > DoClone ( ) 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()

virtual T end_time ( ) const
virtual
Warning
Support for overriding this as a virtual function is deprecated and will be removed on or after 2025-08-01. Subclasses should override the protected function do_end_time(), instead.

Reimplemented in DiscreteTimeTrajectory< T >.

◆ 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()

virtual Eigen::Index rows ( ) const
virtual
Returns
The number of rows in the matrix returned by value().
Warning
Support for overriding this as a virtual function is deprecated and will be removed on or after 2025-08-01. Subclasses should override the protected function do_rows(), instead.

Reimplemented in PiecewisePolynomial< T >, PiecewisePolynomial< double >, PiecewisePolynomial< AutoDiffXd >, and DiscreteTimeTrajectory< T >.

◆ start_time()

virtual T start_time ( ) const
virtual
Warning
Support for overriding this as a virtual function is deprecated and will be removed on or after 2025-08-01. Subclasses should override the protected function do_start_time(), instead.

Reimplemented in DiscreteTimeTrajectory< T >.

◆ value()

virtual MatrixX<T> value ( const T &  t) const
virtual

Evaluates the trajectory at the given time t.

Parameters
tThe time at which to evaluate the trajectory.
Returns
The matrix of evaluated values.
Warning
Support for overriding this as a virtual function is deprecated and will be removed on or after 2025-08-01. Subclasses should override the protected function do_value(), instead.

Reimplemented in PiecewisePolynomial< T >, PiecewisePolynomial< double >, PiecewisePolynomial< AutoDiffXd >, PiecewiseConstantCurvatureTrajectory< T >, PiecewiseConstantCurvatureTrajectory< double >, DiscreteTimeTrajectory< T >, BezierCurve< T >, BezierCurve< double >, BsplineTrajectory< T >, BsplineTrajectory< drake::symbolic::Expression >, PathParameterizedTrajectory< T >, and CompositeTrajectory< T >.

◆ 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: