Solar
Public Member Functions | List of all members
SolAR::MODULES::G2O::SolAROptimizationG2O Class Reference

Bundle adjustment optimization. UUID: 870d89ba-bb5f-460a-a817-1fcb6473df70 More...

#include <SolAROptimizationG2O.h>

Inheritance diagram for SolAR::MODULES::G2O::SolAROptimizationG2O:
Inheritance graph
[legend]
Collaboration diagram for SolAR::MODULES::G2O::SolAROptimizationG2O:
Collaboration graph
[legend]

Public Member Functions

FrameworkReturnCode setMap (const SRef< datastructure::Map > map) override
 set map reference to optimize More...
 
double bundleAdjustment (datastructure::CamCalibration &K, datastructure::CamDistortion &D, const std::vector< uint32_t > &selectKeyframes={}) override
 solve a non-linear problem related to bundle adjustement statement expressed as: minArg(pts3ds,intrinsics,extrinsics) = MIN_cam_i(MIN_3d_j(pts2d_j - reproje(pt3ds_j,intrinsics_i,extrinsics_i)), More...
 
double optimizeSim3 (datastructure::CamCalibration &K1, datastructure::CamCalibration &K2, const SRef< Keyframe > &keyframe1, const SRef< Keyframe > &keyframe2, const std::vector< DescriptorMatch > &matches, const std::vector< Point3Df > &pts3D1, const std::vector< Point3Df > &pts3D2, datastructure::Transform3Df &pose) override
 solve a non-linear problem related to sim3D optimization between two overlaped keyframes of two different maps: More...
 
void unloadComponent () override final
 

Detailed Description

Bundle adjustment optimization. UUID: 870d89ba-bb5f-460a-a817-1fcb6473df70

Injectables
SolAR::api::storage::IPointCloudManager
SolAR::api::storage::IKeyframesManager
SolAR::api::storage::ICovisibilityGraphManager
Properties
nbIterationsLocal
type: int; range : [0..MAX INT]; default: 10
nbIterationsGlobal
type: int; range : [0..MAX INT]; default: 10
setVerbose (0 = false, 1 = true)
type: int; range : [0, 1]; default: 0
nbMaxFixedKeyframes
type: int; range : [0..MAX INT]; default: 0
errorOutlier
type: float; range : [0..MAX FLOAT]; default: 3.f
useSpanningTree (0 = false, 1 = true)
type: int; range : [0, 1]; default: 0
isRobust (0 = false, 1 = true)
type: int; range : [0, 1]; default: 1
fixedMap (0 = false, 1 = true)
type: int; range : [0, 1]; default: 0
fixedKeyframes (0 = false, 1 = true)
type: int; range : [0, 1]; default: 0

Member Function Documentation

◆ bundleAdjustment()

double SolAR::MODULES::G2O::SolAROptimizationG2O::bundleAdjustment ( datastructure::CamCalibration &  K,
datastructure::CamDistortion &  D,
const std::vector< uint32_t > &  selectKeyframes = {} 
)
override

solve a non-linear problem related to bundle adjustement statement expressed as: minArg(pts3ds,intrinsics,extrinsics) = MIN_cam_i(MIN_3d_j(pts2d_j - reproje(pt3ds_j,intrinsics_i,extrinsics_i)),

Parameters
[in,out]Kcamera calibration parameters responsible of 3D points generation.
[in,out]Dcamera distorsion parameters responsible of 3D points generation
[in]selectKeyframes: selected views to bundle following a given strategies. If it is empty then take all keyframes into account to perform global bundle adjustment.
Returns
the mean re-projection error after optimization.

◆ optimizeSim3()

double SolAR::MODULES::G2O::SolAROptimizationG2O::optimizeSim3 ( datastructure::CamCalibration &  K1,
datastructure::CamCalibration &  K2,
const SRef< Keyframe > &  keyframe1,
const SRef< Keyframe > &  keyframe2,
const std::vector< DescriptorMatch > &  matches,
const std::vector< Point3Df > &  pts3D1,
const std::vector< Point3Df > &  pts3D2,
datastructure::Transform3Df &  pose 
)
override

solve a non-linear problem related to sim3D optimization between two overlaped keyframes of two different maps:

Parameters
[in]K1camera calibration parameters responsible of 3D points generation from map 1.
[in]K2camera calibration parameters responsible of 3D points generation from map 2.
[in]keyframe1first overlapping keyframe from map 1.
[in]keyframe2second overlapping keyframe from map 2.
[in]matchesmatches between two keyframes.
[in]pts3D1first set of 3D points.
[in]pts3D2second set of 3D points.
[in,out]poseSim3 matrix pose between map1 and map2
Returns
the mean re-projection error.

◆ setMap()

FrameworkReturnCode SolAR::MODULES::G2O::SolAROptimizationG2O::setMap ( const SRef< datastructure::Map >  map)
override

set map reference to optimize

Parameters
[in]mapthe input map.
Returns
FrameworkReturnCode::SUCCESS if the map is set, else FrameworkReturnCode::_ERROR.

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