pinocchio  3.3.1
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
LieGroupGenericTpl< LieGroupCollection > Struct Template Reference
Inheritance diagram for LieGroupGenericTpl< LieGroupCollection >:
Collaboration diagram for LieGroupGenericTpl< LieGroupCollection >:

Public Types

enum  { Options = LieGroupCollection::Options }
 
typedef LieGroupCollection::LieGroupVariant Base
 
typedef LieGroupCollection::LieGroupVariant LieGroupVariant
 
typedef LieGroupCollection::Scalar Scalar
 
- Public Types inherited from LieGroupBase< LieGroupGenericTpl< LieGroupCollection > >
enum  
 
typedef Eigen::Matrix< Scalar, NQ, 1, Options > ConfigVector_t
 
typedef int Index
 
typedef Eigen::Matrix< Scalar, NV, NV, Options > JacobianMatrix_t
 
typedef LieGroupGenericTpl< LieGroupCollection > LieGroupDerived
 
typedef traits< LieGroupDerived >::Scalar Scalar
 
typedef Eigen::Matrix< Scalar, NV, 1, Options > TangentVector_t
 

Public Member Functions

template<typename LieGroupDerived >
 LieGroupGenericTpl (const LieGroupBase< LieGroupDerived > &lg_base)
 
 LieGroupGenericTpl (const LieGroupGenericTpl &lg_generic)=default
 
template<typename LieGroup >
 LieGroupGenericTpl (const LieGroupVariant &lg_variant)
 
bool isEqual_impl (const LieGroupGenericTpl &other) const
 
std::string name () const
 
int nq () const
 
int nv () const
 
bool operator!= (const LieGroupGenericTpl &other) const
 
LieGroupGenericTploperator= (const LieGroupGenericTpl &other)=default
 
bool operator== (const LieGroupGenericTpl &other) const
 
LieGroupVariant & toVariant ()
 
const LieGroupVariant & toVariant () const
 
- Public Member Functions inherited from LieGroupBase< LieGroupGenericTpl< LieGroupCollection > >
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, AssignmentOperatorType op=SETTO) 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 AssignmentOperatorType op=SETTO) 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 AssignmentOperatorType op=SETTO) const
 Computes the Jacobian of a small variation of the configuration 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< JacobianIn_t > &Jin, int self, const Eigen::MatrixBase< JacobianOut_t > &Jout, const AssignmentOperatorType op=SETTO) const
 
void dIntegrate_dq (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, int self, const Eigen::MatrixBase< JacobianIn_t > &Jin, const Eigen::MatrixBase< JacobianOut_t > &Jout, const AssignmentOperatorType op=SETTO) const
 
void dIntegrate_dv (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianOut_t > &J, const AssignmentOperatorType op=SETTO) const
 Computes the Jacobian of a small variation of the tangent vector into tangent space at identity. More...
 
void dIntegrate_dv (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, int self, const Eigen::MatrixBase< JacobianIn_t > &Jin, const Eigen::MatrixBase< JacobianOut_t > &Jout, const AssignmentOperatorType op=SETTO) const
 
void dIntegrate_dv (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianIn_t > &Jin, int self, const Eigen::MatrixBase< JacobianOut_t > &Jout, const AssignmentOperatorType op=SETTO) const
 
void dIntegrateTransport (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianIn_t > &Jin, const Eigen::MatrixBase< JacobianOut_t > &Jout, const ArgumentPosition arg) const
 Transport a matrix from the terminal to the initial tangent space of the integrate operation, with respect to the configuration or the velocity arguments. More...
 
void dIntegrateTransport (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< Jacobian_t > &J, const ArgumentPosition arg) const
 Transport in place a matrix from the terminal to the initial tangent space of the integrate operation, with respect to the configuration or the velocity arguments. More...
 
void dIntegrateTransport_dq (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianIn_t > &Jin, const Eigen::MatrixBase< JacobianOut_t > &Jout) const
 Transport a matrix from the terminal to the initial tangent space of the integrate operation, with respect to the configuration argument. More...
 
void dIntegrateTransport_dq (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< Jacobian_t > &J) const
 Transport in place a matrix from the terminal to the initial tangent space of the integrate operation, with respect to the configuration argument. More...
 
void dIntegrateTransport_dv (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianIn_t > &Jin, const Eigen::MatrixBase< JacobianOut_t > &Jout) const
 Transport a matrix from the terminal to the initial tangent space of the integrate operation, with respect to the velocity argument. More...
 
void dIntegrateTransport_dv (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< Jacobian_t > &J) const
 Transport in place a matrix from the terminal to the initial tangent space of the integrate operation, with respect to the velocity argument. 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...
 
bool isNormalized (const Eigen::MatrixBase< Config_t > &qin, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
 Check whether the input joint configuration is normalized. 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...
 
void dDifference (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< JacobianIn_t > &Jin, int self, const Eigen::MatrixBase< JacobianOut_t > &Jout, const AssignmentOperatorType op=SETTO) const
 
void dDifference (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, int self, const Eigen::MatrixBase< JacobianIn_t > &Jin, const Eigen::MatrixBase< JacobianOut_t > &Jout, const AssignmentOperatorType op=SETTO) const
 
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...
 
bool operator== (const LieGroupBase &other) const
 
bool operator!= (const LieGroupBase &other) const
 
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 dIntegrate_product_impl (const Config_t &q, const Tangent_t &v, const JacobianIn_t &Jin, JacobianOut_t &Jout, bool dIntegrateOnTheLeft, const ArgumentPosition arg, const AssignmentOperatorType op) const
 
void dDifference_product_impl (const ConfigL_t &q0, const ConfigR_t &q1, const JacobianIn_t &Jin, JacobianOut_t &Jout, bool dDifferenceOnTheLeft, const AssignmentOperatorType op) 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
 
bool isNormalized_impl (const Eigen::MatrixBase< Config_t > &qin, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) 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
 
bool isEqual_impl (const LieGroupBase &) const
 Default equality check. By default, two LieGroupBase of same type are considered equal.
 
bool isDifferent_impl (const LieGroupBase &other) 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.
 
LieGroupGenericTpl< LieGroupCollection > & derived ()
 
const LieGroupGenericTpl< LieGroupCollection > & derived () const
 

Additional Inherited Members

- Protected Member Functions inherited from LieGroupBase< LieGroupGenericTpl< LieGroupCollection > >
 LieGroupBase ()
 
 LieGroupBase (const LieGroupBase &)
 
LieGroupBaseoperator= (const LieGroupBase &)
 

Detailed Description

template<typename LieGroupCollection>
struct pinocchio::LieGroupGenericTpl< LieGroupCollection >

Definition at line 29 of file liegroup-generic.hpp.


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