Applies a bundle adjustment to optimize a 3D map and keyframes. UUID: 4897fc13-682c-4e95-8aba-abd9f7a17193
More...
#include <SolARBundlerCeres.h>
|
void | unloadComponent () override final |
|
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 (CamCalibration &K1, 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, Transform3Df &pose) override |
| solve a non-linear problem related to sim3D optimization between two overlaped keyframes of two different maps: More...
|
|
Applies a bundle adjustment to optimize a 3D map and keyframes. UUID: 4897fc13-682c-4e95-8aba-abd9f7a17193
- Injectables
SolAR::api::storage::IPointCloudManager |
SolAR::api::storage::IKeyframesManager |
SolAR::api::storage::ICovisibilityGraphManager |
- Properties
iterationsCount | number of mx iterations number |
type: int; range : [0..MAX INT]; default: 10 |
fixedMap | fixing map control (0 = false, 1 = true) |
type: int; range : [0,1]; default: 0 |
fixedKeyframes | fixing extrinsic control (0 = false, 1 = true) |
type: int; range : [0,1]; default: 0 |
fixedIntrinsics | fixing extrinsic control (0 = false, 1 = true) |
type: int; range : [0,1]; default: 1 |
fixedFirstPose | fixing first pose control (0 = false, 1 = true) |
type: int; range : [0,1]; default: 1 |
fixedNeighbourKeyframes | fixing neighbour keyframes control (0 = false, 1 = true) |
type: int; range : [0,1]; default: 1 |
nbMaxFixedKeyframes | maximum number of fixed neighbour keyframes |
type: uint; range : [0..MAX UINT]; default: 100 |
useSpanningTree | (0 = false, 1 = true) |
type: int; range : [0..MAX INT]; default: 0 |
◆ bundleAdjustment()
double SolAR::MODULES::CERES::SolARBundlerCeres::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] | K | camera calibration parameters responsible of 3D points generation. |
[in,out] | D | camera 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::CERES::SolARBundlerCeres::optimizeSim3 |
( |
CamCalibration & |
K1, |
|
|
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, |
|
|
Transform3Df & |
pose |
|
) |
| |
|
override |
solve a non-linear problem related to sim3D optimization between two overlaped keyframes of two different maps:
- Parameters
-
[in] | K1 | camera calibration parameters responsible of 3D points generation from map 1. |
[in] | K2 | camera calibration parameters responsible of 3D points generation from map 2. |
[in] | keyframe1 | first overlapping keyframe from map 1. |
[in] | keyframe2 | second overlapping keyframe from map 2. |
[in] | matches | matches between two keyframes. |
[in] | pts3D1 | first set of 3D points. |
[in] | pts3D2 | second set of 3D points. |
[in,out] | pose | Sim3 matrix pose between map1 and map2 |
- Returns
- the mean re-projection error.
◆ setMap()
FrameworkReturnCode SolAR::MODULES::CERES::SolARBundlerCeres::setMap |
( |
const SRef< datastructure::Map > |
map | ) |
|
|
override |
set map reference to optimize
- Parameters
-
- Returns
- FrameworkReturnCode::SUCCESS if the map is set, else FrameworkReturnCode::_ERROR.
The documentation for this class was generated from the following file: