Template Class MotionBase

Inheritance Relationships

Derived Types

Class Documentation

template<class Derived>
class MotionBase

Subclassed by pinocchio::MotionDense< MotionRef< Vector6ArgType > >, pinocchio::MotionDense< MotionRef< const Vector6ArgType > >, pinocchio::MotionDense< MotionTpl< _Scalar, _Options > >, pinocchio::MotionDense< pinocchio::MotionTpl >, pinocchio::MotionDense< MotionTpl< Scalar, _Options > >, pinocchio::MotionDense< pinocchio::MotionRef >, pinocchio::MotionDense< Derived >

Public Functions

MOTION_TYPEDEF_TPL(Derived)
inline Derived &derived()
inline const Derived &derived() const
inline ConstAngularType angular() const
inline ConstLinearType linear() const
inline AngularType angular()
inline LinearType linear()
template<typename V3Like>
inline void angular(const Eigen::MatrixBase<V3Like> &w)
template<typename V3Like>
inline void linear(const Eigen::MatrixBase<V3Like> &v)
inline operator PlainReturnType() const
inline PlainReturnType plain() const
inline ToVectorConstReturnType toVector() const
inline ToVectorReturnType toVector()
inline operator Vector6() const
inline ActionMatrixType toActionMatrix() const
inline ActionMatrixType toDualActionMatrix() const
inline operator Matrix6() const
inline HomogeneousMatrixType toHomogeneousMatrix() const

The homogeneous representation of the motion vector \( \xi \).

With \( \hat{\xi} = \left( \begin{array}{cc} \omega & v \\ 0 & 0 \\ \end{array} \right) \),

\[ {}^a\dot{M}_b = \hat{\xi} {}^aM_b \]

Note

This function is provided for completeness, but it is not the best way to use Motion quantities in terms of sparsity exploitation and general efficiency. For integration, the recommended way is to use Motion vectors along with the integrate function.

inline void setZero()
template<typename M2>
inline bool operator==(const MotionBase<M2> &other) const
template<typename M2>
inline bool operator!=(const MotionBase<M2> &other) const
inline Derived operator-() const
inline Derived operator+(const MotionBase<Derived> &v) const
inline Derived operator-(const MotionBase<Derived> &v) const
inline Derived &operator+=(const MotionBase<Derived> &v)
inline Derived &operator-=(const MotionBase<Derived> &v)
template<typename OtherScalar>
inline internal::RHSScalarMultiplication<Derived, OtherScalar>::ReturnType operator*(const OtherScalar &alpha) const
template<typename OtherScalar>
inline Derived operator/(const OtherScalar &alpha) const
template<typename OtherSpatialType>
inline MotionAlgebraAction<OtherSpatialType, Derived>::ReturnType cross(const OtherSpatialType &d) const
inline bool isApprox(const Derived &other, const Scalar &prec = Eigen::NumTraits<Scalar>::dummy_precision()) const
inline bool isZero(const Scalar &prec = Eigen::NumTraits<Scalar>::dummy_precision()) const
template<typename S2, int O2>
inline SE3GroupAction<Derived>::ReturnType se3Action(const SE3Tpl<S2, O2> &m) const
template<typename S2, int O2>
inline SE3GroupAction<Derived>::ReturnType se3ActionInverse(const SE3Tpl<S2, O2> &m) const
template<typename ForceDerived>
inline Scalar dot(const ForceDense<ForceDerived> &f) const
inline void disp(std::ostream &os) const

Friends

inline friend std::ostream &operator<<(std::ostream &os, const MotionBase<Derived> &v)