Angular error cost function for a point landmark in the sensor frame. Parameters are delta update of the frame pose and the landmark position.
More...
#include <AngularAdjustmentCERESAnalytic.h>
|
| AngularErrCeres_pointxd_dx (const Eigen::Vector3d &bearing_vector, const Eigen::Affine3d &T_s_f, const Eigen::Affine3d &T_f_w, const Eigen::Vector3d &t_w_lmk, const double sigma=1) |
|
| ~AngularErrCeres_pointxd_dx () |
|
virtual bool | Evaluate (double const *const *parameters, double *residuals, double **jacobians) const |
|
|
const Eigen::Vector3d | _bearing_vector |
| Bearing vector of the landmark in the sensor frame. More...
|
|
const Eigen::Affine3d | _T_s_f |
| Transform of the frame w.r.t. the sensor. More...
|
|
const Eigen::Affine3d | _T_f_w |
| Transform of the world w.r.t. the frame. More...
|
|
const Eigen::Vector3d | _t_w_lmk |
| Position of the landmark in the world frame. More...
|
|
const double | _sigma |
| Standard deviation for the residuals, used as a weight. More...
|
|
Angular error cost function for a point landmark in the sensor frame. Parameters are delta update of the frame pose and the landmark position.
This cost function uses bearing vector that is compared to the projection of the landmark on the unit sphere, via an arbitrary tangent plane. This is inspired by "VINS-Mono: A Robust and Versatile Monocular Visual-Inertial State
Estimator" by Qin et al. Source: https://arxiv.org/abs/1708.03852
◆ AngularErrCeres_pointxd_dx()
isae::AngularErrCeres_pointxd_dx::AngularErrCeres_pointxd_dx |
( |
const Eigen::Vector3d & |
bearing_vector, |
|
|
const Eigen::Affine3d & |
T_s_f, |
|
|
const Eigen::Affine3d & |
T_f_w, |
|
|
const Eigen::Vector3d & |
t_w_lmk, |
|
|
const double |
sigma = 1 |
|
) |
| |
|
inline |
◆ ~AngularErrCeres_pointxd_dx()
isae::AngularErrCeres_pointxd_dx::~AngularErrCeres_pointxd_dx |
( |
| ) |
|
|
inline |
◆ Evaluate()
virtual bool isae::AngularErrCeres_pointxd_dx::Evaluate |
( |
double const *const * |
parameters, |
|
|
double * |
residuals, |
|
|
double ** |
jacobians |
|
) |
| const |
|
inlinevirtual |
◆ _bearing_vector
const Eigen::Vector3d isae::AngularErrCeres_pointxd_dx::_bearing_vector |
|
protected |
Bearing vector of the landmark in the sensor frame.
◆ _sigma
const double isae::AngularErrCeres_pointxd_dx::_sigma |
|
protected |
Standard deviation for the residuals, used as a weight.
◆ _T_f_w
const Eigen::Affine3d isae::AngularErrCeres_pointxd_dx::_T_f_w |
|
protected |
Transform of the world w.r.t. the frame.
◆ _T_s_f
const Eigen::Affine3d isae::AngularErrCeres_pointxd_dx::_T_s_f |
|
protected |
Transform of the frame w.r.t. the sensor.
◆ _t_w_lmk
const Eigen::Vector3d isae::AngularErrCeres_pointxd_dx::_t_w_lmk |
|
protected |
Position of the landmark in the world frame.
The documentation for this class was generated from the following file: