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

2D keypoint reprojection error base class. More...

#include <ReprojectionErrorBase.hpp>

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

Public Types

typedef Eigen::Vector2d measurement_t
 Measurement type (2D). More...
 
typedef Eigen::Matrix2d covariance_t
 Covariance / information matrix type (2x2). More...
 

Public Member Functions

virtual void setMeasurement (const measurement_t &measurement)=0
 Set the measurement. More...
 
virtual void setInformation (const covariance_t &information)=0
 Set the information. More...
 
virtual const measurement_tmeasurement () const =0
 Get the measurement. More...
 
virtual const covariance_tinformation () const =0
 Get the information matrix. More...
 
virtual const covariance_tcovariance () const =0
 Get the covariance matrix. 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...
 
virtual bool EvaluateWithMinimalJacobians (double const *const *parameters, double *residuals, double **jacobians, double **jacobiansMinimal) const =0
 This evaluates the error term and additionally computes the Jacobians in the minimal internal representation. More...
 
virtual std::string typeInfo () const =0
 Residual block type as string. More...
 
virtual size_t residualDim () const =0
 Get dimension of residuals. More...
 
virtual size_t parameterBlocks () const =0
 Get the number of parameter blocks this is connected to. More...
 
virtual size_t parameterBlockDim (size_t parameterBlockId) const =0
 get the dimension of a parameter block this is connected to. More...
 

Additional Inherited Members

- Public Attributes inherited from okvis::ceres::ReprojectionErrorBase
uint64_t cameraId_
 ID of the camera. More...
 

Detailed Description

2D keypoint reprojection error base class.

Member Typedef Documentation

Covariance / information matrix type (2x2).

Measurement type (2D).

Member Function Documentation

virtual const covariance_t& okvis::ceres::ReprojectionError2dBase::covariance ( ) const
pure virtual

Get the covariance matrix.

Returns
The inverse information (covariance) matrix.

Implemented in okvis::ceres::ReprojectionError< GEOMETRY_TYPE >.

virtual const covariance_t& okvis::ceres::ReprojectionError2dBase::information ( ) const
pure virtual

Get the information matrix.

Returns
The information (weight) matrix (2x2).

Implemented in okvis::ceres::ReprojectionError< GEOMETRY_TYPE >.

virtual const measurement_t& okvis::ceres::ReprojectionError2dBase::measurement ( ) const
pure virtual

Get the measurement.

Returns
The measurement vector (2d).

Implemented in okvis::ceres::ReprojectionError< GEOMETRY_TYPE >.

virtual void okvis::ceres::ReprojectionError2dBase::setInformation ( const covariance_t information)
pure virtual

Set the information.

Parameters
[in]informationThe information (weight) matrix (2x2).

Implemented in okvis::ceres::ReprojectionError< GEOMETRY_TYPE >.

virtual void okvis::ceres::ReprojectionError2dBase::setMeasurement ( const measurement_t measurement)
pure virtual

Set the measurement.

Parameters
[in]measurementThe measurement vector (2d).

Implemented in okvis::ceres::ReprojectionError< GEOMETRY_TYPE >.


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