93 bool GetPredictPose(
const double lidar_time,
TransformD *inspva_pose,
97 void UpdateState(
const int ret,
const double time);
100 bool LoadLidarExtrinsic(
const std::string &file_path,
103 bool LoadLidarHeight(
const std::string &file_path,
LidarHeight *height);
105 double ComputeDeltaYawLimit(
const int64_t index_cur,
106 const int64_t index_stable,
107 const double limit_min,
const double limit_max);
112 PoseForcast *pose_forecastor_;
114 std::string map_path_;
115 std::string lidar_extrinsic_file_;
116 std::string lidar_height_file_;
117 int localization_mode_ = 2;
118 int yaw_align_mode_ = 2;
119 int lidar_filter_size_ = 17;
120 double delta_yaw_limit_ = 0.00436;
121 double init_delta_yaw_limit_ = 0.02618;
122 double compensate_pitch_roll_limit_ = 0.035;
123 int utm_zone_id_ = 50;
124 double map_coverage_theshold_ = 0.8;
128 bool is_get_first_lidar_msg_ =
false;
134 double pre_location_time_ = 0;
145 bool reinit_flag_ =
false;
148 bool if_use_avx_ =
false;
151 double imu_lidar_max_delay_time_ = 0.4;
153 bool is_unstable_reset_ =
false;
154 int unstable_count_ = 0;
155 double unstable_threshold_ = 0.3;
157 int out_map_count_ = 0;
161 int64_t forecast_timer_ = 0;
163 static constexpr double DEG_TO_RAD = 0.017453292519943;
167 EIGEN_MAKE_ALIGNED_OPERATOR_NEW