Variables

OptimizableVariable

namespace Tangent
template<typename ScalarType, size_t Dimension>
class OptimizableVariableBase
#include <OptimizableVariable.h>

Base class for optimizable variables.

Derive from this class to create a new variable type. Derived classes must:

  • Call update(dx) to apply a perturbation vector

  • Optionally override ensureUpdateIsRevertible(dx) if the variable has constraints (see InverseDepth.h for an example)

Update convention:

  • Euclidean: value += dx

  • Lie groups: value = value * exp(dx)

For autodiff support, also implement getValue() and liftToJet() free functions. See SE3.h for an example.

Template Parameters:
  • ScalarType – Floating point type (float or double)

  • Dimension – Tangent space dimension (size of dx vector)

Public Types

typedef ScalarType scalar_type

Public Functions

inline void ensureUpdateIsRevertible(Eigen::Matrix<double, Dimension, 1> &dx)

Clamps dx so that update(-dx) correctly reverses update(dx).

Override this if your variable has constraints (e.g., must stay positive). Called by the optimizer before applying updates.

Public Static Attributes

static const size_t dimension = Dimension

SE3

namespace Tangent

Functions

inline const Sophus::SE3d &getValue(const SE3 &se3)

Extract raw value for residual-only computation.

template<typename T, int N>
Sophus::SE3<Jet<T, N>> liftToJet(const SE3 &se3, int offset)

Lift SE3 to Jet space for automatic differentiation.

Parameterization: [omega(3), v(3)] matching update() convention.

class SE3 : public Tangent::OptimizableVariableBase<double, 6>
#include <SE3.h>

Sophus SE3 transformation.

The update is applied as a so3 + translation update not an se3 update.

The order of the delta vector is [rotation, translation].

Public Functions

SE3() = default
inline SE3(const Sophus::SE3<double> &se3)
inline SE3(Sophus::SE3<double> se3)
inline void update(const Eigen::Matrix<double, 6, 1> &dx)

Public Members

Sophus::SE3<double> value

SO3

namespace Tangent

Functions

inline const Sophus::SO3d &getValue(const SO3 &so3)

Extract raw value for residual-only computation.

template<typename T, int N>
Sophus::SO3<Jet<T, N>> liftToJet(const SO3 &so3, int offset)

Lift SO3 to Jet space for automatic differentiation.

Parameterization: omega(3) matching update() convention: R_new = R * exp(dx)

class SO3 : public Tangent::OptimizableVariableBase<double, 3>
#include <SO3.h>

Sophus SO3 transformation.

The order of the delta vector is [wx,wy,wz].

Public Functions

SO3() = default
inline SO3(const Sophus::SO3<double> &so3)
inline void update(const Eigen::Matrix<double, 3, 1> &dx)

Public Members

Sophus::SO3<double> value

InverseDepth

namespace Tangent

Functions

inline double getValue(const InverseDepth &dinv)

Extract raw value for residual-only computation.

template<typename T, int N>
Jet<T, N> liftToJet(const InverseDepth &dinv, int offset)

Lift InverseDepth to Jet space for automatic differentiation.

class InverseDepth : public Tangent::OptimizableVariableBase<double, 1>
#include <InverseDepth.h>

Stores the inverse depth of an observed point.

The inverse depth is always a member of (0, infinity].

Public Functions

InverseDepth() = default
inline InverseDepth(double dinv)
inline void ensureUpdateIsRevertible(Eigen::Matrix<double, 1, 1> &dx)
inline void update(const Eigen::Matrix<double, 1, 1> &dx)

Public Members

double value

SimpleScalar

namespace Tangent

Functions

inline double getValue(const SimpleScalar &scalar)

Extract raw value for residual-only computation.

template<typename T>
auto getValue(const T &var) -> std::enable_if_t<std::is_base_of_v<SimpleScalar, T> && !std::is_same_v<T, SimpleScalar>, double>

Generic getValue for scalar-like derived types.

Enables autodiff for classes that derive from SimpleScalar.

template<typename T, int N>
Jet<T, N> liftToJet(const SimpleScalar &scalar, int offset)

Lift SimpleScalar to Jet space for automatic differentiation.

template<typename T, int N, typename Variable>
auto liftToJet(const Variable &var, int offset) -> std::enable_if_t<std::is_base_of_v<SimpleScalar, Variable> && !std::is_same_v<Variable, SimpleScalar>, Jet<T, N>>

Generic liftToJet for scalar-like derived types.

Enables autodiff for classes that derive from SimpleScalar.

class SimpleScalar : public Tangent::OptimizableVariableBase<double, 1>
#include <SimpleScalar.h>

Public Functions

SimpleScalar() = default
inline SimpleScalar(double val)
inline void update(const Eigen::Matrix<double, 1, 1> &dx)

Public Members

double value