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

Detailed Description

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

A DiscreteTimeTrajectory is a Trajectory whose value is only defined at discrete time points.

Calling value() at a time that is not equal to one of those times (up to a tolerance) will throw. This trajectory does not have well-defined time-derivatives.

In some applications, it may be preferable to use PiecewisePolynomial<T>::ZeroOrderHold instead of a DiscreteTimeTrajectory (and we offer a method here to easily convert). Note if the breaks are periodic, then one can also achieve a similar result in a Diagram by using the DiscreteTimeTrajectory in a TrajectorySource and connecting a ZeroOrderHold system to the output port, but remember that this will add discrete state to your diagram.

So why not always use the zero-order hold (ZOH) trajectory? This class forces us to be more precise in our implementations. For instance, consider the case of a solution to a discrete-time finite-horizon linear quadratic regulator (LQR) problem. In this case, the solution to the Riccati equation is a DiscreteTimeTrajectory, K(t). Implementing

x(t) -> MatrixGain(-K(t)) -> u(t)

in a block diagram is perfectly correct, and if the u(t) is only connected to the original system that it was designed for, then K(t) will only get evaluated at the defined sample times, and all is well. But if you wire it up to a continuous-time system, then K(t) may be evaluated at arbitrary times, and may throw. If one wishes to use the K(t) solution on a continuous-time system, then we can use

x(t) -> MatrixGain(-K(t)) -> ZOH -> u(t).

This is different, and more correct than implementing K(t) as a zero-order hold trajectory, because in this version, both K(t) and the inputs x(t) will only be evaluated at the discrete-time input. If t_s was the most recent discrete sample time, then this means u(t) = -K(t_s)*x(t_s) instead of u(t) = -K(t_s)*x(t). Using x(t_s) and having a true zero-order hold on u(t) is the correct model for the discrete-time LQR result.

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

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

Public Member Functions

 DiscreteTimeTrajectory ()=default
 Default constructor creates the empty trajectory. More...
 
 DiscreteTimeTrajectory (const Eigen::Ref< const VectorX< T >> &times, const Eigen::Ref< const MatrixX< T >> &values, double time_comparison_tolerance=std::numeric_limits< double >::epsilon())
 Constructs a trajectory of vector values at the specified times. More...
 
 DiscreteTimeTrajectory (const std::vector< T > &times, const std::vector< MatrixX< T >> &values, double time_comparison_tolerance=std::numeric_limits< double >::epsilon())
 Constructs a trajectory of matrix values at the specified times. More...
 
 ~DiscreteTimeTrajectory () final
 
PiecewisePolynomial< T > ToZeroOrderHold () const
 Converts the discrete-time trajectory using PiecewisePolynomial<T>::ZeroOrderHold(). More...
 
double time_comparison_tolerance () const
 The trajectory is only defined at finite sample times. More...
 
int num_times () const
 Returns the number of discrete times where the trajectory value is defined. More...
 
const std::vector< T > & get_times () const
 Returns the times where the trajectory value is defined. More...
 
MatrixX< T > value (const T &t) const final
 Returns the value of the trajectory at t. More...
 
Eigen::Index rows () const final
 Returns the number of rows in the MatrixX<T> returned by value(). More...
 
Eigen::Index cols () const final
 Returns the number of cols in the MatrixX<T> returned by value(). More...
 
start_time () const final
 Returns the minimum value of get_times(). More...
 
end_time () const final
 Returns the maximum value of get_times(). More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 DiscreteTimeTrajectory (const DiscreteTimeTrajectory &)=default
 
DiscreteTimeTrajectoryoperator= (const DiscreteTimeTrajectory &)=default
 
 DiscreteTimeTrajectory (DiscreteTimeTrajectory &&)=default
 
DiscreteTimeTrajectoryoperator= (DiscreteTimeTrajectory &&)=default
 
- Public Member Functions inherited from Trajectory< T >
virtual ~Trajectory ()
 
virtual std::unique_ptr< Trajectory< T > > Clone () const
 
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 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
 
 Trajectory (const Trajectory &)=default
 
Trajectoryoperator= (const Trajectory &)=default
 
 Trajectory (Trajectory &&)=default
 
Trajectoryoperator= (Trajectory &&)=default
 

Constructor & Destructor Documentation

◆ DiscreteTimeTrajectory() [1/5]

DiscreteTimeTrajectory ( const DiscreteTimeTrajectory< T > &  )
default

◆ DiscreteTimeTrajectory() [2/5]

◆ DiscreteTimeTrajectory() [3/5]

Default constructor creates the empty trajectory.

◆ DiscreteTimeTrajectory() [4/5]

DiscreteTimeTrajectory ( const Eigen::Ref< const VectorX< T >> &  times,
const Eigen::Ref< const MatrixX< T >> &  values,
double  time_comparison_tolerance = std::numeric_limits< double >::epsilon() 
)

Constructs a trajectory of vector values at the specified times.

Precondition
times must differ by more than time_comparison_tolerance and be monotonically increasing.
values must have times.size() columns.
time_comparison_tolerance must be >= 0.
Exceptions
ifT=symbolic:Expression and times are not constants.

◆ DiscreteTimeTrajectory() [5/5]

DiscreteTimeTrajectory ( const std::vector< T > &  times,
const std::vector< MatrixX< T >> &  values,
double  time_comparison_tolerance = std::numeric_limits< double >::epsilon() 
)

Constructs a trajectory of matrix values at the specified times.

Precondition
times should differ by more than time_comparison_tolerance and be monotonically increasing.
values must have times.size() elements, each with the same number of rows and columns.
time_comparison_tolerance must be >= 0.
Exceptions
ifT=symbolic:Expression and times are not constants.

◆ ~DiscreteTimeTrajectory()

Member Function Documentation

◆ cols()

Eigen::Index cols ( ) const
finalvirtual

Returns the number of cols in the MatrixX<T> returned by value().

Precondition
num_times() > 0.

Reimplemented from Trajectory< T >.

◆ end_time()

T end_time ( ) const
finalvirtual

Returns the maximum value of get_times().

Precondition
num_times() > 0.

Reimplemented from Trajectory< T >.

◆ get_times()

const std::vector<T>& get_times ( ) const

Returns the times where the trajectory value is defined.

◆ num_times()

int num_times ( ) const

Returns the number of discrete times where the trajectory value is defined.

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ rows()

Eigen::Index rows ( ) const
finalvirtual

Returns the number of rows in the MatrixX<T> returned by value().

Precondition
num_times() > 0.

Reimplemented from Trajectory< T >.

◆ start_time()

T start_time ( ) const
finalvirtual

Returns the minimum value of get_times().

Precondition
num_times() > 0.

Reimplemented from Trajectory< T >.

◆ time_comparison_tolerance()

double time_comparison_tolerance ( ) const

The trajectory is only defined at finite sample times.

This method returns the tolerance used determine which time sample (if any) matches a query time on calls to value(t).

◆ ToZeroOrderHold()

PiecewisePolynomial<T> ToZeroOrderHold ( ) const

Converts the discrete-time trajectory using PiecewisePolynomial<T>::ZeroOrderHold().

◆ value()

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

Returns the value of the trajectory at t.

Exceptions
std::exceptionif t is not within tolerance of one of the sample times.

Reimplemented from Trajectory< T >.


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