Template Struct LieGroupBase
Defined in File liegroup-base.hpp
Struct Documentation
-
template<typename Derived>
struct LieGroupBase 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.
- Parameters:
q – [in] the initial configuration.
v – [in] the tangent velocity.
qout – [out] the configuration integrated.
-
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.
This function computes the Jacobian of the configuration vector variation (component-vise) with respect to a small variation in the tangent.
Remark
This function might be useful for instance when using google-ceres to compute the Jacobian of the integrate operation.
- Parameters:
q – [in] configuration vector.
J – [out] the Jacobian of the log of the Integrate operation w.r.t. the configuration vector q.
-
template<ArgumentPosition arg, class Config_t, class Tangent_t, class JacobianOut_t>
inline 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.
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.
- Parameters:
q – [in] configuration vector.
v – [in] tangent vector.
op – [in] assignment operator (SETTO, ADDTO or RMTO).
J – [out] the Jacobian of the Integrate operation w.r.t. the argument arg.
- Template Parameters:
arg – ARG0 (resp. ARG1) to get the Jacobian with respect to q (resp. v).
-
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.
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.
- Parameters:
q – [in] configuration vector.
v – [in] tangent vector.
arg – [in] ARG0 (resp. ARG1) to get the Jacobian with respect to q (resp. v).
op – [in] assignment operator (SETTO, ADDTO and RMTO).
J – [out] the Jacobian of the Integrate operation w.r.t. the argument arg.
-
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.
This Jacobian corresponds to the Jacobian of \( (\mathbf{q} \oplus \delta \mathbf{q}) \oplus \mathbf{v} \) with \( \delta \mathbf{q} \rightarrow 0 \).
- Parameters:
q – [in] configuration vector.
v – [in] tangent vector.
op – [in] assignment operator (SETTO, ADDTO or RMTO).
J – [out] the Jacobian of the Integrate operation w.r.t. the configuration vector q.
-
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.
This Jacobian corresponds to the Jacobian of \( \mathbf{q} \oplus (\mathbf{v} + \delta \mathbf{v}) \) with \( \delta \mathbf{v} \rightarrow 0 \).
- Parameters:
q – [in] configuration vector.
v – [in] tangent vector.
op – [in] assignment operator (SETTO, ADDTO or RMTO).
J – [out] the Jacobian of the Integrate operation w.r.t. the tangent vector v.
-
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 originate 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 as vectorial spaces, this operation corresponds to Identity. For Lie groups, its corresponds to the canonical vector field transportation.
- Parameters:
q – [in] configuration vector.
v – [in] tangent vector
Jin – [in] the input matrix
arg – [in] argument with respect to which the differentiation is performed (ARG0 corresponding to q, and ARG1 to v)
Jout – [out] Transported matrix
-
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 originate 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 as vectorial spaces, this operation corresponds to Identity. For Lie groups, its corresponds to the canonical vector field transportation.
- Parameters:
q – [in] configuration vector.
v – [in] tangent vector
Jin – [in] the input matrix
Jout – [out] Transported matrix
-
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 originate 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 as vectorial spaces, this operation corresponds to Identity. For Lie groups, its corresponds to the canonical vector field transportation.
- Parameters:
q – [in] configuration vector.
v – [in] tangent vector
Jin – [in] the input matrix
Jout – [out] Transported matrix
-
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 originate 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 as vectorial spaces, this operation corresponds to Identity. For Lie groups, its corresponds to the canonical vector field transportation.
- Parameters:
q – [in] configuration vector.
v – [in] tangent vector
J – [inout] the inplace matrix
arg – [in] argument with respect to which the differentiation is performed (ARG0 corresponding to q, and ARG1 to v)
-
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 originate 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 as vectorial spaces, this operation corresponds to Identity. For Lie groups, its corresponds to the canonical vector field transportation.
- Parameters:
q – [in] configuration vector.
v – [in] tangent vector
Jin – [inout] the inplace matrix
-
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 originate 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 as vectorial spaces, this operation corresponds to Identity. For Lie groups, its corresponds to the canonical vector field transportation.
- Parameters:
q – [in] configuration vector.
v – [in] tangent vector
J – [inout] the inplace matrix
-
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.
- Parameters:
q0 – [in] the initial configuration to interpolate.
q1 – [in] the final configuration to interpolate.
u – [in] in [0;1] the absicca along the interpolation.
qout – [out] the interpolated configuration (q0 if u = 0, q1 if u = 1)
q0 – [in] Initial configuration to interpolate
q1 – [in] Final configuration to interpolate
u – [in] u in [0;1] position along the interpolation.
- Returns:
The interpolated configuration (q0 if u = 0, q1 if u = 1)
-
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.
Note
If the input vector is too small (i.e., qout.norm()==0), then it is left unchanged. It is therefore possible that after this method is called
isNormalized(qout)
is still false.- Parameters:
qout – [inout] the normalized joint configuration.
-
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.
- Parameters:
qin – [in] The joint configuration to check.
- Returns:
true if the input vector is normalized, false otherwise.
-
template<class Config_t>
void random(const Eigen::MatrixBase<Config_t> &qout) const Generate a random joint configuration, normalizing quaternions when necessary.
Warning
Do not take into account the joint limits. To shoot a configuration uniformingly depending on joint limits, see randomConfiguration.
Warning
Do not take into account the joint limits. To shoot a configuration uniformingly depending on joint limits, see randomConfiguration
- Parameters:
qout – [out] the random joint configuration.
- Returns:
The joint configuration
-
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.
- Parameters:
lower_pos_limit – [in] the lower joint limit vector.
upper_pos_limit – [in] the upper joint limit vector.
qout – [out] the random joint configuration in the two bounds.
-
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.
\cheatsheet \( q_1 \ominus q_0 = - \left( q_0 \ominus q_1 \right) \)
Note
Both inputs must be well-formed configuration vectors. The output of this function is unspecified if inputs contain NaNs or extremal values for the underlying scalar type.
- Parameters:
q0 – [in] the initial configuration vector.
q1 – [in] the terminal configuration vector.
v – [out] the corresponding velocity.
-
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.
\cheatsheet \( \frac{\partial\ominus}{\partial q_1} \frac{\partial\oplus}{\partial v} = I \)
Warning
because \( q_1 \ominus q_0 = - \left( q_0 \ominus q_1 \right) \), you may be tempted to write \( \frac{\partial\ominus}{\partial q_1} = - \frac{\partial\ominus}{\partial q_0} \). This is false in the general case because \( \frac{\partial\ominus}{\partial q_i} \) expects an input velocity relative to frame i. See SpecialEuclideanOperationTpl<3,_Scalar,_Options>::dDifference_impl.
- Template Parameters:
arg – ARG0 (resp. ARG1) to get the Jacobian with respect to q0 (resp. q1).
- Parameters:
q0 – [in] the initial configuration vector.
q1 – [in] the terminal configuration vector.
J – [out] the Jacobian of the difference operation.
-
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.
- Parameters:
q0 – [in] the initial configuration vector.
q1 – [in] the terminal configuration vector.
arg – [in] ARG0 (resp. ARG1) to get the Jacobian with respect to q0 (resp. q1).
J – [out] the Jacobian of the difference operation.
-
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.
- Parameters:
q0 – [in] the initial configuration vector.
q1 – [in] the terminal configuration vector.
d – [out] the corresponding distance betwenn q0 and q1.
-
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.
- Parameters:
q0 – [in] the initial configuration vector.
q1 – [in] the terminal configuration vector.
- Returns:
The corresponding distance.
-
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.
\cheatsheet \( q_1 \equiv q_0 \oplus \left( q_1 \ominus q_0 \right) \) ( \(\equiv\) means equivalent, not equal).
- Parameters:
q0 – [in] Configuration 0
q1 – [in] Configuration 1
-
inline bool operator==(const LieGroupBase &other) const
-
inline 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>
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
-
inline bool isEqual_impl(const LieGroupBase&) const
Default equality check. By default, two LieGroupBase of same type are considered equal.
-
inline bool isDifferent_impl(const LieGroupBase &other) const
-
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.
-
ConfigVector_t neutral() const
Get neutral element as a vector.
-
std::string name() const
Get name of instance.
Protected Functions
-
inline LieGroupBase()
Default constructor.
Prevent the construction of derived class.
-
inline LieGroupBase(const LieGroupBase&)
Copy constructor
Prevent the copy of derived class.
-
inline LieGroupBase &operator=(const LieGroupBase&)
-
template<class ConfigIn_t, class Tangent_t, class ConfigOut_t>