|
GLIM
|
Sub mapping-related callbacks. More...
#include <callbacks.hpp>

Static Public Attributes | |
| static CallbackSlot< void(const double stamp, const Eigen::Vector3d &linear_acc, const Eigen::Vector3d &angular_vel)> | on_insert_imu |
| IMU input callback. | |
| static CallbackSlot< void(const EstimationFrame::ConstPtr &frame)> | on_insert_frame |
| Odometry estimation result input callback. | |
| static CallbackSlot< void(int id, const EstimationFrame::ConstPtr &keyframe)> | on_new_keyframe |
| SubMap keyframe creation callback. | |
| static CallbackSlot< void(gtsam::NonlinearFactorGraph &graph, gtsam::Values &values)> | on_optimize_submap |
| SubMap optimization callback (just before optimization) | |
| static CallbackSlot< void(const gtsam_points::LevenbergMarquardtOptimizationStatus &status, const gtsam::Values &values)> | on_optimization_status |
| Optimization status callback. | |
| static CallbackSlot< void(const SubMap::ConstPtr &submap)> | on_new_submap |
| SubMap creation callback. | |
Sub mapping-related callbacks.
|
static |
Odometry estimation result input callback.
| frame | Marginalized odometry estimation frame |
|
static |
IMU input callback.
| stamp | Timestamp |
| linear_acc | Linear acceleration |
| angular_vel | Angular velocity |
|
static |
|
static |
|
static |
Optimization status callback.
| status | Optimization status |
| values | Current estimate |
|
static |
SubMap optimization callback (just before optimization)
| graph | Factor graph |
| values | Values to be optimized |