Apollo 10.0
自动驾驶开放平台
ndt_localization.h
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2018 The Apollo Authors. All Rights Reserved.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *****************************************************************************/
16#pragma once
17
18#include <list>
19#include <memory>
20#include <string>
21
22#include "Eigen/Geometry"
23#include "modules/common_msgs/sensor_msgs/ins.pb.h"
24#include "modules/common_msgs/sensor_msgs/pointcloud.pb.h"
27#include "modules/common_msgs/localization_msgs/gps.pb.h"
28#include "modules/common_msgs/localization_msgs/localization.pb.h"
30
31namespace apollo {
32namespace localization {
33namespace ndt {
34
36 LidarHeight() : height(0.0), height_var(0.0) {}
37 double height;
38 double height_var;
39};
40
42 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
43 double timestamp = 0.0;
44 Eigen::Affine3d pose;
45};
46
48 public:
49 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
50
51 public:
53 ~NDTLocalization() { tf_buffer_ = nullptr; }
55 void Init();
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);
64 bool IsServiceStarted();
66 void GetLocalization(LocalizationEstimate* localization) const;
68 void GetLidarLocalization(LocalizationEstimate* lidar_localization) const;
70 void GetLocalizationStatus(LocalizationStatus* localization_status) const;
72 inline int GetZoneId() const { return zone_id_; }
74 inline double GetOnlineResolution() const { return online_resolution_; }
75
76 private:
78 void LidarMsgTransfer(const std::shared_ptr<drivers::PointCloud>& message,
79 LidarFrame* lidar_frame);
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);
95 void FillLocalizationMsgHeader(LocalizationEstimate* localization);
97 void ComposeLocalizationEstimate(
98 const Eigen::Affine3d& pose,
99 const std::shared_ptr<localization::Gps>& odometry_msg,
100 LocalizationEstimate* localization);
101 void ComposeLidarResult(double time_stamp, const Eigen::Affine3d& pose,
102 LocalizationEstimate* localization);
104 void ComposeLocalizationStatus(const drivers::gnss::InsStat& status,
105 LocalizationStatus* localization_status);
107 bool FindNearestOdometryStatus(const double odometry_timestamp,
108 drivers::gnss::InsStat* status);
109
110 private:
111 std::string module_name_ = "ndt_localization";
112 LocalizationPoseBuffer pose_buffer_;
113
114 transform::Buffer* tf_buffer_ = nullptr;
115 std::string tf_target_frame_id_ = "";
116 std::string tf_source_frame_id_ = "";
117
118 LidarLocatorNdt lidar_locator_;
119 int zone_id_ = 10;
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_ = "";
125 LidarHeight lidar_height_;
126 Eigen::Affine3d lidar_pose_;
127 Eigen::Affine3d velodyne_extrinsic_;
128 LocalizationEstimate lidar_localization_result_;
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;
135
136 std::list<TimeStampPose, Eigen::aligned_allocator<TimeStampPose>>
137 odometry_buffer_;
138 std::mutex odometry_buffer_mutex_;
139 unsigned int odometry_buffer_size_ = 0;
140 const unsigned int max_odometry_buffer_size_ = 100;
141
142 LocalizationEstimate localization_result_;
143 LocalizationStatus localization_status_;
144
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;
149
150 bool ndt_debug_log_flag_ = false;
151};
152
153} // namespace ndt
154} // namespace localization
155} // namespace apollo
void LidarCallback(const std::shared_ptr< drivers::PointCloud > &lidar_msg)
receive lidar pointcloud message
double GetOnlineResolution() const
get online resolution for ndt localization
void GetLidarLocalization(LocalizationEstimate *lidar_localization) const
get ndt localization result
void OdometryCallback(const std::shared_ptr< localization::Gps > &odometry_msg)
receive odometry message
void OdometryStatusCallback(const std::shared_ptr< drivers::gnss::InsStat > &status_msg)
receive ins status message
void GetLocalizationStatus(LocalizationStatus *localization_status) const
get localization status
void GetLocalization(LocalizationEstimate *localization) const
output localization result
class register implement
Definition arena_queue.h:37
EIGEN_MAKE_ALIGNED_OPERATOR_NEW double timestamp