39 #ifndef INCLUDE_OKVIS_CERES_REPROJECTIONERRORBASE_HPP_
40 #define INCLUDE_OKVIS_CERES_REPROJECTIONERRORBASE_HPP_
42 #include "ceres/ceres.h"
51 public ::ceres::SizedCostFunction<2 ,
virtual void setMeasurement(const measurement_t &measurement)=0
Set the measurement.
virtual const measurement_t & measurement() const =0
Get the measurement.
Reprojection error base class.
Definition: ReprojectionErrorBase.hpp:50
Simple interface class the errors implemented here should inherit from.
Definition: ErrorInterface.hpp:53
uint64_t cameraId_
ID of the camera.
Definition: ReprojectionErrorBase.hpp:67
virtual const covariance_t & information() const =0
Get the information matrix.
2D keypoint reprojection error base class.
Definition: ReprojectionErrorBase.hpp:71
Eigen::Vector2d measurement_t
Measurement type (2D).
Definition: ReprojectionErrorBase.hpp:75
virtual void setInformation(const covariance_t &information)=0
Set the information.
Eigen::Matrix2d covariance_t
Covariance / information matrix type (2x2).
Definition: ReprojectionErrorBase.hpp:78
virtual const covariance_t & covariance() const =0
Get the covariance matrix.
uint64_t cameraId() const
Camera ID.
Definition: ReprojectionErrorBase.hpp:57
void setCameraId(uint64_t cameraId)
Set camera ID.
Definition: ReprojectionErrorBase.hpp:63