Drake
Drake C++ Documentation
DerivativeTrajectory< T > Class Template Referencefinal

Detailed Description

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

Trajectory objects provide derivatives by implementing DoEvalDerivative and DoMakeDerivative.

DoEvalDerivative evaluates the derivative value at a point in time. DoMakeDerivative returns a new Trajectory object which represents the derivative.

In some cases, it is easy to implement DoEvalDerivative, but difficult or inefficient to implement DoMakeDerivative natively. And it may be just as efficient to use DoEvalDerivative even in repeated evaluations of the derivative. The DerivativeTrajectory class helps with this case – given a nominal Trajectory, it provides a Trajectory interface that calls nominal.EvalDerivative() to implement Trajectory::value().

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

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

Public Member Functions

 DerivativeTrajectory (const Trajectory< T > &nominal, int derivative_order=1)
 Creates a DerivativeTrajectory representing the derivative_order derivatives of nominal. More...
 
 ~DerivativeTrajectory () final
 
std::unique_ptr< Trajectory< T > > Clone () const final
 
MatrixX< T > value (const T &t) const final
 Evaluates the trajectory at the given time t. More...
 
Eigen::Index rows () const final
 
Eigen::Index cols () const final
 
start_time () const final
 
end_time () const final
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 DerivativeTrajectory (const DerivativeTrajectory &)=default
 
DerivativeTrajectoryoperator= (const DerivativeTrajectory &)=default
 
 DerivativeTrajectory (DerivativeTrajectory &&)=default
 
DerivativeTrajectoryoperator= (DerivativeTrajectory &&)=default
 
- Public Member Functions inherited from Trajectory< T >
virtual ~Trajectory ()
 
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...
 

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

◆ DerivativeTrajectory() [1/3]

DerivativeTrajectory ( const DerivativeTrajectory< T > &  )
default

◆ DerivativeTrajectory() [2/3]

◆ DerivativeTrajectory() [3/3]

DerivativeTrajectory ( const Trajectory< T > &  nominal,
int  derivative_order = 1 
)
explicit

Creates a DerivativeTrajectory representing the derivative_order derivatives of nominal.

This constructor makes a Clone() of nominal and does not hold on to the reference.

Exceptions
std::exceptionif !nominal.has_derivative().
std::exceptionif derivative_order < 0.

◆ ~DerivativeTrajectory()

Member Function Documentation

◆ Clone()

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

Implements Trajectory< T >.

◆ cols()

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

Implements Trajectory< T >.

◆ end_time()

T end_time ( ) const
finalvirtual

Implements Trajectory< T >.

◆ operator=() [1/2]

DerivativeTrajectory& operator= ( DerivativeTrajectory< T > &&  )
default

◆ operator=() [2/2]

DerivativeTrajectory& operator= ( const DerivativeTrajectory< T > &  )
default

◆ rows()

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

Implements Trajectory< T >.

◆ start_time()

T start_time ( ) const
finalvirtual

Implements Trajectory< T >.

◆ value()

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

Evaluates the trajectory at the given time t.

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

Implements Trajectory< T >.


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