|
trajectory_collection
|
Classes | |
| class | BangBangInterpolator |
| Interpolator with bang-bang control. More... | |
| class | CubicHermiteSpline |
| Cubic Hermite spline. More... | |
| class | CubicInterpolator |
| Cubic interpolator. More... | |
| struct | BoundaryConstraint |
| Boundary constraint. More... | |
| class | CubicSpline |
| Cubic spline. More... | |
| class | Func |
| Mathematical function. More... | |
| class | PiecewiseFunc |
| Piecewise function. More... | |
| class | Polynomial |
| Polynomial function. More... | |
| class | Constant |
| Constant function. More... | |
| class | Interpolator |
| Interpolator of a sequence of waypoints. More... | |
Typedefs | |
| template<class T > | |
| using | LinearPolynomial = Polynomial< T, 1 > |
| Linear polynomial function. More... | |
| template<class T > | |
| using | QuadraticPolynomial = Polynomial< T, 2 > |
| Quadratic polynomial function. More... | |
| template<class T > | |
| using | CubicPolynomial = Polynomial< T, 3 > |
| Cubic polynomial function. More... | |
Enumerations | |
| enum class | BoundaryConstraintType { Velocity = 0 , Acceleration } |
| Type of boundary constraint. More... | |
Functions | |
| template<class T > | |
| T | interpolate (const T &start, const T &end, double ratio) |
| Calculate the value interpolating from start to end. More... | |
| template<> | |
| Eigen::Quaterniond | interpolate (const Eigen::Quaterniond &start, const Eigen::Quaterniond &end, double ratio) |
| Calculate the Quaternion interpolating from start to end. More... | |
| template<> | |
| Eigen::Matrix3d | interpolate (const Eigen::Matrix3d &start, const Eigen::Matrix3d &end, double ratio) |
| Calculate the 3D matrix interpolating from start to end. More... | |
| template<> | |
| sva::PTransformd | interpolate (const sva::PTransformd &start, const sva::PTransformd &end, double ratio) |
| Calculate the pose interpolating from start to end. More... | |
| template<class T , class U = T> | |
| U | interpolateDerivative (const T &start, const T &end, double, int order=1) |
| Calculate the derivative value interpolating from start to end. More... | |
| template<> | |
| double | interpolateDerivative (const double &start, const double &end, double, int order) |
| Calculate the derivative of scalar value interpolating from start to end. More... | |
| template<> | |
| Eigen::Vector3d | interpolateDerivative (const Eigen::Quaterniond &start, const Eigen::Quaterniond &end, double, int order) |
| Calculate the derivative of Quaternion interpolating from start to end. More... | |
| template<> | |
| Eigen::Vector3d | interpolateDerivative (const Eigen::Matrix3d &start, const Eigen::Matrix3d &end, double, int order) |
| Calculate the derivative of 3D matrix interpolating from start to end. More... | |
| template<> | |
| sva::MotionVecd | interpolateDerivative (const sva::PTransformd &start, const sva::PTransformd &end, double, int order) |
| Calculate the derivative of pose interpolating from start to end. More... | |
| template<> | |
| sva::ForceVecd | interpolateDerivative (const sva::ForceVecd &start, const sva::ForceVecd &end, double, int order) |
| Calculate the derivative of wrench interpolating from start to end. More... | |
| using TrajColl::CubicPolynomial = typedef Polynomial<T, 3> |
| using TrajColl::LinearPolynomial = typedef Polynomial<T, 1> |
| using TrajColl::QuadraticPolynomial = typedef Polynomial<T, 2> |
|
strong |
Type of boundary constraint.
| Enumerator | |
|---|---|
| Velocity | Velocity constraint. |
| Acceleration | Acceleration constraint. |
Definition at line 10 of file CubicSpline.h.
|
inline |
Calculate the 3D matrix interpolating from start to end.
| start | start value |
| end | end value |
| ratio | interpolation ratio |
Definition at line 36 of file ElementInterpolation.h.
|
inline |
Calculate the Quaternion interpolating from start to end.
| start | start value |
| end | end value |
| ratio | interpolation ratio |
Definition at line 25 of file ElementInterpolation.h.
|
inline |
Calculate the pose interpolating from start to end.
| start | start value |
| end | end value |
| ratio | interpolation ratio |
Definition at line 47 of file ElementInterpolation.h.
|
inline |
Calculate the value interpolating from start to end.
| T | value type |
| start | start value |
| end | end value |
| ratio | interpolation ratio |
Definition at line 14 of file ElementInterpolation.h.
|
inline |
Calculate the derivative of scalar value interpolating from start to end.
| start | start value |
| end | end value |
| ratio | interpolation ratio |
| order | derivative order |
Definition at line 85 of file ElementInterpolation.h.
|
inline |
Calculate the derivative of 3D matrix interpolating from start to end.
| start | start value |
| end | end value |
| ratio | interpolation ratio |
| order | derivative order |
Definition at line 130 of file ElementInterpolation.h.
|
inline |
Calculate the derivative of Quaternion interpolating from start to end.
| start | start value |
| end | end value |
| ratio | interpolation ratio |
| order | derivative order |
Definition at line 107 of file ElementInterpolation.h.
|
inline |
Calculate the derivative of wrench interpolating from start to end.
| start | start value |
| end | end value |
| ratio | interpolation ratio |
| order | derivative order |
Definition at line 175 of file ElementInterpolation.h.
|
inline |
Calculate the derivative of pose interpolating from start to end.
| start | start value |
| end | end value |
| ratio | interpolation ratio |
| order | derivative order |
Definition at line 153 of file ElementInterpolation.h.
|
inline |
Calculate the derivative value interpolating from start to end.
| T | value type |
| U | derivative type |
| start | start value |
| end | end value |
| ratio | interpolation ratio |
| order | derivative order |
Definition at line 61 of file ElementInterpolation.h.