Template Struct TangentBase

Inheritance Relationships

Derived Types

Struct Documentation

template<class _Derived>
struct TangentBase

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

See also

LieGroupBase.

Subclassed by manif::BundleTangentBase< Map< const manif::BundleTangent< _Scalar, T… >, 0 > >, manif::BundleTangentBase< Map< manif::BundleTangent< _Scalar, T… >, 0 > >, manif::BundleTangentBase< BundleTangent< _Scalar, _T… > >, manif::RnTangentBase< Map< const manif::RnTangent< _Scalar, _N >, 0 > >, manif::RnTangentBase< Map< manif::RnTangent< _Scalar, _N >, 0 > >, manif::RnTangentBase< RnTangent< _Scalar, _N > >, manif::SE2TangentBase< Map< const manif::SE2Tangent< _Scalar >, 0 > >, manif::SE2TangentBase< Map< manif::SE2Tangent< _Scalar >, 0 > >, manif::SE2TangentBase< SE2Tangent< _Scalar > >, manif::SE3TangentBase< Map< const manif::SE3Tangent< _Scalar >, 0 > >, manif::SE3TangentBase< Map< manif::SE3Tangent< _Scalar >, 0 > >, manif::SE3TangentBase< SE3Tangent< _Scalar > >, manif::SE_2_3TangentBase< Map< const manif::SE_2_3Tangent< _Scalar >, 0 > >, manif::SE_2_3TangentBase< Map< manif::SE_2_3Tangent< _Scalar >, 0 > >, manif::SE_2_3TangentBase< SE_2_3Tangent< _Scalar > >, manif::SGal3TangentBase< Map< const manif::SGal3Tangent< _Scalar >, 0 > >, manif::SGal3TangentBase< Map< manif::SGal3Tangent< _Scalar >, 0 > >, manif::SGal3TangentBase< SGal3Tangent< _Scalar > >, manif::SO2TangentBase< Map< const manif::SO2Tangent< _Scalar >, 0 > >, manif::SO2TangentBase< Map< manif::SO2Tangent< _Scalar >, 0 > >, manif::SO2TangentBase< SO2Tangent< _Scalar > >, manif::SO3TangentBase< Map< const manif::SO3Tangent< _Scalar >, 0 > >, manif::SO3TangentBase< Map< manif::SO3Tangent< _Scalar >, 0 > >, manif::SO3TangentBase< SO3Tangent< _Scalar > >, manif::BundleTangentBase< _Derived >, manif::RnTangentBase< _Derived >, manif::SE2TangentBase< _Derived >, manif::SE3TangentBase< _Derived >, manif::SE_2_3TangentBase< _Derived >, manif::SGal3TangentBase< _Derived >, manif::SO2TangentBase< _Derived >, manif::SO3TangentBase< _Derived >

Public Types

using Scalar = typename internal::traits<_Derived>::Scalar
using LieGroup = typename internal::traits<_Derived>::LieGroup
using Tangent = typename internal::traits<_Derived>::Tangent
using DataType = typename internal::traits<_Derived>::DataType
using Jacobian = typename internal::traits<_Derived>::Jacobian
using LieAlg = typename internal::traits<_Derived>::LieAlg
using InnerWeightsMatrix = Jacobian
using OptJacobianRef = tl::optional<Eigen::Ref<Jacobian>>
template<typename _Scalar>
using TangentTemplate = typename internal::traitscast<Tangent, _Scalar>::cast

Public Functions

template<typename _Derived>
_Derived &operator=(const TangentBase &t)
template<typename _DerivedOther>
_Derived &operator=(const TangentBase<_DerivedOther> &t)
template<class _NewScalar>
TangentBase<_Derived>::template TangentTemplate<_NewScalar> cast() const

Public Static Attributes

static constexpr int Dim = internal::traits<_Derived>::Dim
static constexpr int RepSize = internal::traits<_Derived>::RepSize
static constexpr int DoF = internal::traits<_Derived>::DoF

Protected Functions

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

Assignment operator.

Assignment operator.

Parameters:
  • t[in] An element of the same Tangent group.

  • t[in] An element of the same Tangent group.

Returns:

A reference to this.

Returns:

A reference to this.

template<typename _EigenDerived>
_Derived &operator=(const Eigen::MatrixBase<_EigenDerived> &v)

Assignment operator.

See also

DataType.

Parameters:

t[in] A DataType object.

Returns:

A reference to this.

DataType &coeffs()

Access the underlying data by 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>
TangentTemplate<_NewScalar> cast() const

Cast the Tangent object to a copy of a different scalar type.

_Derived &setZero()

Set the Tangent object this to Zero.

Returns:

A reference to this.

_Derived &setRandom()

Set the LieGroup object this to a random value.

Returns:

A reference to this.

template<typename _EigenDerived>
_Derived &setVee(const Eigen::MatrixBase<_EigenDerived> &a)

Set the Tangent object this from an object in the Lie algebra.

Parameters:

a[in] An object in the Lie algebra.

Returns:

A reference to this.

LieAlg generator(const int i) const

Get the ith basis element of the Lie Algebra.

Returns:

the ith basis element of the Lie Algebra.

InnerWeightsMatrix innerWeights() const

Get the weight matrix of the Weighted Euclidean inner product, relative to the space basis.

See also

generator

Returns:

the weight matrix.

template<typename _DerivedOther>
Scalar inner(const TangentBase<_DerivedOther> &t) const

Get inner product of this and another Tangent weighted by W.

See also

innerWeights()

Note

ip = v0’ . W . v1

Returns:

The inner product of this and t.

Scalar weightedNorm() const

Get the Euclidean weighted norm.

See also

innerWeights()

Returns:

The Euclidean weighted norm.

Scalar squaredWeightedNorm() const

Get the squared Euclidean weighted norm.

See also

innerWeights()

See also

WeightedNorm()

Returns:

The squared Euclidean weighted norm.

LieAlg hat() const

Hat operator of the Tangent element.

Note

See Eq. (10).

Returns:

The isomorphic element in the Lie algebra.

LieGroup exp(OptJacobianRef J_m_t = OptJacobianRef{}) const

Get the Lie group element.

Note

This is the exp() map with the argument in vector form.

Note

See Eq. (23).

Parameters:

-optional-[out] J_m_t Jacobian of the Lie groupe element wrt this.

Returns:

Associated Lie group element.

MANIF_DEPRECATED LieGroup retract (OptJacobianRef J_m_t=OptJacobianRef{}) const

This function is deprecated. Please considere using exp instead.

LieGroup rplus(const LieGroup &m, OptJacobianRef J_mout_t = {}, OptJacobianRef J_mout_m = {}) 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_t Jacobian of the oplus operation wrt this.

  • -optional-[out] J_mout_m Jacobian of the oplus operation wrt group element.

Returns:

An element of the Lie group.

LieGroup lplus(const LieGroup &m, OptJacobianRef J_mout_t = {}, OptJacobianRef J_mout_m = {}) 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_t Jacobian of the oplus operation wrt this.

  • -optional-[out] J_mout_m Jacobian of the oplus operation wrt the group element.

Returns:

An element of the Lie group.

LieGroup plus(const LieGroup &m, OptJacobianRef J_mout_t = {}, OptJacobianRef J_mout_m = {}) const

An alias for the right oplus operation.

See also

rplus

template<typename _DerivedOther>
Tangent plus(const TangentBase<_DerivedOther> &t, OptJacobianRef J_mout_ta = {}, OptJacobianRef J_mout_tb = {}) const
template<typename _DerivedOther>
Tangent minus(const TangentBase<_DerivedOther> &t, OptJacobianRef J_mout_ta = {}, OptJacobianRef J_mout_tb = {}) const
Jacobian rjac() const

Get the right Jacobian.

Note

this is the right Jacobian of exp, what is commonly known as “the right Jacobian”.

Note

See Eq. (41) for the right Jacobian of general functions.

Note

See Eqs. (126,143,163,179,191) for implementations of the right Jacobian of exp.

Jacobian ljac() const

Get the left Jacobian.

Note

this is the left Jacobian of exp, what is commonly known as “the left Jacobian”.

Note

See Eq. (44) for the left Jacobian of general functions.

Note

See Eqs. (126,145,164,179,191) for implementations of the left Jacobian of exp.

template<typename U = _Derived>
std::enable_if<internal::has_rjacinv<U>::value, typenameTangentBase<U>::Jacobian>::type rjacinv() const

Note

Calls Derived’s ‘overload’

template<typename U = _Derived>
std::enable_if<!internal::has_rjacinv<U>::value, typenameTangentBase<U>::Jacobian>::type rjacinv() const

Note

Calls Base default impl

template<typename U = _Derived>
std::enable_if<internal::has_ljacinv<U>::value, typenameTangentBase<U>::Jacobian>::type ljacinv() const

Note

Calls Derived’s ‘overload’

template<typename U = _Derived>
std::enable_if<!internal::has_ljacinv<U>::value, typenameTangentBase<U>::Jacobian>::type ljacinv() const

Note

Calls Base default impl

Jacobian smallAdj() const
Returns:

[description]

template<typename _DerivedOther>
Tangent bracket(const TangentBase<_DerivedOther> &b) const

Compute the Lie bracket [this,b] in vector form.

Template Parameters:

_DerivedOther

Parameters:

b – Another tangent object of the same group.

Returns:

The Lie bracket [this,b] in vector form.

template<typename _EigenDerived>
bool isApprox(const Eigen::MatrixBase<_EigenDerived> &v, const Scalar eps = Constants<Scalar>::eps) const

Evaluate whether this and v are ‘close’.

This evaluation is performed element-wise.

Parameters:
  • v[in] A vector.

  • eps[in] Threshold for equality copmarison.

Returns:

true if the Tangent element t is ‘close’ to this, false otherwise.

template<typename _DerivedOther>
bool isApprox(const TangentBase<_DerivedOther> &t, const Scalar eps = Constants<Scalar>::eps) const

Evaluate whether this and t are ‘close’.

This evaluation is performed element-wise.

Parameters:
  • t[in] An element of the same Tangent group.

  • eps[in] Threshold for equality copmarison.

Returns:

true if the Tangent element t is ‘close’ to this, false otherwise.

template<typename T>
auto operator<<(T &&v) -> decltype(std::declval<DataType>().(std::forward<T>(v)))
Tangent operator-() const

Equivalent to v * -1.

LieGroup operator+(const LieGroup &m) const

Left oplus operator.

See also

lplus.

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

In-place plus operator, simple vector in-place plus operation.

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

In-place minus operator, simple vector in-place minus operation.

template<typename _EigenDerived>
_Derived &operator+=(const Eigen::MatrixBase<_EigenDerived> &v)

In-place plus operator, simple vector in-place plus operation.

template<typename _EigenDerived>
_Derived &operator-=(const Eigen::MatrixBase<_EigenDerived> &v)

In-place minus operator, simple vector in-place minus operation.

Tangent operator*=(const Scalar scalar)

Multiply the underlying vector with a scalar.

Tangent operator/=(const Scalar scalar)

Divide the underlying vector with a scalar.

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 Tangent Zero()

Static helper the create a Tangent object set to Zero.

static Tangent Random()

Static helper the create a random Tangent object.

static LieAlg Generator(const int i)

Static helper to get a Basis of the Lie group.

static InnerWeightsMatrix InnerWeights()

Static helper to get a Basis of the Lie group.

template<typename _DerivedOther>
static Tangent Bracket(const TangentBase<_Derived> &a, const TangentBase<_DerivedOther> &b)

Compute the Lie bracket [a,b] in vector form.

Template Parameters:

_DerivedOther

Parameters:
  • a – A Tangent object.

  • b – A second Tangent object.

Returns:

The Lie bracket [a,b] in vector form.

template<typename _EigenDerived>
static Tangent Vee(const Eigen::MatrixBase<_EigenDerived> &alg)

Instantiate a Tangent from a Lie algebra object.

See also

hat

Template Parameters:

_EigenDerived

Parameters:

alg – A tangent object expressed in the Lie algebra.

Returns:

a Tangent object.