Public Types | |
enum | { Options = traits<LieGroupDerived>::Options , NQ = traits<LieGroupDerived>::NQ , NV = traits<LieGroupDerived>::NV } |
typedef Eigen::Matrix< Scalar, NQ, 1, Options > | ConfigVector_t |
typedef int | Index |
typedef Eigen::Matrix< Scalar, NV, NV, Options > | JacobianMatrix_t |
typedef Derived | LieGroupDerived |
typedef traits< LieGroupDerived >::Scalar | Scalar |
typedef Eigen::Matrix< Scalar, NV, 1, Options > | TangentVector_t |
Public Member Functions | |
API with return value as argument | |
template<class ConfigIn_t , class Tangent_t , class ConfigOut_t > | |
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... | |
template<class Config_t , class Jacobian_t > | |
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... | |
template<ArgumentPosition arg, class Config_t , class Tangent_t , class JacobianOut_t > | |
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... | |
template<class Config_t , class Tangent_t , class JacobianOut_t > | |
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... | |
template<class Config_t , class Tangent_t , class JacobianOut_t > | |
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... | |
template<class Config_t , class Tangent_t , class JacobianIn_t , class JacobianOut_t > | |
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 |
template<class Config_t , class Tangent_t , class JacobianIn_t , class JacobianOut_t > | |
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 |
template<class Config_t , class Tangent_t , class JacobianOut_t > | |
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... | |
template<class Config_t , class Tangent_t , class JacobianIn_t , class JacobianOut_t > | |
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 |
template<class Config_t , class Tangent_t , class JacobianIn_t , class JacobianOut_t > | |
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 |
template<class Config_t , class Tangent_t , class JacobianIn_t , class JacobianOut_t > | |
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... | |
template<class Config_t , class Tangent_t , class JacobianIn_t , class JacobianOut_t > | |
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... | |
template<class Config_t , class Tangent_t , class JacobianIn_t , class JacobianOut_t > | |
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... | |
template<class Config_t , class Tangent_t , class Jacobian_t > | |
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... | |
template<class Config_t , class Tangent_t , class Jacobian_t > | |
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... | |
template<class Config_t , class Tangent_t , class Jacobian_t > | |
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... | |
template<class ConfigL_t , class ConfigR_t , class ConfigOut_t > | |
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... | |
template<class Config_t > | |
void | normalize (const Eigen::MatrixBase< Config_t > &qout) const |
Normalize the joint configuration given as input. For instance, the quaternion must be unitary. More... | |
template<class Config_t > | |
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... | |
template<class Config_t > | |
void | random (const Eigen::MatrixBase< Config_t > &qout) const |
Generate a random joint configuration, normalizing quaternions when necessary. More... | |
template<class ConfigL_t , class ConfigR_t , class ConfigOut_t > | |
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... | |
template<class ConfigL_t , class ConfigR_t , class Tangent_t > | |
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... | |
template<ArgumentPosition arg, class ConfigL_t , class ConfigR_t , class JacobianOut_t > | |
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... | |
template<class ConfigL_t , class ConfigR_t , class JacobianOut_t > | |
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... | |
template<ArgumentPosition arg, class ConfigL_t , class ConfigR_t , class JacobianIn_t , class JacobianOut_t > | |
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 |
template<ArgumentPosition arg, class ConfigL_t , class ConfigR_t , class JacobianIn_t , class JacobianOut_t > | |
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 |
template<class ConfigL_t , class ConfigR_t > | |
Scalar | squaredDistance (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1) const |
Squared distance between two joint configurations. More... | |
template<class ConfigL_t , class ConfigR_t > | |
Scalar | distance (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1) const |
Distance between two configurations of the joint. More... | |
template<class ConfigL_t , class ConfigR_t > | |
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 |
API that allocates memory | |
template<class Config_t , class Tangent_t > | |
ConfigVector_t | integrate (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v) const |
template<class ConfigL_t , class ConfigR_t > | |
ConfigVector_t | interpolate (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Scalar &u) const |
ConfigVector_t | random () const |
template<class ConfigL_t , class ConfigR_t > | |
ConfigVector_t | randomConfiguration (const Eigen::MatrixBase< ConfigL_t > &lower_pos_limit, const Eigen::MatrixBase< ConfigR_t > &upper_pos_limit) const |
template<class ConfigL_t , class ConfigR_t > | |
TangentVector_t | difference (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1) const |
Default implementations | |
template<class Config_t , class Tangent_t , class JacobianIn_t , class JacobianOut_t > | |
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 |
template<ArgumentPosition arg, class ConfigL_t , class ConfigR_t , class JacobianIn_t , class JacobianOut_t > | |
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 |
template<class ConfigL_t , class ConfigR_t , class ConfigOut_t > | |
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 |
template<class Config_t > | |
void | normalize_impl (const Eigen::MatrixBase< Config_t > &qout) const |
template<class Config_t > | |
bool | isNormalized_impl (const Eigen::MatrixBase< Config_t > &qin, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const |
template<class ConfigL_t , class ConfigR_t > | |
Scalar | squaredDistance_impl (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1) const |
template<class ConfigL_t , class ConfigR_t > | |
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. | |
Derived & | derived () |
const Derived & | derived () const |
Protected Member Functions | |
LieGroupBase () | |
LieGroupBase (const LieGroupBase &) | |
LieGroupBase & | operator= (const LieGroupBase &) |
Definition at line 44 of file liegroup-base.hpp.
|
inlineprotected |
Default constructor.
Prevent the construction of derived class.
Definition at line 722 of file liegroup-base.hpp.
|
inlineprotected |
Copy constructor
Prevent the copy of derived class.
Definition at line 729 of file liegroup-base.hpp.
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.
arg | ARG0 (resp. ARG1) to get the Jacobian with respect to q0 (resp. q1). |
[in] | q0 | the initial configuration vector. |
[in] | q1 | the terminal configuration vector. |
[out] | J | the Jacobian of the difference operation. |
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.
[in] | q0 | the initial configuration vector. |
[in] | q1 | the terminal configuration vector. |
[in] | arg | ARG0 (resp. ARG1) to get the Jacobian with respect to q0 (resp. q1). |
[out] | J | the Jacobian of the difference operation. |
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.
[in] | q0 | the initial configuration vector. |
[in] | q1 | the terminal configuration vector. |
[out] | v | the corresponding velocity. |
|
inline |
Computes the Jacobian of a small variation of the configuration vector or the tangent vector into tangent space at identity.
This Jacobian corresponds to the Jacobian of \( (\mathbf{q} \oplus \delta \mathbf{q}) \oplus \mathbf{v} \) with \( \delta \mathbf{q} \rightarrow 0 \) if arg == ARG0 or \( \delta \mathbf{v} \rightarrow 0 \) if arg == ARG1.
[in] | q | configuration vector. |
[in] | v | tangent vector. |
[in] | op | assignment operator (SETTO, ADDTO or RMTO). |
arg | ARG0 (resp. ARG1) to get the Jacobian with respect to q (resp. v). |
[out] | J | the Jacobian of the Integrate operation w.r.t. the argument arg. |
Definition at line 112 of file liegroup-base.hpp.
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.
This Jacobian corresponds to the Jacobian of \( (\mathbf{q} \oplus \delta \mathbf{q}) \oplus \mathbf{v} \) with \( \delta \mathbf{q} \rightarrow 0 \) if arg == ARG0 or \( \delta \mathbf{v} \rightarrow 0 \) if arg == ARG1.
[in] | q | configuration vector. |
[in] | v | tangent vector. |
[in] | arg | ARG0 (resp. ARG1) to get the Jacobian with respect to q (resp. v). |
[in] | op | assignment operator (SETTO, ADDTO and RMTO). |
[out] | J | the Jacobian of the Integrate operation w.r.t. the argument arg. |
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.
This Jacobian corresponds to the Jacobian of \( (\mathbf{q} \oplus \delta \mathbf{q}) \oplus \mathbf{v} \) with \( \delta \mathbf{q} \rightarrow 0 \).
[in] | q | configuration vector. |
[in] | v | tangent vector. |
[in] | op | assignment operator (SETTO, ADDTO or RMTO). |
[out] | J | the Jacobian of the Integrate operation w.r.t. the configuration vector q. |
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.
This Jacobian corresponds to the Jacobian of \( \mathbf{q} \oplus (\mathbf{v} + \delta \mathbf{v}) \) with \( \delta \mathbf{v} \rightarrow 0 \).
[in] | q | configuration vector. |
[in] | v | tangent vector. |
[in] | op | assignment operator (SETTO, ADDTO or RMTO). |
[out] | J | the Jacobian of the Integrate operation w.r.t. the tangent vector v. |
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.
This function performs the parallel transportation of an input matrix whose columns are expressed in the tangent space of the integrated element \( q \oplus v \), to the tangent space at \( q \). In other words, this functions transforms a tangent vector expressed at \( q \oplus v \) to a tangent vector expressed at \( q \), considering that the change of configuration between \( q \oplus v \) and \( q \) may alter the value of this tangent vector. A typical example of parallel transportation is the action operated by a rigid transformation \( M \in \text{SE}(3)\) on a spatial velocity \( v \in \text{se}(3)\). In the context of configuration spaces assimilated to vector spaces, this operation corresponds to Identity. For Lie groups, its corresponds to the canonical vector field transportation.
[in] | q | configuration vector. |
[in] | v | tangent vector |
[in,out] | J | the inplace matrix |
[in] | arg | argument with respect to which the differentiation is performed (ARG0 corresponding to q, and ARG1 to v) |
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.
This function performs the parallel transportation of an input matrix whose columns are expressed in the tangent space of the integrated element \( q \oplus v \), to the tangent space at \( q \). In other words, this functions transforms a tangent vector expressed at \( q \oplus v \) to a tangent vector expressed at \( q \), considering that the change of configuration between \( q \oplus v \) and \( q \) may alter the value of this tangent vector. A typical example of parallel transportation is the action operated by a rigid transformation \( M \in \text{SE}(3)\) on a spatial velocity \( v \in \text{se}(3)\). In the context of configuration spaces assimilated to vector spaces, this operation corresponds to Identity. For Lie groups, its corresponds to the canonical vector field transportation.
[in] | q | configuration vector. |
[in] | v | tangent vector |
[in] | Jin | the input matrix |
[in] | arg | argument with respect to which the differentiation is performed (ARG0 corresponding to q, and ARG1 to v) |
[out] | Jout | Transported matrix |
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.
This function performs the parallel transportation of an input matrix whose columns are expressed in the tangent space of the integrated element \( q \oplus v \), to the tangent space at \( q \). In other words, this functions transforms a tangent vector expressed at \( q \oplus v \) to a tangent vector expressed at \( q \), considering that the change of configuration between \( q \oplus v \) and \( q \) may alter the value of this tangent vector. A typical example of parallel transportation is the action operated by a rigid transformation \( M \in \text{SE}(3)\) on a spatial velocity \( v \in \text{se}(3)\). In the context of configuration spaces assimilated to vector spaces, this operation corresponds to Identity. For Lie groups, its corresponds to the canonical vector field transportation.
[in] | q | configuration vector. |
[in] | v | tangent vector |
[in,out] | Jin | the inplace matrix |
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.
This function performs the parallel transportation of an input matrix whose columns are expressed in the tangent space of the integrated element \( q \oplus v \), to the tangent space at \( q \). In other words, this functions transforms a tangent vector expressed at \( q \oplus v \) to a tangent vector expressed at \( q \), considering that the change of configuration between \( q \oplus v \) and \( q \) may alter the value of this tangent vector. A typical example of parallel transportation is the action operated by a rigid transformation \( M \in \text{SE}(3)\) on a spatial velocity \( v \in \text{se}(3)\). In the context of configuration spaces assimilated to vector spaces, this operation corresponds to Identity. For Lie groups, its corresponds to the canonical vector field transportation.
[in] | q | configuration vector. |
[in] | v | tangent vector |
[in] | Jin | the input matrix |
[out] | Jout | Transported matrix |
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.
This function performs the parallel transportation of an input matrix whose columns are expressed in the tangent space of the integrated element \( q \oplus v \), to the tangent space at \( q \). In other words, this functions transforms a tangent vector expressed at \( q \oplus v \) to a tangent vector expressed at \( q \), considering that the change of configuration between \( q \oplus v \) and \( q \) may alter the value of this tangent vector. A typical example of parallel transportation is the action operated by a rigid transformation \( M \in \text{SE}(3)\) on a spatial velocity \( v \in \text{se}(3)\). In the context of configuration spaces assimilated to vector spaces, this operation corresponds to Identity. For Lie groups, its corresponds to the canonical vector field transportation.
[in] | q | configuration vector. |
[in] | v | tangent vector |
[in,out] | J | the inplace matrix |
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.
This function performs the parallel transportation of an input matrix whose columns are expressed in the tangent space of the integrated element \( q \oplus v \), to the tangent space at \( q \). In other words, this functions transforms a tangent vector expressed at \( q \oplus v \) to a tangent vector expressed at \( q \), considering that the change of configuration between \( q \oplus v \) and \( q \) may alter the value of this tangent vector. A typical example of parallel transportation is the action operated by a rigid transformation \( M \in \text{SE}(3)\) on a spatial velocity \( v \in \text{se}(3)\). In the context of configuration spaces assimilated to vector spaces, this operation corresponds to Identity. For Lie groups, its corresponds to the canonical vector field transportation.
[in] | q | configuration vector. |
[in] | v | tangent vector |
[in] | Jin | the input matrix |
[out] | Jout | Transported matrix |
Scalar distance | ( | const Eigen::MatrixBase< ConfigL_t > & | q0, |
const Eigen::MatrixBase< ConfigR_t > & | q1 | ||
) | const |
Distance between two configurations of the joint.
[in] | q0 | the initial configuration vector. |
[in] | q1 | the terminal configuration vector. |
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.
[in] | q | the initial configuration. |
[in] | v | the tangent velocity. |
[out] | qout | the configuration integrated. |
void integrateCoeffWiseJacobian | ( | const Eigen::MatrixBase< Config_t > & | q, |
const Eigen::MatrixBase< Jacobian_t > & | J | ||
) | const |
Computes the Jacobian of the integrate operator around zero.
This function computes the Jacobian of the configuration vector variation (component-vise) with respect to a small variation in the tangent.
[in] | q | configuration vector. |
[out] | J | the Jacobian of the log of the Integrate operation w.r.t. the configuration vector q. |
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.
[in] | q0 | the initial configuration to interpolate. |
[in] | q1 | the final configuration to interpolate. |
[in] | u | in [0;1] the absicca along the interpolation. |
[out] | qout | the interpolated configuration (q0 if u = 0, q1 if u = 1) |
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.
[in] | qin | The joint configuration to check. |
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.
[in] | q0 | Configuration 0 |
[in] | q1 | Configuration 1 |
void normalize | ( | const Eigen::MatrixBase< Config_t > & | qout | ) | const |
Normalize the joint configuration given as input. For instance, the quaternion must be unitary.
isNormalized(qout)
is still false.[in,out] | qout | the normalized joint configuration. |
Index nq | ( | ) | const |
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.
|
inlineprotected |
Copy assignment operator
Prevent the copy of derived class.
Definition at line 736 of file liegroup-base.hpp.
void random | ( | const Eigen::MatrixBase< Config_t > & | qout | ) | const |
Generate a random joint configuration, normalizing quaternions when necessary.
[out] | qout | the random joint configuration. |
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.
[in] | lower_pos_limit | the lower joint limit vector. |
[in] | upper_pos_limit | the upper joint limit vector. |
[out] | qout | the random joint configuration in the two bounds. |
Scalar squaredDistance | ( | const Eigen::MatrixBase< ConfigL_t > & | q0, |
const Eigen::MatrixBase< ConfigR_t > & | q1 | ||
) | const |
Squared distance between two joint configurations.
[in] | q0 | the initial configuration vector. |
[in] | q1 | the terminal configuration vector. |
[out] | d | the corresponding distance betwenn q0 and q1. |