Template Struct LieGroupBase¶
Defined in File lie_group_base.h
Inheritance Relationships¶
Derived Types¶
public manif::BundleBase< Map< const manif::Bundle< _Scalar, T... >, 0 > >
(Template Struct BundleBase)public manif::BundleBase< Map< manif::Bundle< _Scalar, T... >, 0 > >
(Template Struct BundleBase)public manif::BundleBase< Bundle< _Scalar, _T ... > >
(Template Struct BundleBase)public manif::RnBase< Map< const manif::Rn< _Scalar, _N >, 0 > >
(Template Struct RnBase)public manif::RnBase< Map< manif::Rn< _Scalar, _N >, 0 > >
(Template Struct RnBase)public manif::RnBase< Rn< _Scalar, _N > >
(Template Struct RnBase)public manif::SE2Base< Map< const manif::SE2< _Scalar >, 0 > >
(Template Struct SE2Base)public manif::SE2Base< Map< manif::SE2< _Scalar >, 0 > >
(Template Struct SE2Base)public manif::SE2Base< SE2< _Scalar > >
(Template Struct SE2Base)public manif::SE3Base< Map< const manif::SE3< _Scalar >, 0 > >
(Template Struct SE3Base)public manif::SE3Base< Map< manif::SE3< _Scalar >, 0 > >
(Template Struct SE3Base)public manif::SE3Base< SE3< _Scalar > >
(Template Struct SE3Base)public manif::SE_2_3Base< Map< const manif::SE_2_3< _Scalar >, 0 > >
(Template Struct SE_2_3Base)public manif::SE_2_3Base< Map< manif::SE_2_3< _Scalar >, 0 > >
(Template Struct SE_2_3Base)public manif::SE_2_3Base< SE_2_3< _Scalar > >
(Template Struct SE_2_3Base)public manif::SGal3Base< Map< const manif::SGal3< _Scalar >, 0 > >
(Template Struct SGal3Base)public manif::SGal3Base< Map< manif::SGal3< _Scalar >, 0 > >
(Template Struct SGal3Base)public manif::SGal3Base< SGal3< _Scalar > >
(Template Struct SGal3Base)public manif::SO2Base< Map< const manif::SO2< _Scalar >, 0 > >
(Template Struct SO2Base)public manif::SO2Base< Map< manif::SO2< _Scalar >, 0 > >
(Template Struct SO2Base)public manif::SO2Base< SO2< _Scalar > >
(Template Struct SO2Base)public manif::SO3Base< Map< const manif::SO3< _Scalar >, 0 > >
(Template Struct SO3Base)public manif::SO3Base< Map< manif::SO3< _Scalar >, 0 > >
(Template Struct SO3Base)public manif::SO3Base< SO3< _Scalar > >
(Template Struct SO3Base)public manif::BundleBase< _Derived >
(Template Struct BundleBase)public manif::RnBase< _Derived >
(Template Struct RnBase)public manif::SE2Base< _Derived >
(Template Struct SE2Base)public manif::SE3Base< _Derived >
(Template Struct SE3Base)public manif::SE_2_3Base< _Derived >
(Template Struct SE_2_3Base)public manif::SGal3Base< _Derived >
(Template Struct SGal3Base)public manif::SO2Base< _Derived >
(Template Struct SO2Base)public manif::SO3Base< _Derived >
(Template Struct SO3Base)
Struct Documentation¶
-
template<class _Derived>
struct LieGroupBase¶ Base class for Lie groups. Defines the minimum common API.
See also
Subclassed by manif::BundleBase< Map< const manif::Bundle< _Scalar, T… >, 0 > >, manif::BundleBase< Map< manif::Bundle< _Scalar, T… >, 0 > >, manif::BundleBase< Bundle< _Scalar, _T … > >, manif::RnBase< Map< const manif::Rn< _Scalar, _N >, 0 > >, manif::RnBase< Map< manif::Rn< _Scalar, _N >, 0 > >, manif::RnBase< Rn< _Scalar, _N > >, manif::SE2Base< Map< const manif::SE2< _Scalar >, 0 > >, manif::SE2Base< Map< manif::SE2< _Scalar >, 0 > >, manif::SE2Base< SE2< _Scalar > >, manif::SE3Base< Map< const manif::SE3< _Scalar >, 0 > >, manif::SE3Base< Map< manif::SE3< _Scalar >, 0 > >, manif::SE3Base< SE3< _Scalar > >, manif::SE_2_3Base< Map< const manif::SE_2_3< _Scalar >, 0 > >, manif::SE_2_3Base< Map< manif::SE_2_3< _Scalar >, 0 > >, manif::SE_2_3Base< SE_2_3< _Scalar > >, manif::SGal3Base< Map< const manif::SGal3< _Scalar >, 0 > >, manif::SGal3Base< Map< manif::SGal3< _Scalar >, 0 > >, manif::SGal3Base< SGal3< _Scalar > >, manif::SO2Base< Map< const manif::SO2< _Scalar >, 0 > >, manif::SO2Base< Map< manif::SO2< _Scalar >, 0 > >, manif::SO2Base< SO2< _Scalar > >, manif::SO3Base< Map< const manif::SO3< _Scalar >, 0 > >, manif::SO3Base< Map< manif::SO3< _Scalar >, 0 > >, manif::SO3Base< SO3< _Scalar > >, manif::BundleBase< _Derived >, manif::RnBase< _Derived >, manif::SE2Base< _Derived >, manif::SE3Base< _Derived >, manif::SE_2_3Base< _Derived >, manif::SGal3Base< _Derived >, manif::SO2Base< _Derived >, manif::SO3Base< _Derived >
Public Types
-
template<typename _Scalar>
using LieGroupTemplate = typename internal::traitscast<LieGroup, _Scalar>::cast¶
Public Functions
-
template<typename _Derived>
_Derived &operator=(const LieGroupBase &m)¶
-
template<typename _DerivedOther>
_Derived &operator=(const LieGroupBase<_DerivedOther> &m)¶
-
template<class _NewScalar>
LieGroupBase<_Derived>::template LieGroupTemplate<_NewScalar> cast() const¶
Public Static Attributes
-
static const OptJacobianRef _ = {}¶
Helper for skipping an optional parameter.
Protected Functions
- template<typename _DerivedOther> MANIF_DEFAULT_CONSTRUCTOR(LieGroupBase) public _Derived & operator= (const LieGroupBase< _DerivedOther > &m)
Assignment operator.
Assignment operator.
Note
This is a special case of the templated operator=. Its purpose is to prevent a default operator= from hiding the templated operator=.
- Parameters:
An – [in] element of the Lie group.
An – [in] element of the Lie group.
- Returns:
A reference to this.
- Returns:
A reference to this.
-
template<typename _EigenDerived>
_Derived &operator=(const Eigen::MatrixBase<_EigenDerived> &data)¶ Assignment operator given Eigen object.
- Parameters:
An – [in] element of the Lie group.
- Returns:
A reference to this.
-
template<class _NewScalar>
LieGroupTemplate<_NewScalar> cast() const¶ Cast the LieGroup object to a copy of a different scalar type.
-
_Derived &setIdentity()¶
Set the LieGroup object this to Identity.
See also
Eq. (2).
- Returns:
A reference to this.
-
_Derived &setRandom()¶
Set the LieGroup object this to a random value.
Note
Randomization happens in the tangent space so that M = Log(tau.random)
- Returns:
A reference to this.
-
LieGroup inverse(OptJacobianRef J_m_t = {}) const¶
Get the inverse of the LieGroup object this.
See also
Note
See Eq. (3).
- Parameters:
-optional- – [out] J_m_t Jacobian of the inverse wrt this.
- Returns:
The Inverse of this.
-
Tangent log(OptJacobianRef J_t_m = {}) const¶
Get the corresponding Lie algebra element in vector form.
See also
Eq. (24).
Note
This is the log() map in vector form.
- Parameters:
-optional- – [out] J_t_m Jacobian of the tangent wrt this.
- Returns:
The tangent element in vector form.
- MANIF_DEPRECATED Tangent lift (OptJacobianRef J_t_m={}) const
This function is deprecated. Please considere using log instead.
-
template<typename _DerivedOther>
LieGroup compose(const LieGroupBase<_DerivedOther> &m, OptJacobianRef J_mc_ma = {}, OptJacobianRef J_mc_mb = {}) const¶ Composition of this and another element of the same Lie group.
Note
See Eqs. (1,2,3,4).
- Parameters:
m – [in] Another element of the same Lie group.
-optional- – [out] J_mc_ma Jacobian of the composition wrt this.
-optional- – [out] J_mc_mb Jacobian of the composition wrt m.
- Returns:
The composition of ‘this . m’.
-
template<typename _EigenDerived>
Vector act(const Eigen::MatrixBase<_EigenDerived> &v, tl::optional<Eigen::Ref<Eigen::Matrix<Scalar, Dim, DoF>>> J_vout_m = {}, tl::optional<Eigen::Ref<Eigen::Matrix<Scalar, Dim, Dim>>> J_vout_v = {}) const¶ Get the action of the Lie group object on a point.
- Parameters:
v – [in] A point.
-optional- – [out] J_vout_m Jacobian of the new object wrt this.
-optional- – [out] J_vout_v Jacobian of the new object wrt input object.
- Returns:
A point acted upon by the object.
-
template<typename _DerivedOther>
LieGroup rplus(const TangentBase<_DerivedOther> &t, OptJacobianRef J_mout_m = {}, OptJacobianRef J_mout_t = {}) const¶ Right oplus operation of the Lie group.
Note
See Eq. (25).
- Parameters:
t – [in] An element of the tangent of the Lie group.
-optional- – [out] J_mout_m Jacobian of the oplus operation wrt this.
-optional- – [out] J_mout_t Jacobian of the oplus operation wrt the tangent element.
- Returns:
An element of the Lie group.
-
template<typename _DerivedOther>
LieGroup lplus(const TangentBase<_DerivedOther> &t, OptJacobianRef J_mout_m = {}, OptJacobianRef J_mout_t = {}) const¶ Left oplus operation of the Lie group.
Note
See Eq. (27).
- Parameters:
t – [in] An element of the tangent of the Lie group.
-optional- – [out] J_mout_m Jacobian of the oplus operation wrt this.
-optional- – [out] J_mout_t Jacobian of the oplus operation wrt the tangent element.
- Returns:
An element of the Lie group.
-
template<typename _DerivedOther>
LieGroup plus(const TangentBase<_DerivedOther> &t, OptJacobianRef J_mout_m = {}, OptJacobianRef J_mout_t = {}) const¶ An alias for the right oplus operation.
See also
-
template<typename _DerivedOther>
Tangent rminus(const LieGroupBase<_DerivedOther> &m, OptJacobianRef J_t_ma = {}, OptJacobianRef J_t_mb = {}) const¶ Right ominus operation of the Lie group.
Note
See Eq. (26).
- Parameters:
m – [in] Another element of the same Lie group.
-optional- – [out] J_t_ma Jacobian of the ominus operation wrt this.
-optional- – [out] J_t_mb Jacobian of the ominus operation wrt the other element.
- Returns:
An element of the tangent space of the Lie group.
-
template<typename _DerivedOther>
Tangent lminus(const LieGroupBase<_DerivedOther> &m, OptJacobianRef J_t_ma = {}, OptJacobianRef J_t_mb = {}) const¶ Left ominus operation of the Lie group.
Note
See Eq. (28).
- Parameters:
m – [in] Another element of the same Lie group.
-optional- – [out] J_t_ma Jacobian of the ominus operation wrt this.
-optional- – [out] J_t_mb Jacobian of the ominus operation wrt the other element.
- Returns:
An element of the tangent space of the Lie group.
-
template<typename _DerivedOther>
Tangent minus(const LieGroupBase<_DerivedOther> &m, OptJacobianRef J_t_ma = {}, OptJacobianRef J_t_mb = {}) const¶ An alias for the right ominus operation.
See also
-
template<typename _DerivedOther>
LieGroup between(const LieGroupBase<_DerivedOther> &m, OptJacobianRef J_mc_ma = {}, OptJacobianRef J_mc_mb = {}) const¶ - Parameters:
m – [in] [description]
-optional- – [out] J_mc_ma [description]
-optional- – [out] J_mc_mb [description]
- Returns:
[description]
-
template<typename _DerivedOther>
bool isApprox(const LieGroupBase<_DerivedOther> &m, const Scalar eps = Constants<Scalar>::eps) const¶ Evaluate whether this and m are ‘close’.
See also
- Parameters:
m – [in] An element of the same Lie Group.
eps – [in] Threshold for equality comparison.
- Returns:
true if the Lie group element m is ‘close’ to this, false otherwise.
-
template<typename _DerivedOther>
bool operator==(const LieGroupBase<_DerivedOther> &m) const¶ Equality operator.
See also
- Parameters:
An – [in] element of the same Lie group.
- Returns:
true if the Lie group element m is ‘close’ to this, false otherwise.
-
template<typename _DerivedOther>
inline bool operator!=(const LieGroupBase<_DerivedOther> &m) const¶ Inequality operator.
See also
operator==.
- Parameters:
An – [in] element of the same Lie group.
- Returns:
false if the Lie group element m is ‘close’ to this, true otherwise.
-
template<typename _DerivedOther>
LieGroup operator+(const TangentBase<_DerivedOther> &t) const¶ Right oplus operator.
See also
-
template<typename _DerivedOther>
_Derived &operator+=(const TangentBase<_DerivedOther> &t)¶ Right in-place oplus operator.
See also
-
template<typename _DerivedOther>
Tangent operator-(const LieGroupBase<_DerivedOther> &m) const¶ Right ominus operator.
See also
-
template<typename _DerivedOther>
LieGroup operator*(const LieGroupBase<_DerivedOther> &m) const¶ Lie group composition operator.
See also
-
template<typename _DerivedOther>
_Derived &operator*=(const LieGroupBase<_DerivedOther> &m)¶ Lie group in-place composition operator.
See also
-
inline constexpr unsigned int size() const¶
The size of the underlying vector.
-
template<typename _Scalar>