Solar
Public Member Functions | List of all members
SolAR::api::solver::map::IBundler Class Referenceabstract

Optimizes a system of 3D points and keyframes. UUID: 35b9bdb7-d23c-4909-984f-ae7f9a292e6c More...

#include <IBundler.h>

Inheritance diagram for SolAR::api::solver::map::IBundler:
Inheritance graph
[legend]
Collaboration diagram for SolAR::api::solver::map::IBundler:
Collaboration graph
[legend]

Public Member Functions

 IBundler ()=default
 IBundler default constructor.
 
virtual ~IBundler ()=default
 ~IBundler default destructor
 
virtual FrameworkReturnCode setMap (const SRef< SolAR::datastructure::Map > map)=0
 set map reference to optimize More...
 
virtual double bundleAdjustment (SolAR::datastructure::CamCalibration &K, SolAR::datastructure::CamDistortion &D, const std::vector< uint32_t > &selectKeyframes={})=0
 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...
 
virtual double optimizeSim3 (SolAR::datastructure::CamCalibration &K1, SolAR::datastructure::CamCalibration &K2, const SRef< SolAR::datastructure::Keyframe > &keyframe1, const SRef< SolAR::datastructure::Keyframe > &keyframe2, const std::vector< SolAR::datastructure::DescriptorMatch > &matches, const std::vector< SolAR::datastructure::Point3Df > &pts3D1, const std::vector< SolAR::datastructure::Point3Df > &pts3D2, SolAR::datastructure::Transform3Df &pose)=0
 solve a non-linear problem related to sim3D optimization between two overlaped keyframes of two different maps: More...
 

Detailed Description

Optimizes a system of 3D points and keyframes. UUID: 35b9bdb7-d23c-4909-984f-ae7f9a292e6c

Member Function Documentation

◆ bundleAdjustment()

virtual double SolAR::api::solver::map::IBundler::bundleAdjustment ( SolAR::datastructure::CamCalibration K,
SolAR::datastructure::CamDistortion D,
const std::vector< uint32_t > &  selectKeyframes = {} 
)
pure virtual

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]selectKeyframesselected 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()

virtual double SolAR::api::solver::map::IBundler::optimizeSim3 ( SolAR::datastructure::CamCalibration K1,
SolAR::datastructure::CamCalibration K2,
const SRef< SolAR::datastructure::Keyframe > &  keyframe1,
const SRef< SolAR::datastructure::Keyframe > &  keyframe2,
const std::vector< SolAR::datastructure::DescriptorMatch > &  matches,
const std::vector< SolAR::datastructure::Point3Df > &  pts3D1,
const std::vector< SolAR::datastructure::Point3Df > &  pts3D2,
SolAR::datastructure::Transform3Df pose 
)
pure virtual

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()

virtual FrameworkReturnCode SolAR::api::solver::map::IBundler::setMap ( const SRef< SolAR::datastructure::Map map)
pure virtual

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: