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

Detailed Description

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

Represents a piecewise-trajectory with piece \(j\) given by:

\[ x(t) = K e^{A (t - t_j)} \alpha_j + \sum_{i=0}^k \beta_{j,i}(t-t_j)^i, \]

where \(k\) is the order of the piecewise_polynomial_part and \(t_j\) is the start time of the \(j\)-th segment.

This particular form can represent the solution to a linear dynamical system driven by a piecewise-polynomial input:

\[ \dot{x}(t) = A x(t) + B u(t), \]

where the input \( u(t) \) is a piecewise-polynomial function of time. See [1] for details and a motivating use case.

[1] R. Tedrake, S. Kuindersma, R. Deits and K. Miura, "A closed-form solution for real-time ZMP gait generation and feedback stabilization," 2015 IEEE-RAS 15th International Conference on Humanoid Robots (Humanoids), Seoul, 2015, pp. 936-940.

Template Parameters
TThe scalar type, which must be double.

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

Public Member Functions

 ExponentialPlusPiecewisePolynomial ()=default
 
template<typename DerivedK , typename DerivedA , typename DerivedAlpha >
 ExponentialPlusPiecewisePolynomial (const Eigen::MatrixBase< DerivedK > &K, const Eigen::MatrixBase< DerivedA > &A, const Eigen::MatrixBase< DerivedAlpha > &alpha, const PiecewisePolynomial< T > &piecewise_polynomial_part)
 
 ExponentialPlusPiecewisePolynomial (const PiecewisePolynomial< T > &piecewise_polynomial_part)
 
 ~ExponentialPlusPiecewisePolynomial () override=default
 
std::unique_ptr< Trajectory< T > > Clone () const override
 
MatrixX< T > value (const T &t) const override
 Evaluates the trajectory at the given time t. More...
 
ExponentialPlusPiecewisePolynomial derivative (int derivative_order=1) const
 
Eigen::Index rows () const override
 
Eigen::Index cols () const override
 
void shiftRight (double offset)
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 ExponentialPlusPiecewisePolynomial (const ExponentialPlusPiecewisePolynomial &)=default
 
ExponentialPlusPiecewisePolynomialoperator= (const ExponentialPlusPiecewisePolynomial &)=default
 
 ExponentialPlusPiecewisePolynomial (ExponentialPlusPiecewisePolynomial &&)=default
 
ExponentialPlusPiecewisePolynomialoperator= (ExponentialPlusPiecewisePolynomial &&)=default
 
- Public Member Functions inherited from PiecewiseTrajectory< T >
 ~PiecewiseTrajectory () override=default
 
int get_number_of_segments () const
 
start_time (int segment_number) const
 
end_time (int segment_number) const
 
duration (int segment_number) const
 
start_time () const override
 
end_time () const override
 
boolean< T > is_time_in_range (const T &t) const
 Returns true iff t >= getStartTime() && t <= getEndTime(). More...
 
int get_segment_index (const T &t) const
 
const std::vector< T > & get_segment_times () const
 
void segment_number_range_check (int segment_number) const
 
- Public Member Functions inherited from Trajectory< T >
virtual ~Trajectory ()=default
 
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

- Static Public Member Functions inherited from PiecewiseTrajectory< T >
static std::vector< T > RandomSegmentTimes (int num_segments, std::default_random_engine &generator)
 
- Static Public Attributes inherited from PiecewiseTrajectory< T >
static constexpr double kEpsilonTime = std::numeric_limits<double>::epsilon()
 Minimum delta quantity used for comparing time. More...
 
- Protected Member Functions inherited from PiecewiseTrajectory< T >
 PiecewiseTrajectory ()=default
 
 PiecewiseTrajectory (const std::vector< T > &breaks)
 breaks increments must be greater or equal to kEpsilonTime. More...
 
bool SegmentTimesEqual (const PiecewiseTrajectory &b, double tol=kEpsilonTime) const
 
const std::vector< T > & breaks () const
 
std::vector< T > & get_mutable_breaks ()
 
 PiecewiseTrajectory (const PiecewiseTrajectory &)=default
 
PiecewiseTrajectoryoperator= (const PiecewiseTrajectory &)=default
 
 PiecewiseTrajectory (PiecewiseTrajectory &&)=default
 
PiecewiseTrajectoryoperator= (PiecewiseTrajectory &&)=default
 
- 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
 
 Trajectory (const Trajectory &)=default
 
Trajectoryoperator= (const Trajectory &)=default
 
 Trajectory (Trajectory &&)=default
 
Trajectoryoperator= (Trajectory &&)=default
 

Constructor & Destructor Documentation

◆ ExponentialPlusPiecewisePolynomial() [1/5]

◆ ExponentialPlusPiecewisePolynomial() [2/5]

◆ ExponentialPlusPiecewisePolynomial() [3/5]

◆ ExponentialPlusPiecewisePolynomial() [4/5]

ExponentialPlusPiecewisePolynomial ( const Eigen::MatrixBase< DerivedK > &  K,
const Eigen::MatrixBase< DerivedA > &  A,
const Eigen::MatrixBase< DerivedAlpha > &  alpha,
const PiecewisePolynomial< T > &  piecewise_polynomial_part 
)

◆ ExponentialPlusPiecewisePolynomial() [5/5]

ExponentialPlusPiecewisePolynomial ( const PiecewisePolynomial< T > &  piecewise_polynomial_part)

◆ ~ExponentialPlusPiecewisePolynomial()

~ExponentialPlusPiecewisePolynomial ( )
overridedefault

Member Function Documentation

◆ Clone()

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

Implements Trajectory< T >.

◆ cols()

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

Implements Trajectory< T >.

◆ derivative()

ExponentialPlusPiecewisePolynomial derivative ( int  derivative_order = 1) const

◆ operator=() [1/2]

◆ operator=() [2/2]

◆ rows()

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

Implements Trajectory< T >.

◆ shiftRight()

void shiftRight ( double  offset)

◆ value()

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

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: