36 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
44 double imu_bias_noise;
45 Eigen::Isometry3d T_lidar_imu;
46 Eigen::Matrix<double, 6, 1> imu_bias;
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;
57 bool use_isam2_dogleg;
58 double isam2_relinearize_skip;
59 double isam2_relinearize_thresh;
63 bool save_imu_rate_trajectory;
66 int num_smoother_update_threads;
74 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
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;
84 virtual void create_frame(EstimationFrame::Ptr& frame) {}
87 virtual void fallback_smoother() {}
88 virtual void update_frames(
const int current,
const gtsam::NonlinearFactorGraph& new_factors);
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);
95 std::unique_ptr<OdometryEstimationIMUParams> params;
98 Eigen::Isometry3d T_lidar_imu;
99 Eigen::Isometry3d T_imu_lidar;
102 int marginalized_cursor;
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;
114 std::unique_ptr<FixedLagSmootherExt> smoother;
116 std::shared_ptr<void> tbb_task_arena;