# PoseLib
This library provides a collection of minimal solvers for camera pose estimation. The focus is on calibrated absolute pose estimation problems from different types of correspondences (e.g. point-point, point-line, line-point, line-line).
The goals of this project are to provide
* Fast and robust implementation of the current state-of-the-art solvers.
* Consistent calling interface between different solvers.
* Minimize dependencies, both external (currently only [Eigen](http://eigen.tuxfamily.org/)) and internal. Each solver is (mostly) stand-alone, making it easy to extract only a specific solver to integrate into other frameworks.
* Robust estimators (based on LO-RANSAC) that just works out-of-the-box for most cases.
# Robust Estimation and Non-linear Refinement
We provide robust estimators for the most common problems
* Absolute pose from points (and lines)
* Essential / Fundamental matrix
* Homography
* Generalized relative pose
It is fairly straight-forward to implement robust estimators for other problems. See for example [absolute_pose.h](PoseLib/robust/estimators/absolute_pose.h). If you implement estimators for other problems, please consider submitting a pull-request.
In [robust.h](PoseLib/robust.h) we provide interfaces which normalizes the data, calls the RANSAC and runs a post-RANSAC non-linear refinement. It is also possible to directly call the individual components as well (see e.g. [ransac.h](PoseLib/robust/ransac.h), [bundle.h](PoseLib/robust/bundle.h), etc.). The RANSAC is straight-forward implementation of LO-RANSAC which generate hypothesis with minimal solvers and relies on non-linear refinement for refitting.
The robust estimator takes the following options
```c++
struct RansacOptions {
size_t max_iterations = 100000;
size_t min_iterations = 1000;
double dyn_num_trials_mult = 3.0;
double success_prob = 0.9999;
double max_reproj_error = 12.0; // used for 2D-3D matches
double max_epipolar_error = 1.0; // used for 2D-2D matches
unsigned long seed = 0;
// If we should use PROSAC sampling. Assumes data is sorted
bool progressive_sampling = false;
size_t max_prosac_iterations = 100000;
// Whether to use real focal length checking for F estimation: https://arxiv.org/abs/2311.16304
// Assumes that principal points of both cameras are at origin.
bool real_focal_check = false;
};
```
and the non-linear refinement
```c++
struct BundleOptions {
size_t max_iterations = 100;
enum LossType {
TRIVIAL, TRUNCATED, HUBER, CAUCHY, TRUNCATED_LE_ZACH
} loss_type = LossType::CAUCHY;
double loss_scale = 1.0;
double gradient_tol = 1e-8;
double step_tol = 1e-8;
double initial_lambda = 1e-3;
double min_lambda = 1e-10;
double max_lambda = 1e10;
bool verbose = false;
};
```
Note that in [robust.h](PoseLib/robust.h) this is only used for the post-RANSAC refinement.
In [bundle.h](PoseLib/robust/bundle.h) we provide non-linear refinement for different problems. Mainly minimizing reprojection error and Sampson error as these performed best in our internal evaluations. These are used in the LO-RANSAC to perform non-linear refitting. Most estimators directly minimize the MSAC score (using `loss_type = TRUNCATED` and `loss_scale = threshold`) over all input correspondences. In practice we found that this works quite well and avoids recursive LO where inliers are added in steps.
## Camera models
PoseLib use [COLMAP](https://colmap.github.io/cameras.html)-compatible camera models. These are defined in [colmap_models.h](PoseLib/misc/colmap_models.h). Currently we only support
* SIMPLE_PINHOLE
* PINHOLE
* SIMPLE_RADIAL
* RADIAL
* OPENCV
but it is relatively straight-forward to add other models. If you do so please consider opening a pull-request. In contrast to COLMAP, we require analytical jacobians for the distortion mappings which make it a bit more work to port them.
The `Camera` struct currently contains `width`/`height` fields, however these are not used anywhere in the code-base and are provided simply to be consistent with COLMAP. The `Camera` class also provides the helper function `initialize_from_txt(str)` which initializes the camera from a line given by the `cameras.txt` file of a COLMAP reconstruction.
The python bindings also expose the `poselib.Camera` class with `focal(), focal_x(), focal_y(), model_name(), prinicipal_point()` read-only methods and a read-write `params` property, but currently this is only used as a return type for some methods. To supply camera information to robust estimators you should use python `dicts` as shown below.
## Python bindings
The python bindings can be installed by running `pip install .`. The python bindings expose all minimal solvers, e.g. `poselib.p3p(x,X)`, as well as all robust estimators from [robust.h](PoseLib/robust.h).
Examples of how the robust estimators can be called are
```python
camera = {'model': 'SIMPLE_PINHOLE', 'width': 1200, 'height': 800, 'params': [960, 600, 400]}
pose, info = poselib.estimate_absolute_pose(p2d, p3d, camera, {'max_reproj_error': 16.0}, {})
```
or
```python
F, info = poselib.estimate_fundamental_matrix(p2d_1, p2d_2, {'max_epipolar_error': 0.75, 'progressive_sampling': True}, {})
```
The return value `info` is a dict containing information about the robust estimation (inliers, iterations, etc). The last two options are dicts which describe the `RansacOptions` and `BundleOptions`. Ommited values are set to their default (see above), except for the `loss_scale` used for the Cauchy loss which is set to half of the threshold used in RANSAC (which seems to be a good heuristic). Dicts with the default options can be obtained as `opt = poselib.RansacOptions()` or `poselib.BundleOptions()`.
Some of the available estimators are listed below, check [pyposelib.cpp](pybind/pyposelib.cpp) and [robust.h](PoseLib/robust.h) for more details. The table also shows which error threshold is used in the estimation (`RansacOptions.max_reproj_error` or `RansacOptions.max_epipolar_error`). All thresholds are given in pixels.
| Method | Arguments | (RansacOptions) Threshold |
| --- | --- | --- |
| <sub>`estimate_absolute_pose`</sub> | <sub> `(p2d, p3d, camera, ransac_opt,bundle_opt)`</sub> | <sub>`max_reproj_error` </sub> |
| <sub>`estimate_absolute_pose_pnpl`</sub> | <sub>`(p2d, p3d, l2d_1, l2d_2, l3d_1, l3d_2, camera, ransac_opt, bundle_opt)` </sub> | <sub>`max_reproj_error` (points), `max_epipolar_error` (lines) |
| <sub>`estimate_generalized_absolute_pose` | <sub>`(p2ds, p3ds, camera_ext, cameras, ransac_opt, bundle_opt)`</sub> | <sub>`max_reproj_error`</sub> |
| <sub>`estimate_relative_pose`</sub> | <sub>`(x1, x2, camera1, camera2, ransac_opt, bundle_opt)`</sub> | <sub>`max_epipolar_error` </sub>|
| <sub>`estimate_shared_focal_relative_pose`</sub> | <sub>`(x1, x2, pp, ransac_opt, bundle_opt)`</sub> | <sub>`max_epipolar_error` </sub>|
| <sub>`estimate_fundamental`</sub> | <sub>`(x1, x2, ransac_opt, bundle_opt)`</sub> | <sub>`max_epipolar_error`</sub> |
| <sub>`estimate_homography`</sub> | <sub>`(x1, x2, ransac_opt, bundle_opt)`</sub> | <sub>`max_reproj_error`</sub> |
| <sub>`estimate_generalized_relative_pose`</sub> | <sub>`(matches, camera1_ext, cameras1, camera2_ext, cameras2, ransac_opt, bundle_opt)`</sub> | <sub>`max_epipolar_error`</sub> |
### Storing poses and estimated camera parameters
To handle poses and cameras we provide the following classes:
- `CameraPose`: This class is the return type for the most of the methods. While the class internally represent the pose with `q` and `t`, it also exposes `R` (3x3) and `Rt` (3x4) which are read/write, i.e. you can do `pose.R = Rnew` and it will update the underlying quaternion `q`.
- `Image`: Following COLMAP, this class stores information about the camera (`image.camera`) and its pose (`image.pose`) used to take an image.
- `ImagePair`: This class holds information about two cameras (`image_pair.camera1`, `image_pair.
没有合适的资源?快使用搜索试试~ 我知道了~
相机姿态校准-基于C++实现的用于校准相机姿态估计的最小求解器-附项目源码-优质项目实战.zip
共368个文件
h:90个
py:62个
cpp:51个
1.该资源内容由用户上传,如若侵权请联系客服进行举报
2.虚拟产品一经售出概不退款(资源遇到问题,请及时私信上传者)
2.虚拟产品一经售出概不退款(资源遇到问题,请及时私信上传者)
版权申诉
0 下载量 107 浏览量
2024-05-14
15:36:29
上传
评论
收藏 1.19MB ZIP 举报
温馨提示
相机姿态校准_基于C++实现的用于校准相机姿态估计的最小求解器_附项目源码_优质项目实战
资源推荐
资源详情
资源评论
收起资源包目录
相机姿态校准-基于C++实现的用于校准相机姿态估计的最小求解器-附项目源码-优质项目实战.zip (368个子文件)
gen_relpose_6pt.cc 129KB
relpose_6pt_focal.cc 95KB
pyposelib.cc 45KB
up1p2pl.cc 37KB
qep.cc 35KB
bundle.cc 31KB
re3q3.cc 27KB
relpose_5pt.cc 25KB
problem_generator.cc 24KB
robust.cc 23KB
colmap_models.cc 21KB
benchmark.cc 19KB
utils.cc 18KB
p2p2pl.cc 16KB
relative_pose.cc 11KB
p4pf.cc 10KB
ransac.cc 10KB
p3p.cc 9KB
essential.cc 9KB
gp4ps.cc 9KB
p5lp_radial.cc 9KB
gen_relpose_upright_4pt.cc 8KB
univariate.cc 8KB
p3p_ding.cc 8KB
ugp4pl.cc 8KB
absolute_pose.cc 7KB
up4pl.cc 5KB
sampling.cc 5KB
relpose_upright_3pt.cc 4KB
ugp3ps.cc 4KB
relpose_8pt.cc 4KB
up2p.cc 4KB
up1p1ll.cc 4KB
relpose_upright_planar_2pt.cc 4KB
hybrid_pose.cc 3KB
ugp2p.cc 3KB
p2p1ll.cc 3KB
p1p2ll.cc 3KB
homography_4pt.cc 3KB
gp3p.cc 3KB
relpose_7pt.cc 3KB
p6lp.cc 3KB
p3ll.cc 3KB
homography.cc 3KB
relpose_upright_planar_3pt.cc 2KB
gen_relpose_5p1pt.cc 1KB
setup.cfg 2KB
.clang-format 996B
.clang-format 229B
.clang-tidy 3KB
pybind11Common.cmake 14KB
FindPythonLibsNew.cmake 11KB
pybind11NewTools.cmake 9KB
pybind11Tools.cmake 8KB
SetEnv.cmake 4KB
LibraryConfig.cmake 3KB
FindEigen3.cmake 3KB
CMakeRegistry.cmake 3KB
FindCatch.cmake 2KB
JoinPaths.cmake 817B
CODEOWNERS 182B
.codespell-ignore-lines 1KB
test_pytypes.cpp 30KB
test_class.cpp 24KB
test_virtual_functions.cpp 22KB
test_stl.cpp 21KB
test_methods_and_attributes.cpp 21KB
test_sequences_and_iterators.cpp 21KB
test_numpy_dtypes.cpp 21KB
test_numpy_array.cpp 19KB
test_eigen_matrix.cpp 19KB
test_smart_ptr.cpp 18KB
test_factory_constructors.cpp 18KB
test_interpreter.cpp 16KB
test_builtin_casters.cpp 16KB
test_multiple_inheritance.cpp 12KB
test_exceptions.cpp 12KB
test_copy_move.cpp 11KB
test_callbacks.cpp 11KB
test_kwargs_and_defaults.cpp 9KB
test_operator_overloading.cpp 9KB
test_buffers.cpp 8KB
test_custom_type_casters.cpp 7KB
test_pickling.cpp 7KB
pybind11_cross_module_tests.cpp 6KB
test_enum.cpp 6KB
test_constants_and_functions.cpp 5KB
test_gil_scoped.cpp 5KB
test_stl_binders.cpp 5KB
test_tagbased_polymorphic.cpp 5KB
test_docstring_options.cpp 4KB
pybind11_tests.cpp 4KB
test_numpy_vectorize.cpp 4KB
test_local_bindings.cpp 4KB
test_modules.cpp 4KB
test_call_policies.cpp 4KB
test_iostream.cpp 4KB
test_const_name.cpp 4KB
cross_module_gil_utils.cpp 3KB
test_chrono.cpp 3KB
共 368 条
- 1
- 2
- 3
- 4
资源评论
极智视界
- 粉丝: 2w+
- 资源: 1600
下载权益
C知道特权
VIP文章
课程特权
开通VIP
上传资源 快速赚钱
- 我的内容管理 展开
- 我的资源 快来上传第一个资源
- 我的收益 登录查看自己的收益
- 我的积分 登录查看自己的积分
- 我的C币 登录后查看C币余额
- 我的收藏
- 我的下载
- 下载帮助
安全验证
文档复制为VIP权益,开通VIP直接复制
信息提交成功