Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
SignalizedIntersectionManager.cpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2022 LEIDOS.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
5 * use this file except in compliance with the License. You may obtain a copy of
6 * 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, WITHOUT
12 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
13 * License for the specific language governing permissions and limitations under
14 * the License.
15 */
16
17#include <boost/archive/binary_iarchive.hpp>
18#include <boost/archive/binary_oarchive.hpp>
20#include <algorithm>
21#include <j2735_v2x_msgs/msg/lane_type_attributes.hpp>
22
23namespace carma_wm
24{
25 void SignalizedIntersectionManager::setTargetFrame(const std::string& target_frame)
26 {
27 target_frame_ = target_frame;
28 }
29
31 {
32 max_lane_width_ = max_lane_width;
33 }
34
36 {
37 bool is_same = true;
38 if (rhs.intersection_id_to_regem_id_ != this->intersection_id_to_regem_id_)
39 {
40 is_same = false;
41 }
42 if (rhs.signal_group_to_entry_lanelet_ids_ != this->signal_group_to_entry_lanelet_ids_)
43 {
44 is_same = false;
45 }
46 if (rhs.signal_group_to_exit_lanelet_ids_ != this->signal_group_to_exit_lanelet_ids_)
47 {
48 is_same = false;
49 }
50 if (rhs.signal_group_to_traffic_light_id_ != this->signal_group_to_traffic_light_id_)
51 {
52 is_same = false;
53 }
54
55 return is_same;
56 }
57
58 void SignalizedIntersectionManager::convertLaneToLaneletId(std::unordered_map<uint8_t, lanelet::Id>& entry, std::unordered_map<uint8_t, lanelet::Id>& exit, const carma_v2x_msgs::msg::IntersectionGeometry& intersection,
59 const std::shared_ptr<lanelet::LaneletMap>& map, std::shared_ptr<const lanelet::routing::RoutingGraph> current_routing_graph)
60 {
61 std::unordered_map<uint8_t, std::unordered_set<uint16_t>> signal_group_to_exit_lanes;
62 std::unordered_map<uint8_t, std::unordered_set<uint16_t>> signal_group_to_entry_lanes;
63
64 if (target_frame_ == "")
65 {
66 throw std::invalid_argument("Map is not initialized yet as the georeference was not found...");
67 }
68
69 lanelet::projection::LocalFrameProjector local_projector(target_frame_.c_str());
70
71 lanelet::GPSPoint gps_point;
72 gps_point.lat = intersection.ref_point.latitude;
73 gps_point.lon = intersection.ref_point.longitude;
74 gps_point.ele = intersection.ref_point.elevation;
75
76 auto ref_node = local_projector.forward(gps_point);
77
78 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Reference node in map frame x: " << ref_node.x() << ", y: " << ref_node.y());
79
80
81 for (auto lane : intersection.lane_list)
82 {
83 if (lane.lane_attributes.lane_type.choice != j2735_v2x_msgs::msg::LaneTypeAttributes::VEHICLE)
84 {
85 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Lane id: " << (int)lane.lane_id << ", is not a lane for vehicle. Only vehicle road is currently supported. Skipping..." );
86 continue;
87 }
88 std::vector<lanelet::Point3d> node_list;
89
90 double curr_x = ref_node.x();
91 double curr_y = ref_node.y();
92
93 if (intersection_coord_correction_.find(intersection.id.id) != intersection_coord_correction_.end())
94 {
95 curr_x += intersection_coord_correction_[intersection.id.id].first;
96 curr_y += intersection_coord_correction_[intersection.id.id].second;
97 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Applied reference point correction, delta_x: " << intersection_coord_correction_[intersection.id.id].first <<
98 ", delta_y: " << intersection_coord_correction_[intersection.id.id].second << ", to intersection id: " << (int)lane.lane_id);
99 }
100
101 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Processing Lane id: " << (int)lane.lane_id);
102
103 size_t min_number_of_points = 2; // two points minimum are required
104
105 size_t size_of_available_points = lane.node_list.nodes.node_set_xy.size();
106
107 if (size_of_available_points < min_number_of_points)
108 {
109 RCLCPP_WARN_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Not enough points are provided to match a lane. Skipping... ");
110 continue;
111 }
112
113 for (size_t i = 0; i < size_of_available_points; i ++ )
114 {
115 curr_x = lane.node_list.nodes.node_set_xy[i].delta.x + curr_x;
116 curr_y = lane.node_list.nodes.node_set_xy[i].delta.y + curr_y;
117 lanelet::Point3d curr_node{map->pointLayer.uniqueId(), curr_x, curr_y, 0};
118
119 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Current node x: " << curr_x << ", y: " << curr_y);
120
121 node_list.push_back(curr_node);
122 }
123
124 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Lane directions: " << (int)lane.lane_attributes.directional_use.lane_direction);
125
126 if (lane.lane_attributes.directional_use.lane_direction == LANE_DIRECTION::INGRESS)
127 {
128 // flip direction if ingress to pick up correct lanelets
129 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Reversed the node list!");
130 std::reverse(node_list.begin(), node_list.end());
131 }
132
133 for (auto node : node_list)
134 {
135 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "intersection: " << intersection.id.id << ", " << node.x() << ", " << node.y());
136 }
137 intersection_nodes_[intersection.id.id].insert(intersection_nodes_[intersection.id.id].end(), node_list.begin(), node_list.end());
138
139 // save which signal group connect to which exit lanes
140 for (auto connection : lane.connect_to_list)
141 {
142 signal_group_to_exit_lanes[connection.signal_group].emplace(connection.connecting_lane.lane);
143
144 if (lane.lane_attributes.directional_use.lane_direction == LANE_DIRECTION::INGRESS)
145 signal_group_to_entry_lanes[connection.signal_group].emplace(lane.lane_id);
146 }
147
148 // query corresponding lanelet lane from local map
149 auto affected_llts = carma_wm::query::getAffectedLaneletOrAreas(node_list, map, current_routing_graph, max_lane_width_);
150
151 if (affected_llts.empty())
152 {
153 // https://github.com/usdot-fhwa-stol/carma-platform/issues/1593
154 // Open issue TODO on how this error is handled
155 RCLCPP_WARN_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Given offset points are not inside the map for lane: " << (int)lane.lane_id);
156 continue;
157 }
158
159 lanelet::Id corresponding_lanelet_id;
160 if (lane.lane_attributes.directional_use.lane_direction == LANE_DIRECTION::EGRESS)
161 {
162 corresponding_lanelet_id = affected_llts.front().id();
163 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Default corresponding_lanelet_id: " << corresponding_lanelet_id <<", in EGRESS");
164
165 }
166 else //ingress
167 {
168 corresponding_lanelet_id = affected_llts.back().id();
169 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Default corresponding_lanelet_id: " << corresponding_lanelet_id <<", in INGRESS");
170 }
171
172 for (auto llt : affected_llts) // filter out intersection lanelets
173 {
174 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Checking if we can get entry/exit from lanelet " << llt.id());
175 //TODO direction of affected_llts may play role, but it should be good
176 if (llt.lanelet().get().hasAttribute("turn_direction") &&
177 (llt.lanelet().get().attribute("turn_direction").value().compare("left") == 0 ||
178 llt.lanelet().get().attribute("turn_direction").value().compare("right") == 0))
179 {
180 std::vector<lanelet::ConstLanelet> connecting_llts;
181 if (lane.lane_attributes.directional_use.lane_direction == LANE_DIRECTION::EGRESS)
182 {
183 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "lanelet " << llt.id() << " is actually part of the intersecion. Trying to detect EGRESS...");
184 connecting_llts = current_routing_graph->following(llt.lanelet().get());
185 }
186 else
187 {
188 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "lanelet " << llt.id() << " is actually part of the intersecion. Trying to detect INGRESS...");
189 connecting_llts = current_routing_graph->previous(llt.lanelet().get());
190 }
191
192 if (!connecting_llts.empty())
193 {
194 corresponding_lanelet_id = connecting_llts[0].id();
195 }
196 else
197 {
198 RCLCPP_WARN_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Interestingly, did not detect here");
199 continue;
200 }
201
202 break;
203 }
204 }
205
206 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Found existing lanelet id: " << corresponding_lanelet_id);
207
208 if (lane.lane_attributes.directional_use.lane_direction == LANE_DIRECTION::INGRESS)
209 {
210 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Detected INGRESS, " << (int)lane.lane_id);
211 entry[lane.lane_id] = corresponding_lanelet_id;
212 }
213 else if (lane.lane_attributes.directional_use.lane_direction == LANE_DIRECTION::EGRESS)
214 {
215 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Detected EGRESS, " << (int)lane.lane_id);
216 exit[lane.lane_id] = corresponding_lanelet_id;
217 }
218 // ignoring types that are neither ingress nor egress
219 }
220
221 // convert and save exit lane ids into lanelet ids with their corresponding signal group ids
222 for (auto iter = signal_group_to_exit_lanes.begin(); iter != signal_group_to_exit_lanes.end(); iter++)
223 {
224 for (auto exit_lane : iter->second)
225 {
226 if (exit.find(exit_lane) != exit.end())
227 {
228 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Adding exit_lane id: " << exit_lane);
229 signal_group_to_exit_lanelet_ids_[iter->first].insert(exit[exit_lane]);
230 }
231 else
232 {
233 // https://github.com/usdot-fhwa-stol/carma-platform/issues/1593
234 // Open issue TODO on how this error is handled
235 RCLCPP_WARN_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Unable to convert exit lane Id: " + std::to_string((int)exit_lane) + ", to lanelet id using the given MAP.msg!");
236 }
237 }
238 }
239
240 // convert and save entry lane ids into lanelet ids with their corresponding signal group ids
241 for (auto iter = signal_group_to_entry_lanes.begin(); iter != signal_group_to_entry_lanes.end(); iter++)
242 {
243 for (auto entry_lane : iter->second)
244 {
245 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Adding entry_lane id: " << entry_lane);
246 if (entry.find(entry_lane) != entry.end())
247 {
248 signal_group_to_entry_lanelet_ids_[iter->first].insert(entry[entry_lane]);
249 }
250 else
251 {
252 // https://github.com/usdot-fhwa-stol/carma-platform/issues/1593
253 // Open issue TODO on how this error is handled
254 RCLCPP_WARN_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Unable to convert entry lane Id: " + std::to_string((int)entry_lane) + ", to lanelet id using the given MAP.msg!");
255 }
256 }
257 }
258 }
259
260 lanelet::Id SignalizedIntersectionManager::matchSignalizedIntersection(const lanelet::Lanelets& entry_llts, const lanelet::Lanelets& exit_llts)
261 {
262 lanelet::Id matching_id = lanelet::InvalId;
263
264 std::vector<lanelet::SignalizedIntersectionPtr> existing_si;
265
266 for (auto llt : entry_llts)
267 {
268 auto intersections = llt.regulatoryElementsAs<lanelet::SignalizedIntersection>();
269
270 if (intersections.empty())
271 {
272 // no match if any of the entry lanelet is not part of any intersection.
273 break;
274 }
275 existing_si.insert(existing_si.end(), intersections.begin(),intersections.end());
276 }
277
278 for (auto intersection : existing_si)
279 {
280 auto existing_entry_llts = intersection->getEntryLanelets();
281 auto existing_exit_llts = intersection->getExitLanelets();
282
283 if (existing_exit_llts.size() != exit_llts.size() || existing_entry_llts.size() != entry_llts.size())
284 continue;
285
286 bool is_different = false;
287
288 for (auto llt: existing_entry_llts)
289 {
290 if (std::find(entry_llts.begin(), entry_llts.end(), llt) == entry_llts.end())
291 {
292 is_different = true;
293
294 break;
295 }
296 }
297
298 for (auto llt: existing_exit_llts)
299 {
300 if (std::find(exit_llts.begin(), exit_llts.end(), llt) == exit_llts.end())
301 {
302 is_different = true;
303
304 break;
305 }
306 }
307
308 if (!is_different)
309 {
310 // found a match
311 matching_id = intersection->id();
312
313 break;
314 }
315
316 }
317
318 return matching_id;
319 }
320
321 std::shared_ptr<lanelet::CarmaTrafficSignal> SignalizedIntersectionManager::createTrafficSignalUsingSGID(uint8_t signal_group_id, const lanelet::Lanelets& entry_lanelets, const lanelet::Lanelets& exit_lanelets)
322 {
323 std::vector<lanelet::LineString3d> stop_lines;
324 for (auto llt : entry_lanelets)
325 {
326 std::vector<lanelet::Point3d> points;
327 points.push_back(lanelet::Point3d(lanelet::utils::getId(), llt.leftBound2d().back().x(), llt.leftBound2d().back().y(), 0));
328 points.push_back(lanelet::Point3d(lanelet::utils::getId(), llt.rightBound().back().x(), llt.rightBound().back().y(), 0));
329
330 lanelet::LineString3d stop_line(lanelet::utils::getId(), points);
331 stop_lines.push_back(stop_line);
332 }
333
334 lanelet::Id traffic_light_id = lanelet::utils::getId();
335 std::shared_ptr<lanelet::CarmaTrafficSignal> traffic_light(new lanelet::CarmaTrafficSignal(lanelet::CarmaTrafficSignal::buildData(traffic_light_id, stop_lines, entry_lanelets, exit_lanelets)));
336 signal_group_to_traffic_light_id_[signal_group_id] = traffic_light_id;
337
338 for (auto llt : exit_lanelets)
339 {
340 signal_group_to_exit_lanelet_ids_[signal_group_id].insert(llt.id());
341 }
342 for (auto llt : entry_lanelets)
343 {
344 signal_group_to_entry_lanelet_ids_[signal_group_id].insert(llt.id());
345 }
346 return traffic_light;
347 }
348
349 void SignalizedIntersectionManager::createIntersectionFromMapMsg(std::vector<lanelet::SignalizedIntersectionPtr>& sig_intersections, std::vector<lanelet::CarmaTrafficSignalPtr>& traffic_signals, const carma_v2x_msgs::msg::MapData& map_msg,
350 const std::shared_ptr<lanelet::LaneletMap>& map, std::shared_ptr<const lanelet::routing::RoutingGraph> routing_graph)
351 {
352
353 if (target_frame_ == "")
354 {
355 RCLCPP_WARN_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Georeference is not loaded yet. Returning without processing this MAP msg.");
356 return;
357 }
358
359 for (auto const& intersection : map_msg.intersections)
360 {
361 std::unordered_map<uint8_t, lanelet::Id> entry;
362 std::unordered_map<uint8_t, lanelet::Id> exit;
363
364 convertLaneToLaneletId(entry, exit, intersection, map, routing_graph);
365
366 std::vector<lanelet::Lanelet> entry_llts;
367 std::vector<lanelet::Lanelet> exit_llts;
368
369 for (auto iter = entry.begin(); iter != entry.end(); iter++)
370 {
371 entry_llts.push_back(map->laneletLayer.get(iter->second));
372 }
373 for (auto iter = exit.begin(); iter != exit.end(); iter++)
374 {
375 exit_llts.push_back(map->laneletLayer.get(iter->second));
376 }
377
378 lanelet::Id intersection_id = matchSignalizedIntersection(entry_llts, exit_llts);
379
380 if (intersection_id == lanelet::InvalId)
381 {
382 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "No existing intersection found. Creating a new one...");
383 intersection_id = lanelet::utils::getId();
384
385 std::vector<lanelet::Lanelet> interior_llts = identifyInteriorLanelets(entry_llts, map);
386
387 std::shared_ptr<lanelet::SignalizedIntersection> sig_inter(new lanelet::SignalizedIntersection
388 (lanelet::SignalizedIntersection::buildData(intersection_id, entry_llts, exit_llts, interior_llts)));
389 intersection_id_to_regem_id_[intersection.id.id] = intersection_id;
390 regem_id_to_intersection_id_[intersection_id] = intersection.id.id;
391 sig_intersections.push_back(sig_inter);
392 }
393 }
394
395
396 // create signal group for each from the message
397 // check if it already exists
398 for (auto sig_grp_pair : signal_group_to_exit_lanelet_ids_)
399 {
400 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Creating signal for: " << (int)sig_grp_pair.first);
401 // ignore the traffic signals already inside
402 if (signal_group_to_traffic_light_id_.find(sig_grp_pair.first) != signal_group_to_traffic_light_id_.end() &&
403 map->regulatoryElementLayer.exists(signal_group_to_traffic_light_id_[sig_grp_pair.first]))
404 {
405 continue;
406 }
407
408 std::vector<lanelet::Lanelet> exit_lanelets;
409 for (auto iter = sig_grp_pair.second.begin(); iter != sig_grp_pair.second.end(); iter++)
410 {
411 exit_lanelets.push_back(map->laneletLayer.get(*iter));
412 }
413 std::vector<lanelet::Lanelet> entry_lanelets;
414 for (auto iter = signal_group_to_entry_lanelet_ids_[sig_grp_pair.first].begin(); iter != signal_group_to_entry_lanelet_ids_[sig_grp_pair.first].end(); iter++)
415 {
416 entry_lanelets.push_back(map->laneletLayer.get(*iter));
417 }
418
419 traffic_signals.push_back(createTrafficSignalUsingSGID(sig_grp_pair.first, entry_lanelets, exit_lanelets));
420 }
421 }
422
423 lanelet::Lanelets SignalizedIntersectionManager::identifyInteriorLanelets(const lanelet::Lanelets& entry_llts, const std::shared_ptr<lanelet::LaneletMap>& map)
424 {
425 lanelet::BasicLineString2d polygon_corners;
426
427 if (entry_llts.size() < 2) //at least two lanes (1 ingress and 1 egress) needed to form intersection
428 {
429 return {};
430 }
431
432 for (auto llt : entry_llts)
433 {
434 lanelet::BasicPoint2d pt(llt.centerline2d().back().x(), llt.centerline2d().back().y());
435 polygon_corners.push_back(pt);
436 }
437 lanelet::BasicPolygon2d polygon(polygon_corners);
438 auto interior_llt_pairs = lanelet::geometry::findWithin2d(map->laneletLayer, polygon);
439 lanelet::Lanelets interior_llts;
440
441 for (auto pair : interior_llt_pairs)
442 {
443 if (std::find(entry_llts.begin(),entry_llts.end(), pair.second) == entry_llts.end())
444 interior_llts.push_back(pair.second);
445 }
446 return interior_llts;
447 }
448
450 {
456
457 return *this;
458 }
459
461 {
467 }
468} // namespace carma_wm
This class manages and keeps track of all signalized intersections in the map. All of the SPAT and MA...
lanelet::Lanelets identifyInteriorLanelets(const lanelet::Lanelets &entry_llts, const std::shared_ptr< lanelet::LaneletMap > &map)
Returns carma traffic signal and saves all id relevant id mappings (signal group to lanelet id) inter...
lanelet::Id matchSignalizedIntersection(const lanelet::Lanelets &entry_llts, const lanelet::Lanelets &exit_llts)
Returns existing signalized intersection with same entry and exit llts if exists.
std::unordered_map< uint16_t, std::vector< lanelet::Point3d > > intersection_nodes_
std::unordered_map< uint16_t, std::pair< double, double > > intersection_coord_correction_
void setTargetFrame(const std::string &target_frame)
Saves the georeference string to be used for converting MAP.msg coordinates.
std::unordered_map< uint8_t, std::unordered_set< lanelet::Id > > signal_group_to_entry_lanelet_ids_
std::unordered_map< lanelet::Id, uint16_t > regem_id_to_intersection_id_
std::unordered_map< uint16_t, lanelet::Id > intersection_id_to_regem_id_
std::shared_ptr< lanelet::CarmaTrafficSignal > createTrafficSignalUsingSGID(uint8_t signal_group_id, const lanelet::Lanelets &entry_lanelets, const lanelet::Lanelets &exit_lanelets)
Returns carma traffic signal and saves all id relevant id mappings (signal group to lanelet id) inter...
SignalizedIntersectionManager & operator=(SignalizedIntersectionManager other)
Assignment operator that copies everything except the traffic signal states. This is to keep the stat...
bool operator==(const SignalizedIntersectionManager &rhs)
Equality operator that checks if every mapping are same except the traffic signal states....
std::unordered_map< uint8_t, std::unordered_set< lanelet::Id > > signal_group_to_exit_lanelet_ids_
std::unordered_map< uint8_t, lanelet::Id > signal_group_to_traffic_light_id_
void convertLaneToLaneletId(std::unordered_map< uint8_t, lanelet::Id > &entry, std::unordered_map< uint8_t, lanelet::Id > &exit, const carma_v2x_msgs::msg::IntersectionGeometry &intersection, const std::shared_ptr< lanelet::LaneletMap > &map, std::shared_ptr< const lanelet::routing::RoutingGraph > current_routing_graph)
Returns mapping of MAP lane id to lanelet id for the given map and intersection.msg in the MAP....
void setMaxLaneWidth(double max_lane_width)
Sets the max lane width in meters. Map msg points are associated to a lanelet if they are within this...
void createIntersectionFromMapMsg(std::vector< lanelet::SignalizedIntersectionPtr > &intersections, std::vector< lanelet::CarmaTrafficSignalPtr > &traffic_signals, const carma_v2x_msgs::msg::MapData &map_msg, const std::shared_ptr< lanelet::LaneletMap > &map, std::shared_ptr< const lanelet::routing::RoutingGraph > routing_graph)
Create relevant signalized intersection and carma traffic signals based on the MAP....
auto to_string(const UtmZone &zone) -> std::string
Definition: utm_zone.cpp:21
lanelet::ConstLaneletOrAreas getAffectedLaneletOrAreas(const lanelet::Points3d &gf_pts, const lanelet::LaneletMapPtr &lanelet_map, std::shared_ptr< const lanelet::routing::RoutingGraph > routing_graph, double max_lane_width)
Gets the affected lanelet or areas based on the points in the given map's frame.