An angular cost function that depends on the depth of the landmark and the scale of the motion.
More...
#include <AngularAdjustmentCERESAnalytic.h>
|
| AngularErrorScaleDepth (const Eigen::Vector3d &bearing_vector, const Eigen::Vector3d &bearing_vector_cam, const Eigen::Affine3d &T_cam0_cam0p, const Eigen::Affine3d &T_cam_cam0, const double depth, const double sigma) |
|
| AngularErrorScaleDepth () |
|
virtual bool | Evaluate (double const *const *parameters, double *residuals, double **jacobians) const |
|
An angular cost function that depends on the depth of the landmark and the scale of the motion.
◆ AngularErrorScaleDepth() [1/2]
isae::AngularErrorScaleDepth::AngularErrorScaleDepth |
( |
const Eigen::Vector3d & |
bearing_vector, |
|
|
const Eigen::Vector3d & |
bearing_vector_cam, |
|
|
const Eigen::Affine3d & |
T_cam0_cam0p, |
|
|
const Eigen::Affine3d & |
T_cam_cam0, |
|
|
const double |
depth, |
|
|
const double |
sigma |
|
) |
| |
|
inline |
◆ AngularErrorScaleDepth() [2/2]
isae::AngularErrorScaleDepth::AngularErrorScaleDepth |
( |
| ) |
|
|
inline |
◆ Evaluate()
virtual bool isae::AngularErrorScaleDepth::Evaluate |
( |
double const *const * |
parameters, |
|
|
double * |
residuals, |
|
|
double ** |
jacobians |
|
) |
| const |
|
inlinevirtual |
◆ _bearing_vector
Eigen::Vector3d isae::AngularErrorScaleDepth::_bearing_vector |
◆ _bearing_vector_cam
Eigen::Vector3d isae::AngularErrorScaleDepth::_bearing_vector_cam |
◆ _depth
double isae::AngularErrorScaleDepth::_depth |
◆ _sigma
double isae::AngularErrorScaleDepth::_sigma |
◆ _T_cam0_cam0p
Eigen::Affine3d isae::AngularErrorScaleDepth::_T_cam0_cam0p |
◆ _T_cam_cam0
Eigen::Affine3d isae::AngularErrorScaleDepth::_T_cam_cam0 |
The documentation for this class was generated from the following file: