A Trajectory represents a time-varying matrix, indexed by a single scalar time.
T | The 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 | |
Trajectory & | operator= (const Trajectory &)=default |
Trajectory (Trajectory &&)=default | |
Trajectory & | operator= (Trajectory &&)=default |
|
virtual |
|
protecteddefault |
|
protecteddefault |
|
protecteddefault |
|
pure virtual |
Implemented in PiecewisePolynomial< T >, PiecewisePolynomial< double >, PiecewisePolynomial< AutoDiffXd >, BezierCurve< T >, BezierCurve< double >, PiecewiseQuaternionSlerp< T >, ExponentialPlusPiecewisePolynomial< T >, ExponentialPlusPiecewisePolynomial< double >, PiecewisePose< T >, BsplineTrajectory< T >, StackedTrajectory< T >, BsplineTrajectory< drake::symbolic::Expression >, DerivativeTrajectory< T >, CompositeTrajectory< T >, and PathParameterizedTrajectory< T >.
|
pure virtual |
Implemented in PiecewisePolynomial< T >, PiecewisePolynomial< double >, PiecewisePolynomial< AutoDiffXd >, BezierCurve< T >, BezierCurve< double >, PiecewiseQuaternionSlerp< T >, ExponentialPlusPiecewisePolynomial< T >, ExponentialPlusPiecewisePolynomial< double >, PiecewisePose< T >, BsplineTrajectory< T >, BsplineTrajectory< drake::symbolic::Expression >, StackedTrajectory< T >, PathParameterizedTrajectory< T >, CompositeTrajectory< T >, and DerivativeTrajectory< T >.
|
protectedvirtual |
|
protectedvirtual |
|
pure virtual |
Implemented in BezierCurve< T >, BezierCurve< double >, BsplineTrajectory< T >, BsplineTrajectory< drake::symbolic::Expression >, StackedTrajectory< T >, PathParameterizedTrajectory< T >, DerivativeTrajectory< T >, PiecewiseTrajectory< T >, PiecewiseTrajectory< double >, and PiecewiseTrajectory< AutoDiffXd >.
Evaluates the derivative of this
at the given time t
.
Returns the nth derivative, where n
is the value of derivative_order
.
std::exception | if derivative_order is negative. |
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.
std::unique_ptr<Trajectory<T> > MakeDerivative | ( | int | derivative_order = 1 | ) | const |
Takes the derivative of this Trajectory.
derivative_order | The number of times to take the derivative before returning. |
std::exception | if derivative_order is negative. |
|
protecteddefault |
|
protecteddefault |
|
pure virtual |
Implemented in PiecewisePolynomial< T >, PiecewisePolynomial< double >, PiecewisePolynomial< AutoDiffXd >, BezierCurve< T >, BezierCurve< double >, PiecewiseQuaternionSlerp< T >, ExponentialPlusPiecewisePolynomial< T >, ExponentialPlusPiecewisePolynomial< double >, PiecewisePose< T >, BsplineTrajectory< T >, BsplineTrajectory< drake::symbolic::Expression >, StackedTrajectory< T >, PathParameterizedTrajectory< T >, CompositeTrajectory< T >, and DerivativeTrajectory< T >.
|
pure virtual |
Implemented in BezierCurve< T >, BezierCurve< double >, BsplineTrajectory< T >, BsplineTrajectory< drake::symbolic::Expression >, StackedTrajectory< T >, PathParameterizedTrajectory< T >, DerivativeTrajectory< T >, PiecewiseTrajectory< T >, PiecewiseTrajectory< double >, and PiecewiseTrajectory< AutoDiffXd >.
|
pure virtual |
Evaluates the trajectory at the given time t
.
t | The time at which to evaluate the trajectory. |
Implemented in PiecewisePolynomial< T >, PiecewisePolynomial< double >, PiecewisePolynomial< AutoDiffXd >, BezierCurve< T >, BezierCurve< double >, PiecewiseQuaternionSlerp< T >, PiecewisePose< T >, ExponentialPlusPiecewisePolynomial< T >, ExponentialPlusPiecewisePolynomial< double >, BsplineTrajectory< T >, BsplineTrajectory< drake::symbolic::Expression >, StackedTrajectory< T >, PathParameterizedTrajectory< T >, DerivativeTrajectory< T >, and CompositeTrajectory< T >.
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.
std::exception | if both cols and rows are not equal to 1. |
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.
std::exception | if both cols and rows are not equal to 1. |