GLIM
Loading...
Searching...
No Matches
Static Public Attributes | List of all members
glim::SubMappingCallbacks Struct Reference

Sub mapping-related callbacks. More...

#include <callbacks.hpp>

Collaboration diagram for glim::SubMappingCallbacks:
Collaboration graph
[legend]

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.
 

Detailed Description

Sub mapping-related callbacks.

Member Data Documentation

◆ on_insert_frame

CallbackSlot<void(const EstimationFrame::ConstPtr& frame)> glim::SubMappingCallbacks::on_insert_frame
static

Odometry estimation result input callback.

Parameters
frameMarginalized odometry estimation frame

◆ on_insert_imu

CallbackSlot<void(const double stamp, const Eigen::Vector3d& linear_acc, const Eigen::Vector3d& angular_vel)> glim::SubMappingCallbacks::on_insert_imu
static

IMU input callback.

Parameters
stampTimestamp
linear_accLinear acceleration
angular_velAngular velocity

◆ on_new_keyframe

CallbackSlot<void(int id, const EstimationFrame::ConstPtr& keyframe)> glim::SubMappingCallbacks::on_new_keyframe
static

SubMap keyframe creation callback.

Parameters
idSubMap ID
keyframeNew keyframe

◆ on_new_submap

CallbackSlot<void(const SubMap::ConstPtr& submap)> glim::SubMappingCallbacks::on_new_submap
static

SubMap creation callback.

Parameters
submapNew SubMap

◆ on_optimization_status

CallbackSlot<void(const gtsam_points::LevenbergMarquardtOptimizationStatus& status, const gtsam::Values& values)> glim::SubMappingCallbacks::on_optimization_status
static

Optimization status callback.

Parameters
statusOptimization status
valuesCurrent estimate

◆ on_optimize_submap

CallbackSlot<void(gtsam::NonlinearFactorGraph& graph, gtsam::Values& values)> glim::SubMappingCallbacks::on_optimize_submap
static

SubMap optimization callback (just before optimization)

Parameters
graphFactor graph
valuesValues to be optimized

The documentation for this struct was generated from the following file: