Apollo 10.0
自动驾驶开放平台
localization_lidar.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
17#pragma once
18
19#include <string>
20#include <vector>
21
22#include "cyber/common/log.h"
23#include "localization_msf/lidar_locator.h"
31
32namespace apollo {
33namespace localization {
34namespace msf {
35
36struct LidarFrame {
38 double measurement_time; // unix time
39 std::vector<double> pt_xs;
40 std::vector<double> pt_ys;
41 std::vector<double> pt_zs;
42 std::vector<unsigned char> intensities;
43};
44
46 MapNodeData(const int w, const int h)
47 : width(w),
48 height(h),
49 intensities(new float[width * height]),
50 intensities_var(new float[width * height]),
51 altitudes(new float[width * height]),
52 count(new unsigned int[width * height]) {}
54 delete[] intensities;
55 intensities = nullptr;
56 delete[] intensities_var;
57 intensities_var = nullptr;
58 delete[] altitudes;
59 altitudes = nullptr;
60 delete[] count;
61 count = nullptr;
62 }
63 int width;
64 int height;
67 float* altitudes;
68 unsigned int* count;
69};
70
72 public:
84
85 public:
90
91 bool Init(const std::string& map_path, const unsigned int search_range_x,
92 const unsigned int search_range_y, const int zone_id,
93 const unsigned int resolution_id = 0);
94
95 void SetVelodyneExtrinsic(const Eigen::Affine3d& pose);
96
97 void SetVehicleHeight(double height);
98
99 void SetValidThreshold(float valid_threashold);
100
101 void SetImageAlignMode(int mode);
102
103 void SetLocalizationMode(int mode);
104
105 void SetDeltaYawLimit(double limit);
106
107 void SetDeltaPitchRollLimit(double limit);
108
109 int Update(const unsigned int frame_idx, const Eigen::Affine3d& pose,
110 const Eigen::Vector3d velocity, const LidarFrame& lidar_frame,
111 bool use_avx = false);
112
113 void GetResult(Eigen::Affine3d* location, Eigen::Matrix3d* covariance,
114 double* location_score);
115
116 void GetLocalizationDistribution(Eigen::MatrixXd* distribution);
117
118 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
119
120 protected:
121 void ComposeMapNode(const Eigen::Vector3d& trans);
122
123 void RefineAltitudeFromMap(Eigen::Affine3d* pose);
124
125 protected:
126 LidarLocator* lidar_locator_;
131 double resolution_ = 0.125;
133
137 Eigen::Vector2d map_left_top_corner_;
138 unsigned int resolution_id_ = 0;
139 int zone_id_ = 50;
140 bool is_map_loaded_ = false;
141
145 Eigen::Affine3d velodyne_extrinsic_;
146};
147
148} // namespace msf
149} // namespace localization
150} // namespace apollo
apollo::localization::msf::pyramid_map::FloatMatrix FloatMatrix
apollo::localization::msf::pyramid_map::UIntMatrix UIntMatrix
apollo::localization::msf::pyramid_map::PyramidMapMatrix PyramidMapMatrix
int Update(const unsigned int frame_idx, const Eigen::Affine3d &pose, const Eigen::Vector3d velocity, const LidarFrame &lidar_frame, bool use_avx=false)
apollo::localization::msf::pyramid_map::MapNodeIndex MapNodeIndex
bool Init(const std::string &map_path, const unsigned int search_range_x, const unsigned int search_range_y, const int zone_id, const unsigned int resolution_id=0)
void GetResult(Eigen::Affine3d *location, Eigen::Matrix3d *covariance, double *location_score)
void ComposeMapNode(const Eigen::Vector3d &trans)
void GetLocalizationDistribution(Eigen::MatrixXd *distribution)
apollo::localization::msf::pyramid_map::PyramidMapNodePool PyramidMapNodePool
apollo::localization::msf::pyramid_map::PyramidMap PyramidMap
void SetVelodyneExtrinsic(const Eigen::Affine3d &pose)
apollo::localization::msf::pyramid_map::PyramidMapConfig PyramidMapConfig
apollo::localization::msf::pyramid_map::PyramidMapNode PyramidMapNode
The class of LocalizationIntegParam
class register implement
Definition arena_queue.h:37
std::vector< unsigned char > intensities