GLIM
Loading...
Searching...
No Matches
callbacks.hpp
1#pragma once
2
3#include <map>
4#include <glim/util/callback_slot.hpp>
5#include <glim/odometry/estimation_frame.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 IncrementalFixedLagSmootherExt;
20class IncrementalFixedLagSmootherExtWithFallback;
21} // namespace gtsam_points
22
23namespace glim {
24
29public:
35 static CallbackSlot<void(const PreprocessedFrame::ConstPtr& points, const Eigen::Isometry3d& T_odom_lidar)> on_updated;
36
41 static CallbackSlot<void(const EstimationFrame::ConstPtr& estimated_frame)> on_finished;
42};
43
49#ifdef GLIM_USE_OPENCV
55 static CallbackSlot<void(const double stamp, const cv::Mat& image)> on_insert_image;
56#endif
57
64 static CallbackSlot<void(const double stamp, const Eigen::Vector3d& linear_acc, const Eigen::Vector3d& angular_vel)> on_insert_imu;
65
70 static CallbackSlot<void(const PreprocessedFrame::Ptr& frame)> on_insert_frame;
71
76 static CallbackSlot<void(const EstimationFrame::ConstPtr& frame)> on_new_frame;
77
83 static CallbackSlot<void(const EstimationFrame::ConstPtr& frame)> on_update_new_frame;
84
91 static CallbackSlot<void(const std::vector<EstimationFrame::ConstPtr>& frames)> on_update_frames;
92
99 static CallbackSlot<void(const std::vector<EstimationFrame::ConstPtr>& keyframes)> on_update_keyframes;
100
105 static CallbackSlot<void(const std::vector<EstimationFrame::ConstPtr>& marginalized_frames)> on_marginalized_frames;
106
111 static CallbackSlot<void(const std::vector<EstimationFrame::ConstPtr>& marginalized_keyframes)> on_marginalized_keyframes;
112
119 static CallbackSlot<void(
120 gtsam_points::IncrementalFixedLagSmootherExtWithFallback& smoother,
121 gtsam::NonlinearFactorGraph& new_factors,
122 gtsam::Values& new_values,
123 std::map<std::uint64_t, double>& new_stamps)>
125
130 static CallbackSlot<void(gtsam_points::IncrementalFixedLagSmootherExtWithFallback& smoother)> on_smoother_update_finish;
131
137};
138
139} // namespace glim
Callback slot to hold and trigger multiple callbacks.
Definition callback_slot.hpp:11
IMU state initialization-related callbacks.
Definition callbacks.hpp:28
static CallbackSlot< void(const PreprocessedFrame::ConstPtr &points, const Eigen::Isometry3d &T_odom_lidar)> on_updated
Initialization update callback.
Definition callbacks.hpp:35
static CallbackSlot< void(const EstimationFrame::ConstPtr &estimated_frame)> on_finished
IMU state initialization termination callback.
Definition callbacks.hpp:41
Odometry estimation-related callbacks.
Definition callbacks.hpp:48
static CallbackSlot< void(gtsam_points::IncrementalFixedLagSmootherExtWithFallback &smoother)> on_smoother_update_finish
Odometry estimation optimization callback (just after optimization)
Definition callbacks.hpp:130
static CallbackSlot< void(const EstimationFrame::ConstPtr &frame)> on_update_new_frame
New odometry estimation frame update callback (Sensor state corrected with point cloud observation)
Definition callbacks.hpp:83
static CallbackSlot< void(const std::vector< EstimationFrame::ConstPtr > &keyframes)> on_update_keyframes
Odometry estimation keyframes update callback.
Definition callbacks.hpp:99
static CallbackSlot< void(const std::vector< EstimationFrame::ConstPtr > &marginalized_keyframes)> on_marginalized_keyframes
Odometry estimation keyframe marginalization callback.
Definition callbacks.hpp:111
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:64
static CallbackSlot< void(gtsam_points::IncrementalFixedLagSmootherExtWithFallback &smoother, gtsam::NonlinearFactorGraph &new_factors, gtsam::Values &new_values, std::map< std::uint64_t, double > &new_stamps)> on_smoother_update
Odometry estimation optimization callback (just before optimization)
Definition callbacks.hpp:124
static CallbackSlot< void(const PreprocessedFrame::Ptr &frame)> on_insert_frame
PointCloud input callback.
Definition callbacks.hpp:70
static CallbackSlot< void(const EstimationFrame::ConstPtr &frame)> on_new_frame
New odometry estimation frame creation callback (Sensor state predicted with IMU forward integration)
Definition callbacks.hpp:76
static CallbackSlot< void(const std::vector< EstimationFrame::ConstPtr > &marginalized_frames)> on_marginalized_frames
Odometry estimation frame marginalization callback.
Definition callbacks.hpp:105
static CallbackSlot< void(const std::vector< EstimationFrame::ConstPtr > &frames)> on_update_frames
Odometry estimation frames update callback.
Definition callbacks.hpp:91
static CallbackSlot< void(double)> on_smoother_corruption
Smoother corruption callback.
Definition callbacks.hpp:136