49 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
57 void OdometryCallback(
const std::shared_ptr<localization::Gps>& odometry_msg);
59 void LidarCallback(
const std::shared_ptr<drivers::PointCloud>& lidar_msg);
62 const std::shared_ptr<drivers::gnss::InsStat>& status_msg);
78 void LidarMsgTransfer(
const std::shared_ptr<drivers::PointCloud>& message,
81 bool LoadLidarExtrinsic(
const std::string& file_path,
82 Eigen::Affine3d* lidar_extrinsic);
84 bool LoadLidarHeight(
const std::string& file_path,
LidarHeight* height);
86 bool LoadZoneIdFromFolder(
const std::string& folder_path,
int* zone_id);
88 bool QueryPoseFromTF(
double time, Eigen::Affine3d* pose);
91 bool QueryPoseFromBuffer(
double time, Eigen::Affine3d* pose);
93 bool ZeroOdometry(
const Eigen::Affine3d& pose);
97 void ComposeLocalizationEstimate(
98 const Eigen::Affine3d& pose,
99 const std::shared_ptr<localization::Gps>& odometry_msg,
101 void ComposeLidarResult(
double time_stamp,
const Eigen::Affine3d& pose,
107 bool FindNearestOdometryStatus(
const double odometry_timestamp,
111 std::string module_name_ =
"ndt_localization";
115 std::string tf_target_frame_id_ =
"";
116 std::string tf_source_frame_id_ =
"";
120 double max_height_ = 100.0;
121 int localization_seq_num_ = 0;
122 unsigned int resolution_id_ = 0;
123 double online_resolution_ = 2.0;
124 std::string map_path_ =
"";
126 Eigen::Affine3d lidar_pose_;
127 Eigen::Affine3d velodyne_extrinsic_;
129 double ndt_score_ = 0;
130 unsigned int bad_score_count_ = 0;
131 unsigned int bad_score_count_threshold_ = 10;
132 double warnning_ndt_score_ = 1.0;
133 double error_ndt_score_ = 2.0;
134 bool is_service_started_ =
false;
136 std::list<TimeStampPose, Eigen::aligned_allocator<TimeStampPose>>
138 std::mutex odometry_buffer_mutex_;
139 unsigned int odometry_buffer_size_ = 0;
140 const unsigned int max_odometry_buffer_size_ = 100;
145 std::list<drivers::gnss::InsStat> odometry_status_list_;
146 size_t odometry_status_list_max_size_ = 10;
147 std::mutex odometry_status_list_mutex_;
148 double odometry_status_time_diff_threshold_ = 1.0;
150 bool ndt_debug_log_flag_ =
false;