|
OKVIS ROS
|
The 2D keypoint reprojection error. More...
#include <ReprojectionError.hpp>
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_t & | measurement () const |
| Get the measurement. More... | |
| virtual const covariance_t & | information () const |
| Get the information matrix. More... | |
| virtual const covariance_t & | covariance () 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... | |
The 2D keypoint reprojection error.
| GEOMETRY_TYPE | The camera gemetry type. |
| typedef ::ceres::SizedCostFunction<2, 7, 4, 7> okvis::ceres::ReprojectionError< GEOMETRY_TYPE >::base_t |
The base class type.
| typedef Eigen::Vector2d okvis::ceres::ReprojectionError< GEOMETRY_TYPE >::keypoint_t |
The keypoint type (measurement type).
| okvis::ceres::ReprojectionError< GEOMETRY_T >::ReprojectionError | ( | ) |
Default constructor.
| 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.
| [in] | cameraGeometry | The underlying camera geometry. |
| [in] | cameraId | The id of the camera in the okvis::cameras::NCameraSystem. |
| [in] | measurement | The measurement. |
| [in] | information | The information (weight) matrix. |
|
inlinevirtual |
Trivial destructor.
|
inlinevirtual |
Get the covariance matrix.
Implements okvis::ceres::ReprojectionError2dBase.
|
virtual |
This evaluates the error term and additionally computes the Jacobians.
| parameters | Pointer to the parameters (see ceres) |
| residuals | Pointer to the residual vector (see ceres) |
| jacobians | Pointer to the Jacobians (see ceres) |
|
virtual |
This evaluates the error term and additionally computes the Jacobians in the minimal internal representation.
| parameters | Pointer to the parameters (see ceres) |
| residuals | Pointer to the residual vector (see ceres) |
| jacobians | Pointer to the Jacobians (see ceres) |
| jacobiansMinimal | Pointer to the minimal Jacobians (equivalent to jacobians). |
Implements okvis::ceres::ErrorInterface.
|
inlinevirtual |
Get the information matrix.
Implements okvis::ceres::ReprojectionError2dBase.
|
inlinevirtual |
Get the measurement.
Implements okvis::ceres::ReprojectionError2dBase.
|
inlinevirtual |
Dimension of an individual parameter block.
| [in] | parameterBlockId | ID of the parameter block of interest. |
Implements okvis::ceres::ErrorInterface.
|
inlinevirtual |
Number of parameter blocks.
Implements okvis::ceres::ErrorInterface.
|
inlinevirtual |
Residual dimension.
Implements okvis::ceres::ErrorInterface.
|
inline |
Set the underlying camera model.
| [in] | cameraGeometry | The camera geometry. |
|
virtual |
Set the information.
| [in] | information | The information (weight) matrix. |
Implements okvis::ceres::ReprojectionError2dBase.
|
inlinevirtual |
Set the measurement.
| [in] | measurement | The measurement. |
Implements okvis::ceres::ReprojectionError2dBase.
|
inlinevirtual |
Residual block type as string.
Implements okvis::ceres::ErrorInterface.
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef GEOMETRY_TYPE okvis::ceres::ReprojectionError< GEOMETRY_TYPE >::camera_geometry_t |
Make the camera geometry type accessible.
|
protected |
The camera model:
|
protected |
The 2x2 covariance matrix.
|
protected |
The 2x2 information matrix.
|
static |
Number of residuals (2)
|
protected |
The (2D) measurement.
|
protected |
The 2x2 square root information matrix.
1.8.6