Template Struct SpecialEuclideanOperationTpl< 3, _Scalar, _Options >

Inheritance Relationships

Base Type

Struct Documentation

template<typename _Scalar, int _Options>
struct SpecialEuclideanOperationTpl<3, _Scalar, _Options> : public pinocchio::LieGroupBase<SpecialEuclideanOperationTpl<3, _Scalar, _Options>>

SE(3)

Public Types

typedef CartesianProductOperation<VectorSpaceOperationTpl<3, Scalar, Options>, SpecialOrthogonalOperationTpl<3, Scalar, Options>> R3crossSO3_t
typedef Eigen::Quaternion<Scalar, Options> Quaternion_t
typedef Eigen::Map<Quaternion_t> QuaternionMap_t
typedef Eigen::Map<const Quaternion_t> ConstQuaternionMap_t
typedef SE3Tpl<Scalar, Options> Transformation_t
typedef SE3Tpl<Scalar, Options> SE3
typedef Eigen::NumTraits<Scalar>::Real RealScalar

Public Functions

PINOCCHIO_LIE_GROUP_TPL_PUBLIC_INTERFACE(SpecialEuclideanOperationTpl)

Public Static Functions

static inline Index nq()

Get dimension of Lie Group vector representation

For instance, for SO(3), the dimension of the vector representation is 4 (quaternion) while the dimension of the tangent space is 3.

static inline Index nv()

Get dimension of Lie Group tangent space.

static inline ConfigVector_t neutral()
static inline std::string name()
template<class ConfigL_t, class ConfigR_t, class Tangent_t>
static inline void difference_impl(const Eigen::MatrixBase<ConfigL_t> &q0, const Eigen::MatrixBase<ConfigR_t> &q1, const Eigen::MatrixBase<Tangent_t> &d)
template<ArgumentPosition arg, class ConfigL_t, class ConfigR_t, class JacobianOut_t>
static inline void dDifference_impl(const Eigen::MatrixBase<ConfigL_t> &q0, const Eigen::MatrixBase<ConfigR_t> &q1, const Eigen::MatrixBase<JacobianOut_t> &J)

\cheatsheet \( \frac{\partial\ominus}{\partial q_1} {}^1X_0 = - \frac{\partial\ominus}{\partial q_0} \)

template<class ConfigIn_t, class Velocity_t, class ConfigOut_t>
static inline void integrate_impl(const Eigen::MatrixBase<ConfigIn_t> &q, const Eigen::MatrixBase<Velocity_t> &v, const Eigen::MatrixBase<ConfigOut_t> &qout)
template<class Config_t, class Jacobian_t>
static inline void integrateCoeffWiseJacobian_impl(const Eigen::MatrixBase<Config_t> &q, const Eigen::MatrixBase<Jacobian_t> &J)
template<class Config_t, class Tangent_t, class JacobianOut_t>
static inline void dIntegrate_dq_impl(const Eigen::MatrixBase<Config_t>&, const Eigen::MatrixBase<Tangent_t> &v, const Eigen::MatrixBase<JacobianOut_t> &J, const AssignmentOperatorType op = SETTO)
template<class Config_t, class Tangent_t, class JacobianOut_t>
static inline void dIntegrate_dv_impl(const Eigen::MatrixBase<Config_t>&, const Eigen::MatrixBase<Tangent_t> &v, const Eigen::MatrixBase<JacobianOut_t> &J, const AssignmentOperatorType op = SETTO)
template<class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
static inline void dIntegrateTransport_dq_impl(const Eigen::MatrixBase<Config_t>&, const Eigen::MatrixBase<Tangent_t> &v, const Eigen::MatrixBase<JacobianIn_t> &Jin, const Eigen::MatrixBase<JacobianOut_t> &J_out)
template<class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
static inline void dIntegrateTransport_dv_impl(const Eigen::MatrixBase<Config_t>&, const Eigen::MatrixBase<Tangent_t> &v, const Eigen::MatrixBase<JacobianIn_t> &Jin, const Eigen::MatrixBase<JacobianOut_t> &J_out)
template<class Config_t, class Tangent_t, class Jacobian_t>
static inline void dIntegrateTransport_dq_impl(const Eigen::MatrixBase<Config_t>&, const Eigen::MatrixBase<Tangent_t> &v, const Eigen::MatrixBase<Jacobian_t> &J_out)
template<class Config_t, class Tangent_t, class Jacobian_t>
static inline void dIntegrateTransport_dv_impl(const Eigen::MatrixBase<Config_t>&, const Eigen::MatrixBase<Tangent_t> &v, const Eigen::MatrixBase<Jacobian_t> &J_out)
template<class ConfigL_t, class ConfigR_t>
static inline Scalar squaredDistance_impl(const Eigen::MatrixBase<ConfigL_t> &q0, const Eigen::MatrixBase<ConfigR_t> &q1)
template<class Config_t>
static inline void normalize_impl(const Eigen::MatrixBase<Config_t> &qout)
template<class Config_t>
static inline bool isNormalized_impl(const Eigen::MatrixBase<Config_t> &qin, const Scalar &prec)
template<class Config_t>
static inline void random_impl(const Eigen::MatrixBase<Config_t> &qout)
template<class ConfigL_t, class ConfigR_t, class ConfigOut_t>
static inline void randomConfiguration_impl(const Eigen::MatrixBase<ConfigL_t> &lower, const Eigen::MatrixBase<ConfigR_t> &upper, const Eigen::MatrixBase<ConfigOut_t> &qout)
template<class ConfigL_t, class ConfigR_t>
static inline bool isSameConfiguration_impl(const Eigen::MatrixBase<ConfigL_t> &q0, const Eigen::MatrixBase<ConfigR_t> &q1, const Scalar &prec)