-
Notifications
You must be signed in to change notification settings - Fork 178
Add the rotation averager to GLOMAP #113
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Changes from 20 commits
2645de1
2b4346e
a0dc97b
150f1cf
7b40ec8
34f27b5
3224311
eb90ceb
ab2994e
cb8a81d
6aaef6e
1579996
7129c0c
19510e5
9d37415
0b6944d
610a74f
95f92cf
964f6bd
d801b74
b7a3ac2
5684246
0dc9a9b
79d5501
abbc491
b26ccbc
0274f85
aad2630
9f132ea
0189436
8818b41
db5bb79
f2366e1
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,62 @@ | ||
| # Gravity-aligned Rotation Averaging with Circular Regression | ||
|
|
||
| [Project page](https://lpanaf.github.io/eccv24_ra1dof/) | [Paper](https://www.ecva.net/papers/eccv_2024/papers_ECCV/papers/05651.pdf) | [Supp.](https://lpanaf.github.io/assets/pdf/eccv24_ra1dof_sm.pdf) | ||
| --- | ||
|
|
||
| ## About | ||
|
|
||
| This project aims at solving the rotation averaging problem with gravity prior. | ||
| To achieve this, circular regression is leveraged. | ||
|
|
||
| If you use this project for your research, please cite | ||
| ``` | ||
| @inproceedings{pan2024ra1dof, | ||
| author={Pan, Linfei and Pollefeys, Marc and Barath, Daniel}, | ||
| title={{Gravity-aligned Rotation Averaging with Circular Regression}}, | ||
| booktitle={European Conference on Computer Vision (ECCV)}, | ||
| year={2024}, | ||
| } | ||
| ``` | ||
|
|
||
| ## Getting Started | ||
| Install GLOMAP as instrcucted in [README](../README.md). | ||
| Then, call the rotation averager (3 degree-of-freedom) via | ||
| ``` | ||
| glomap rotation_averager --relpose_path RELPOSE_PATH --output_path OUTPUT_PATH | ||
| ``` | ||
|
|
||
| If gravity directions are available, call the rotation averager (1 degree-of-freedom) via | ||
| ``` | ||
| glomap rotation_averager \ | ||
| --relpose_path RELPOSE_PATH \ | ||
| --output_path OUTPUT_PATH \ | ||
| --gravity_path GRAVTIY PATH | ||
| ``` | ||
| It is recommended to set `--use_stratified=1` if only a subset of images have gravity direction. | ||
| If gravity measurements are subject to i.i.d. noise, they can be refined by setting `--refine_gravity=1`. | ||
|
|
||
|
|
||
| ## File Formats | ||
| ### Relative Pose | ||
| The relative pose file is expected to be of the following format | ||
| ``` | ||
| IMAGE_NAME_1 IMAGE_NAME_2 QW QX QY QZ TX TY TZ | ||
| ``` | ||
| Only images contained in at least one relative pose will be included in the following procedure. | ||
| The relative pose should be <sub>2</sub>R<sub>1</sub> x<sub>1</sub> + <sub>2</sub>t<sub>1</sub> = x<sub>2</sub>. | ||
|
|
||
| ### Gravity Direction | ||
| The gravity direction file is expected to be of the following format | ||
| ``` | ||
| IMAGE_NAME GX GY GZ | ||
| ``` | ||
| The gravity direction $g$ should $[0, 1, 0]$ if the image is parallel to the ground plane, and the estimated rotation would have the property that $R_i \cdot [0, 1, 0]^\top = g$. | ||
| If is acceptable if only a subset of all images have gravity direciton. | ||
| If the specified image name does not match any known image name from relative pose, it is ignored. | ||
|
|
||
| ### Output | ||
| The estimated global rotation will be in the following format | ||
| ``` | ||
| IMAGE_NAME QW QX QY QZ | ||
| ``` | ||
| Any images that are not within the largest connected component of the view-graph formed by the relative pose will be ignored. |
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,64 @@ | ||
| #include "rotation_averager.h" | ||
|
|
||
| namespace glomap { | ||
|
|
||
| bool RotationAverager::Solve(ViewGraph& view_graph, | ||
| std::unordered_map<image_t, Image>& images) { | ||
| view_graph.KeepLargestConnectedComponents(images); | ||
|
|
||
| bool solve_1dof_system = false; | ||
| solve_1dof_system = solve_1dof_system || options_.use_gravity; | ||
| solve_1dof_system = solve_1dof_system && options_.use_stratified; | ||
lpanaf marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
|
|
||
| ViewGraph view_graph_grav; | ||
| image_pair_t total_pairs = 0; | ||
| image_pair_t grav_pairs = 0; | ||
| if (solve_1dof_system) { | ||
| // Prepare two sets: ones all with gravity, and one does not have gravity. | ||
| // Solve them separately first, then solve them in a single system | ||
| for (const auto& [pair_id, image_pair] : view_graph.image_pairs) { | ||
| if (!image_pair.is_valid) continue; | ||
|
|
||
| image_t image_id1 = image_pair.image_id1; | ||
| image_t image_id2 = image_pair.image_id2; | ||
|
|
||
| Image& image1 = images[image_id1]; | ||
| Image& image2 = images[image_id2]; | ||
|
|
||
| if (!image1.is_registered || !image2.is_registered) continue; | ||
|
|
||
| total_pairs++; | ||
|
|
||
| if (image1.gravity_info.has_gravity && image2.gravity_info.has_gravity) { | ||
| view_graph_grav.image_pairs.emplace( | ||
| pair_id, | ||
| ImagePair(image_id1, image_id2, image_pair.cam2_from_cam1)); | ||
| grav_pairs++; | ||
| } | ||
| } | ||
| } | ||
|
|
||
| // If there is no image pairs with gravity or most image pairs are with | ||
| // gravity, then just run the 3dof version | ||
| bool status = false; | ||
| status = status || grav_pairs == 0; | ||
|
||
| status = status || grav_pairs > total_pairs * 0.95; | ||
| solve_1dof_system = solve_1dof_system && (!status); | ||
|
|
||
| if (solve_1dof_system) { | ||
| // Run the 1dof optimization | ||
| LOG(INFO) << "Solving subset 1DoF rotation averaging problem in the mixed " | ||
| "prior system"; | ||
| int num_img_grv = view_graph_grav.KeepLargestConnectedComponents(images); | ||
| RotationEstimator rotation_estimator_grav(options_); | ||
| if (!rotation_estimator_grav.EstimateRotations(view_graph_grav, images)) { | ||
| return false; | ||
| } | ||
| view_graph.KeepLargestConnectedComponents(images); | ||
| } | ||
|
|
||
| RotationEstimator rotation_estimator(options_); | ||
| return rotation_estimator.EstimateRotations(view_graph, images); | ||
| } | ||
|
|
||
| } // namespace glomap | ||
| Original file line number | Diff line number | Diff line change | ||||
|---|---|---|---|---|---|---|
| @@ -0,0 +1,22 @@ | ||||||
| #pragma once | ||||||
|
|
||||||
| #include "glomap/estimators/global_rotation_averaging.h" | ||||||
|
|
||||||
| namespace glomap { | ||||||
|
|
||||||
| struct RotationAveragerOptions : public RotationEstimatorOptions { | ||||||
| bool use_stratified = true; | ||||||
| }; | ||||||
|
|
||||||
| class RotationAverager { | ||||||
|
||||||
| public: | ||||||
| RotationAverager(const RotationAveragerOptions& options) | ||||||
|
||||||
| RotationAverager(const RotationAveragerOptions& options) | |
| explicit RotationAverager(const RotationAveragerOptions& options) |
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,87 @@ | ||
|
|
||
| #include "glomap/controllers/rotation_averager.h" | ||
|
|
||
| #include "glomap/controllers/option_manager.h" | ||
| #include "glomap/estimators/gravity_refinement.h" | ||
| #include "glomap/io/colmap_io.h" | ||
| #include "glomap/io/pose_io.h" | ||
| #include "glomap/types.h" | ||
|
|
||
| #include <colmap/util/misc.h> | ||
| #include <colmap/util/timer.h> | ||
|
|
||
| namespace glomap { | ||
| // ------------------------------------- | ||
| // Running Global Rotation Averager | ||
| // ------------------------------------- | ||
| int RunRotationAverager(int argc, char** argv) { | ||
| std::string relpose_path; | ||
| std::string output_path; | ||
| std::string gravity_path = ""; | ||
|
|
||
| bool use_stratified = true; | ||
| bool refine_gravity = false; | ||
|
|
||
| OptionManager options; | ||
| options.AddRequiredOption("relpose_path", &relpose_path); | ||
| options.AddRequiredOption("output_path", &output_path); | ||
| options.AddDefaultOption("gravity_path", &gravity_path); | ||
| options.AddDefaultOption("use_stratified", &use_stratified); | ||
| options.AddDefaultOption("refine_gravity", &refine_gravity); | ||
| options.AddGravityRefinerOptions(); | ||
| options.Parse(argc, argv); | ||
|
|
||
| if (!colmap::ExistsFile(relpose_path)) { | ||
| LOG(ERROR) << "`relpose_path` is not a file"; | ||
| return EXIT_FAILURE; | ||
| } | ||
|
|
||
| if (gravity_path != "" && !colmap::ExistsFile(gravity_path)) { | ||
| LOG(ERROR) << "`gravity_path` is not a file"; | ||
| return EXIT_FAILURE; | ||
| } | ||
|
|
||
| RotationAveragerOptions rotation_averager_options; | ||
| rotation_averager_options.skip_initialization = true; | ||
| rotation_averager_options.use_gravity = true; | ||
|
|
||
| rotation_averager_options.use_stratified = use_stratified; | ||
|
|
||
| // Load the database | ||
| ViewGraph view_graph; | ||
| std::unordered_map<image_t, Image> images; | ||
|
|
||
| ReadRelPose(relpose_path, images, view_graph); | ||
|
|
||
| if (gravity_path != "") { | ||
| ReadGravity(gravity_path, images); | ||
| } | ||
|
|
||
| int num_img = view_graph.KeepLargestConnectedComponents(images); | ||
| LOG(INFO) << num_img << " / " << images.size() | ||
| << " are within the largest connected component"; | ||
|
|
||
| if (refine_gravity && gravity_path != "") { | ||
| GravityRefiner grav_refiner(*options.gravity_refiner); | ||
| grav_refiner.RefineGravity(view_graph, images); | ||
| } | ||
|
|
||
| RotationAverager rotation_averager(rotation_averager_options); | ||
| colmap::Timer run_timer; | ||
| run_timer.Start(); | ||
| if (!rotation_averager.Solve(view_graph, images)) { | ||
| LOG(ERROR) << "Failed to solve global rotation averaging"; | ||
| return EXIT_FAILURE; | ||
| } | ||
| run_timer.Pause(); | ||
| LOG(INFO) << "Global rotation averaging done in " | ||
| << run_timer.ElapsedSeconds() << " seconds"; | ||
|
|
||
| // Write out the estimated rotation | ||
| WriteGlobalRotation(output_path, images); | ||
| LOG(INFO) << "Global rotation averaging done" << std::endl; | ||
|
|
||
| return EXIT_SUCCESS; | ||
| } | ||
|
|
||
| } // namespace glomap |
Uh oh!
There was an error while loading. Please reload this page.