Apollo 10.0
自动驾驶开放平台
localization_lidar_process.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
22#pragma once
23
24#include <string>
25
26#include "Eigen/Core"
27#include "Eigen/Geometry"
28
29// TODO(Localization): Fix the typo of "forecast".
30#include "localization_msf/pose_forcast.h"
31#include "localization_msf/sins_struct.h"
35#include "modules/common_msgs/localization_msgs/localization.pb.h"
36#include "modules/common_msgs/localization_msgs/localization_status.pb.h"
37#include "modules/localization/proto/measure.pb.h"
38#include "modules/localization/proto/sins_pva.pb.h"
39
44namespace apollo {
45namespace localization {
46namespace msf {
47
49
50enum class LidarState { NOT_VALID = 0, NOT_STABLE, OK };
51
58
60 LidarHeight() : height(0.0), height_var(0.0) {}
61 double height;
62 double height_var;
63};
64
71 public:
72 typedef Eigen::Affine3d TransformD;
73 typedef Eigen::Vector3d Vector3D;
74 typedef Eigen::Matrix3d Matrix3D;
75
78
79 // Initialization.
81 // Lidar pcd process and get result.
82 void PcdProcess(const LidarFrame &lidar_frame);
83 void GetResult(int *lidar_status, TransformD *location,
84 Matrix3D *covariance) const;
85 int GetResult(LocalizationEstimate *lidar_local_msg);
86 // Integrated navagation pva process.
87 void IntegPvaProcess(const InsPva &sins_pva_msg);
88 // Raw Imu process.
89 void RawImuProcess(const ImuData &imu_msg);
90
91 private:
92 // Sub-functions for process.
93 bool GetPredictPose(const double lidar_time, TransformD *inspva_pose,
94 ForecastState *forecast_state);
95 bool CheckState();
96 bool CheckDelta(const LidarFrame &frame, const TransformD &inspva_pose);
97 void UpdateState(const int ret, const double time);
98
99 // Load lidar-imu extrinsic parameter.
100 bool LoadLidarExtrinsic(const std::string &file_path,
101 TransformD *lidar_extrinsic);
102 // Load lidar height (the distance between lidar and ground).
103 bool LoadLidarHeight(const std::string &file_path, LidarHeight *height);
104
105 double ComputeDeltaYawLimit(const int64_t index_cur,
106 const int64_t index_stable,
107 const double limit_min, const double limit_max);
108
109 private:
110 // Lidar localization.
111 LocalizationLidar *locator_;
112 PoseForcast *pose_forecastor_;
113
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;
125 TransformD lidar_extrinsic_;
126 LidarHeight lidar_height_;
127
128 bool is_get_first_lidar_msg_ = false;
129 TransformD cur_predict_location_;
130 TransformD pre_predict_location_;
131 Vector3D velocity_;
132 TransformD pre_location_;
133 TransformD location_;
134 double pre_location_time_ = 0;
135
136 // Information used to output.
137 Matrix3D location_covariance_;
138 LidarState lidar_status_;
139
140 LocalLidarStatus local_lidar_status_ =
142 LocalLidarQuality local_lidar_quality_ =
144
145 bool reinit_flag_ = false;
146
147 // if use avx to accelerate lidar localization algorithm
148 bool if_use_avx_ = false;
149
150 // imu and lidar max delay time
151 double imu_lidar_max_delay_time_ = 0.4;
152
153 bool is_unstable_reset_ = false;
154 int unstable_count_ = 0;
155 double unstable_threshold_ = 0.3;
156
157 int out_map_count_ = 0;
158
160 ForecastState forecast_integ_state_;
161 int64_t forecast_timer_ = 0;
162
163 static constexpr double DEG_TO_RAD = 0.017453292519943;
164 static constexpr double DEG_TO_RAD2 = DEG_TO_RAD * DEG_TO_RAD;
165
166 public:
167 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
168};
169
170} // namespace msf
171} // namespace localization
172} // namespace apollo
A general class to denote the return status of an API call.
Definition status.h:43
apollo::common::Status Init(const LocalizationIntegParam &params)
void GetResult(int *lidar_status, TransformD *location, Matrix3D *covariance) const
The class of LocalizationIntegParam
#define DEG_TO_RAD
class register implement
Definition arena_queue.h:37