SaDVIO
Public Member Functions | Protected Attributes | List of all members
isae::ReprojectionErrCeres_linexd_dx Class Reference

Reprojection error cost function for a line landmark. The parameters are the delta update of the frame and the delta update of the line 3D parametrization. More...

#include <BundleAdjustmentCERESAnalytic.h>

Inheritance diagram for isae::ReprojectionErrCeres_linexd_dx:
Inheritance graph
[legend]
Collaboration diagram for isae::ReprojectionErrCeres_linexd_dx:
Collaboration graph
[legend]

Public Member Functions

 ReprojectionErrCeres_linexd_dx (const std::vector< Eigen::Vector2d > &p2ds, const std::shared_ptr< ImageSensor > &cam, const Eigen::Affine3d &T_w_lmk, const std::shared_ptr< AModel3d > &model3d, const double sigma=1.0)
 
 ~ReprojectionErrCeres_linexd_dx ()
 
virtual bool Evaluate (double const *const *parameters, double *residuals, double **jacobians) const
 

Protected Attributes

const std::vector< Eigen::Vector2d > p2ds_
 2D point observations of the line landmark More...
 
const std::shared_ptr< ImageSensorcam_
 Camera sensor used to project the landmark. More...
 
const Eigen::Affine3d T_w_lmk_
 Transform of the landmark in the world frame. More...
 
const std::shared_ptr< AModel3dmodel3d_
 3D model of the line landmark More...
 
Eigen::Matrix2d info_sqrt_
 Square root of the information matrix for the residuals. More...
 

Detailed Description

Reprojection error cost function for a line landmark. The parameters are the delta update of the frame and the delta update of the line 3D parametrization.

BEWARE: This funciton requires that the jacobians are derived in the projection function of the camera model.

Constructor & Destructor Documentation

◆ ReprojectionErrCeres_linexd_dx()

isae::ReprojectionErrCeres_linexd_dx::ReprojectionErrCeres_linexd_dx ( const std::vector< Eigen::Vector2d > &  p2ds,
const std::shared_ptr< ImageSensor > &  cam,
const Eigen::Affine3d &  T_w_lmk,
const std::shared_ptr< AModel3d > &  model3d,
const double  sigma = 1.0 
)
inline

◆ ~ReprojectionErrCeres_linexd_dx()

isae::ReprojectionErrCeres_linexd_dx::~ReprojectionErrCeres_linexd_dx ( )
inline

Member Function Documentation

◆ Evaluate()

virtual bool isae::ReprojectionErrCeres_linexd_dx::Evaluate ( double const *const *  parameters,
double *  residuals,
double **  jacobians 
) const
inlinevirtual

Member Data Documentation

◆ cam_

const std::shared_ptr<ImageSensor> isae::ReprojectionErrCeres_linexd_dx::cam_
protected

Camera sensor used to project the landmark.

◆ info_sqrt_

Eigen::Matrix2d isae::ReprojectionErrCeres_linexd_dx::info_sqrt_
protected

Square root of the information matrix for the residuals.

◆ model3d_

const std::shared_ptr<AModel3d> isae::ReprojectionErrCeres_linexd_dx::model3d_
protected

3D model of the line landmark

◆ p2ds_

const std::vector<Eigen::Vector2d> isae::ReprojectionErrCeres_linexd_dx::p2ds_
protected

2D point observations of the line landmark

◆ T_w_lmk_

const Eigen::Affine3d isae::ReprojectionErrCeres_linexd_dx::T_w_lmk_
protected

Transform of the landmark in the world frame.


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