Carma-platform v4.11.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 {
110 std::string("Logging Once: Not enough points are provided to match a lane. Skipping... ")
111 + "| intersection id: " + std::to_string((int)intersection.id.id));
112 continue;
113 }
114
115 for (size_t i = 0; i < size_of_available_points; i ++ )
116 {
117 curr_x = lane.node_list.nodes.node_set_xy[i].delta.x + curr_x;
118 curr_y = lane.node_list.nodes.node_set_xy[i].delta.y + curr_y;
119 lanelet::Point3d curr_node{map->pointLayer.uniqueId(), curr_x, curr_y, 0};
120
121 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Current node x: " << curr_x << ", y: " << curr_y);
122
123 node_list.push_back(curr_node);
124 }
125
126 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Lane directions: " << (int)lane.lane_attributes.directional_use.lane_direction);
127
128 if (lane.lane_attributes.directional_use.lane_direction == LANE_DIRECTION::INGRESS)
129 {
130 // flip direction if ingress to pick up correct lanelets
131 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Reversed the node list!");
132 std::reverse(node_list.begin(), node_list.end());
133 }
134
135 for (auto node : node_list)
136 {
137 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "intersection: " << intersection.id.id << ", " << node.x() << ", " << node.y());
138 }
139 intersection_nodes_[intersection.id.id].insert(intersection_nodes_[intersection.id.id].end(), node_list.begin(), node_list.end());
140
141 // save which signal group connect to which exit lanes
142 for (auto connection : lane.connect_to_list)
143 {
144 signal_group_to_exit_lanes[connection.signal_group].emplace(connection.connecting_lane.lane);
145
146 if (lane.lane_attributes.directional_use.lane_direction == LANE_DIRECTION::INGRESS)
147 signal_group_to_entry_lanes[connection.signal_group].emplace(lane.lane_id);
148 }
149
150 // query corresponding lanelet lane from local map
151 auto affected_llts = carma_wm::query::getAffectedLaneletOrAreas(node_list, map, current_routing_graph, max_lane_width_);
152
153 if (affected_llts.empty())
154 {
155 // https://github.com/usdot-fhwa-stol/carma-platform/issues/1593
156 // Open issue TODO on how this error is handled
157 logWarnOnce("Logging Once: Given offset points are not inside the map for lane: "
158 + std::to_string((int)lane.lane_id)
159 + "| intersection id: " + std::to_string((int)intersection.id.id));
160 continue;
161 }
162
163 lanelet::Id corresponding_lanelet_id;
164 if (lane.lane_attributes.directional_use.lane_direction == LANE_DIRECTION::EGRESS)
165 {
166 corresponding_lanelet_id = affected_llts.front().id();
167 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Default corresponding_lanelet_id: " << corresponding_lanelet_id <<", in EGRESS");
168
169 }
170 else //ingress
171 {
172 corresponding_lanelet_id = affected_llts.back().id();
173 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Default corresponding_lanelet_id: " << corresponding_lanelet_id <<", in INGRESS");
174 }
175
176 for (auto llt : affected_llts) // filter out intersection lanelets
177 {
178 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Checking if we can get entry/exit from lanelet " << llt.id());
179 //TODO direction of affected_llts may play role, but it should be good
180 if (llt.lanelet().get().hasAttribute("turn_direction") &&
181 (llt.lanelet().get().attribute("turn_direction").value().compare("left") == 0 ||
182 llt.lanelet().get().attribute("turn_direction").value().compare("right") == 0))
183 {
184 std::vector<lanelet::ConstLanelet> connecting_llts;
185 if (lane.lane_attributes.directional_use.lane_direction == LANE_DIRECTION::EGRESS)
186 {
187 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "lanelet " << llt.id() << " is actually part of the intersecion. Trying to detect EGRESS...");
188 connecting_llts = current_routing_graph->following(llt.lanelet().get());
189 }
190 else
191 {
192 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "lanelet " << llt.id() << " is actually part of the intersecion. Trying to detect INGRESS...");
193 connecting_llts = current_routing_graph->previous(llt.lanelet().get());
194 }
195
196 if (!connecting_llts.empty())
197 {
198 corresponding_lanelet_id = connecting_llts[0].id();
199 }
200 else
201 {
203 std::string("Logging Once: No connecting lanelets were detected inside!")
204 + " | intersection id: " + std::to_string((int)intersection.id.id));
205 continue;
206 }
207
208 break;
209 }
210 }
211
212 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Found existing lanelet id: " << corresponding_lanelet_id);
213
214 if (lane.lane_attributes.directional_use.lane_direction == LANE_DIRECTION::INGRESS)
215 {
216 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Detected INGRESS, " << (int)lane.lane_id);
217 entry[lane.lane_id] = corresponding_lanelet_id;
218 }
219 else if (lane.lane_attributes.directional_use.lane_direction == LANE_DIRECTION::EGRESS)
220 {
221 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Detected EGRESS, " << (int)lane.lane_id);
222 exit[lane.lane_id] = corresponding_lanelet_id;
223 }
224 // ignoring types that are neither ingress nor egress
225 }
226
227 // convert and save exit lane ids into lanelet ids with their corresponding signal group ids
228 for (auto iter = signal_group_to_exit_lanes.begin(); iter != signal_group_to_exit_lanes.end(); iter++)
229 {
230 for (auto exit_lane : iter->second)
231 {
232 if (exit.find(exit_lane) != exit.end())
233 {
234 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Adding exit_lane id: " << exit_lane);
235 signal_group_to_exit_lanelet_ids_[iter->first].insert(exit[exit_lane]);
236 }
237 else
238 {
239 // https://github.com/usdot-fhwa-stol/carma-platform/issues/1593
240 // Open issue TODO on how this error is handled
241 logWarnOnce("Logging Once: Unable to convert exit lane Id: "
242 + std::to_string((int)exit_lane) + ", to lanelet id using the given MAP.msg!"
243 + "| intersection id: " + std::to_string((int)intersection.id.id));
244 }
245 }
246 }
247
248 // convert and save entry lane ids into lanelet ids with their corresponding signal group ids
249 for (auto iter = signal_group_to_entry_lanes.begin(); iter != signal_group_to_entry_lanes.end(); iter++)
250 {
251 for (auto entry_lane : iter->second)
252 {
253 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Adding entry_lane id: " << entry_lane);
254 if (entry.find(entry_lane) != entry.end())
255 {
256 signal_group_to_entry_lanelet_ids_[iter->first].insert(entry[entry_lane]);
257 }
258 else
259 {
260 // https://github.com/usdot-fhwa-stol/carma-platform/issues/1593
261 // Open issue TODO on how this error is handled
262 logWarnOnce("Logging Once: Unable to convert entry lane Id: "
263 + std::to_string((int)entry_lane) + ", to lanelet id using the given MAP.msg!"
264 + "| intersection id: " + std::to_string((int)intersection.id.id));
265 }
266 }
267 }
268 }
269
270 lanelet::Id SignalizedIntersectionManager::matchSignalizedIntersection(const lanelet::Lanelets& entry_llts, const lanelet::Lanelets& exit_llts)
271 {
272 lanelet::Id matching_id = lanelet::InvalId;
273
274 std::vector<lanelet::SignalizedIntersectionPtr> existing_si;
275
276 for (auto llt : entry_llts)
277 {
278 auto intersections = llt.regulatoryElementsAs<lanelet::SignalizedIntersection>();
279
280 if (intersections.empty())
281 {
282 // no match if any of the entry lanelet is not part of any intersection.
283 break;
284 }
285 existing_si.insert(existing_si.end(), intersections.begin(),intersections.end());
286 }
287
288 for (auto intersection : existing_si)
289 {
290 auto existing_entry_llts = intersection->getEntryLanelets();
291 auto existing_exit_llts = intersection->getExitLanelets();
292
293 if (existing_exit_llts.size() != exit_llts.size() || existing_entry_llts.size() != entry_llts.size())
294 continue;
295
296 bool is_different = false;
297
298 for (auto llt: existing_entry_llts)
299 {
300 if (std::find(entry_llts.begin(), entry_llts.end(), llt) == entry_llts.end())
301 {
302 is_different = true;
303
304 break;
305 }
306 }
307
308 for (auto llt: existing_exit_llts)
309 {
310 if (std::find(exit_llts.begin(), exit_llts.end(), llt) == exit_llts.end())
311 {
312 is_different = true;
313
314 break;
315 }
316 }
317
318 if (!is_different)
319 {
320 // found a match
321 matching_id = intersection->id();
322
323 break;
324 }
325
326 }
327
328 return matching_id;
329 }
330
331 std::shared_ptr<lanelet::CarmaTrafficSignal> SignalizedIntersectionManager::createTrafficSignalUsingSGID(uint8_t signal_group_id, const lanelet::Lanelets& entry_lanelets, const lanelet::Lanelets& exit_lanelets)
332 {
333 std::vector<lanelet::LineString3d> stop_lines;
334 for (auto llt : entry_lanelets)
335 {
336 std::vector<lanelet::Point3d> points;
337 points.push_back(lanelet::Point3d(lanelet::utils::getId(), llt.leftBound2d().back().x(), llt.leftBound2d().back().y(), 0));
338 points.push_back(lanelet::Point3d(lanelet::utils::getId(), llt.rightBound().back().x(), llt.rightBound().back().y(), 0));
339
340 lanelet::LineString3d stop_line(lanelet::utils::getId(), points);
341 stop_lines.push_back(stop_line);
342 }
343
344 lanelet::Id traffic_light_id = lanelet::utils::getId();
345 std::shared_ptr<lanelet::CarmaTrafficSignal> traffic_light(new lanelet::CarmaTrafficSignal(lanelet::CarmaTrafficSignal::buildData(traffic_light_id, stop_lines, entry_lanelets, exit_lanelets)));
346 signal_group_to_traffic_light_id_[signal_group_id] = traffic_light_id;
347
348 for (auto llt : exit_lanelets)
349 {
350 signal_group_to_exit_lanelet_ids_[signal_group_id].insert(llt.id());
351 }
352 for (auto llt : entry_lanelets)
353 {
354 signal_group_to_entry_lanelet_ids_[signal_group_id].insert(llt.id());
355 }
356 return traffic_light;
357 }
358
359 void SignalizedIntersectionManager::createIntersectionFromMapMsg(std::vector<lanelet::SignalizedIntersectionPtr>& sig_intersections, std::vector<lanelet::CarmaTrafficSignalPtr>& traffic_signals, const carma_v2x_msgs::msg::MapData& map_msg,
360 const std::shared_ptr<lanelet::LaneletMap>& map, std::shared_ptr<const lanelet::routing::RoutingGraph> routing_graph)
361 {
362
363 if (target_frame_ == "")
364 {
365 logWarnOnce("Logging Once: Georeference is not loaded yet. Returning without processing this MAP msg.");
366 return;
367 }
368
369 for (auto const& intersection : map_msg.intersections)
370 {
371 std::unordered_map<uint8_t, lanelet::Id> entry;
372 std::unordered_map<uint8_t, lanelet::Id> exit;
373
374 convertLaneToLaneletId(entry, exit, intersection, map, routing_graph);
375
376 std::vector<lanelet::Lanelet> entry_llts;
377 std::vector<lanelet::Lanelet> exit_llts;
378
379 for (auto iter = entry.begin(); iter != entry.end(); iter++)
380 {
381 entry_llts.push_back(map->laneletLayer.get(iter->second));
382 }
383 for (auto iter = exit.begin(); iter != exit.end(); iter++)
384 {
385 exit_llts.push_back(map->laneletLayer.get(iter->second));
386 }
387
388 lanelet::Id intersection_id = matchSignalizedIntersection(entry_llts, exit_llts);
389
390 if (intersection_id == lanelet::InvalId)
391 {
392 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "No existing intersection found. Creating a new one...");
393 intersection_id = lanelet::utils::getId();
394
395 std::vector<lanelet::Lanelet> interior_llts = identifyInteriorLanelets(entry_llts, map);
396
397 std::shared_ptr<lanelet::SignalizedIntersection> sig_inter(new lanelet::SignalizedIntersection
398 (lanelet::SignalizedIntersection::buildData(intersection_id, entry_llts, exit_llts, interior_llts)));
399 intersection_id_to_regem_id_[intersection.id.id] = intersection_id;
400 regem_id_to_intersection_id_[intersection_id] = intersection.id.id;
401 sig_intersections.push_back(sig_inter);
402 }
403 }
404
405
406 // create signal group for each from the message
407 // check if it already exists
408 for (auto sig_grp_pair : signal_group_to_exit_lanelet_ids_)
409 {
410 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::SignalizedIntersectionManager"), "Creating signal for: " << (int)sig_grp_pair.first);
411 // ignore the traffic signals already inside
412 if (signal_group_to_traffic_light_id_.find(sig_grp_pair.first) != signal_group_to_traffic_light_id_.end() &&
413 map->regulatoryElementLayer.exists(signal_group_to_traffic_light_id_[sig_grp_pair.first]))
414 {
415 continue;
416 }
417
418 std::vector<lanelet::Lanelet> exit_lanelets;
419 for (auto iter = sig_grp_pair.second.begin(); iter != sig_grp_pair.second.end(); iter++)
420 {
421 exit_lanelets.push_back(map->laneletLayer.get(*iter));
422 }
423 std::vector<lanelet::Lanelet> entry_lanelets;
424 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++)
425 {
426 entry_lanelets.push_back(map->laneletLayer.get(*iter));
427 }
428
429 if (entry_lanelets.empty())
430 {
431 logWarnOnce("Logging Once: Unable to create traffic signal for signal group id: "
432 + std::to_string((int)sig_grp_pair.first)
433 + " as entry lanelets are empty!");
434 continue;
435 }
436 traffic_signals.push_back(createTrafficSignalUsingSGID(sig_grp_pair.first, entry_lanelets, exit_lanelets));
437 }
438 }
439
440 lanelet::Lanelets SignalizedIntersectionManager::identifyInteriorLanelets(const lanelet::Lanelets& entry_llts, const std::shared_ptr<lanelet::LaneletMap>& map)
441 {
442 lanelet::BasicLineString2d polygon_corners;
443
444 if (entry_llts.size() < 2) //at least two lanes (1 ingress and 1 egress) needed to form intersection
445 {
446 return {};
447 }
448
449 for (auto llt : entry_llts)
450 {
451 lanelet::BasicPoint2d pt(llt.centerline2d().back().x(), llt.centerline2d().back().y());
452 polygon_corners.push_back(pt);
453 }
454 lanelet::BasicPolygon2d polygon(polygon_corners);
455 auto interior_llt_pairs = lanelet::geometry::findWithin2d(map->laneletLayer, polygon);
456 lanelet::Lanelets interior_llts;
457
458 for (auto pair : interior_llt_pairs)
459 {
460 if (std::find(entry_llts.begin(),entry_llts.end(), pair.second) == entry_llts.end())
461 interior_llts.push_back(pair.second);
462 }
463 return interior_llts;
464 }
465
467 {
473
474 return *this;
475 }
476
478 {
484 }
485
486 void SignalizedIntersectionManager::processSpatFromMsg(const carma_v2x_msgs::msg::SPAT &spat_msg, const std::shared_ptr<lanelet::LaneletMap>& semantic_map)
487 {
489 {
490 return;
491 }
492
493 if (!semantic_map)
494 {
495 RCLCPP_INFO_STREAM(rclcpp::get_logger("carma_wm"), "Map is not set yet.");
496 return;
497 }
498
499 if (spat_msg.intersection_state_list.empty())
500 {
501 logWarnOnce("Logging Once: No intersection_state_list in the newly received SPAT msg. Returning...");
502 return;
503 }
504
505 for (const auto& curr_intersection : spat_msg.intersection_state_list)
506 {
507 for (const auto& current_movement_state : curr_intersection.movement_list)
508 {
509 lanelet::Id curr_light_id = getTrafficSignalId(curr_intersection.id.id, current_movement_state.signal_group);
510
511 if (curr_light_id == lanelet::InvalId)
512 {
513 continue;
514 }
515
516 lanelet::CarmaTrafficSignalPtr curr_light =
517 getTrafficSignal(curr_light_id, semantic_map);
518
519 if (curr_light == nullptr)
520 {
521 continue;
522 }
523
524 // all maneuver types in same signal group is currently expected to share signal timing, so only 0th index is used when setting states
525 if (current_movement_state.movement_event_list.empty())
526 {
527 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm"), "Movement_event_list is empty . intersection_id: " << (int)curr_intersection.id.id << ", and signal_group_id: " << (int)current_movement_state.signal_group);
528 continue;
529 }
530 else
531 {
532 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm"), "Movement_event_list size: " << current_movement_state.movement_event_list.size() << " . intersection_id: " << (int)curr_intersection.id.id << ", and signal_group_id: " << (int)current_movement_state.signal_group);
533 }
534
535 curr_light->revision_ = curr_intersection.revision; // valid SPAT msg
536
537 auto [new_end_times_and_states, new_start_times ]=
538 extract_signal_states_from_movement_state(curr_intersection, current_movement_state);
539
540 curr_light->recorded_time_stamps = new_end_times_and_states;
541 curr_light->recorded_start_time_stamps = new_start_times;
542 }
543 }
544 }
545
551 static std::mutex log_mutex;
552
553 std::lock_guard<std::mutex> lock(log_mutex);
555 RCLCPP_INFO_STREAM(rclcpp::get_logger("carma_wm"), message);
557 }
558 }
559
565 static std::mutex log_mutex;
566
567 std::lock_guard<std::mutex> lock(log_mutex);
569 RCLCPP_WARN_STREAM(rclcpp::get_logger("carma_wm"), message);
571 }
572 }
573
574 lanelet::Id SignalizedIntersectionManager::getTrafficSignalId(uint16_t intersection_id, uint8_t signal_group_id)
575 {
576 lanelet::Id signal_id = lanelet::InvalId;
577
578 // Printing only once because MAP/SPAT is broadcasted frequently and can easily spam the log
579 if (intersection_id_to_regem_id_.find(intersection_id) == intersection_id_to_regem_id_.end())
580 {
581 // Currently, platform is not supporting multiple intersections, so if the id exists
582 // signal_group is expected to be for that intersection
583 logWarnOnce("Logging Once: Intersection id: "
584 + std::to_string((int)intersection_id)
585 + " is not found in the map. Only printing once. Returning...");
586 return lanelet::InvalId;
587 }
588
589 if (signal_group_to_traffic_light_id_.find(signal_group_id)
591 {
592 signal_id = signal_group_to_traffic_light_id_[signal_group_id];
593 }
594 else
595 {
596 logWarnOnce("Logging Once: Signal group id: "
597 + std::to_string((int)signal_group_id) + " for intersection id: "
598 + std::to_string((int)intersection_id) + " is not found in the map. "
599 + "Only printing once until found. Returning...");
600 return signal_id;
601 }
602
603 logInfoOnce("Signal group id: "
604 + std::to_string((int)signal_group_id) + " for intersection id: "
605 + std::to_string((int)intersection_id) + " is found in the map with regem id: "
606 + std::to_string((int)signal_id));
607
608 return signal_id;
609 }
610
611 lanelet::CarmaTrafficSignalPtr SignalizedIntersectionManager::getTrafficSignal(const
612 lanelet::Id& id, const std::shared_ptr<lanelet::LaneletMap>& semantic_map) const
613 {
614 auto general_regem = semantic_map->regulatoryElementLayer.get(id);
615
616 auto lanelets_general = semantic_map->laneletLayer.findUsages(general_regem);
617 if (lanelets_general.empty())
618 {
620 "Logging Once: There was an error querying lanelet for traffic light with id: "
621 + std::to_string((int)id));
622 }
623
624 if (auto curr_light_list =
625 lanelets_general[0].regulatoryElementsAs<lanelet::CarmaTrafficSignal>();
626 curr_light_list.empty())
627 {
629 "Logging Once: There was an error querying traffic light with id: "
630 + std::to_string((int)id));
631 return nullptr;
632 }
633
634 lanelet::CarmaTrafficSignalPtr curr_light;
635
636 for (auto signal : lanelets_general[0].regulatoryElementsAs<lanelet::CarmaTrafficSignal>())
637 {
638 if (signal->id() == id)
639 {
640 curr_light = signal;
641 break;
642 }
643 }
644
645 if (!curr_light)
646 {
648 "Logging Once: Was not able to find traffic signal with id: "
649 + std::to_string((int)id) + ", ignoring...");
650 return nullptr;
651 }
652
653 return curr_light;
654 }
655
656 std::tuple<std::vector<std::pair<boost::posix_time::ptime, lanelet::CarmaTrafficSignalState>>,
657 std::vector<boost::posix_time::ptime>>
659 const carma_v2x_msgs::msg::IntersectionState& curr_intersection,
660 const carma_v2x_msgs::msg::MovementState& current_movement_state)
661 {
662 std::vector<std::pair<boost::posix_time::ptime, lanelet::CarmaTrafficSignalState>>
663 min_end_t_and_states;
664
665 std::vector<boost::posix_time::ptime> start_time_and_states;
666
667 for(const auto& current_movement_event:current_movement_state.movement_event_list)
668 {
669 // raw min_end_time in seconds measured from the most recent full hour
670 boost::posix_time::ptime min_end_time = lanelet::time::timeFromSec(
671 current_movement_event.timing.min_end_time);
672 boost::posix_time::ptime start_time = lanelet::time::timeFromSec(
673 current_movement_event.timing.start_time);
674
675 min_end_time = min_end_time_converter_minute_of_year(min_end_time,
676 curr_intersection.moy_exists,curr_intersection.moy,
677 use_sim_time_, use_real_time_spat_in_sim_); // Accounting minute of the year
678
679 start_time = min_end_time_converter_minute_of_year(start_time,
680 curr_intersection.moy_exists,curr_intersection.moy,
681 use_sim_time_, use_real_time_spat_in_sim_); // Accounting minute of the year
682
683 auto received_state = static_cast<lanelet::CarmaTrafficSignalState>(
684 current_movement_event.event_state.movement_phase_state);
685
686 min_end_t_and_states.push_back(std::make_pair(min_end_time, received_state));
687
688 start_time_and_states.push_back(start_time);
689
690 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm"), "intersection id: "
691 << (int)curr_intersection.id.id << ", signal: " << (int)current_movement_state.signal_group
692 << ", start_time: " << std::to_string(lanelet::time::toSec(start_time))
693 << ", end_time: " << std::to_string(lanelet::time::toSec(min_end_time))
694 << ", state: " << received_state);
695 }
696
697 return std::make_tuple(min_end_t_and_states, start_time_and_states);
698 }
699
701 boost::posix_time::ptime min_end_time,bool moy_exists,uint32_t moy, bool is_simulation,
702 bool use_real_time_spat_in_sim)
703 {
704 double simulation_time_difference_in_seconds = 0.0;
705 double wall_time_offset_in_seconds = 0.0;
706 // NOTE: In simulation, ROS1 clock (often coming from CARLA) can have a large time ahead.
707 // the timing calculated here is in Simulation time, which is behind. Therefore, the world model adds the offset to make it meaningful to carma-platform:
708 // https://github.com/usdot-fhwa-stol/carma-platform/issues/2217
710 {
711 simulation_time_difference_in_seconds = ros1_clock_.value().seconds() - simulation_clock_.value().seconds();
712 }
713 else if (ros1_clock_ && use_real_time_spat_in_sim)
714 {
715 // NOTE: If carma-platform is running in simulation with clock synced to sim time but the incoming spat information is based on wall clock
716 // the spat signal phase time must be offset to sim time.
717 wall_time_offset_in_seconds = (std::chrono::duration<double>(std::chrono::system_clock::now().time_since_epoch()).count()) - ros1_clock_.value().seconds();
718 }
719
720 min_end_time += lanelet::time::durationFromSec(simulation_time_difference_in_seconds);
721 min_end_time -= lanelet::time::durationFromSec(wall_time_offset_in_seconds);
722
723 if (moy_exists) //account for minute of the year
724 {
725 auto inception_boost(boost::posix_time::time_from_string("1970-01-01 00:00:00.000")); // inception of epoch
726 auto duration_since_inception(lanelet::time::durationFromSec(std::chrono::duration<double>(std::chrono::system_clock::now().time_since_epoch()).count()));
727 auto curr_time_boost = inception_boost + duration_since_inception;
728
729 int curr_year = curr_time_boost.date().year();
730
731 // Force the current year to start of epoch if it is simulation
732 if (is_simulation && !use_real_time_spat_in_sim)
733 curr_year = 1970;
734
735 auto curr_year_start_boost(boost::posix_time::time_from_string(std::to_string(curr_year)+ "-01-01 00:00:00.000"));
736
737 auto curr_minute_stamp_boost = curr_year_start_boost + boost::posix_time::minutes((int)moy);
738
739 long hours_of_day = curr_minute_stamp_boost.time_of_day().hours();
740 long curr_month = curr_minute_stamp_boost.date().month();
741 long curr_day = curr_minute_stamp_boost.date().day();
742
743 auto curr_day_boost(boost::posix_time::time_from_string(std::to_string(curr_year) + "/" + std::to_string(curr_month) + "/" + std::to_string(curr_day) +" 00:00:00.000")); // GMT is the standard
744 auto curr_hour_boost = curr_day_boost + boost::posix_time::hours(hours_of_day);
745
746 min_end_time += lanelet::time::durationFromSec(lanelet::time::toSec(curr_hour_boost));
747 return min_end_time;
748 }
749 else
750 {
751 return min_end_time; // return unchanged
752 }
753 }
754
755} // 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::tuple< std::vector< std::pair< boost::posix_time::ptime, lanelet::CarmaTrafficSignalState > >, std::vector< boost::posix_time::ptime > > extract_signal_states_from_movement_state(const carma_v2x_msgs::msg::IntersectionState &curr_intersection, const carma_v2x_msgs::msg::MovementState &current_movement_state)
Extract tuple of 1) vector of pair of traffic signal states' min_end_time and their states,...
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.
void logInfoOnce(const std::string &message) const
Log an info message only once per unique message.
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_
lanelet::Id getTrafficSignalId(uint16_t intersection_id, uint8_t signal_id)
helper for traffic signal 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...
lanelet::CarmaTrafficSignalPtr getTrafficSignal(const lanelet::Id &id, const std::shared_ptr< lanelet::LaneletMap > &semantic_map) const
helper for getting traffic signal with given lanelet::Id
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_
void processSpatFromMsg(const carma_v2x_msgs::msg::SPAT &spat_msg, const std::shared_ptr< lanelet::LaneletMap > &semantic_map)
processSpatFromMsg update map's traffic light states with SPAT msg NOTE: This is enabled in the indiv...
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 logWarnOnce(const std::string &message) const
Log a warning message only once per unique message.
boost::posix_time::ptime min_end_time_converter_minute_of_year(boost::posix_time::ptime min_end_time, bool moy_exists, uint32_t moy=0, bool is_simulation=true, bool use_real_time_spat_in_sim=false)
update minimum end time to account for minute of the year
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.