GLIM
Loading...
Searching...
No Matches
async_sub_mapping.hpp
1#pragma once
2
3#include <atomic>
4#include <thread>
5#include <glim/mapping/sub_mapping.hpp>
6#include <glim/util/concurrent_vector.hpp>
7
8namespace glim {
9
15public:
20 AsyncSubMapping(const std::shared_ptr<glim::SubMappingBase>& sub_mapping);
21
27
28#ifdef GLIM_USE_OPENCV
34 void insert_image(const double stamp, const cv::Mat& image);
35#endif
36
43 void insert_imu(const double stamp, const Eigen::Vector3d& linear_acc, const Eigen::Vector3d& angular_vel);
44
49 void insert_frame(const EstimationFrame::ConstPtr& odom_frame);
50
55 void join();
56
61 int workload() const;
62
67 std::vector<SubMap::Ptr> get_results();
68
69private:
70 void run();
71
72private:
73 std::atomic_bool kill_switch; // Flag to stop the thread immediately (Hard kill switch)
74 std::atomic_bool end_of_sequence; // Flag to stop the thread when the input queues become empty (Soft kill switch)
75 std::thread thread;
76
77#ifdef GLIM_USE_OPENCV
79#endif
82
83 ConcurrentVector<SubMap::Ptr> output_submap_queue;
84
85 std::shared_ptr<glim::SubMappingBase> sub_mapping;
86};
87
88} // namespace glim
SubMapping executor to wrap and asynchronously run a sub mapping object.
Definition async_sub_mapping.hpp:14
AsyncSubMapping(const std::shared_ptr< glim::SubMappingBase > &sub_mapping)
Construct a new Async Sub Mapping object.
void insert_frame(const EstimationFrame::ConstPtr &odom_frame)
Insert an odometry estimation frame.
void insert_imu(const double stamp, const Eigen::Vector3d &linear_acc, const Eigen::Vector3d &angular_vel)
Insert an IMU data.
int workload() const
Number of data in the input queue (for load control)
~AsyncSubMapping()
Destroy the Async Sub Mapping object.
void join()
Wait for the sub mapping thread.
std::vector< SubMap::Ptr > get_results()
Get the created submaps.
Simple thread-safe vector with mutex-lock.
Definition concurrent_vector.hpp:48