Template Struct LieGroupBase

Inheritance Relationships

Derived Types

Struct Documentation

template<class _Derived>
struct LieGroupBase

Base class for Lie groups. Defines the minimum common API.

See also

TangentBase.

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

using Scalar = typename internal::traits<_Derived>::Scalar
using LieGroup = typename internal::traits<_Derived>::LieGroup
using DataType = typename internal::traits<_Derived>::DataType
using Tangent = typename internal::traits<_Derived>::Tangent
using Jacobian = typename internal::traits<_Derived>::Jacobian
using Vector = typename internal::traits<_Derived>::Vector
using OptJacobianRef = tl::optional<Eigen::Ref<Jacobian>>
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 constexpr int Dim = internal::traits<_Derived>::Dim
static constexpr int DoF = internal::traits<_Derived>::DoF
static constexpr int RepSize = internal::traits<_Derived>::RepSize
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.

DataType &coeffs()

Access the underlying data by const reference.

const DataType &coeffs() const

Access the underlying data by const reference.

Scalar *data()

Access the underlying data by pointer.

const Scalar *data() const

Access the underlying data by const pointer.

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

TangentBase.

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.

Jacobian adj() const

Get the Adjoint of the Lie group element this.

Note

See Eq. (29).

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

rplus

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

rminus

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’.

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

isApprox.

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

rplus.

template<typename _DerivedOther>
_Derived &operator+=(const TangentBase<_DerivedOther> &t)

Right in-place oplus operator.

See also

rplus.

template<typename _DerivedOther>
Tangent operator-(const LieGroupBase<_DerivedOther> &m) const

Right ominus operator.

See also

rminus.

template<typename _DerivedOther>
LieGroup operator*(const LieGroupBase<_DerivedOther> &m) const

Lie group composition operator.

See also

compose.

template<typename _DerivedOther>
_Derived &operator*=(const LieGroupBase<_DerivedOther> &m)

Lie group in-place composition operator.

See also

compose.

inline auto operator[](const unsigned int i) const -> decltype(coeffs()[i])

Access the ith coeffs.

inline auto operator[](const unsigned int i) -> decltype(coeffs()[i])

Access the ith coeffs.

inline constexpr unsigned int size() const

The size of the underlying vector.

inline _Derived &derived() & noexcept
inline const _Derived &derived() const & noexcept

Protected Static Functions

static LieGroup Identity()

Static helper to create a Lie group object set at Identity.

static LieGroup Random()

Static helper to create a random object of the Lie group.