pinocchio  UNKNOWN
SpecialEuclideanOperation< 3 > Struct Template Reference

SE(3) More...

#include <multibody/liegroup/special-euclidean.hpp>

Inheritance diagram for SpecialEuclideanOperation< 3 >:
[legend]
Collaboration diagram for SpecialEuclideanOperation< 3 >:
[legend]

Public Types

typedef CartesianProductOperation< VectorSpaceOperation< 3 >, SpecialOrthogonalOperation< 3 > > R3crossSO3_t
 
typedef Eigen::Quaternion< Scalar > Quaternion_t
 
typedef Eigen::Map< Quaternion_t > QuaternionMap_t
 
typedef Eigen::Map< const Quaternion_t > ConstQuaternionMap_t
 
typedef SE3 Transformation_t
 
- Public Types inherited from LieGroupBase< SpecialEuclideanOperation< 3 > >
enum  
 
typedef SpecialEuclideanOperation< 3 > LieGroupDerived
 
typedef int Index
 
typedef traits< LieGroupDerived >::Scalar Scalar
 
typedef Eigen::Matrix< Scalar, NQ, 1 > ConfigVector_t
 
typedef Eigen::Matrix< Scalar, NV, 1 > TangentVector_t
 
typedef Eigen::Matrix< Scalar, NV, NV > JacobianMatrix_t
 

Public Member Functions

 SE3_LIE_GROUP_PUBLIC_INTERFACE (SpecialEuclideanOperation)
 
Index nq () const
 
Index nv () const
 Get dimension of Lie Group tangent space.
 
ConfigVector_t neutral () const
 
std::string name () const
 
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< SpecialEuclideanOperation< 3 > >
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 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 the Integrate operation. 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 the Integrate operation. 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 Jdifference (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< JacobianLOut_t > &J0, const Eigen::MatrixBase< JacobianROut_t > &J1) const
 Computes the Jacobian of the difference operation. 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.
 
SpecialEuclideanOperation< 3 > & derived ()
 
const SpecialEuclideanOperation< 3 > & 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 ConfigL_t , class ConfigR_t , class JacobianLOut_t , class JacobianROut_t >
static void Jdifference_impl (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< JacobianLOut_t > &J0, const Eigen::MatrixBase< JacobianROut_t > &J1)
 
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 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 ConfigL_t , class ConfigR_t >
static double squaredDistance_impl (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1)
 
template<class Config_t >
static void normalize_impl (const Eigen::MatrixBase< Config_t > &qout)
 
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)
 

Additional Inherited Members

- Protected Member Functions inherited from LieGroupBase< SpecialEuclideanOperation< 3 > >
 LieGroupBase ()
 
 LieGroupBase (const LieGroupBase &)
 

Detailed Description

template<>
struct se3::SpecialEuclideanOperation< 3 >

SE(3)

Definition at line 319 of file special-euclidean.hpp.

Member Function Documentation

Index nq ( ) const
inline

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 334 of file special-euclidean.hpp.


The documentation for this struct was generated from the following file: