GLIM
Loading...
Searching...
No Matches
odometry_estimation_imu.hpp
1#pragma once
2
3#include <map>
4#include <memory>
5#include <random>
6
7#include <glim/odometry/odometry_estimation_base.hpp>
8#include <gtsam_points/util/gtsam_migration.hpp>
9#include <gtsam_points/util/indexed_sliding_window.hpp>
10
11namespace gtsam {
12class Pose3;
13class Values;
14class ImuFactor;
15class NonlinearFactorGraph;
16} // namespace gtsam
17
18namespace gtsam_points {
19class IncrementalFixedLagSmootherExt;
20class IncrementalFixedLagSmootherExtWithFallback;
21} // namespace gtsam_points
22
23namespace glim {
24
25class IMUIntegration;
26class IMUValidation;
27class CloudDeskewing;
28class CloudCovarianceEstimation;
29class InitialStateEstimation;
30
35public:
36 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
37
40
41public:
42 // Sensor params;
43 bool fix_imu_bias;
44 double imu_bias_noise;
45 Eigen::Isometry3d T_lidar_imu;
46 Eigen::Matrix<double, 6, 1> imu_bias;
47
48 // Init state
49 std::string initialization_mode;
50 bool estimate_init_state;
51 Eigen::Isometry3d init_T_world_imu;
52 Eigen::Vector3d init_v_world_imu;
53 double init_pose_damping_scale;
54
55 // Optimization params
56 double smoother_lag;
57 bool use_isam2_dogleg;
58 double isam2_relinearize_skip;
59 double isam2_relinearize_thresh;
60
61 // Logging params
62 bool validate_imu;
63 bool save_imu_rate_trajectory;
64
65 int num_threads; // Number of threads for preprocessing and per-factor parallelism
66 int num_smoother_update_threads; // Number of threads for TBB parallelism in smoother update (should be kept 1)
67};
68
73public:
74 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
75
76 OdometryEstimationIMU(std::unique_ptr<OdometryEstimationIMUParams>&& params);
77 virtual ~OdometryEstimationIMU() override;
78
79 virtual void insert_imu(const double stamp, const Eigen::Vector3d& linear_acc, const Eigen::Vector3d& angular_vel) override;
80 virtual EstimationFrame::ConstPtr insert_frame(const PreprocessedFrame::Ptr& frame, std::vector<EstimationFrame::ConstPtr>& marginalized_frames) override;
81 virtual std::vector<EstimationFrame::ConstPtr> get_remaining_frames() override;
82
83protected:
84 virtual void create_frame(EstimationFrame::Ptr& frame) {}
85 virtual gtsam::NonlinearFactorGraph create_factors(const int current, const gtsam_points::shared_ptr<gtsam::ImuFactor>& imu_factor, gtsam::Values& new_values) = 0;
86
87 virtual void fallback_smoother() {}
88 virtual void update_frames(const int current, const gtsam::NonlinearFactorGraph& new_factors);
89
90 virtual void
91 update_smoother(const gtsam::NonlinearFactorGraph& new_factors, const gtsam::Values& new_values, const std::map<std::uint64_t, double>& new_stamp, int update_count = 0);
92 virtual void update_smoother(int update_count = 1);
93
94protected:
95 std::unique_ptr<OdometryEstimationIMUParams> params;
96
97 // Sensor extrinsic params
98 Eigen::Isometry3d T_lidar_imu;
99 Eigen::Isometry3d T_imu_lidar;
100
101 // Frames & keyframes
102 int marginalized_cursor;
104
105 // Utility classes
106 std::unique_ptr<InitialStateEstimation> init_estimation;
107 std::unique_ptr<IMUIntegration> imu_integration;
108 std::unique_ptr<IMUValidation> imu_validation;
109 std::unique_ptr<CloudDeskewing> deskewing;
110 std::unique_ptr<CloudCovarianceEstimation> covariance_estimation;
111
112 // Optimizer
114 std::unique_ptr<FixedLagSmootherExt> smoother;
115
116 std::shared_ptr<void> tbb_task_arena;
117};
118
119} // namespace glim
Odometry estimation base class.
Definition odometry_estimation_base.hpp:22
Base class for LiDAR-IMU odometry estimation.
Definition odometry_estimation_imu.hpp:72
virtual EstimationFrame::ConstPtr insert_frame(const PreprocessedFrame::Ptr &frame, std::vector< EstimationFrame::ConstPtr > &marginalized_frames) override
Insert a point cloud.
virtual void insert_imu(const double stamp, const Eigen::Vector3d &linear_acc, const Eigen::Vector3d &angular_vel) override
Insert an IMU data.
virtual std::vector< EstimationFrame::ConstPtr > get_remaining_frames() override
Pop out the remaining non-marginalized frames (called at the end of the sequence)
Definition loose_initial_state_estimation.hpp:9
Parameters for OdometryEstimationIMU.
Definition odometry_estimation_imu.hpp:34