template<typename T>
class drake::trajectories::Trajectory< T >
A Trajectory represents a time-varying matrix, indexed by a single scalar time.
- Template Parameters
-
#include <drake/common/trajectories/trajectory.h>
◆ ~Trajectory()
◆ Trajectory() [1/3]
◆ Trajectory() [2/3]
◆ Trajectory() [3/3]
◆ Clone()
◆ cols()
Eigen::Index cols |
( |
| ) |
const |
- Returns
- The number of columns in the matrix returned by value().
◆ do_cols()
virtual Eigen::Index do_cols |
( |
| ) |
const |
|
protectedpure virtual |
◆ do_end_time()
virtual T do_end_time |
( |
| ) |
const |
|
protectedpure virtual |
◆ do_has_derivative()
virtual bool do_has_derivative |
( |
| ) |
const |
|
protectedvirtual |
◆ do_rows()
virtual Eigen::Index do_rows |
( |
| ) |
const |
|
protectedpure virtual |
◆ do_start_time()
virtual T do_start_time |
( |
| ) |
const |
|
protectedpure virtual |
◆ do_value()
virtual MatrixX<T> do_value |
( |
const T & |
t | ) |
const |
|
protectedpure virtual |
◆ DoClone()
virtual std::unique_ptr<Trajectory<T> > DoClone |
( |
| ) |
const |
|
protectedpure virtual |
◆ 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()
◆ 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::exception | if 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_order | The number of times to take the derivative before returning. |
- Returns
- The nth derivative of this object.
- Exceptions
-
std::exception | if derivative_order is negative. |
◆ operator=() [1/2]
◆ operator=() [2/2]
◆ rows()
Eigen::Index rows |
( |
| ) |
const |
- Returns
- The number of rows in the matrix returned by value().
◆ start_time()
◆ value()
MatrixX<T> value |
( |
const T & |
t | ) |
const |
Evaluates the trajectory at the given time t
.
- Parameters
-
t | The time at which to evaluate the trajectory. |
- Returns
- The matrix of evaluated values.
◆ 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::exception | if 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::exception | if both cols and rows are not equal to 1. |
The documentation for this class was generated from the following file: