GLIM
Loading...
Searching...
No Matches
callbacks.hpp
1#pragma once
2
3#include <glim/util/callback_slot.hpp>
4#include <glim/odometry/estimation_frame.hpp>
5#include <glim/mapping/sub_map.hpp>
6
7#ifdef GLIM_USE_OPENCV
8namespace cv {
9class Mat;
10}
11#endif
12
13namespace gtsam {
14class Values;
15class NonlinearFactorGraph;
16} // namespace gtsam
17
18namespace gtsam_points {
19class ISAM2Ext;
20class ISAM2ResultExt;
21class LevenbergMarquardtOptimizationStatus;
22} // namespace gtsam_points
23
24namespace glim {
25
31#ifdef GLIM_USE_OPENCV
37 static CallbackSlot<void(const double stamp, const cv::Mat& image)> on_insert_image;
38#endif
39
46 static CallbackSlot<void(const double stamp, const Eigen::Vector3d& linear_acc, const Eigen::Vector3d& angular_vel)> on_insert_imu;
47
52 static CallbackSlot<void(const EstimationFrame::ConstPtr& frame)> on_insert_frame;
53
59 static CallbackSlot<void(int id, const EstimationFrame::ConstPtr& keyframe)> on_new_keyframe;
60
66 static CallbackSlot<void(gtsam::NonlinearFactorGraph& graph, gtsam::Values& values)> on_optimize_submap;
67
73 static CallbackSlot<void(const gtsam_points::LevenbergMarquardtOptimizationStatus& status, const gtsam::Values& values)> on_optimization_status;
74
79 static CallbackSlot<void(const SubMap::ConstPtr& submap)> on_new_submap;
80};
81
87#ifdef GLIM_USE_OPENCV
93 static CallbackSlot<void(const double stamp, const cv::Mat& image)> on_insert_image;
94#endif
95
102 static CallbackSlot<void(const double stamp, const Eigen::Vector3d& linear_acc, const Eigen::Vector3d& angular_vel)> on_insert_imu;
103
110 static CallbackSlot<void(const SubMap::ConstPtr& submap)> on_insert_submap;
111
118 static CallbackSlot<void(const std::vector<SubMap::Ptr>& submaps)> on_update_submaps;
119
126 static CallbackSlot<void(gtsam_points::ISAM2Ext& isam2, gtsam::NonlinearFactorGraph& new_factors, gtsam::Values& new_values)> on_smoother_update;
127
133 static CallbackSlot<void(gtsam_points::ISAM2Ext& isam2, const gtsam_points::ISAM2ResultExt& result)> on_smoother_update_result;
134
140
146
153};
154} // namespace glim
Callback slot to hold and trigger multiple callbacks.
Definition callback_slot.hpp:11
Global mapping-related callbacks.
Definition callbacks.hpp:86
static CallbackSlot< void()> request_to_recover
Request the global mapping module to detect and recover from a graph corruption.
Definition callbacks.hpp:145
static CallbackSlot< void()> request_to_optimize
Request the global mapping module to perform optimization.
Definition callbacks.hpp:139
static CallbackSlot< void(double)> request_to_find_overlapping_submaps
Request the global mapping module to find new overlapping submaps.
Definition callbacks.hpp:152
static CallbackSlot< void(const double stamp, const Eigen::Vector3d &linear_acc, const Eigen::Vector3d &angular_vel)> on_insert_imu
IMU input callback.
Definition callbacks.hpp:102
static CallbackSlot< void(const std::vector< SubMap::Ptr > &submaps)> on_update_submaps
SubMap states update callback.
Definition callbacks.hpp:118
static CallbackSlot< void(const SubMap::ConstPtr &submap)> on_insert_submap
SubMap input callback.
Definition callbacks.hpp:110
static CallbackSlot< void(gtsam_points::ISAM2Ext &isam2, gtsam::NonlinearFactorGraph &new_factors, gtsam::Values &new_values)> on_smoother_update
Global optimization callback (just before optimization)
Definition callbacks.hpp:126
static CallbackSlot< void(gtsam_points::ISAM2Ext &isam2, const gtsam_points::ISAM2ResultExt &result)> on_smoother_update_result
Global optimization result callback (just after optimization)
Definition callbacks.hpp:133
Sub mapping-related callbacks.
Definition callbacks.hpp:30
static CallbackSlot< void(gtsam::NonlinearFactorGraph &graph, gtsam::Values &values)> on_optimize_submap
SubMap optimization callback (just before optimization)
Definition callbacks.hpp:66
static CallbackSlot< void(int id, const EstimationFrame::ConstPtr &keyframe)> on_new_keyframe
SubMap keyframe creation callback.
Definition callbacks.hpp:59
static CallbackSlot< void(const gtsam_points::LevenbergMarquardtOptimizationStatus &status, const gtsam::Values &values)> on_optimization_status
Optimization status callback.
Definition callbacks.hpp:73
static CallbackSlot< void(const SubMap::ConstPtr &submap)> on_new_submap
SubMap creation callback.
Definition callbacks.hpp:79
static CallbackSlot< void(const double stamp, const Eigen::Vector3d &linear_acc, const Eigen::Vector3d &angular_vel)> on_insert_imu
IMU input callback.
Definition callbacks.hpp:46
static CallbackSlot< void(const EstimationFrame::ConstPtr &frame)> on_insert_frame
Odometry estimation result input callback.
Definition callbacks.hpp:52