SE(3) More...
#include <multibody/liegroup/special-euclidean.hpp>
Public Types | |
| typedef Eigen::Map< const Quaternion_t > | ConstQuaternionMap_t |
| typedef Eigen::Quaternion< Scalar, Options > | Quaternion_t |
| typedef Eigen::Map< Quaternion_t > | QuaternionMap_t |
| typedef CartesianProductOperation< VectorSpaceOperationTpl< 3, Scalar, Options >, SpecialOrthogonalOperationTpl< 3, Scalar, Options > > | R3crossSO3_t |
| typedef SE3Tpl< Scalar, Options > | SE3 |
| typedef SE3Tpl< Scalar, Options > | Transformation_t |
Public Types inherited from LieGroupBase< SpecialEuclideanOperationTpl< 3, _Scalar, _Options > > | |
| enum | |
| typedef Eigen::Matrix< Scalar, NQ, 1, Options > | ConfigVector_t |
| typedef int | Index |
| typedef Eigen::Matrix< Scalar, NV, NV, Options > | JacobianMatrix_t |
| typedef SpecialEuclideanOperationTpl< 3, _Scalar, _Options > | LieGroupDerived |
| typedef traits< LieGroupDerived >::Scalar | Scalar |
| typedef Eigen::Matrix< Scalar, NV, 1, Options > | TangentVector_t |
Public Member Functions | |
| template<ArgumentPosition arg, class ConfigL_t , class ConfigR_t , class JacobianOut_t > | |
| void | dDifference_impl (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< JacobianOut_t > &J) const |
| PINOCCHIO_LIE_GROUP_TPL_PUBLIC_INTERFACE (SpecialEuclideanOperationTpl) | |
| template<class Config_t > | |
| void | random_impl (const Eigen::MatrixBase< Config_t > &qout) const |
| template<class ConfigL_t , class ConfigR_t , class ConfigOut_t > | |
| void | randomConfiguration_impl (const Eigen::MatrixBase< ConfigL_t > &lower, const Eigen::MatrixBase< ConfigR_t > &upper, const Eigen::MatrixBase< ConfigOut_t > &qout) const |
Public Member Functions inherited from LieGroupBase< SpecialEuclideanOperationTpl< 3, _Scalar, _Options > > | |
| void | integrate (const Eigen::MatrixBase< ConfigIn_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< ConfigOut_t > &qout) const |
| Integrate a joint's configuration with a tangent vector during one unit time duration. More... | |
| void | integrateCoeffWiseJacobian (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Jacobian_t > &J) const |
| Computes the Jacobian of the integrate operator around zero. More... | |
| void | dIntegrate (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianOut_t > &J) const |
| Computes the Jacobian of a small variation of the configuration vector or the tangent vector into tangent space at identity. More... | |
| void | dIntegrate (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianOut_t > &J, const ArgumentPosition arg) const |
| Computes the Jacobian of a small variation of the configuration vector or the tangent vector into tangent space at identity. More... | |
| void | dIntegrate_dq (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianOut_t > &J) const |
| Computes the Jacobian of a small variation of the configuration vector into tangent space at identity. More... | |
| void | dIntegrate_dv (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianOut_t > &J) const |
| Computes the Jacobian of a small variation of the tangent vector into tangent space at identity. More... | |
| void | interpolate (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Scalar &u, const Eigen::MatrixBase< ConfigOut_t > &qout) const |
| Interpolation between two joint's configurations. More... | |
| void | normalize (const Eigen::MatrixBase< Config_t > &qout) const |
| Normalize the joint configuration given as input. For instance, the quaternion must be unitary. More... | |
| void | random (const Eigen::MatrixBase< Config_t > &qout) const |
| Generate a random joint configuration, normalizing quaternions when necessary. More... | |
| void | randomConfiguration (const Eigen::MatrixBase< ConfigL_t > &lower_pos_limit, const Eigen::MatrixBase< ConfigR_t > &upper_pos_limit, const Eigen::MatrixBase< ConfigOut_t > &qout) const |
| Generate a configuration vector uniformly sampled among provided limits. More... | |
| void | difference (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< Tangent_t > &v) const |
| Computes the tangent vector that must be integrated during one unit time to go from q0 to q1. More... | |
| void | dDifference (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< JacobianOut_t > &J) const |
| Computes the Jacobian of the difference operation with respect to q0 or q1. More... | |
| void | dDifference (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< JacobianOut_t > &J, const ArgumentPosition arg) const |
| Computes the Jacobian of the difference operation with respect to q0 or q1. More... | |
| Scalar | squaredDistance (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1) const |
| Squared distance between two joint configurations. More... | |
| Scalar | distance (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1) const |
| Distance between two configurations of the joint. More... | |
| bool | isSameConfiguration (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const |
| Check if two configurations are equivalent within the given precision. More... | |
| ConfigVector_t | integrate (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v) const |
| ConfigVector_t | interpolate (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Scalar &u) const |
| ConfigVector_t | random () const |
| ConfigVector_t | randomConfiguration (const Eigen::MatrixBase< ConfigL_t > &lower_pos_limit, const Eigen::MatrixBase< ConfigR_t > &upper_pos_limit) const |
| TangentVector_t | difference (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1) const |
| void | interpolate_impl (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Scalar &u, const Eigen::MatrixBase< ConfigOut_t > &qout) const |
| void | normalize_impl (const Eigen::MatrixBase< Config_t > &qout) const |
| Scalar | squaredDistance_impl (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1) const |
| bool | isSameConfiguration_impl (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Scalar &prec) const |
| Index | nq () const |
| Index | nv () const |
| Get dimension of Lie Group tangent space. | |
| ConfigVector_t | neutral () const |
| Get neutral element as a vector. | |
| std::string | name () const |
| Get name of instance. | |
| SpecialEuclideanOperationTpl< 3, _Scalar, _Options > & | derived () |
| const SpecialEuclideanOperationTpl< 3, _Scalar, _Options > & | derived () const |
Static Public Member Functions | |
| template<class ConfigL_t , class ConfigR_t , class Tangent_t > | |
| static void | difference_impl (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< Tangent_t > &d) |
| template<class Config_t , class Tangent_t , class JacobianOut_t > | |
| static void | dIntegrate_dq_impl (const Eigen::MatrixBase< Config_t > &, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianOut_t > &J) |
| template<class Config_t , class Tangent_t , class JacobianOut_t > | |
| static void | dIntegrate_dv_impl (const Eigen::MatrixBase< Config_t > &, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianOut_t > &J) |
| template<class ConfigIn_t , class Velocity_t , class ConfigOut_t > | |
| static 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 void | integrateCoeffWiseJacobian_impl (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Jacobian_t > &J) |
| template<class ConfigL_t , class ConfigR_t > | |
| static bool | isSameConfiguration_impl (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Scalar &prec) |
| static std::string | name () |
| static ConfigVector_t | neutral () |
| template<class Config_t > | |
| static void | normalize_impl (const Eigen::MatrixBase< Config_t > &qout) |
| static Index | nq () |
| static Index | nv () |
| Get dimension of Lie Group tangent space. | |
| template<class ConfigL_t , class ConfigR_t > | |
| static Scalar | squaredDistance_impl (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1) |
Additional Inherited Members | |
Protected Member Functions inherited from LieGroupBase< SpecialEuclideanOperationTpl< 3, _Scalar, _Options > > | |
| LieGroupBase () | |
| LieGroupBase (const LieGroupBase &) | |
SE(3)
Definition at line 387 of file special-euclidean.hpp.
|
inline |
Definition at line 444 of file special-euclidean.hpp.
References pinocchio::exp6(), pinocchio::quaternion::firstOrderNormalize(), pinocchio::quaternion::Jexp3CoeffWise(), pinocchio::Jexp6(), pinocchio::Jlog3(), pinocchio::Jlog6(), pinocchio::quaternion::log3(), pinocchio::normalize(), pinocchio::nq(), pinocchio::nv(), and pinocchio::skew().
|
inlinestatic |
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.
Definition at line 404 of file special-euclidean.hpp.