GLIM
Loading...
Searching...
No Matches
bundle_adjustment_modal.hpp
1#pragma once
2
3#include <gtsam/nonlinear/NonlinearFactor.h>
4#include <gtsam_points/types/point_cloud.hpp>
5#include <glk/drawable.hpp>
6
7#include <glim/mapping/sub_map.hpp>
8
9namespace guik {
10class GLCanvas;
11class ProgressModal;
12class ProgressInterface;
13} // namespace guik
14
15namespace glim {
16
21public:
22 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
23
26
27 void set_frames(const std::vector<SubMap::ConstPtr>& submaps, const std::vector<Eigen::Isometry3d>& submap_poses, const Eigen::Vector3d& center);
28
29 gtsam::NonlinearFactor::shared_ptr run();
30
31private:
32 void update_indicator();
33 std::vector<std::pair<int, int>> extract_points(double radius);
34 Eigen::Vector3d calc_eigenvalues(const std::vector<std::pair<int, int>>& point_indices);
35 double auto_radius(guik::ProgressInterface& progress);
36
37 gtsam::NonlinearFactor::shared_ptr create_factor();
38
39 void draw_canvas();
40
41private:
42 bool request_to_open;
43 std::unique_ptr<guik::GLCanvas> canvas;
44 std::unique_ptr<guik::ProgressModal> progress_modal;
45
46 float radius;
47 float min_radius;
48 float max_radius;
49 int min_points;
50 int max_points;
51 float plane_eps;
52
53 int num_points;
54 Eigen::Vector3d eigenvalues;
55
56 Eigen::Vector4d center;
57 std::vector<glim::SubMap::ConstPtr> submaps;
58 std::vector<std::shared_ptr<const glk::Drawable>> submap_drawables;
59 std::vector<Eigen::Isometry3d> submap_poses;
60};
61
62} // namespace glim
ImGUI modal for creating bundle adjustment factors.
Definition bundle_adjustment_modal.hpp:20