Apollo  6.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"
29 
30 namespace apollo {
31 namespace perception {
32 namespace map {
33 
34 class HDMapInput {
35  public:
36  // thread safe
37  bool Init();
38  bool Reset();
39  bool GetRoiHDMapStruct(const base::PointD& pointd, const double distance,
40  std::shared_ptr<base::HdmapStruct> hdmap_struct_prt);
41  bool GetNearestLaneDirection(const base::PointD& pointd,
42  Eigen::Vector3d* lane_direction);
43  bool GetSignals(const Eigen::Vector3d& pointd, double forward_distance,
44  std::vector<apollo::hdmap::Signal>* signals);
45 
46  private:
47  bool InitHDMap();
48  bool InitInternal();
49 
50  void MergeBoundaryJunction(
51  const std::vector<apollo::hdmap::RoadRoiPtr>& boundary,
52  const std::vector<apollo::hdmap::JunctionInfoConstPtr>& junctions,
55  road_polygons_ptr,
57  junction_polygons_ptr);
58 
59  bool GetRoadBoundaryFilteredByJunctions(
62  junctions,
63  apollo::common::EigenVector<base::RoadBoundary>* flt_road_boundaries_ptr);
64 
65  void DownsamplePoints(const base::PointDCloudPtr& raw_cloud_ptr,
66  base::PointCloud<base::PointD>* polygon_ptr,
67  size_t min_points_num_for_sample = 15) const;
68 
69  void SplitBoundary(
70  const base::PointCloud<base::PointD>& boundary_line,
72  junctions,
74  boundary_line_vec_ptr);
75 
76  bool GetSignalsFromHDMap(const Eigen::Vector3d& pointd,
77  double forward_distance,
78  std::vector<apollo::hdmap::Signal>* signals);
79 
80  bool inited_ = false;
81  lib::Mutex mutex_;
82  std::unique_ptr<apollo::hdmap::HDMap> hdmap_;
83  int hdmap_sample_step_ = 5;
84  std::string hdmap_file_;
85 
87 };
88 
89 } // namespace map
90 } // namespace perception
91 } // namespace apollo
std::vector< EigenType, Eigen::aligned_allocator< EigenType > > EigenVector
Definition: eigen_defs.h:32
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Definition: point.h:28
bool GetNearestLaneDirection(const base::PointD &pointd, Eigen::Vector3d *lane_direction)
Eigen::Vector3d Vector3d
Definition: frame_transform.h:27
Definition: hdmap_input.h:34
Definition: mutex.h:24
Definition: point_cloud.h:37
bool GetSignals(const Eigen::Vector3d &pointd, double forward_distance, std::vector< apollo::hdmap::Signal > *signals)
#define DECLARE_SINGLETON(classname)
Definition: macros.h:52
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:485