|
GLIM
|
Odometry estimation-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 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. | |
Odometry estimation-related callbacks.
|
static |
PointCloud input callback.
| frame | Preprocessed point cloud frame |
|
static |
IMU input callback.
| stamp | Timestamp |
| linear_acc | Linear acceleration |
| angular_vel | Angular velocity |
|
static |
Odometry estimation frame marginalization callback.
| marginalized_frames | Marginalized odometry frames |
|
static |
Odometry estimation keyframe marginalization callback.
| marginalized_keyframes | Marginalized odometry keyframes |
|
static |
New odometry estimation frame creation callback (Sensor state predicted with IMU forward integration)
| frame | Odometry estimation frame (deskewed points and initial transformation estimate) |
|
static |
Smoother corruption callback.
|
static |
Odometry estimation optimization callback (just before optimization)
| smoother | FixedLagSmoother |
| new_factors | New factors to be inserted into the graph |
| new_values | New values to be inserted into the graph |
|
static |
Odometry estimation optimization callback (just after optimization)
| smoother | FixedLagSmoother |
|
static |
Odometry estimation frames update callback.
| frames | Updated frames |
|
static |
Odometry estimation keyframes update callback.
| keyframes | Updated keyframes |
|
static |
New odometry estimation frame update callback (Sensor state corrected with point cloud observation)
| frame | Updated odometry estimation frame |
on_update_frames with only the latest frame