Apollo 10.0
自动驾驶开放平台
hdmap_util.cc
浏览该文件的文档.
1/* Copyright 2017 The Apollo Authors. All Rights Reserved.
2
3Licensed under the Apache License, Version 2.0 (the "License");
4you may not use this file except in compliance with the License.
5You may obtain a copy of the License at
6
7 http://www.apache.org/licenses/LICENSE-2.0
8
9Unless required by applicable law or agreed to in writing, software
10distributed under the License is distributed on an "AS IS" BASIS,
11WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12See the License for the specific language governing permissions and
13limitations under the License.
14=========================================================================*/
16
17#include <string>
18#include <vector>
19
20#include "absl/strings/str_split.h"
21#include "cyber/common/file.h"
22
23namespace apollo {
24namespace hdmap {
25
27
28namespace {
29
30// Find the first existing file from a list of candidates: "file_a|file_b|...".
31std::string FindFirstExist(const std::string& dir, const std::string& files) {
32 const std::vector<std::string> candidates = absl::StrSplit(files, '|');
33 for (const auto& filename : candidates) {
34 const std::string file_path = absl::StrCat(FLAGS_map_dir, "/", filename);
35 if (cyber::common::PathExists(file_path)) {
36 return file_path;
37 }
38 }
39 AERROR << "No existing file found in " << dir << "/" << files
40 << ". Fallback to first candidate as default result.";
41 ACHECK(!candidates.empty()) << "Please specify at least one map.";
42 return absl::StrCat(FLAGS_map_dir, "/", candidates[0]);
43}
44
45} // namespace
46
47std::string BaseMapFile() {
48 if (FLAGS_use_navigation_mode) {
49 AWARN << "base_map file is not used when FLAGS_use_navigation_mode is true";
50 }
51 return FLAGS_test_base_map_filename.empty()
52 ? FindFirstExist(FLAGS_map_dir, FLAGS_base_map_filename)
53 : FindFirstExist(FLAGS_map_dir, FLAGS_test_base_map_filename);
54}
55
56std::string SimMapFile() {
57 if (FLAGS_use_navigation_mode) {
58 AWARN << "sim_map file is not used when FLAGS_use_navigation_mode is true";
59 }
60 return FindFirstExist(FLAGS_map_dir, FLAGS_sim_map_filename);
61}
62
63std::string RoutingMapFile() {
64 if (FLAGS_use_navigation_mode) {
65 AWARN << "routing_map file is not used when FLAGS_use_navigation_mode is "
66 "true";
67 }
68 return FindFirstExist(FLAGS_map_dir, FLAGS_routing_map_filename);
69}
70
71std::unique_ptr<HDMap> CreateMap(const std::string& map_file_path) {
72 std::unique_ptr<HDMap> hdmap(new HDMap());
73 if (hdmap->LoadMapFromFile(map_file_path) != 0) {
74 AERROR << "Failed to load HDMap " << map_file_path;
75 return nullptr;
76 }
77 AINFO << "Load HDMap success: " << map_file_path;
78 return hdmap;
79}
80
81std::unique_ptr<HDMap> CreateMap(const MapMsg& map_msg) {
82 std::unique_ptr<HDMap> hdmap(new HDMap());
83 if (hdmap->LoadMapFromProto(map_msg.hdmap()) != 0) {
84 AERROR << "Failed to load RelativeMap: "
85 << map_msg.header().ShortDebugString();
86 return nullptr;
87 }
88 return hdmap;
89}
90
91std::unique_ptr<HDMap> HDMapUtil::base_map_ = nullptr;
92uint64_t HDMapUtil::base_map_seq_ = 0;
93std::mutex HDMapUtil::base_map_mutex_;
94
95std::unique_ptr<HDMap> HDMapUtil::sim_map_ = nullptr;
96std::mutex HDMapUtil::sim_map_mutex_;
97
98const HDMap* HDMapUtil::BaseMapPtr(const MapMsg& map_msg) {
99 std::lock_guard<std::mutex> lock(base_map_mutex_);
100 if (base_map_ != nullptr &&
101 base_map_seq_ == map_msg.header().sequence_num()) {
102 // avoid re-create map in the same cycle.
103 return base_map_.get();
104 } else {
105 base_map_ = CreateMap(map_msg);
106 base_map_seq_ = map_msg.header().sequence_num();
107 }
108 return base_map_.get();
109}
110
112 // TODO(all) Those logics should be removed to planning
113 /*if (FLAGS_use_navigation_mode) {
114 std::lock_guard<std::mutex> lock(base_map_mutex_);
115 auto* relative_map = AdapterManager::GetRelativeMap();
116 if (!relative_map) {
117 AERROR << "RelativeMap adapter is not registered";
118 return nullptr;
119 }
120 if (relative_map->Empty()) {
121 AERROR << "RelativeMap is empty";
122 return nullptr;
123 }
124 const auto& latest = relative_map->GetLatestObserved();
125 if (base_map_ != nullptr &&
126 base_map_seq_ == latest.header().sequence_num()) {
127 // avoid re-create map in the same cycle.
128 return base_map_.get();
129 } else {
130 base_map_ = CreateMap(latest);
131 base_map_seq_ = latest.header().sequence_num();
132 }
133 } else*/
134 if (base_map_ == nullptr) {
135 std::lock_guard<std::mutex> lock(base_map_mutex_);
136 if (base_map_ == nullptr) { // Double check.
137 base_map_ = CreateMap(BaseMapFile());
138 }
139 }
140 return base_map_.get();
141}
142
143const HDMap& HDMapUtil::BaseMap() { return *CHECK_NOTNULL(BaseMapPtr()); }
144
146 if (FLAGS_use_navigation_mode) {
147 return BaseMapPtr();
148 } else if (sim_map_ == nullptr) {
149 std::lock_guard<std::mutex> lock(sim_map_mutex_);
150 if (sim_map_ == nullptr) { // Double check.
151 sim_map_ = CreateMap(SimMapFile());
152 }
153 }
154 return sim_map_.get();
155}
156
157const HDMap& HDMapUtil::SimMap() { return *CHECK_NOTNULL(SimMapPtr()); }
158
160 {
161 std::lock_guard<std::mutex> lock(base_map_mutex_);
162 base_map_ = CreateMap(BaseMapFile());
163 }
164 {
165 std::lock_guard<std::mutex> lock(sim_map_mutex_);
166 sim_map_ = CreateMap(SimMapFile());
167 }
168 return base_map_ != nullptr && sim_map_ != nullptr;
169}
170
172 {
173 std::lock_guard<std::mutex> lock(base_map_mutex_);
174 base_map_ = CreateMap(BaseMapFile());
175 }
176 return base_map_ != nullptr;
177}
178
179} // namespace hdmap
180} // namespace apollo
static const HDMap * BaseMapPtr()
static const HDMap & BaseMap()
static const HDMap & SimMap()
static bool ReloadBaseMap()
static const HDMap * SimMapPtr()
High-precision map loader interface.
Definition hdmap.h:54
#define ACHECK(cond)
Definition log.h:80
#define AERROR
Definition log.h:44
#define AINFO
Definition log.h:42
#define AWARN
Definition log.h:43
bool PathExists(const std::string &path)
Check if the path exists.
Definition file.cc:195
std::unique_ptr< HDMap > CreateMap(const std::string &map_file_path)
Definition hdmap_util.cc:71
std::string SimMapFile()
get simulation map file path from flags.
Definition hdmap_util.cc:56
std::string RoutingMapFile()
get routing map file path from flags.
Definition hdmap_util.cc:63
std::string BaseMapFile()
get base map file path from flags.
Definition hdmap_util.cc:47
class register implement
Definition arena_queue.h:37
optional uint32 sequence_num
Definition header.proto:16
optional apollo::common::Header header
optional apollo::hdmap::Map hdmap