An angular cost function for line landmarks that depends on the delta update of the frame pose and the line parameters.
More...
#include <AngularAdjustmentCERESAnalytic.h>
|
| AngularErrCeres_linexd_dx (const std::vector< Eigen::Vector3d > &bearing_vectors, const Eigen::Affine3d &T_s_f, const Eigen::Affine3d &T_f_w, const Eigen::Affine3d &T_w_lmk, const double sigma=1) |
|
| ~AngularErrCeres_linexd_dx () |
|
virtual bool | Evaluate (double const *const *parameters, double *residuals, double **jacobians) const |
|
|
const std::vector< Eigen::Vector3d > | _bearing_vectors |
| Bearing vectors of the line 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::Affine3d | _T_w_lmk |
| Pose of the landmark in the world frame. More...
|
|
const double | _sigma |
| Standard deviation for the residuals, used as a weight. More...
|
|
An angular cost function for line landmarks that depends on the delta update of the frame pose and the line parameters.
◆ AngularErrCeres_linexd_dx()
isae::AngularErrCeres_linexd_dx::AngularErrCeres_linexd_dx |
( |
const std::vector< Eigen::Vector3d > & |
bearing_vectors, |
|
|
const Eigen::Affine3d & |
T_s_f, |
|
|
const Eigen::Affine3d & |
T_f_w, |
|
|
const Eigen::Affine3d & |
T_w_lmk, |
|
|
const double |
sigma = 1 |
|
) |
| |
|
inline |
◆ ~AngularErrCeres_linexd_dx()
isae::AngularErrCeres_linexd_dx::~AngularErrCeres_linexd_dx |
( |
| ) |
|
|
inline |
◆ Evaluate()
virtual bool isae::AngularErrCeres_linexd_dx::Evaluate |
( |
double const *const * |
parameters, |
|
|
double * |
residuals, |
|
|
double ** |
jacobians |
|
) |
| const |
|
inlinevirtual |
◆ _bearing_vectors
const std::vector<Eigen::Vector3d> isae::AngularErrCeres_linexd_dx::_bearing_vectors |
|
protected |
Bearing vectors of the line in the sensor frame.
◆ _sigma
const double isae::AngularErrCeres_linexd_dx::_sigma |
|
protected |
Standard deviation for the residuals, used as a weight.
◆ _T_f_w
const Eigen::Affine3d isae::AngularErrCeres_linexd_dx::_T_f_w |
|
protected |
Transform of the world w.r.t. the frame.
◆ _T_s_f
const Eigen::Affine3d isae::AngularErrCeres_linexd_dx::_T_s_f |
|
protected |
Transform of the frame w.r.t. the sensor.
◆ _T_w_lmk
const Eigen::Affine3d isae::AngularErrCeres_linexd_dx::_T_w_lmk |
|
protected |
Pose of the landmark in the world frame.
The documentation for this class was generated from the following file: