Apollo  v5.5.0
Open source self driving car software
hdmap_input.h
Go to the documentation of this file.
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 <memory>
20 #include <string>
21 #include <vector>
22 
23 #include "cyber/common/macros.h"
24 #include "modules/map/hdmap/hdmap.h"
25 #include "modules/map/hdmap/hdmap_common.h"
28 
29 namespace apollo {
30 namespace perception {
31 namespace map {
32 
33 class HDMapInput {
34  public:
35  // thread safe
36  bool Init();
37  bool Reset();
38  bool GetRoiHDMapStruct(const base::PointD& pointd, const double distance,
39  std::shared_ptr<base::HdmapStruct> hdmap_struct_prt);
40  bool GetNearestLaneDirection(const base::PointD& pointd,
41  Eigen::Vector3d* lane_direction);
42  bool GetSignals(const Eigen::Vector3d& pointd, double forward_distance,
43  std::vector<apollo::hdmap::Signal>* signals);
44 
45  private:
46  bool InitHDMap();
47  bool InitInternal();
48 
49  void MergeBoundaryJunction(
50  const std::vector<apollo::hdmap::RoadRoiPtr>& boundary,
51  const std::vector<apollo::hdmap::JunctionInfoConstPtr>& junctions,
52  std::vector<base::RoadBoundary>* road_boundaries_ptr,
53  std::vector<base::PolygonDType>* road_polygons_ptr,
54  std::vector<base::PolygonDType>* junction_polygons_ptr);
55 
56  bool GetRoadBoundaryFilteredByJunctions(
57  const std::vector<base::RoadBoundary>& road_boundaries,
58  const std::vector<base::PointCloud<base::PointD>>& junctions,
59  std::vector<base::RoadBoundary>* flt_road_boundaries_ptr);
60 
61  void DownsamplePoints(const base::PointDCloudPtr& raw_cloud_ptr,
62  base::PointCloud<base::PointD>* polygon_ptr,
63  size_t min_points_num_for_sample = 15) const;
64 
65  void SplitBoundary(
66  const base::PointCloud<base::PointD>& boundary_line,
67  const std::vector<base::PointCloud<base::PointD>>& junctions,
68  std::vector<base::PointCloud<base::PointD>>* boundary_line_vec_ptr);
69 
70  bool GetSignalsFromHDMap(const Eigen::Vector3d& pointd,
71  double forward_distance,
72  std::vector<apollo::hdmap::Signal>* signals);
73 
74  bool inited_ = false;
75  lib::Mutex mutex_;
76  std::unique_ptr<apollo::hdmap::HDMap> hdmap_;
77  int hdmap_sample_step_ = 5;
78  std::string hdmap_file_;
79 
80  DECLARE_SINGLETON(HDMapInput)
81 };
82 
83 } // namespace map
84 } // namespace perception
85 } // namespace apollo
Definition: blob.h:72
Definition: point.h:29
bool GetNearestLaneDirection(const base::PointD &pointd, Eigen::Vector3d *lane_direction)
Definition: hdmap_input.h:33
Definition: mutex.h:24
Definition: point_cloud.h:33
bool GetSignals(const Eigen::Vector3d &pointd, double forward_distance, std::vector< apollo::hdmap::Signal > *signals)
bool GetRoiHDMapStruct(const base::PointD &pointd, const double distance, std::shared_ptr< base::HdmapStruct > hdmap_struct_prt)
std::shared_ptr< PointDCloud > PointDCloudPtr
Definition: point_cloud.h:475