template<class _Derived>
manif::TangentBase struct

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

Derived classes

template<typename _Derived>
struct BundleTangentBase
The base class of the Bundle tangent.
template<typename _Derived>
struct BundleTangentBase
The base class of the Bundle tangent.
template<typename _Derived>
struct BundleTangentBase
The base class of the Bundle tangent.
template<typename _Derived>
struct RnTangentBase
The base class of the R^n tangent.
template<typename _Derived>
struct RnTangentBase
The base class of the R^n tangent.
template<typename _Derived>
struct RnTangentBase
The base class of the R^n tangent.
template<typename _Derived>
struct SE2TangentBase
The base class of the SE2 tangent.
template<typename _Derived>
struct SE2TangentBase
The base class of the SE2 tangent.
template<typename _Derived>
struct SE2TangentBase
The base class of the SE2 tangent.
template<typename _Derived>
struct SE3TangentBase
The base class of the SE3 tangent.
template<typename _Derived>
struct SE3TangentBase
The base class of the SE3 tangent.
template<typename _Derived>
struct SE3TangentBase
The base class of the SE3 tangent.
template<typename _Derived>
struct SE_2_3TangentBase
The base class of the SE_2_3 tangent.
template<typename _Derived>
struct SE_2_3TangentBase
The base class of the SE_2_3 tangent.
template<typename _Derived>
struct SE_2_3TangentBase
The base class of the SE_2_3 tangent.
template<typename _Derived>
struct SGal3TangentBase
The base class of the SGal3 tangent.
template<typename _Derived>
struct SGal3TangentBase
The base class of the SGal3 tangent.
template<typename _Derived>
struct SGal3TangentBase
The base class of the SGal3 tangent.
template<typename _Derived>
struct SO2TangentBase
The base class of the SO2 tangent.
template<typename _Derived>
struct SO2TangentBase
The base class of the SO2 tangent.
template<typename _Derived>
struct SO2TangentBase
The base class of the SO2 tangent.
template<typename _Derived>
struct SO3TangentBase
The base class of the SO3 tangent.
template<typename _Derived>
struct SO3TangentBase
The base class of the SO3 tangent.
template<typename _Derived>
struct SO3TangentBase
The base class of the SO3 tangent.
template<typename _Derived>
struct BundleTangentBase
The base class of the Bundle tangent.
template<typename _Derived>
struct RnTangentBase
The base class of the R^n tangent.
template<typename _Derived>
struct SE2TangentBase
The base class of the SE2 tangent.
template<typename _Derived>
struct SE3TangentBase
The base class of the SE3 tangent.
template<typename _Derived>
struct SE_2_3TangentBase
The base class of the SE_2_3 tangent.
template<typename _Derived>
struct SGal3TangentBase
The base class of the SGal3 tangent.
template<typename _Derived>
struct SO2TangentBase
The base class of the SO2 tangent.
template<typename _Derived>
struct SO3TangentBase
The base class of the SO3 tangent.

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 static variables

static int Dim constexpr
static int RepSize constexpr
static int DoF constexpr

Public static functions

static auto Zero() -> Tangent
Static helper the create a Tangent object set to Zero.
static auto Random() -> Tangent
Static helper the create a random Tangent object.
static auto Generator(const int i) -> LieAlg
Static helper to get a Basis of the Lie group.
static auto InnerWeights() -> InnerWeightsMatrix
Static helper to get a Basis of the Lie group.

Public functions

auto operator=(const TangentBase& t) -> _Derived&
Assignment operator.
template<typename _DerivedOther>
auto operator=(const TangentBase<_DerivedOther>& t) -> _Derived&
Assignment operator.
template<typename _EigenDerived>
auto operator=(const Eigen::MatrixBase<_EigenDerived>& v) -> _Derived&
Assignment operator.
auto coeffs() -> DataType&
Access the underlying data by reference.
auto coeffs() const -> const DataType&
Access the underlying data by const reference.
auto data() -> Scalar*
Access the underlying data by pointer.
auto data() const -> const Scalar*
Access the underlying data by const pointer.
template<class _NewScalar>
auto cast() const -> TangentTemplate<_NewScalar>
Cast the Tangent object to a copy of a different scalar type.
auto setZero() -> _Derived&
Set the Tangent object this to Zero.
auto setRandom() -> _Derived&
Set the LieGroup object this to a random value.
auto generator(const int i) const -> LieAlg
Get the ith basis element of the Lie Algebra.
auto innerWeights() const -> InnerWeightsMatrix
Get the weight matrix of the Weighted Euclidean inner product, relative to the space basis.
template<typename _DerivedOther>
auto inner(const TangentBase<_DerivedOther>& t) const -> Scalar
Get inner product of this and another Tangent weighted by W.
auto weightedNorm() const -> Scalar
Get the Euclidean weighted norm.
auto squaredWeightedNorm() const -> Scalar
Get the squared Euclidean weighted norm.
auto hat() const -> LieAlg
Hat operator of the Tangent element.
auto exp(OptJacobianRef J_m_t = OptJacobianRef{}) const -> LieGroup
Get the Lie group element.
auto retract(OptJacobianRef J_m_t = OptJacobianRef{}) const -> MANIF_DEPRECATED LieGroup
This function is deprecated. Please considere using exp instead.
auto rplus(const LieGroup& m, OptJacobianRef J_mout_t = {}, OptJacobianRef J_mout_m = {}) const -> LieGroup
Right oplus operation of the Lie group.
auto lplus(const LieGroup& m, OptJacobianRef J_mout_t = {}, OptJacobianRef J_mout_m = {}) const -> LieGroup
Left oplus operation of the Lie group.
auto plus(const LieGroup& m, OptJacobianRef J_mout_t = {}, OptJacobianRef J_mout_m = {}) const -> LieGroup
An alias for the right oplus operation.
template<typename _DerivedOther>
auto plus(const TangentBase<_DerivedOther>& t, OptJacobianRef J_mout_ta = {}, OptJacobianRef J_mout_tb = {}) const -> Tangent
template<typename _DerivedOther>
auto minus(const TangentBase<_DerivedOther>& t, OptJacobianRef J_mout_ta = {}, OptJacobianRef J_mout_tb = {}) const -> Tangent
auto rjac() const -> Jacobian
Get the right Jacobian.
auto ljac() const -> Jacobian
Get the left Jacobian.
template<typename U = _Derived>
auto rjacinv() const -> std::enable_if<internal::has_rjacinv<U>::value, typename TangentBase<U>::Jacobian>::type
template<typename U = _Derived>
auto rjacinv() const -> std::enable_if<! internal::has_rjacinv<U>::value, typename TangentBase<U>::Jacobian>::type
template<typename U = _Derived>
auto ljacinv() const -> std::enable_if<internal::has_ljacinv<U>::value, typename TangentBase<U>::Jacobian>::type
template<typename U = _Derived>
auto ljacinv() const -> std::enable_if<! internal::has_ljacinv<U>::value, typename TangentBase<U>::Jacobian>::type
auto smallAdj() const -> Jacobian
template<typename _EigenDerived>
auto isApprox(const Eigen::MatrixBase<_EigenDerived>& v, const Scalar eps = Constants<Scalar>::eps) const -> bool
Evaluate whether this and v are 'close'.
template<typename _DerivedOther>
auto isApprox(const TangentBase<_DerivedOther>& t, const Scalar eps = Constants<Scalar>::eps) const -> bool
Evaluate whether this and t are 'close'.
template<typename T>
auto operator<<(T&& v) -> auto
auto operator-() const -> Tangent
Equivalent to v * -1.
auto operator+(const LieGroup& m) const -> LieGroup
Left oplus operator.
template<typename _DerivedOther>
auto operator+=(const TangentBase<_DerivedOther>& t) -> _Derived&
In-place plus operator, simple vector in-place plus operation.
template<typename _DerivedOther>
auto operator-=(const TangentBase<_DerivedOther>& t) -> _Derived&
In-place minus operator, simple vector in-place minus operation.
template<typename _EigenDerived>
auto operator+=(const Eigen::MatrixBase<_EigenDerived>& v) -> _Derived&
In-place plus operator, simple vector in-place plus operation.
template<typename _EigenDerived>
auto operator-=(const Eigen::MatrixBase<_EigenDerived>& v) -> _Derived&
In-place minus operator, simple vector in-place minus operation.
auto operator*=(const Scalar scalar) -> Tangent
Multiply the underlying vector with a scalar.
auto operator/=(const Scalar scalar) -> Tangent
Divide the underlying vector with a scalar.
auto operator[](const unsigned int i) -> auto
Access the ith coeffs.
auto operator[](const unsigned int i) -> auto
Access the ith coeffs.
auto size() const -> unsigned int constexpr
The size of the underlying vector.
template<class _NewScalar>
auto cast() const -> TangentBase<_Derived>::template TangentTemplate<_NewScalar>

Protected functions

auto derived() & -> _Derived& noexcept
auto derived() const & -> const _Derived& noexcept

Function documentation

template<class _Derived>
_Derived& manif::TangentBase<_Derived>::operator=(const TangentBase& t)

Assignment operator.

Parameters
in An element of the same Tangent group.
Returns A reference to this.

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

Assignment operator.

Parameters
in An element of the same Tangent group.
Returns A reference to this.

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

Assignment operator.

Returns A reference to this.

template<class _Derived>
_Derived& manif::TangentBase<_Derived>::setZero()

Set the Tangent object this to Zero.

Returns A reference to this.

template<class _Derived>
_Derived& manif::TangentBase<_Derived>::setRandom()

Set the LieGroup object this to a random value.

Returns A reference to this.

template<class _Derived>
LieAlg manif::TangentBase<_Derived>::generator(const int i) const

Get the ith basis element of the Lie Algebra.

Returns the ith basis element of the Lie Algebra.

template<class _Derived>
InnerWeightsMatrix manif::TangentBase<_Derived>::innerWeights() const

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

Returns the weight matrix.

template<class _Derived> template<typename _DerivedOther>
Scalar manif::TangentBase<_Derived>::inner(const TangentBase<_DerivedOther>& t) const

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

Returns The inner product of this and t.

template<class _Derived>
Scalar manif::TangentBase<_Derived>::weightedNorm() const

Get the Euclidean weighted norm.

Returns The Euclidean weighted norm.

template<class _Derived>
Scalar manif::TangentBase<_Derived>::squaredWeightedNorm() const

Get the squared Euclidean weighted norm.

Returns The squared Euclidean weighted norm.

template<class _Derived>
LieAlg manif::TangentBase<_Derived>::hat() const

Hat operator of the Tangent element.

Returns The isomorphic element in the Lie algebra.

template<class _Derived>
LieGroup manif::TangentBase<_Derived>::exp(OptJacobianRef J_m_t = OptJacobianRef{}) const

Get the Lie group element.

Returns Associated Lie group element.

template<class _Derived>
LieGroup manif::TangentBase<_Derived>::rplus(const LieGroup& m, OptJacobianRef J_mout_t = {}, OptJacobianRef J_mout_m = {}) const

Right oplus operation of the Lie group.

Returns An element of the Lie group.

template<class _Derived>
LieGroup manif::TangentBase<_Derived>::lplus(const LieGroup& m, OptJacobianRef J_mout_t = {}, OptJacobianRef J_mout_m = {}) const

Left oplus operation of the Lie group.

Returns An element of the Lie group.

template<class _Derived>
LieGroup manif::TangentBase<_Derived>::plus(const LieGroup& m, OptJacobianRef J_mout_t = {}, OptJacobianRef J_mout_m = {}) const

An alias for the right oplus operation.

template<class _Derived>
Jacobian manif::TangentBase<_Derived>::rjac() const

Get the right Jacobian.

template<class _Derived>
Jacobian manif::TangentBase<_Derived>::ljac() const

Get the left Jacobian.

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

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

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

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

template<class _Derived>
Jacobian manif::TangentBase<_Derived>::smallAdj() const

Returns [description]

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

Evaluate whether this and v are 'close'.

Parameters
in A vector.
eps in Threshold for equality copmarison.
Returns true if the Tangent element t is 'close' to this, false otherwise.

This evaluation is performed element-wise.

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

Evaluate whether this and t are 'close'.

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

This evaluation is performed element-wise.

template<class _Derived>
LieGroup manif::TangentBase<_Derived>::operator+(const LieGroup& m) const

Left oplus operator.