4#include <Eigen/Geometry>
6#include <opencv2/core.hpp>
9#include <glim/mapping/sub_map.hpp>
10#include <gtsam_points/types/point_cloud.hpp>
33 virtual void insert_image(
const double stamp,
const cv::Mat& image);
42 virtual void insert_imu(
const double stamp,
const Eigen::Vector3d& linear_acc,
const Eigen::Vector3d& angular_vel);
69 virtual void save(
const std::string& path) {}
74 virtual gtsam_points::PointCloud::Ptr
export_points() {
return nullptr; }
81 static std::shared_ptr<GlobalMappingBase>
load_module(
const std::string& so_name);
84 std::shared_ptr<spdlog::logger> logger;
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.