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

Absolute error of a pose. More...

#include <PoseError.hpp>

Inheritance diagram for okvis::ceres::PoseError:
okvis::ceres::ErrorInterface

Public Types

typedef Eigen::Matrix< double, 6, 6 > information_t
 The information matrix type (6x6). More...
 
typedef Eigen::Matrix< double, 6, 6 > covariance_t
 The covariance matrix type (same as information). More...
 

Public Member Functions

 PoseError ()
 Default constructor. More...
 
 PoseError (const okvis::kinematics::Transformation &measurement, const Eigen::Matrix< double, 6, 6 > &information)
 Construct with measurement and information matrix. More...
 
 PoseError (const okvis::kinematics::Transformation &measurement, double translationVariance, double rotationVariance)
 Construct with measurement and variance. More...
 
virtual ~PoseError ()
 Trivial destructor. More...
 
virtual bool Evaluate (double const *const *parameters, double *residuals, double **jacobians) const
 This evaluates the error term and additionally computes the Jacobians. More...
 
virtual bool EvaluateWithMinimalJacobians (double const *const *parameters, double *residuals, double **jacobians, double **jacobiansMinimal) const
 This evaluates the error term and additionally computes the Jacobians in the minimal internal representation. More...
 
size_t residualDim () const
 Residual dimension. More...
 
size_t parameterBlocks () const
 Number of parameter blocks. More...
 
size_t parameterBlockDim (size_t parameterBlockId) const
 Dimension of an individual parameter block. More...
 
virtual std::string typeInfo () const
 Return parameter block type as string. More...
 
Setters
void setMeasurement (const okvis::kinematics::Transformation &measurement)
 Set the measurement. More...
 
void setInformation (const information_t &information)
 Set the information. More...
 
Getters
const
okvis::kinematics::Transformation
measurement () const
 Get the measurement. More...
 
const information_tinformation () const
 Get the information matrix. More...
 
const information_tcovariance () const
 Get the covariance matrix. More...
 
- Public Member Functions inherited from okvis::ceres::ErrorInterface
EIGEN_MAKE_ALIGNED_OPERATOR_NEW ErrorInterface ()
 Constructor. More...
 
virtual ~ErrorInterface ()
 Destructor (does nothing). More...
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW
typedef::ceres::SizedCostFunction< 6, 7 > 
base_t
 The base class type. More...
 

Static Public Attributes

static const int kNumResiduals = 6
 The number of residuals (6). More...
 

Protected Attributes

okvis::kinematics::Transformation measurement_
 The pose measurement. More...
 
information_t information_
 The 6x6 information matrix. More...
 
information_t squareRootInformation_
 The 6x6 square root information matrix. More...
 
covariance_t covariance_
 The 6x6 covariance matrix. More...
 

Detailed Description

Absolute error of a pose.

Member Typedef Documentation

typedef Eigen::Matrix<double, 6, 6> okvis::ceres::PoseError::covariance_t

The covariance matrix type (same as information).

typedef Eigen::Matrix<double, 6, 6> okvis::ceres::PoseError::information_t

The information matrix type (6x6).

Constructor & Destructor Documentation

okvis::ceres::PoseError::PoseError ( )
inline

Default constructor.

okvis::ceres::PoseError::PoseError ( const okvis::kinematics::Transformation measurement,
const Eigen::Matrix< double, 6, 6 > &  information 
)

Construct with measurement and information matrix.

Parameters
[in]measurementThe measurement.
[in]informationThe information (weight) matrix.
okvis::ceres::PoseError::PoseError ( const okvis::kinematics::Transformation measurement,
double  translationVariance,
double  rotationVariance 
)

Construct with measurement and variance.

Parameters
[in]measurementThe measurement.
[in]translationVarianceThe translation variance.
[in]rotationVarianceThe rotation variance.
virtual okvis::ceres::PoseError::~PoseError ( )
inlinevirtual

Trivial destructor.

Member Function Documentation

const information_t& okvis::ceres::PoseError::covariance ( ) const
inline

Get the covariance matrix.

Returns
The inverse information (covariance) matrix.
bool okvis::ceres::PoseError::Evaluate ( double const *const *  parameters,
double *  residuals,
double **  jacobians 
) const
virtual

This evaluates the error term and additionally computes the Jacobians.

Parameters
parametersPointer to the parameters (see ceres)
residualsPointer to the residual vector (see ceres)
jacobiansPointer to the Jacobians (see ceres)
Returns
success of th evaluation.
bool okvis::ceres::PoseError::EvaluateWithMinimalJacobians ( double const *const *  parameters,
double *  residuals,
double **  jacobians,
double **  jacobiansMinimal 
) const
virtual

This evaluates the error term and additionally computes the Jacobians in the minimal internal representation.

Parameters
parametersPointer to the parameters (see ceres)
residualsPointer to the residual vector (see ceres)
jacobiansPointer to the Jacobians (see ceres)
jacobiansMinimalPointer to the minimal Jacobians (equivalent to jacobians).
Returns
Success of the evaluation.

Implements okvis::ceres::ErrorInterface.

const information_t& okvis::ceres::PoseError::information ( ) const
inline

Get the information matrix.

Returns
The information (weight) matrix.
const okvis::kinematics::Transformation& okvis::ceres::PoseError::measurement ( ) const
inline

Get the measurement.

Returns
The measurement vector.
size_t okvis::ceres::PoseError::parameterBlockDim ( size_t  parameterBlockId) const
inlinevirtual

Dimension of an individual parameter block.

Implements okvis::ceres::ErrorInterface.

size_t okvis::ceres::PoseError::parameterBlocks ( ) const
inlinevirtual

Number of parameter blocks.

Implements okvis::ceres::ErrorInterface.

size_t okvis::ceres::PoseError::residualDim ( ) const
inlinevirtual

Residual dimension.

Implements okvis::ceres::ErrorInterface.

void okvis::ceres::PoseError::setInformation ( const information_t information)

Set the information.

Parameters
[in]informationThe information (weight) matrix.
void okvis::ceres::PoseError::setMeasurement ( const okvis::kinematics::Transformation measurement)
inline

Set the measurement.

Parameters
[in]measurementThe measurement.
virtual std::string okvis::ceres::PoseError::typeInfo ( ) const
inlinevirtual

Return parameter block type as string.

Implements okvis::ceres::ErrorInterface.

Member Data Documentation

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef ::ceres::SizedCostFunction<6, 7> okvis::ceres::PoseError::base_t

The base class type.

covariance_t okvis::ceres::PoseError::covariance_
protected

The 6x6 covariance matrix.

information_t okvis::ceres::PoseError::information_
protected

The 6x6 information matrix.

const int okvis::ceres::PoseError::kNumResiduals = 6
static

The number of residuals (6).

okvis::kinematics::Transformation okvis::ceres::PoseError::measurement_
protected

The pose measurement.

information_t okvis::ceres::PoseError::squareRootInformation_
protected

The 6x6 square root information matrix.


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