maliput
Trajectory< T > Class Template Referenceabstract

Detailed Description

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

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

@tparam_default_scalars

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

Inheritance diagram for Trajectory< T >:
[legend]

Public Member Functions

virtual ~Trajectory ()=default
 
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...
 
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
 

Constructor & Destructor Documentation

◆ ~Trajectory()

virtual ~Trajectory ( )
virtualdefault

◆ Trajectory()

Trajectory ( )
protecteddefault

Member Function Documentation

◆ Clone()

virtual std::unique_ptr<Trajectory<T> > Clone ( ) const
pure virtual
Returns
A deep copy of this Trajectory.

Implemented in PiecewisePolynomial< T >, and PiecewisePolynomial< double >.

◆ cols()

virtual Eigen::Index cols ( ) const
pure virtual
Returns
The number of columns in the matrix returned by value().

Implemented in PiecewisePolynomial< T >, and PiecewisePolynomial< double >.

◆ do_has_derivative()

bool do_has_derivative
protectedvirtual

◆ DoEvalDerivative()

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

◆ DoMakeDerivative()

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

◆ end_time()

virtual T end_time ( ) const
pure virtual

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

Precondition
derivative_order must be non-negative.

◆ has_derivative()

bool has_derivative

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.

◆ rows()

virtual Eigen::Index rows ( ) const
pure virtual
Returns
The number of rows in the matrix returned by value().

Implemented in PiecewisePolynomial< T >, and PiecewisePolynomial< double >.

◆ start_time()

virtual T start_time ( ) const
pure virtual

◆ value()

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

Evaluates the trajectory at the given time t.

Parameters
tThe time at which to evaluate the trajectory.
Returns
The matrix of evaluated values.

Implemented in PiecewisePolynomial< T >, and PiecewisePolynomial< double >.

◆ vector_values()

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.

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