3#include <glim/util/callback_slot.hpp>
4#include <glim/odometry/estimation_frame.hpp>
5#include <glim/mapping/sub_map.hpp>
15class NonlinearFactorGraph;
18namespace gtsam_points {
21class LevenbergMarquardtOptimizationStatus;
37 static CallbackSlot<void(
const double stamp,
const cv::Mat& image)> on_insert_image;
93 static CallbackSlot<void(
const double stamp,
const cv::Mat& image)> on_insert_image;
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