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 vectorOptionally override
ensureUpdateIsRevertible(dx)if the variable has constraints (see InverseDepth.h for an example)
Update convention:
Euclidean:
value += dxLie groups:
value = value * exp(dx)
For autodiff support, also implement
getValue()andliftToJet()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
-
template<typename ScalarType, size_t Dimension>
SE3¶
-
namespace Tangent
Functions
-
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¶
-
SE3() = default¶
-
class SE3 : public Tangent::OptimizableVariableBase<double, 6>¶
SO3¶
-
namespace Tangent
Functions
-
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¶
-
SO3() = default¶
-
class SO3 : public Tangent::OptimizableVariableBase<double, 3>¶
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¶
-
InverseDepth() = default¶
-
inline double getValue(const InverseDepth &dinv)¶
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.
-
inline double getValue(const SimpleScalar &scalar)¶