OKVIS
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
Public Types | Public Member Functions | Private Attributes | List of all members
okvis::ceres::HomogeneousPointParameterBlock Class Reference

Wraps the parameter block for a speed / IMU biases estimate. More...

#include <HomogeneousPointParameterBlock.hpp>

Inheritance diagram for okvis::ceres::HomogeneousPointParameterBlock:
okvis::ceres::ParameterBlockSized< 4, 3, Eigen::Vector4d > okvis::ceres::ParameterBlock

Public Types

typedef Eigen::Vector4d estimate_t
 The estimate type (4D vector). More...
 
typedef ParameterBlockSized
< 4, 3, estimate_t
base_t
 The base class type. More...
 
- Public Types inherited from okvis::ceres::ParameterBlockSized< 4, 3, Eigen::Vector4d >
typedef Eigen::Vector4d parameter_t
 Make the parameter type accessible. More...
 

Public Member Functions

 HomogeneousPointParameterBlock ()
 Default constructor (assumes not fixed). More...
 
 HomogeneousPointParameterBlock (const Eigen::Vector4d &point, uint64_t id, bool initialized=true)
 Constructor with estimate and time. More...
 
 HomogeneousPointParameterBlock (const Eigen::Vector3d &point, uint64_t id, bool initialized=true)
 Constructor with estimate and time. More...
 
virtual ~HomogeneousPointParameterBlock ()
 Trivial destructor. More...
 
virtual void plus (const double *x0, const double *Delta_Chi, double *x0_plus_Delta) const
 Generalization of the addition operation, x_plus_delta = Plus(x, delta) with the condition that Plus(x, 0) = x. More...
 
virtual void plusJacobian (const double *x0, double *jacobian) const
 The jacobian of Plus(x, delta) w.r.t delta at delta = 0. More...
 
virtual void minus (const double *x0, const double *x0_plus_Delta, double *Delta_Chi) const
 Computes the minimal difference between a variable x and a perturbed variable x_plus_delta. More...
 
virtual void liftJacobian (const double *x0, double *jacobian) const
 Computes the Jacobian from minimal space to naively overparameterised space as used by ceres. More...
 
virtual std::string typeInfo () const
 Return parameter block type as string. More...
 
Setters
virtual void setEstimate (const Eigen::Vector4d &point)
 Set estimate of this parameter block. More...
 
void setInitialized (bool initialized)
 Set initialisaiton status. More...
 
Getters
virtual Eigen::Vector4d estimate () const
 Get estimate. More...
 
bool initialized () const
 Get initialisaiton status. More...
 
- Public Member Functions inherited from okvis::ceres::ParameterBlockSized< 4, 3, Eigen::Vector4d >
 ParameterBlockSized ()
 Default constructor – initialises elements in parametes_ to zero. More...
 
virtual ~ParameterBlockSized ()
 Trivial destructor. More...
 
virtual void setParameters (const double *parameters)
 Set exact parameters of this parameter block. More...
 
virtual double * parameters ()
 Get parameters – as a pointer. More...
 
virtual const double * parameters () const
 Get parameters – as a pointer. More...
 
virtual size_t dimension () const
 Get the parameter dimension. More...
 
virtual size_t minimalDimension () const
 Get the internal minimal parameter dimension. More...
 
virtual bool read (std::istream &)
 
virtual bool write (std::ostream &) const
 Writing to file – not implemented. More...
 
- Public Member Functions inherited from okvis::ceres::ParameterBlock
 ParameterBlock ()
 Default constructor, assumes not fixed and no local parameterisation. More...
 
virtual ~ParameterBlock ()
 Trivial destructor. More...
 
void setId (uint64_t id)
 Set parameter block ID. More...
 
void setFixed (bool fixed)
 Whether or not this should be optimised at all. More...
 
uint64_t id () const
 Get parameter block ID. More...
 
bool fixed () const
 Whether or not this is optimised at all. More...
 
virtual void setLocalParameterizationPtr (const ::ceres::LocalParameterization *localParameterizationPtr)
 Set which local parameterisation object to use. More...
 
virtual const
::ceres::LocalParameterization * 
localParameterizationPtr () const
 The local parameterisation object to use. More...
 

Private Attributes

bool initialized_
 Whether or not the 3d position is considered initialised. More...
 

Additional Inherited Members

- Static Public Attributes inherited from okvis::ceres::ParameterBlockSized< 4, 3, Eigen::Vector4d >
static
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
const int 
Dimension
 Dimension of the parameter block. More...
 
static const int MinimalDimension
 Internal (minimal) dimension. More...
 
- Protected Attributes inherited from okvis::ceres::ParameterBlockSized< 4, 3, Eigen::Vector4d >
double parameters_ [Dimension]
 Parameters. More...
 
- Protected Attributes inherited from okvis::ceres::ParameterBlock
uint64_t id_
 ID of the parameter block. More...
 
bool fixed_
 Whether or not this should be optimised at all (ceres::problem::setFixed) More...
 
const
::ceres::LocalParameterization * 
localParameterizationPtr_
 The local parameterisation object to use. More...
 

Detailed Description

Wraps the parameter block for a speed / IMU biases estimate.

Member Typedef Documentation

The base class type.

The estimate type (4D vector).

Constructor & Destructor Documentation

okvis::ceres::HomogeneousPointParameterBlock::HomogeneousPointParameterBlock ( )

Default constructor (assumes not fixed).

okvis::ceres::HomogeneousPointParameterBlock::HomogeneousPointParameterBlock ( const Eigen::Vector4d &  point,
uint64_t  id,
bool  initialized = true 
)

Constructor with estimate and time.

Parameters
[in]pointThe homogeneous point estimate.
[in]idThe (unique) ID of this block.
[in]initializedWhether or not the 3d position is considered initialised.
okvis::ceres::HomogeneousPointParameterBlock::HomogeneousPointParameterBlock ( const Eigen::Vector3d &  point,
uint64_t  id,
bool  initialized = true 
)

Constructor with estimate and time.

Parameters
[in]pointThe homogeneous point estimate.
[in]idThe (unique) ID of this block.
[in]initializedWhether or not the 3d position is considered initialised.
okvis::ceres::HomogeneousPointParameterBlock::~HomogeneousPointParameterBlock ( )
virtual

Trivial destructor.

Member Function Documentation

Eigen::Vector4d okvis::ceres::HomogeneousPointParameterBlock::estimate ( ) const
virtual

Get estimate.

Returns
The estimate.

Implements okvis::ceres::ParameterBlockSized< 4, 3, Eigen::Vector4d >.

bool okvis::ceres::HomogeneousPointParameterBlock::initialized ( ) const
inline

Get initialisaiton status.

Returns
Whether or not the 3d position is considered initialised.
virtual void okvis::ceres::HomogeneousPointParameterBlock::liftJacobian ( const double *  x0,
double *  jacobian 
) const
inlinevirtual

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

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

Implements okvis::ceres::ParameterBlock.

virtual void okvis::ceres::HomogeneousPointParameterBlock::minus ( const double *  x0,
const double *  x0_plus_Delta,
double *  Delta_Chi 
) const
inlinevirtual

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

Parameters
[in]x0Variable.
[in]x0_plus_DeltaPerturbed variable.
[out]Delta_ChiMinimal difference.
Returns
True on success.

Implements okvis::ceres::ParameterBlock.

virtual void okvis::ceres::HomogeneousPointParameterBlock::plus ( const double *  x0,
const double *  Delta_Chi,
double *  x0_plus_Delta 
) const
inlinevirtual

Generalization of the addition operation, x_plus_delta = Plus(x, delta) with the condition that Plus(x, 0) = x.

Parameters
[in]x0Variable.
[in]Delta_ChiPerturbation.
[out]x0_plus_DeltaPerturbed x.

Implements okvis::ceres::ParameterBlock.

virtual void okvis::ceres::HomogeneousPointParameterBlock::plusJacobian ( const double *  x0,
double *  jacobian 
) const
inlinevirtual

The jacobian of Plus(x, delta) w.r.t delta at delta = 0.

Parameters
[in]x0Variable.
[out]jacobianThe Jacobian.

Implements okvis::ceres::ParameterBlock.

void okvis::ceres::HomogeneousPointParameterBlock::setEstimate ( const Eigen::Vector4d &  point)
virtual

Set estimate of this parameter block.

Parameters
[in]pointThe estimate to set this to.

Implements okvis::ceres::ParameterBlockSized< 4, 3, Eigen::Vector4d >.

void okvis::ceres::HomogeneousPointParameterBlock::setInitialized ( bool  initialized)
inline

Set initialisaiton status.

Parameters
[in]initializedWhether or not the 3d position is considered initialised.
virtual std::string okvis::ceres::HomogeneousPointParameterBlock::typeInfo ( ) const
inlinevirtual

Return parameter block type as string.

Implements okvis::ceres::ParameterBlock.

Member Data Documentation

bool okvis::ceres::HomogeneousPointParameterBlock::initialized_
private

Whether or not the 3d position is considered initialised.


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