Template Struct SpecialOrthogonalOperationTpl< 2, _Scalar, _Options >

Inheritance Relationships

Base Type

Struct Documentation

template<typename _Scalar, int _Options>
struct SpecialOrthogonalOperationTpl<2, _Scalar, _Options> : public pinocchio::LieGroupBase<SpecialOrthogonalOperationTpl<2, _Scalar, _Options>>

Public Types

typedef Eigen::Matrix<Scalar, 2, 2> Matrix2
typedef Eigen::NumTraits<Scalar>::Real RealScalar

Public Functions

PINOCCHIO_LIE_GROUP_TPL_PUBLIC_INTERFACE(SpecialOrthogonalOperationTpl)

Public Static Functions

template<typename Matrix2Like>
static inline Matrix2Like::Scalar log(const Eigen::MatrixBase<Matrix2Like> &R)
template<typename Matrix2Like>
static inline Matrix2Like::Scalar Jlog(const Eigen::MatrixBase<Matrix2Like>&)
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)
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>&, 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>&, 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>&, const Eigen::MatrixBase<JacobianIn_t> &Jin, const Eigen::MatrixBase<JacobianOut_t> &Jout)
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>&, const Eigen::MatrixBase<JacobianIn_t> &Jin, const Eigen::MatrixBase<JacobianOut_t> &Jout)
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>&, const Eigen::MatrixBase<Jacobian_t>&)
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>&, const Eigen::MatrixBase<Jacobian_t>&)
template<class ConfigL_t, class ConfigR_t, class ConfigOut_t>
static inline void interpolate_impl(const Eigen::MatrixBase<ConfigL_t> &q0, const Eigen::MatrixBase<ConfigR_t> &q1, const Scalar &u, const Eigen::MatrixBase<ConfigOut_t> &qout)
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>&, const Eigen::MatrixBase<ConfigR_t>&, const Eigen::MatrixBase<ConfigOut_t> &qout)