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::ReprojectionError< GEOMETRY_TYPE > Class Template Reference

The 2D keypoint reprojection error. More...

#include <ReprojectionError.hpp>

Inheritance diagram for okvis::ceres::ReprojectionError< GEOMETRY_TYPE >:
okvis::ceres::ReprojectionError2dBase okvis::ceres::ReprojectionErrorBase okvis::ceres::ErrorInterface

Public Types

typedef
::ceres::SizedCostFunction< 2, 7, 4, 7 > 
base_t
 The base class type. More...
 
typedef Eigen::Vector2d keypoint_t
 The keypoint type (measurement type). More...
 
- Public Types inherited from okvis::ceres::ReprojectionError2dBase
typedef Eigen::Vector2d measurement_t
 Measurement type (2D). More...
 
typedef Eigen::Matrix2d covariance_t
 Covariance / information matrix type (2x2). More...
 

Public Member Functions

 ReprojectionError ()
 Default constructor. More...
 
 ReprojectionError (std::shared_ptr< const camera_geometry_t > cameraGeometry, uint64_t cameraId, const measurement_t &measurement, const covariance_t &information)
 Construct with measurement and information matrix. More...
 
virtual ~ReprojectionError ()
 Trivial destructor. More...
 
virtual void setMeasurement (const measurement_t &measurement)
 Set the measurement. More...
 
void setCameraGeometry (std::shared_ptr< const camera_geometry_t > cameraGeometry)
 Set the underlying camera model. More...
 
virtual void setInformation (const covariance_t &information)
 Set the information. More...
 
virtual const measurement_tmeasurement () const
 Get the measurement. More...
 
virtual const covariance_tinformation () const
 Get the information matrix. More...
 
virtual const covariance_tcovariance () const
 Get the covariance matrix. 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
 Residual block type as string. More...
 
- Public Member Functions inherited from okvis::ceres::ReprojectionErrorBase
uint64_t cameraId () const
 Camera ID. More...
 
void setCameraId (uint64_t cameraId)
 Set camera ID. 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 GEOMETRY_TYPE 
camera_geometry_t
 Make the camera geometry type accessible. More...
 
- Public Attributes inherited from okvis::ceres::ReprojectionErrorBase
uint64_t cameraId_
 ID of the camera. More...
 

Static Public Attributes

static const int kNumResiduals = 2
 Number of residuals (2) More...
 

Protected Attributes

measurement_t measurement_
 The (2D) measurement. More...
 
std::shared_ptr< const
camera_geometry_t
cameraGeometry_
 The camera model: More...
 
covariance_t information_
 The 2x2 information matrix. More...
 
covariance_t squareRootInformation_
 The 2x2 square root information matrix. More...
 
covariance_t covariance_
 The 2x2 covariance matrix. More...
 

Detailed Description

template<class GEOMETRY_TYPE>
class okvis::ceres::ReprojectionError< GEOMETRY_TYPE >

The 2D keypoint reprojection error.

Template Parameters
GEOMETRY_TYPEThe camera gemetry type.

Member Typedef Documentation

template<class GEOMETRY_TYPE >
typedef ::ceres::SizedCostFunction<2, 7, 4, 7> okvis::ceres::ReprojectionError< GEOMETRY_TYPE >::base_t

The base class type.

template<class GEOMETRY_TYPE >
typedef Eigen::Vector2d okvis::ceres::ReprojectionError< GEOMETRY_TYPE >::keypoint_t

The keypoint type (measurement type).

Constructor & Destructor Documentation

template<class GEOMETRY_T >
okvis::ceres::ReprojectionError< GEOMETRY_T >::ReprojectionError ( )

Default constructor.

template<class GEOMETRY_T >
okvis::ceres::ReprojectionError< GEOMETRY_T >::ReprojectionError ( std::shared_ptr< const camera_geometry_t cameraGeometry,
uint64_t  cameraId,
const measurement_t measurement,
const covariance_t information 
)

Construct with measurement and information matrix.

Parameters
[in]cameraGeometryThe underlying camera geometry.
[in]cameraIdThe id of the camera in the okvis::cameras::NCameraSystem.
[in]measurementThe measurement.
[in]informationThe information (weight) matrix.
template<class GEOMETRY_TYPE >
virtual okvis::ceres::ReprojectionError< GEOMETRY_TYPE >::~ReprojectionError ( )
inlinevirtual

Trivial destructor.

Member Function Documentation

template<class GEOMETRY_TYPE >
virtual const covariance_t& okvis::ceres::ReprojectionError< GEOMETRY_TYPE >::covariance ( ) const
inlinevirtual

Get the covariance matrix.

Returns
The inverse information (covariance) matrix.

Implements okvis::ceres::ReprojectionError2dBase.

template<class GEOMETRY_T >
bool okvis::ceres::ReprojectionError< GEOMETRY_T >::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.
template<class GEOMETRY_T >
bool okvis::ceres::ReprojectionError< GEOMETRY_T >::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.

template<class GEOMETRY_TYPE >
virtual const covariance_t& okvis::ceres::ReprojectionError< GEOMETRY_TYPE >::information ( ) const
inlinevirtual

Get the information matrix.

Returns
The information (weight) matrix.

Implements okvis::ceres::ReprojectionError2dBase.

template<class GEOMETRY_TYPE >
virtual const measurement_t& okvis::ceres::ReprojectionError< GEOMETRY_TYPE >::measurement ( ) const
inlinevirtual

Get the measurement.

Returns
The measurement vector.

Implements okvis::ceres::ReprojectionError2dBase.

template<class GEOMETRY_TYPE >
size_t okvis::ceres::ReprojectionError< GEOMETRY_TYPE >::parameterBlockDim ( size_t  parameterBlockId) const
inlinevirtual

Dimension of an individual parameter block.

Parameters
[in]parameterBlockIdID of the parameter block of interest.
Returns
The dimension.

Implements okvis::ceres::ErrorInterface.

template<class GEOMETRY_TYPE >
size_t okvis::ceres::ReprojectionError< GEOMETRY_TYPE >::parameterBlocks ( ) const
inlinevirtual

Number of parameter blocks.

Implements okvis::ceres::ErrorInterface.

template<class GEOMETRY_TYPE >
size_t okvis::ceres::ReprojectionError< GEOMETRY_TYPE >::residualDim ( ) const
inlinevirtual

Residual dimension.

Implements okvis::ceres::ErrorInterface.

template<class GEOMETRY_TYPE >
void okvis::ceres::ReprojectionError< GEOMETRY_TYPE >::setCameraGeometry ( std::shared_ptr< const camera_geometry_t cameraGeometry)
inline

Set the underlying camera model.

Parameters
[in]cameraGeometryThe camera geometry.
template<class GEOMETRY_T >
void okvis::ceres::ReprojectionError< GEOMETRY_T >::setInformation ( const covariance_t information)
virtual

Set the information.

Parameters
[in]informationThe information (weight) matrix.

Implements okvis::ceres::ReprojectionError2dBase.

template<class GEOMETRY_TYPE >
virtual void okvis::ceres::ReprojectionError< GEOMETRY_TYPE >::setMeasurement ( const measurement_t measurement)
inlinevirtual

Set the measurement.

Parameters
[in]measurementThe measurement.

Implements okvis::ceres::ReprojectionError2dBase.

template<class GEOMETRY_TYPE >
virtual std::string okvis::ceres::ReprojectionError< GEOMETRY_TYPE >::typeInfo ( ) const
inlinevirtual

Residual block type as string.

Implements okvis::ceres::ErrorInterface.

Member Data Documentation

template<class GEOMETRY_TYPE >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef GEOMETRY_TYPE okvis::ceres::ReprojectionError< GEOMETRY_TYPE >::camera_geometry_t

Make the camera geometry type accessible.

template<class GEOMETRY_TYPE >
std::shared_ptr<const camera_geometry_t> okvis::ceres::ReprojectionError< GEOMETRY_TYPE >::cameraGeometry_
protected

The camera model:

template<class GEOMETRY_TYPE >
covariance_t okvis::ceres::ReprojectionError< GEOMETRY_TYPE >::covariance_
protected

The 2x2 covariance matrix.

template<class GEOMETRY_TYPE >
covariance_t okvis::ceres::ReprojectionError< GEOMETRY_TYPE >::information_
protected

The 2x2 information matrix.

template<class GEOMETRY_TYPE >
const int okvis::ceres::ReprojectionError< GEOMETRY_TYPE >::kNumResiduals = 2
static

Number of residuals (2)

template<class GEOMETRY_TYPE >
measurement_t okvis::ceres::ReprojectionError< GEOMETRY_TYPE >::measurement_
protected

The (2D) measurement.

template<class GEOMETRY_TYPE >
covariance_t okvis::ceres::ReprojectionError< GEOMETRY_TYPE >::squareRootInformation_
protected

The 2x2 square root information matrix.


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