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

Odometry estimation-related callbacks. More...

#include <callbacks.hpp>

Collaboration diagram for glim::OdometryEstimationCallbacks:
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 PreprocessedFrame::Ptr &frame)> on_insert_frame
 PointCloud input callback.
 
static CallbackSlot< void(const EstimationFrame::ConstPtr &frame)> on_new_frame
 New odometry estimation frame creation callback (Sensor state predicted with IMU forward integration)
 
static CallbackSlot< void(const EstimationFrame::ConstPtr &frame)> on_update_new_frame
 New odometry estimation frame update callback (Sensor state corrected with point cloud observation)
 
static CallbackSlot< void(const std::vector< EstimationFrame::ConstPtr > &frames)> on_update_frames
 Odometry estimation frames update callback.
 
static CallbackSlot< void(const std::vector< EstimationFrame::ConstPtr > &keyframes)> on_update_keyframes
 Odometry estimation keyframes update callback.
 
static CallbackSlot< void(const std::vector< EstimationFrame::ConstPtr > &marginalized_frames)> on_marginalized_frames
 Odometry estimation frame marginalization callback.
 
static CallbackSlot< void(const std::vector< EstimationFrame::ConstPtr > &marginalized_keyframes)> on_marginalized_keyframes
 Odometry estimation keyframe marginalization callback.
 
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)
 
static CallbackSlot< void(gtsam_points::IncrementalFixedLagSmootherExtWithFallback &smoother)> on_smoother_update_finish
 Odometry estimation optimization callback (just after optimization)
 
static CallbackSlot< void(double)> on_smoother_corruption
 Smoother corruption callback.
 

Detailed Description

Odometry estimation-related callbacks.

Member Data Documentation

◆ on_insert_frame

CallbackSlot<void(const PreprocessedFrame::Ptr& frame)> glim::OdometryEstimationCallbacks::on_insert_frame
static

PointCloud input callback.

Parameters
framePreprocessed point cloud frame

◆ on_insert_imu

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

IMU input callback.

Parameters
stampTimestamp
linear_accLinear acceleration
angular_velAngular velocity

◆ on_marginalized_frames

CallbackSlot<void(const std::vector<EstimationFrame::ConstPtr>& marginalized_frames)> glim::OdometryEstimationCallbacks::on_marginalized_frames
static

Odometry estimation frame marginalization callback.

Parameters
marginalized_framesMarginalized odometry frames

◆ on_marginalized_keyframes

CallbackSlot<void(const std::vector<EstimationFrame::ConstPtr>& marginalized_keyframes)> glim::OdometryEstimationCallbacks::on_marginalized_keyframes
static

Odometry estimation keyframe marginalization callback.

Parameters
marginalized_keyframesMarginalized odometry keyframes

◆ on_new_frame

CallbackSlot<void(const EstimationFrame::ConstPtr& frame)> glim::OdometryEstimationCallbacks::on_new_frame
static

New odometry estimation frame creation callback (Sensor state predicted with IMU forward integration)

Parameters
frameOdometry estimation frame (deskewed points and initial transformation estimate)

◆ on_smoother_corruption

CallbackSlot<void(double)> glim::OdometryEstimationCallbacks::on_smoother_corruption
static

Smoother corruption callback.

Note
We should not forget that FixedLagSmoothers are in "gtsam_unstable" directory!!

◆ on_smoother_update

CallbackSlot<void( gtsam_points::IncrementalFixedLagSmootherExtWithFallback& smoother, gtsam::NonlinearFactorGraph& new_factors, gtsam::Values& new_values, std::map<std::uint64_t, double>& new_stamps)> glim::OdometryEstimationCallbacks::on_smoother_update
static

Odometry estimation optimization callback (just before optimization)

Parameters
smootherFixedLagSmoother
new_factorsNew factors to be inserted into the graph
new_valuesNew values to be inserted into the graph

◆ on_smoother_update_finish

CallbackSlot<void(gtsam_points::IncrementalFixedLagSmootherExtWithFallback& smoother)> glim::OdometryEstimationCallbacks::on_smoother_update_finish
static

Odometry estimation optimization callback (just after optimization)

Parameters
smootherFixedLagSmoother

◆ on_update_frames

CallbackSlot<void(const std::vector<EstimationFrame::ConstPtr>& frames)> glim::OdometryEstimationCallbacks::on_update_frames
static

Odometry estimation frames update callback.

Parameters
framesUpdated frames
Note
Sensor states will be updated in the odometry estimation thread Accessing them from another thread is not thread-safe

◆ on_update_keyframes

CallbackSlot<void(const std::vector<EstimationFrame::ConstPtr>& keyframes)> glim::OdometryEstimationCallbacks::on_update_keyframes
static

Odometry estimation keyframes update callback.

Parameters
keyframesUpdated keyframes
Note
Sensor states will be updated in the odometry estimation thread Accessing them from another thread is not thread-safe

◆ on_update_new_frame

CallbackSlot<void(const EstimationFrame::ConstPtr& frame)> glim::OdometryEstimationCallbacks::on_update_new_frame
static

New odometry estimation frame update callback (Sensor state corrected with point cloud observation)

Parameters
frameUpdated odometry estimation frame
Note
This is equivalent to on_update_frames with only the latest frame

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