manif namespace

Namespaces

namespace detail
namespace internal

Classes

template<typename Scalar, typename G>
struct Constants<autodiff::detail::Dual<Scalar, G>>
Specialize Constants traits for autodiff::Dual type.
template<size_type N, typename T>
struct Constants<autodiff::detail::Real<N, T>>
Specialize Constants traits for autodiff::Real type.
template<typename _Scalar, int N>
struct Constants<ceres::Jet<_Scalar, N>>
Specialize Constants traits for the ceres::Jet type.
template<typename _LieGroup>
class CeresConstraintFunctor
template<typename _LieGroup>
class CeresLocalParameterizationFunctor
A wrapper for Ceres autodiff local parameterization.
template<typename _LieGroup>
class CeresManifoldFunctor
A wrapper for Ceres autodiff local parameterization.
template<typename _LieGroup>
class CeresObjectiveFunctor
template<typename _Scalar>
struct Constants
Traits to define some constant scalar.
template<typename _Scalar, template<typename> class ... _T>
struct Bundle
Represents a Bundle (or Composite) element as described in Section IV of the reference paper (see also Example 7).
template<typename _Scalar, template<typename> class ... _T>
struct BundleTangent
Represents a BundleTangent element.
template<typename _Derived>
struct BundleBase
The base class of the Bundle group.
template<typename _Derived>
struct BundleTangentBase
The base class of the Bundle tangent.
template<class _Derived>
struct LieGroupBase
Base class for Lie groups. Defines the minimum common API.
struct runtime_error
struct invalid_argument
template<typename _Scalar, unsigned int _N>
struct Rn
Represents an element of Rn.
template<typename _Scalar, unsigned int _N>
struct RnTangent
Represents an element of tangent space of Rn.
template<typename _Derived>
struct RnBase
The base class of the Rn group.
template<typename _Derived>
struct RnTangentBase
The base class of the R^n tangent.
template<typename _Scalar>
struct SE2
Represents an element of SE2.
template<typename _Scalar>
struct SE2Tangent
Represent an element of the tangent space of SE2.
template<typename _Derived>
struct SE2Base
The base class of the SE2 group.
template<typename _Derived>
struct SE2TangentBase
The base class of the SE2 tangent.
template<typename _Scalar>
struct SE3
Represent an element of SE3.
template<typename _Scalar>
struct SE3Tangent
Represents an element of tangent space of SE3.
template<typename _Derived>
struct SE3Base
The base class of the SE3 group.
template<typename _Derived>
struct SE3TangentBase
The base class of the SE3 tangent.
template<typename _Scalar>
struct SE_2_3
Represent an element of SE_2_3.
template<typename _Scalar>
struct SE_2_3Tangent
Represents an element of tangent space of SE_2_3.
template<typename _Derived>
struct SE_2_3Base
The base class of the SE_2_3 group.
template<typename _Derived>
struct SE_2_3TangentBase
The base class of the SE_2_3 tangent.
template<typename _Scalar>
struct SGal3
Represent an element of SGal3.
template<typename _Scalar>
struct SGal3Tangent
Represents an element of tangent space of SGal3.
template<typename _Derived>
struct SGal3Base
The base class of the SGal3 group.
template<typename _Derived>
struct SGal3TangentBase
The base class of the SGal3 tangent.
template<typename _Scalar>
struct SO2
Represents an element of SO2.
template<typename _Scalar>
struct SO2Tangent
Represents an element of tangent space of SO2.
template<typename _Derived>
struct SO2Base
The base class of the SO2 group.
template<typename _Derived>
struct SO2TangentBase
The base class of the SO2 tangent.
template<typename _Scalar>
struct SO3
Represents an element of SO3.
template<typename _Scalar>
struct SO3Tangent
Represents an element of tangent space of SO3.
template<typename _Derived>
struct SO3Base
The base class of the SO3 group.
template<typename _Derived>
struct SO3TangentBase
The base class of the SO3 tangent.
template<class _Derived>
struct TangentBase
Base class for Lie groups' tangents. Defines the minimum common API.

Enums

enum class INTERP_METHOD { SLERP, CUBIC, CNSMOOTH }

Typedefs

using CeresConstraintSO2 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS
using CeresManifoldSO2 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS
using CeresObjectiveSO2 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS
using CeresConstraintSO3 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS
using CeresManifoldSO3 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS
using CeresObjectiveSO3 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS
using CeresConstraintSE2 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS
using CeresManifoldSE2 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS
using CeresObjectiveSE2 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS
using CeresConstraintSE3 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS
using CeresManifoldSE3 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS
using CeresObjectiveSE3 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS
template<typename Scalar, int S>
using SquareMatrix = Eigen::Matrix<Scalar, S, S>
template<typename _Scalar>
using R1 = Rn<_Scalar, 1>
template<typename _Scalar>
using R2 = Rn<_Scalar, 2>
template<typename _Scalar>
using R3 = Rn<_Scalar, 3>
template<typename _Scalar>
using R4 = Rn<_Scalar, 4>
template<typename _Scalar>
using R5 = Rn<_Scalar, 5>
template<typename _Scalar>
using R6 = Rn<_Scalar, 6>
template<typename _Scalar>
using R7 = Rn<_Scalar, 7>
template<typename _Scalar>
using R8 = Rn<_Scalar, 8>
template<typename _Scalar>
using R9 = Rn<_Scalar, 9>
template<typename _Scalar>
using R1Tangent = RnTangent<_Scalar, 1>
template<typename _Scalar>
using R2Tangent = RnTangent<_Scalar, 2>
template<typename _Scalar>
using R3Tangent = RnTangent<_Scalar, 3>
template<typename _Scalar>
using R4Tangent = RnTangent<_Scalar, 4>
template<typename _Scalar>
using R5Tangent = RnTangent<_Scalar, 5>
template<typename _Scalar>
using R6Tangent = RnTangent<_Scalar, 6>
template<typename _Scalar>
using R7Tangent = RnTangent<_Scalar, 7>
template<typename _Scalar>
using R8Tangent = RnTangent<_Scalar, 8>
template<typename _Scalar>
using R9Tangent = RnTangent<_Scalar, 9>

Functions

template<template<typename LieGroup, typename...Args> class Container, typename LieGroup, typename... Args>
auto average_biinvariant(const Container<LieGroup, Args...>& points, typename LieGroup::Scalar eps = Constants<typename LieGroup::Scalar>::eps, int max_iterations = 20) -> LieGroup
Compute an average point on Lie groups given a list of 'close' points.
template<template<typename LieGroup, typename...Args> class Container, typename LieGroup, typename... Args>
auto average(const Container<LieGroup, Args...>& points, typename LieGroup::Scalar eps = Constants<typename LieGroup::Scalar>::eps, int max_iterations = 20) -> LieGroup
template<template<typename LieGroup, typename...Args> class Container, typename LieGroup, typename... Args>
auto average_frechet_left(const Container<LieGroup, Args...>& points, typename LieGroup::Scalar eps = Constants<typename LieGroup::Scalar>::eps, int max_iterations = 20) -> LieGroup
template<template<typename LieGroup, typename...Args> class Container, typename LieGroup, typename... Args>
auto average_frechet_right(const Container<LieGroup, Args...>& points, typename LieGroup::Scalar eps = Constants<typename LieGroup::Scalar>::eps, int max_iterations = 20) -> LieGroup
template<typename LieGroup>
auto computeBezierCurve(const std::vector<LieGroup>& control_points, const unsigned int degree, const unsigned int k_interp) -> std::vector<typename LieGroup::LieGroup>
Curve fitting using the DeCasteljau algorithm on Lie groups.
template<typename LieGroup>
auto decasteljau(const std::vector<LieGroup>& trajectory, const unsigned int degree, const unsigned int k_interp, const bool closed_curve = false) -> std::vector<typename LieGroup::LieGroup>
Curve fitting using the DeCasteljau algorithm on Lie groups.
template<typename T>
auto binomial_coefficient(const T n, const T k) -> T constexpr
Constexpr function to compute binomial coefficient.
template<typename T>
auto ipow(const T base, const int exp, T carry = 1) -> T constexpr
Constexpr function to compute power.
template<typename T>
auto polynomialBernstein(const T n, const T i, const T t) -> T constexpr
Constexpr function to compute the Bernstein polynomial.
template<typename T>
auto smoothing_phi(const T t, const std::size_t degree) -> T
template<typename _Derived, typename _Scalar>
static auto interpolate_slerp(const LieGroupBase<_Derived>& ma, const LieGroupBase<_Derived>& mb, const _Scalar t) -> LieGroupBase<_Derived>::LieGroup
Slerp interpolation. @detail Interpolate a point mc between ma and mb at t in [0,1]. mc=ma if t=0 mc=mb if t=1.
template<typename _Derived, typename _Scalar>
static auto interpolate_cubic(const LieGroupBase<_Derived>& ma, const LieGroupBase<_Derived>& mb, const _Scalar t, const typename LieGroupBase<_Derived>::Tangent& ta = LieGroupBase<_Derived>::Tangent::Zero(), const typename LieGroupBase<_Derived>::Tangent& tb = LieGroupBase<_Derived>::Tangent::Zero()) -> LieGroupBase<_Derived>::LieGroup
Cubic interpolation. @detail Interpolate a point mc between ma and mb at t in [0,1]. mc=ma if t=0 mc=mb if t=1.
template<typename _Derived, typename _Scalar>
static auto interpolate_smooth(const LieGroupBase<_Derived>& ma, const LieGroupBase<_Derived>& mb, const _Scalar t, const unsigned int m, const typename LieGroupBase<_Derived>::Tangent& ta = LieGroupBase<_Derived>::Tangent::Zero(), const typename LieGroupBase<_Derived>::Tangent& tb = LieGroupBase<_Derived>::Tangent::Zero()) -> LieGroupBase<_Derived>::LieGroup
Smooth interpolation. @detail Interpolate a point mc between ma and mb at t in [0,1]. mc=ma if t=0 mc=mb if t=1.
template<typename _Derived, typename _Scalar>
auto interpolate(const LieGroupBase<_Derived>& ma, const LieGroupBase<_Derived>& mb, const _Scalar t, const INTERP_METHOD method = INTERP_METHOD::SLERP, const typename LieGroupBase<_Derived>::Tangent& ta = LieGroupBase<_Derived>::Tangent::Zero(), const typename LieGroupBase<_Derived>::Tangent& tb = LieGroupBase<_Derived>::Tangent::Zero()) -> LieGroupBase<_Derived>::LieGroup
A helper function for interpolation.
template<typename Ad, typename Derived>
auto autodiffLocalParameterizationJacobian(const manif::LieGroupBase<Derived>& _state) -> Eigen::Matrix<typename Derived::Scalar, Derived::RepSize, Derived::DoF>
template<typename _LieGroup>
auto make_local_parameterization_autodiff() -> std::shared_ptr<ceres::AutoDiffLocalParameterization<CeresLocalParameterizationFunctor<_LieGroup>, _LieGroup::RepSize, _LieGroup::DoF>>
Helper function to create a Ceres autodiff local parameterization wrapper.
template<typename _LieGroup, typename... Args>
auto make_objective_autodiff(Args && ... args) -> std::shared_ptr<ceres::AutoDiffCostFunction<CeresObjectiveFunctor<_LieGroup>, 1, _LieGroup::RepSize>>
Helper function to create a Ceres autodiff objective wrapper.
template<typename _LieGroup, typename... Args>
auto make_constraint_autodiff(Args && ... args) -> std::shared_ptr<ceres::AutoDiffCostFunction<CeresConstraintFunctor<_LieGroup>, _LieGroup::DoF, _LieGroup::RepSize, _LieGroup::RepSize>>
Helper function to create a Ceres autodiff constraint wrapper.
template<typename _Derived>
auto coeffs(const LieGroupBase<_Derived>& lie_group) -> const _Derived::DataType&
template<typename _Derived>
auto coeffs(const TangentBase<_Derived>& tangent) -> const _Derived::DataType&
template<typename _Derived>
auto data(const LieGroupBase<_Derived>& lie_group) -> const _Derived::Scalar*
template<typename _Derived>
auto data(LieGroupBase<_Derived>& lie_group) -> _Derived::Scalar*
template<typename _Derived>
auto data(const TangentBase<_Derived>& tangent) -> const _Derived::Scalar*
template<typename _Derived>
auto data(TangentBase<_Derived>& tangent) -> _Derived::Scalar*
template<typename _Derived>
void identity(LieGroupBase<_Derived>& lie_group)
template<typename _LieGroup>
auto Identity() -> _LieGroup
template<typename _Derived>
void zero(TangentBase<_Derived>& tangent)
template<typename _Tangent>
auto Zero() -> _Tangent
template<typename _Derived>
void random(LieGroupBase<_Derived>& lie_group)
template<typename _Type>
auto Random() -> _Type
template<typename _Derived>
void random(TangentBase<_Derived>& tangent)
template<typename _Derived>
auto inverse(const LieGroupBase<_Derived>& lie_group, typename _Derived::OpJacobianRef J_minv_m = {}) -> _Derived::LieGroup
template<typename _DerivedMan, typename _DerivedTan>
auto rplus(const LieGroupBase<_DerivedMan>& lie_group, const TangentBase<_DerivedTan>& tangent, typename _DerivedMan::OpJacobianRef J_mout_m = {}, typename _DerivedMan::OpJacobianRef J_mout_t = {}) -> _DerivedMan::LieGroup
template<typename _DerivedMan, typename _DerivedTan>
auto lplus(const LieGroupBase<_DerivedMan>& lie_group, const TangentBase<_DerivedTan>& tangent, typename _DerivedMan::OpJacobianRef J_mout_m = {}, typename _DerivedMan::OpJacobianRef J_mout_t = {}) -> _DerivedMan::LieGroup
template<typename _DerivedMan, typename _DerivedTan>
auto plus(const LieGroupBase<_DerivedMan>& lie_group, const TangentBase<_DerivedTan>& tangent, typename _DerivedMan::OpJacobianRef J_mout_m = {}, typename _DerivedMan::OpJacobianRef J_mout_t = {}) -> _DerivedMan::LieGroup
template<typename _Derived0, typename _Derived1>
auto rminus(const LieGroupBase<_Derived0>& lie_group_lhs, const LieGroupBase<_Derived1>& lie_group_rhs, typename _Derived0::OptJacobianRef J_t_ma = {}, typename _Derived0::OptJacobianRef J_t_mb = {}) -> _Derived0::Tangent
template<typename _Derived0, typename _Derived1>
auto lminus(const LieGroupBase<_Derived0>& lie_group_lhs, const LieGroupBase<_Derived1>& lie_group_rhs, typename _Derived0::OptJacobianRef J_t_ma = {}, typename _Derived0::OptJacobianRef J_t_mb = {}) -> _Derived0::Tangent
template<typename _Derived0, typename _Derived1>
auto minus(const LieGroupBase<_Derived0>& lie_group_lhs, const LieGroupBase<_Derived1>& lie_group_rhs, typename _Derived0::OptJacobianRef J_t_ma = {}, typename _Derived0::OptJacobianRef J_t_mb = {}) -> _Derived0::Tangent
template<typename _Derived>
auto lift(const LieGroupBase<_Derived>& lie_group, typename _Derived::OptJacobianRef J_l_m = {}) -> MANIF_DEPRECATED _Derived::Tangent
template<typename _Derived>
auto log(const LieGroupBase<_Derived>& lie_group, typename _Derived::OptJacobianRef J_l_m = {}) -> _Derived::Tangent
template<typename _Derived>
auto retract(const TangentBase<_Derived>& tangent, typename _Derived::OptJacobianRef J_r_t = {}) -> MANIF_DEPRECATED _Derived::LieGroup
template<typename _Derived>
auto exp(const TangentBase<_Derived>& tangent, typename _Derived::OptJacobianRef J_e_t = {}) -> _Derived::LieGroup
template<typename _Derived0, typename _Derived1>
auto compose(const LieGroupBase<_Derived0>& lie_group_lhs, const LieGroupBase<_Derived1>& lie_group_rhs, typename _Derived0::OptJacobianRef J_mc_ma = {}, typename _Derived0::OptJacobianRef J_mc_mb = {}) -> _Derived0::LieGroup
template<typename _Derived0, typename _Derived1>
auto between(const LieGroupBase<_Derived0>& lie_group_lhs, const LieGroupBase<_Derived1>& lie_group_rhs, typename _Derived0::OptJacobianRef J_mc_ma = {}, typename _Derived0::OptJacobianRef J_mc_mb = {}) -> _Derived0::LieGroup
template<typename _Derived>
auto act(const LieGroupBase<_Derived>& lie_group, typename _Derived::Vector v, typename _Derived::OptJacobianRef J_vout_m = {}, typename _Derived::OptJacobianRef J_vout_v = {}) -> _Derived::Vector
template<typename _Scalar>
auto skew(const _Scalar v) -> std::enable_if<std::is_arithmetic<_Scalar>::value||internal::is_ad<_Scalar>::value, Eigen::Matrix<_Scalar, 2, 2>>::type
Return a 2x2 skew matrix given a scalar.
template<typename _Derived>
auto skew(const Eigen::MatrixBase<_Derived>& v) -> std::enable_if<(internal::is_base_of_v<Eigen::MatrixBase<_Derived>, _Derived>) && _Derived::RowsAtCompileTime==3), Eigen::Matrix<typename _Derived::Scalar, 3, 3>>::type
Return a 3x3 skew matrix given 3-vector.
template<typename _Derived>
auto skew(const Eigen::MatrixBase<_Derived>& v) -> std::enable_if<(internal::is_base_of_v<Eigen::MatrixBase<_Derived>, _Derived>) && _Derived::RowsAtCompileTime==Eigen::Dynamic), Eigen::Matrix<typename _Derived::Scalar, Eigen::Dynamic, Eigen::Dynamic>>::type
Return either a 2x2 or a 3x3 skew matrix given a scalar or a 3-vector.
template<typename Scalar>
auto randPointInBall(Scalar radius) -> Eigen::Matrix<Scalar, 3, 1>
template<typename Scalar>
auto randQuat() -> Eigen::Quaternion<Scalar>
template<typename _Stream, typename _Derived>
auto operator<<(_Stream& s, const manif::LieGroupBase<_Derived>& m) -> _Stream&
MANIF_EXTRA_TANGENT_TYPEDEF(SE2Tangent)
MANIF_EXTRA_TANGENT_TYPEDEF(SE3Tangent)
MANIF_EXTRA_TANGENT_TYPEDEF(SE_2_3Tangent)
MANIF_EXTRA_TANGENT_TYPEDEF(SGal3Tangent)
MANIF_EXTRA_TANGENT_TYPEDEF(SO2Tangent)
MANIF_EXTRA_TANGENT_TYPEDEF(SO3Tangent)
template<typename _Derived, typename _DerivedOther>
auto operator+(const TangentBase<_Derived>& ta, const TangentBase<_DerivedOther>& tb) -> TangentBase<_Derived>::Tangent
template<typename _Derived, typename _DerivedOther>
auto operator-(const TangentBase<_Derived>& ta, const TangentBase<_DerivedOther>& tb) -> TangentBase<_Derived>::Tangent
template<typename _Derived, typename _EigenDerived>
auto operator+(const TangentBase<_Derived>& t, const Eigen::MatrixBase<_EigenDerived>& v) -> TangentBase<_Derived>::Tangent
template<typename _Derived, typename _EigenDerived>
auto operator-(const TangentBase<_Derived>& t, const Eigen::MatrixBase<_EigenDerived>& v) -> TangentBase<_Derived>::Tangent
template<typename _EigenDerived, typename _Derived>
auto operator+(const Eigen::MatrixBase<_EigenDerived>& v, const TangentBase<_Derived>& t) -> auto
template<typename _EigenDerived, typename _Derived>
auto operator-(const Eigen::MatrixBase<_EigenDerived>& v, const TangentBase<_Derived>& t) -> auto
template<typename _Derived>
auto operator*(const TangentBase<_Derived>& t, const typename _Derived::Scalar scalar) -> TangentBase<_Derived>::Tangent
template<typename _Derived>
auto operator*(const typename _Derived::Scalar scalar, const TangentBase<_Derived>& t) -> TangentBase<_Derived>::Tangent
template<typename _Derived>
auto operator/(const TangentBase<_Derived>& t, const typename _Derived::Scalar scalar) -> TangentBase<_Derived>::Tangent
template<class _DerivedOther>
auto operator*(const typename TangentBase<_DerivedOther>::Jacobian& J, const TangentBase<_DerivedOther>& t) -> TangentBase<_DerivedOther>::Tangent
template<typename _Derived, typename _DerivedOther>
auto operator==(const TangentBase<_Derived>& ta, const TangentBase<_DerivedOther>& tb) -> bool
template<typename _Derived, typename _EigenDerived>
auto operator==(const TangentBase<_Derived>& t, const Eigen::MatrixBase<_EigenDerived>& v) -> bool
template<typename _Stream, typename _Derived>
auto operator<<(_Stream& s, const manif::TangentBase<_Derived>& m) -> _Stream&
template<typename T>
auto pi2pi(T angle) -> T
Wrap an angle in -pi,pi.
template<typename T>
auto toRad(const T deg) -> T constexpr
Conversion to radians.
template<typename T>
auto toDeg(const T rad) -> T constexpr
Conversion to degrees.
template<typename T>
auto approxSqrtInv(const T x) -> T constexpr
Degree 2 polynomial approximation of 1/sqrt(x) (reciprocal sqrt).