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
-
| T | The scalar type, which must be double. |
|
| | 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 () final |
| |
| ExponentialPlusPiecewisePolynomial | derivative (int derivative_order=1) const |
| |
| void | shiftRight (double offset) |
| |
|
| | ExponentialPlusPiecewisePolynomial (const ExponentialPlusPiecewisePolynomial &)=default |
| |
| ExponentialPlusPiecewisePolynomial & | operator= (const ExponentialPlusPiecewisePolynomial &)=default |
| |
| | ExponentialPlusPiecewisePolynomial (ExponentialPlusPiecewisePolynomial &&)=default |
| |
| ExponentialPlusPiecewisePolynomial & | operator= (ExponentialPlusPiecewisePolynomial &&)=default |
| |
| | ~PiecewiseTrajectory () override |
| |
| int | get_number_of_segments () const |
| |
| T | start_time (int segment_number) const |
| |
| T | end_time (int segment_number) const |
| |
| T | duration (int segment_number) const |
| |
| 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 |
| |
| virtual | ~Trajectory () |
| |
| std::unique_ptr< Trajectory< T > > | Clone () const |
| |
| MatrixX< T > | value (const T &t) const |
| | 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...
|
| |
| Eigen::Index | rows () const |
| |
| Eigen::Index | cols () const |
| |
| T | start_time () const |
| |
| T | end_time () const |
| |