Pose local parameterisation, i.e. for orientation dq(dalpha) x q_bar. Here, we only perturb the translation and yaw though.
More...
#include <PoseLocalParameterization.hpp>
|
virtual | ~PoseLocalParameterization4d () |
| Trivial destructor. More...
|
|
virtual bool | Plus (const double *x, const double *delta, double *x_plus_delta) const |
| Generalization of the addition operation, x_plus_delta = Plus(x, delta) with the condition that Plus(x, 0) = x. More...
|
|
virtual bool | Minus (const double *x, const double *x_plus_delta, double *delta) const |
| Computes the minimal difference between a variable x and a perturbed variable x_plus_delta. More...
|
|
virtual bool | ComputeJacobian (const double *x, double *jacobian) const |
| The jacobian of Plus(x, delta) w.r.t delta at delta = 0. More...
|
|
virtual bool | ComputeLiftJacobian (const double *x, double *jacobian) const |
| Computes the Jacobian from minimal space to naively overparameterised space as used by ceres. More...
|
|
virtual int | GlobalSize () const |
| The parameter block dimension. More...
|
|
virtual int | LocalSize () const |
| The parameter block local dimension. More...
|
|
virtual | ~LocalParamizationAdditionalInterfaces () |
| Trivial destructor. 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...
|
|
|
static bool | plusJacobian (const double *x, double *jacobian) |
| The jacobian of Plus(x, delta) w.r.t delta at delta = 0. More...
|
|
static bool | liftJacobian (const double *x, double *jacobian) |
| Computes the Jacobian from minimal space to naively overparameterised space as used by ceres. More...
|
|
Pose local parameterisation, i.e. for orientation dq(dalpha) x q_bar. Here, we only perturb the translation and yaw though.
virtual okvis::ceres::PoseLocalParameterization4d::~PoseLocalParameterization4d |
( |
| ) |
|
|
inlinevirtual |
bool okvis::ceres::PoseLocalParameterization4d::ComputeJacobian |
( |
const double * |
x, |
|
|
double * |
jacobian |
|
) |
| const |
|
virtual |
The jacobian of Plus(x, delta) w.r.t delta at delta = 0.
- Parameters
-
[in] | x | Variable. |
[out] | jacobian | The Jacobian. |
bool okvis::ceres::PoseLocalParameterization4d::ComputeLiftJacobian |
( |
const double * |
x, |
|
|
double * |
jacobian |
|
) |
| const |
|
virtual |
Computes the Jacobian from minimal space to naively overparameterised space as used by ceres.
- Parameters
-
[in] | x | Variable. |
[out] | jacobian | the Jacobian (dimension minDim x dim). |
- Returns
- True on success.
Implements okvis::ceres::LocalParamizationAdditionalInterfaces.
virtual int okvis::ceres::PoseLocalParameterization4d::GlobalSize |
( |
| ) |
const |
|
inlinevirtual |
The parameter block dimension.
bool okvis::ceres::PoseLocalParameterization4d::liftJacobian |
( |
const double * |
x, |
|
|
double * |
jacobian |
|
) |
| |
|
static |
Computes the Jacobian from minimal space to naively overparameterised space as used by ceres.
- Parameters
-
[in] | x | Variable. |
[out] | jacobian | the Jacobian (dimension minDim x dim). |
- Returns
- True on success.
virtual int okvis::ceres::PoseLocalParameterization4d::LocalSize |
( |
| ) |
const |
|
inlinevirtual |
The parameter block local dimension.
bool okvis::ceres::PoseLocalParameterization4d::Minus |
( |
const double * |
x, |
|
|
const double * |
x_plus_delta, |
|
|
double * |
delta |
|
) |
| const |
|
virtual |
Computes the minimal difference between a variable x and a perturbed variable x_plus_delta.
- Parameters
-
[in] | x | Variable. |
[in] | x_plus_delta | Perturbed variable. |
[out] | delta | minimal difference. |
- Returns
- True on success.
Implements okvis::ceres::LocalParamizationAdditionalInterfaces.
bool okvis::ceres::PoseLocalParameterization4d::Plus |
( |
const double * |
x, |
|
|
const double * |
delta, |
|
|
double * |
x_plus_delta |
|
) |
| const |
|
virtual |
Generalization of the addition operation, x_plus_delta = Plus(x, delta) with the condition that Plus(x, 0) = x.
- Parameters
-
[in] | x | Variable. |
[in] | delta | Perturbation. |
[out] | x_plus_delta | Perturbed x. |
bool okvis::ceres::PoseLocalParameterization4d::plusJacobian |
( |
const double * |
x, |
|
|
double * |
jacobian |
|
) |
| |
|
static |
The jacobian of Plus(x, delta) w.r.t delta at delta = 0.
- Parameters
-
[in] | x | Variable. |
[out] | jacobian | The Jacobian. |
The documentation for this class was generated from the following files: