Template Struct SpecialEuclideanOperationTpl< 2, _Scalar, _Options >

Inheritance Relationships

Base Type

Struct Documentation

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

Public Types

typedef VectorSpaceOperationTpl<2, Scalar, Options> R2_t
typedef SpecialOrthogonalOperationTpl<2, Scalar, Options> SO2_t
typedef CartesianProductOperation<R2_t, SO2_t> R2crossSO2_t
typedef Eigen::Matrix<Scalar, 2, 2, Options> Matrix2
typedef Eigen::Matrix<Scalar, 2, 1, Options> Vector2

Public Functions

PINOCCHIO_LIE_GROUP_TPL_PUBLIC_INTERFACE(SpecialEuclideanOperationTpl)
template<ArgumentPosition arg, class ConfigL_t, class ConfigR_t, class JacobianOut_t>
inline void dDifference_impl(const Eigen::MatrixBase<ConfigL_t> &q0, const Eigen::MatrixBase<ConfigR_t> &q1, const Eigen::MatrixBase<JacobianOut_t> &J) const

Public Static Functions

template<typename TangentVector, typename Matrix2Like, typename Vector2Like>
static inline void exp(const Eigen::MatrixBase<TangentVector> &v, const Eigen::MatrixBase<Matrix2Like> &R, const Eigen::MatrixBase<Vector2Like> &t)
template<typename Matrix2Like, typename Vector2Like, typename Matrix3Like>
static inline void toInverseActionMatrix(const Eigen::MatrixBase<Matrix2Like> &R, const Eigen::MatrixBase<Vector2Like> &t, const Eigen::MatrixBase<Matrix3Like> &M, const AssignmentOperatorType op)
template<typename Matrix2Like, typename Vector2Like, typename TangentVector>
static inline void log(const Eigen::MatrixBase<Matrix2Like> &R, const Eigen::MatrixBase<Vector2Like> &p, const Eigen::MatrixBase<TangentVector> &v)
template<typename Matrix2Like, typename Vector2Like, typename JacobianOutLike>
static inline void Jlog(const Eigen::MatrixBase<Matrix2Like> &R, const Eigen::MatrixBase<Vector2Like> &p, const Eigen::MatrixBase<JacobianOutLike> &J)
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<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)
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)
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)

Protected Static Functions

template<typename Matrix2Like, typename Vector2Like, typename Vector4Like>
static inline void forwardKinematics(const Eigen::MatrixBase<Matrix2Like> &R, const Eigen::MatrixBase<Vector2Like> &t, const Eigen::MatrixBase<Vector4Like> &q)