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

Detailed Description

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

FunctionHandleTrajectory takes a function, value = f(t), and provides a Trajectory interface.

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

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

Public Member Functions

 FunctionHandleTrajectory (std::function< MatrixX< T >(const T &)> func, int rows, int cols=1, double start_time=-std::numeric_limits< double >::infinity(), double end_time=std::numeric_limits< double >::infinity())
 Creates the FunctionHandleTrajectory. More...
 
 ~FunctionHandleTrajectory () 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
 FunctionHandleTrajectory (const FunctionHandleTrajectory &)=default
 
FunctionHandleTrajectoryoperator= (const FunctionHandleTrajectory &)=default
 
 FunctionHandleTrajectory (FunctionHandleTrajectory &&)=default
 
FunctionHandleTrajectoryoperator= (FunctionHandleTrajectory &&)=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
 
virtual MatrixX< T > DoEvalDerivative (const T &t, int derivative_order) const
 
virtual std::unique_ptr< Trajectory< T > > DoMakeDerivative (int derivative_order) const
 
 Trajectory (const Trajectory &)=default
 
Trajectoryoperator= (const Trajectory &)=default
 
 Trajectory (Trajectory &&)=default
 
Trajectoryoperator= (Trajectory &&)=default
 

Constructor & Destructor Documentation

◆ FunctionHandleTrajectory() [1/3]

◆ FunctionHandleTrajectory() [2/3]

◆ FunctionHandleTrajectory() [3/3]

FunctionHandleTrajectory ( std::function< MatrixX< T >(const T &)>  func,
int  rows,
int  cols = 1,
double  start_time = -std::numeric_limits< double >::infinity(),
double  end_time = std::numeric_limits< double >::infinity() 
)

Creates the FunctionHandleTrajectory.

Parameters
funcThe function to be used to evaluate the trajectory.
rowsThe number of rows in the output of the function.
colsThe number of columns in the output of the function.
start_timeThe start time of the trajectory.
end_timeThe end time of the trajectory.
Exceptions
std::exceptionif func == nullptr, rows < 0, cols < 0, start_time > end_time, or if the function returns a matrix of the wrong size.

◆ ~FunctionHandleTrajectory()

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]

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

◆ operator=() [2/2]

FunctionHandleTrajectory& operator= ( const FunctionHandleTrajectory< 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: