GLIM
Loading...
Searching...
No Matches
sub_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/odometry/estimation_frame.hpp>
10#include <glim/mapping/sub_map.hpp>
11
12namespace spdlog {
13class logger;
14}
15
16namespace glim {
17
23public:
25 virtual ~SubMappingBase() {}
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_frame(const EstimationFrame::ConstPtr& frame);
49
54 virtual std::vector<SubMap::Ptr> get_submaps() = 0;
55
60 virtual std::vector<SubMap::Ptr> submit_end_of_sequence() { return std::vector<SubMap::Ptr>(); }
61
67 static std::shared_ptr<SubMappingBase> load_module(const std::string& so_name);
68
69protected:
70 // Logging
71 std::shared_ptr<spdlog::logger> logger;
72};
73} // namespace glim
Sub mapping base class.
Definition sub_mapping_base.hpp:22
virtual std::vector< SubMap::Ptr > submit_end_of_sequence()
Submit the signal to tell end of sequence and collect the remaining submap data.
Definition sub_mapping_base.hpp:60
virtual void insert_frame(const EstimationFrame::ConstPtr &frame)
Insert an odometry estimation frame.
virtual void insert_imu(const double stamp, const Eigen::Vector3d &linear_acc, const Eigen::Vector3d &angular_vel)
Insert an IMU data.
virtual std::vector< SubMap::Ptr > get_submaps()=0
Get the created submaps.
static std::shared_ptr< SubMappingBase > load_module(const std::string &so_name)
Load a sub mapping module from a shared library.