22 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
27 void set_frames(
const std::vector<SubMap::ConstPtr>& submaps,
const std::vector<Eigen::Isometry3d>& submap_poses,
const Eigen::Vector3d& center);
29 gtsam::NonlinearFactor::shared_ptr run();
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);
37 gtsam::NonlinearFactor::shared_ptr create_factor();
43 std::unique_ptr<guik::GLCanvas> canvas;
44 std::unique_ptr<guik::ProgressModal> progress_modal;
54 Eigen::Vector3d eigenvalues;
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;