GLIM
Loading...
Searching...
No Matches
global_mapping_base.hpp
1#pragma once
2
3#include <Eigen/Core>
4#include <Eigen/Geometry>
5#ifdef GLIM_USE_OPENCV
6#include <opencv2/core.hpp>
7#endif
8
9#include <glim/mapping/sub_map.hpp>
10#include <gtsam_points/types/point_cloud.hpp>
11
12namespace spdlog {
13class logger;
14}
15
16namespace glim {
17
23public:
25 virtual ~GlobalMappingBase() {}
26
27#ifdef GLIM_USE_OPENCV
33 virtual void insert_image(const double stamp, const cv::Mat& image);
34#endif
35
42 virtual void insert_imu(const double stamp, const Eigen::Vector3d& linear_acc, const Eigen::Vector3d& angular_vel);
43
48 virtual void insert_submap(const SubMap::Ptr& submap);
49
53 virtual void find_overlapping_submaps(double min_overlap);
54
58 virtual void optimize();
59
63 virtual void recover_graph();
64
69 virtual void save(const std::string& path) {}
70
74 virtual gtsam_points::PointCloud::Ptr export_points() { return nullptr; }
75
81 static std::shared_ptr<GlobalMappingBase> load_module(const std::string& so_name);
82
83protected:
84 std::shared_ptr<spdlog::logger> logger;
85};
86} // namespace glim
Global mapping base class.
Definition global_mapping_base.hpp:22
virtual void insert_imu(const double stamp, const Eigen::Vector3d &linear_acc, const Eigen::Vector3d &angular_vel)
Insert an IMU frame.
virtual gtsam_points::PointCloud::Ptr export_points()
Export all the submap points.
Definition global_mapping_base.hpp:74
virtual void save(const std::string &path)
Save the mapping result.
Definition global_mapping_base.hpp:69
virtual void optimize()
Request to perform optimization.
virtual void recover_graph()
Request to detect and recover graph corruption.
static std::shared_ptr< GlobalMappingBase > load_module(const std::string &so_name)
Load a global mapping module from a shared library.
virtual void find_overlapping_submaps(double min_overlap)
Request to find new overlapping submaps.
virtual void insert_submap(const SubMap::Ptr &submap)
Insert a SubMap.