OKVIS
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
Public Member Functions | List of all members
okvis::ceres::LocalParamizationAdditionalInterfaces Class Referenceabstract

Provides some additional interfaces to ceres' LocalParamization than are needed in the generic marginalisation okvis::ceres::MarginalizationError. More...

#include <LocalParamizationAdditionalInterfaces.hpp>

Inheritance diagram for okvis::ceres::LocalParamizationAdditionalInterfaces:
okvis::ceres::HomogeneousPointLocalParameterization okvis::ceres::PoseLocalParameterization okvis::ceres::PoseLocalParameterization2d okvis::ceres::PoseLocalParameterization3d okvis::ceres::PoseLocalParameterization4d

Public Member Functions

virtual ~LocalParamizationAdditionalInterfaces ()
 Trivial destructor. More...
 
virtual bool Minus (const double *x, const double *x_plus_delta, double *delta) const =0
 Computes the minimal difference between a variable x and a perturbed variable x_plus_delta. More...
 
virtual bool ComputeLiftJacobian (const double *x, double *jacobian) const =0
 Computes the Jacobian from minimal space to naively overparameterised space as used by ceres. More...
 
virtual bool verify (const double *x_raw, double purturbation_magnitude=1.0e-6) const
 Verifies the correctness of an inplementation by means of numeric Jacobians. More...
 

Detailed Description

Provides some additional interfaces to ceres' LocalParamization than are needed in the generic marginalisation okvis::ceres::MarginalizationError.

Constructor & Destructor Documentation

virtual okvis::ceres::LocalParamizationAdditionalInterfaces::~LocalParamizationAdditionalInterfaces ( )
inlinevirtual

Trivial destructor.

Member Function Documentation

virtual bool okvis::ceres::LocalParamizationAdditionalInterfaces::ComputeLiftJacobian ( const double *  x,
double *  jacobian 
) const
pure virtual

Computes the Jacobian from minimal space to naively overparameterised space as used by ceres.

Parameters
[in]xVariable.
[out]jacobianthe Jacobian (dimension minDim x dim).
Returns
True on success.

Implemented in okvis::ceres::PoseLocalParameterization2d, okvis::ceres::PoseLocalParameterization4d, okvis::ceres::PoseLocalParameterization3d, okvis::ceres::HomogeneousPointLocalParameterization, and okvis::ceres::PoseLocalParameterization.

virtual bool okvis::ceres::LocalParamizationAdditionalInterfaces::Minus ( const double *  x,
const double *  x_plus_delta,
double *  delta 
) const
pure virtual

Computes the minimal difference between a variable x and a perturbed variable x_plus_delta.

Parameters
[in]xVariable.
[in]x_plus_deltaPerturbed variable.
[out]deltaminimal difference.
Returns
True on success.

Implemented in okvis::ceres::PoseLocalParameterization2d, okvis::ceres::PoseLocalParameterization4d, okvis::ceres::PoseLocalParameterization3d, okvis::ceres::HomogeneousPointLocalParameterization, and okvis::ceres::PoseLocalParameterization.

bool okvis::ceres::LocalParamizationAdditionalInterfaces::verify ( const double *  x_raw,
double  purturbation_magnitude = 1.0e-6 
) const
virtual

Verifies the correctness of an inplementation by means of numeric Jacobians.

Parameters
[in]x_rawLinearisation point of the variable.
[in]purturbation_magnitudeMagnitude of the delta used for numeric Jacobians.
Returns
True on success.

The documentation for this class was generated from the following files: