|
| BundleAdjustmentCERESNumeric ()=default |
|
| ~BundleAdjustmentCERESNumeric ()=default |
|
| AOptimizer () |
|
void | resetMarginalization () |
|
bool | landmarkOptimization (std::shared_ptr< Frame > &frame) |
| Structure only Bundle Adjustment for a frame. More...
|
|
bool | singleFrameOptimization (std::shared_ptr< Frame > &moving_frame) |
| Motion only Bundle Adjustment for a frame. More...
|
|
bool | singleFrameVIOptimization (std::shared_ptr< isae::Frame > &moving_frame) |
| Visual-Inertial Motion only Bundle Adjustment for a frame. More...
|
|
bool | localMapBA (std::shared_ptr< isae::LocalMap > &local_map, const size_t fixed_frame_number=0) |
| Bundle Adjustment for a local map. More...
|
|
bool | localMapVIOptimization (std::shared_ptr< isae::LocalMap > &local_map, const size_t fixed_frame_number=0) |
| Visual-Inertial Bundle Adjustment for a local map. More...
|
|
double | VIInit (std::shared_ptr< isae::LocalMap > &local_map, Eigen::Matrix3d &R_w_i, bool optim_scale=false) |
| Visual-Inertial Initialization for a local map. More...
|
|
virtual bool | landmarkOptimizationNoFov (std::shared_ptr< Frame > &f, std::shared_ptr< Frame > &fp, Eigen::Affine3d &T_cam0_cam0p, double info_scale) |
| Structure only Bundle Adjustment for a frame with non overlapping fields of view sensors. More...
|
|
virtual bool | marginalize (std::shared_ptr< Frame > &frame0, std::shared_ptr< Frame > &frame1, bool enable_sparsif) |
| Marginalization of a frame and its landmarks. More...
|
|
virtual Eigen::MatrixXd | marginalizeRelative (std::shared_ptr< Frame > &frame0, std::shared_ptr< Frame > &frame1) |
| Marginalization of all the landmarks linked to two frame and computation of the information matrix of the relative pose. More...
|
|
|
uint | addResidualsLocalMap (ceres::Problem &problem, ceres::LossFunction *loss_function, ceres::ParameterBlockOrdering *ordering, std::vector< std::shared_ptr< Frame >> &frame_vector, size_t fixed_frame_number, std::shared_ptr< isae::LocalMap > &local_map) override |
| Add visual residuals to a CERES problem for a local map. More...
|
|
uint | addSingleFrameResiduals (ceres::Problem &problem, ceres::LossFunction *loss_function, std::shared_ptr< Frame > &frame, typed_vec_landmarks &cloud_to_optimize) override |
| Add visual residuals to a CERES problem for a motion only BA. More...
|
|
uint | addLandmarkResiduals (ceres::Problem &problem, ceres::LossFunction *loss_function, typed_vec_landmarks &cloud_to_optimize) override |
| Add visual residuals to a CERES problem for structure only BA. More...
|
|
virtual uint | addMarginalizationResiduals (ceres::Problem &problem, ceres::LossFunction *loss_function, ceres::ParameterBlockOrdering *ordering) |
| Add marginalization residuals to a CERES problem. More...
|
|
uint | addIMUResiduals (ceres::Problem &problem, ceres::LossFunction *loss_function, ceres::ParameterBlockOrdering *ordering, std::vector< std::shared_ptr< Frame >> &frame_vector, size_t fixed_frame_number) |
| Add IMU residuals to a CERES problem. More...
|
|
An optimizer that uses Numeric Cost function for Bundle Adjustment.