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.
carma_wm::SignalizedIntersectionManager Class Reference

This class manages and keeps track of all signalized intersections in the map. All of the SPAT and MAP standard's lane ids to lanelet id mapping is recorded here. NOTE: This class functions do not update the map given. More...

#include <SignalizedIntersectionManager.hpp>

Collaboration diagram for carma_wm::SignalizedIntersectionManager:
Collaboration graph

Public Member Functions

 SignalizedIntersectionManager ()
 
 SignalizedIntersectionManager (const SignalizedIntersectionManager &other)
 Copy constructor that copies everything except the traffic signal states. This is to keep the states although the map is updated or a similar event happened NOTE: The function does not update the map with new elements. More...
 
SignalizedIntersectionManageroperator= (SignalizedIntersectionManager other)
 Assignment operator that copies everything except the traffic signal states. This is to keep the states although the map is updated or a similar event happened NOTE: The function does not update the map with new elements. More...
 
bool operator== (const SignalizedIntersectionManager &rhs)
 Equality operator that checks if every mapping are same except the traffic signal states. This is to keep the states although the map is updated or a similar event happened NOTE: The function does not update the map with new elements. More...
 
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.msg and the lanelet_map NOTE: The function does not update the map with new elements. More...
 
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.msg. This function also records signal_group_id_to its own lanelet id, and also signal group to entry and exit lanelets id mappings. More...
 
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 distance to a lanelet as map msg points are guaranteed to apply to a single lane. More...
 
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. More...
 
void setTargetFrame (const std::string &target_frame)
 Saves the georeference string to be used for converting MAP.msg coordinates. More...
 
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) internally. More...
 
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) internally. More...
 
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 individual nodes through wm_listener's setWMSpatProcessingState() More...
 
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, which is mainly used by CARMA to comply with traffic signals. 2) vector of traffic signal states' start_times that match in order. More...
 
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 More...
 
lanelet::Id getTrafficSignalId (uint16_t intersection_id, uint8_t signal_id)
 helper for traffic signal Id More...
 
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 More...
 
void logInfoOnce (const std::string &message) const
 Log an info message only once per unique message. More...
 
void logWarnOnce (const std::string &message) const
 Log a warning message only once per unique message. More...
 

Public Attributes

std::unordered_map< uint16_t, std::vector< lanelet::Point3d > > intersection_nodes_
 
std::unordered_map< uint16_t, std::pair< double, double > > intersection_coord_correction_
 
std::unordered_map< uint16_t, lanelet::Id > intersection_id_to_regem_id_
 
std::unordered_map< lanelet::Id, uint16_t > regem_id_to_intersection_id_
 
std::unordered_map< uint8_t, lanelet::Id > signal_group_to_traffic_light_id_
 
std::unordered_map< uint8_t, std::unordered_set< lanelet::Id > > signal_group_to_exit_lanelet_ids_
 
std::unordered_map< uint8_t, std::unordered_set< lanelet::Id > > signal_group_to_entry_lanelet_ids_
 
std::optional< rclcpp::Time > ros1_clock_ = std::nullopt
 
std::optional< rclcpp::Time > simulation_clock_ = std::nullopt
 
bool use_sim_time_
 
bool use_real_time_spat_in_sim_
 
SIGNAL_PHASE_PROCESSING spat_processor_state_ = SIGNAL_PHASE_PROCESSING::OFF
 
std::set< std::string > previous_busy_log_streams_
 

Private Attributes

std::string target_frame_ = ""
 
double max_lane_width_ = 4
 

Detailed Description

This class manages and keeps track of all signalized intersections in the map. All of the SPAT and MAP standard's lane ids to lanelet id mapping is recorded here. NOTE: This class functions do not update the map given.

Definition at line 59 of file SignalizedIntersectionManager.hpp.

Constructor & Destructor Documentation

◆ SignalizedIntersectionManager() [1/2]

carma_wm::SignalizedIntersectionManager::SignalizedIntersectionManager ( )
inline

Definition at line 63 of file SignalizedIntersectionManager.hpp.

63{}

◆ SignalizedIntersectionManager() [2/2]

carma_wm::SignalizedIntersectionManager::SignalizedIntersectionManager ( const SignalizedIntersectionManager other)

Copy constructor that copies everything except the traffic signal states. This is to keep the states although the map is updated or a similar event happened NOTE: The function does not update the map with new elements.

Parameters
[out]othermanager

Definition at line 470 of file SignalizedIntersectionManager.cpp.

471 {
472 this->signal_group_to_entry_lanelet_ids_ = other.signal_group_to_entry_lanelet_ids_;
473 this->signal_group_to_exit_lanelet_ids_ = other.signal_group_to_exit_lanelet_ids_;
474 this->intersection_id_to_regem_id_ = other.intersection_id_to_regem_id_;
475 this->signal_group_to_traffic_light_id_ = other.signal_group_to_traffic_light_id_;
476 this->intersection_coord_correction_ = other.intersection_coord_correction_;
477 }
std::unordered_map< uint16_t, std::pair< double, double > > intersection_coord_correction_
std::unordered_map< uint8_t, std::unordered_set< lanelet::Id > > signal_group_to_entry_lanelet_ids_
std::unordered_map< uint16_t, lanelet::Id > intersection_id_to_regem_id_
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_

References intersection_coord_correction_, intersection_id_to_regem_id_, signal_group_to_entry_lanelet_ids_, signal_group_to_exit_lanelet_ids_, and signal_group_to_traffic_light_id_.

Member Function Documentation

◆ convertLaneToLaneletId()

void carma_wm::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,
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.msg. This function also records signal_group_id_to its own lanelet id, and also signal group to entry and exit lanelets id mappings.

Parameters
[out]entrylane id to lanelet id mappings to return
[out]exitlane id to lanelet id mappings to return
intersectionMAP.msg that consists all static data portion of the intersection
maplanelet_map to check
routing_graphof the lanelet map to accurately detect lanes
Exceptions
invalid_argumentif given coordinates in the msg doesn't exist in the map TODO: Need to think about error buffer in the future. Map msgs are made from google maps or open streets maps normally so this function might run into some errors from that.

Definition at line 58 of file SignalizedIntersectionManager.cpp.

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 }
std::unordered_map< uint16_t, std::vector< lanelet::Point3d > > intersection_nodes_
void logWarnOnce(const std::string &message) const
Log a warning message only once per unique message.
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.

References carma_wm::LANE_DIRECTION::EGRESS, carma_wm::query::getAffectedLaneletOrAreas(), process_bag::i, carma_wm::LANE_DIRECTION::INGRESS, intersection_coord_correction_, intersection_nodes_, logWarnOnce(), max_lane_width_, signal_group_to_entry_lanelet_ids_, signal_group_to_exit_lanelet_ids_, target_frame_, and carma_cooperative_perception::to_string().

Referenced by createIntersectionFromMapMsg().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ createIntersectionFromMapMsg()

void carma_wm::SignalizedIntersectionManager::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.msg and the lanelet_map NOTE: The function does not update the map with new elements.

Parameters
[out]intersectionsto return
[out]traffic_signalsto return
map_msgMAP.msg that consists all static data portion of the intersection
maplanelet_map to check
routing_graphof the lanelet map to accurately detect lanes

Definition at line 359 of file SignalizedIntersectionManager.cpp.

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 traffic_signals.push_back(createTrafficSignalUsingSGID(sig_grp_pair.first, entry_lanelets, exit_lanelets));
430 }
431 }
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< lanelet::Id, uint16_t > regem_id_to_intersection_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...
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....

References convertLaneToLaneletId(), createTrafficSignalUsingSGID(), identifyInteriorLanelets(), intersection_id_to_regem_id_, logWarnOnce(), matchSignalizedIntersection(), regem_id_to_intersection_id_, signal_group_to_entry_lanelet_ids_, signal_group_to_exit_lanelet_ids_, signal_group_to_traffic_light_id_, and target_frame_.

Here is the call graph for this function:

◆ createTrafficSignalUsingSGID()

std::shared_ptr< lanelet::CarmaTrafficSignal > carma_wm::SignalizedIntersectionManager::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) internally.

Parameters
signal_group_idof the traffic signal
exit_lltsof the signal_group
entry_lltsof the signal_group
Returns
traffic signal corresponding to the signal group

Definition at line 331 of file SignalizedIntersectionManager.cpp.

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 }

References signal_group_to_entry_lanelet_ids_, signal_group_to_exit_lanelet_ids_, and signal_group_to_traffic_light_id_.

Referenced by createIntersectionFromMapMsg().

Here is the caller graph for this function:

◆ extract_signal_states_from_movement_state()

std::tuple< std::vector< std::pair< boost::posix_time::ptime, lanelet::CarmaTrafficSignalState > >, std::vector< boost::posix_time::ptime > > carma_wm::SignalizedIntersectionManager::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, which is mainly used by CARMA to comply with traffic signals. 2) vector of traffic signal states' start_times that match in order.

Parameters
curr_intersectioncarma_v2x_msgs::msg::IntersectionState from SPAT
current_movement_statecarma_v2x_msgs::msg::MovementState from SPAT
Returns
tuple of 2 vectors. 1) vector of min_end_time and state pairs 2) vector of start_time

Definition at line 651 of file SignalizedIntersectionManager.cpp.

654 {
655 std::vector<std::pair<boost::posix_time::ptime, lanelet::CarmaTrafficSignalState>>
656 min_end_t_and_states;
657
658 std::vector<boost::posix_time::ptime> start_time_and_states;
659
660 for(const auto& current_movement_event:current_movement_state.movement_event_list)
661 {
662 // raw min_end_time in seconds measured from the most recent full hour
663 boost::posix_time::ptime min_end_time = lanelet::time::timeFromSec(
664 current_movement_event.timing.min_end_time);
665 boost::posix_time::ptime start_time = lanelet::time::timeFromSec(
666 current_movement_event.timing.start_time);
667
668 min_end_time = min_end_time_converter_minute_of_year(min_end_time,
669 curr_intersection.moy_exists,curr_intersection.moy,
670 use_sim_time_, use_real_time_spat_in_sim_); // Accounting minute of the year
671
672 start_time = min_end_time_converter_minute_of_year(start_time,
673 curr_intersection.moy_exists,curr_intersection.moy,
674 use_sim_time_, use_real_time_spat_in_sim_); // Accounting minute of the year
675
676 auto received_state = static_cast<lanelet::CarmaTrafficSignalState>(
677 current_movement_event.event_state.movement_phase_state);
678
679 min_end_t_and_states.push_back(std::make_pair(min_end_time, received_state));
680
681 start_time_and_states.push_back(start_time);
682
683 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm"), "intersection id: "
684 << (int)curr_intersection.id.id << ", signal: " << (int)current_movement_state.signal_group
685 << ", start_time: " << std::to_string(lanelet::time::toSec(start_time))
686 << ", end_time: " << std::to_string(lanelet::time::toSec(min_end_time))
687 << ", state: " << received_state);
688 }
689
690 return std::make_tuple(min_end_t_and_states, start_time_and_states);
691 }
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

References min_end_time_converter_minute_of_year(), carma_cooperative_perception::to_string(), use_real_time_spat_in_sim_, and use_sim_time_.

Referenced by processSpatFromMsg().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getTrafficSignal()

lanelet::CarmaTrafficSignalPtr carma_wm::SignalizedIntersectionManager::getTrafficSignal ( const lanelet::Id &  id,
const std::shared_ptr< lanelet::LaneletMap > &  semantic_map 
) const

helper for getting traffic signal with given lanelet::Id

Definition at line 604 of file SignalizedIntersectionManager.cpp.

606 {
607 auto general_regem = semantic_map->regulatoryElementLayer.get(id);
608
609 auto lanelets_general = semantic_map->laneletLayer.findUsages(general_regem);
610 if (lanelets_general.empty())
611 {
613 "Logging Once: There was an error querying lanelet for traffic light with id: "
614 + std::to_string((int)id));
615 }
616
617 if (auto curr_light_list =
618 lanelets_general[0].regulatoryElementsAs<lanelet::CarmaTrafficSignal>();
619 curr_light_list.empty())
620 {
622 "Logging Once: There was an error querying traffic light with id: "
623 + std::to_string((int)id));
624 return nullptr;
625 }
626
627 lanelet::CarmaTrafficSignalPtr curr_light;
628
629 for (auto signal : lanelets_general[0].regulatoryElementsAs<lanelet::CarmaTrafficSignal>())
630 {
631 if (signal->id() == id)
632 {
633 curr_light = signal;
634 break;
635 }
636 }
637
638 if (!curr_light)
639 {
641 "Logging Once: Was not able to find traffic signal with id: "
642 + std::to_string((int)id) + ", ignoring...");
643 return nullptr;
644 }
645
646 return curr_light;
647 }

References logWarnOnce(), and carma_cooperative_perception::to_string().

Referenced by processSpatFromMsg().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getTrafficSignalId()

lanelet::Id carma_wm::SignalizedIntersectionManager::getTrafficSignalId ( uint16_t  intersection_id,
uint8_t  signal_id 
)

helper for traffic signal Id

Definition at line 567 of file SignalizedIntersectionManager.cpp.

568 {
569 lanelet::Id signal_id = lanelet::InvalId;
570
571 // Printing only once because MAP/SPAT is broadcasted frequently and can easily spam the log
572 if (intersection_id_to_regem_id_.find(intersection_id) == intersection_id_to_regem_id_.end())
573 {
574 // Currently, platform is not supporting multiple intersections, so if the id exists
575 // signal_group is expected to be for that intersection
576 logWarnOnce("Logging Once: Intersection id: "
577 + std::to_string((int)intersection_id)
578 + " is not found in the map. Only printing once. Returning...");
579 return lanelet::InvalId;
580 }
581
582 if (signal_group_to_traffic_light_id_.find(signal_group_id)
584 {
585 signal_id = signal_group_to_traffic_light_id_[signal_group_id];
586 }
587 else
588 {
589 logWarnOnce("Logging Once: Signal group id: "
590 + std::to_string((int)signal_group_id) + " for intersection id: "
591 + std::to_string((int)intersection_id) + " is not found in the map. "
592 + "Only printing once until found. Returning...");
593 return signal_id;
594 }
595
596 logInfoOnce("Signal group id: "
597 + std::to_string((int)signal_group_id) + " for intersection id: "
598 + std::to_string((int)intersection_id) + " is found in the map with regem id: "
599 + std::to_string((int)signal_id));
600
601 return signal_id;
602 }
void logInfoOnce(const std::string &message) const
Log an info message only once per unique message.

References intersection_id_to_regem_id_, logInfoOnce(), logWarnOnce(), signal_group_to_traffic_light_id_, and carma_cooperative_perception::to_string().

Referenced by processSpatFromMsg().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ identifyInteriorLanelets()

lanelet::Lanelets carma_wm::SignalizedIntersectionManager::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) internally.

Parameters
signal_group_idof the traffic signal
exit_lltsof the signal_group
entry_lltsof the signal_group
Returns
traffic signal corresponding to the signal group

Definition at line 433 of file SignalizedIntersectionManager.cpp.

434 {
435 lanelet::BasicLineString2d polygon_corners;
436
437 if (entry_llts.size() < 2) //at least two lanes (1 ingress and 1 egress) needed to form intersection
438 {
439 return {};
440 }
441
442 for (auto llt : entry_llts)
443 {
444 lanelet::BasicPoint2d pt(llt.centerline2d().back().x(), llt.centerline2d().back().y());
445 polygon_corners.push_back(pt);
446 }
447 lanelet::BasicPolygon2d polygon(polygon_corners);
448 auto interior_llt_pairs = lanelet::geometry::findWithin2d(map->laneletLayer, polygon);
449 lanelet::Lanelets interior_llts;
450
451 for (auto pair : interior_llt_pairs)
452 {
453 if (std::find(entry_llts.begin(),entry_llts.end(), pair.second) == entry_llts.end())
454 interior_llts.push_back(pair.second);
455 }
456 return interior_llts;
457 }

Referenced by createIntersectionFromMapMsg().

Here is the caller graph for this function:

◆ logInfoOnce()

void carma_wm::SignalizedIntersectionManager::logInfoOnce ( const std::string &  message) const

Log an info message only once per unique message.

Parameters
messageThe message to log

Definition at line 543 of file SignalizedIntersectionManager.cpp.

543 {
544 static std::mutex log_mutex;
545
546 std::lock_guard<std::mutex> lock(log_mutex);
548 RCLCPP_INFO_STREAM(rclcpp::get_logger("carma_wm"), message);
550 }
551 }

References previous_busy_log_streams_.

Referenced by getTrafficSignalId().

Here is the caller graph for this function:

◆ logWarnOnce()

void carma_wm::SignalizedIntersectionManager::logWarnOnce ( const std::string &  message) const

Log a warning message only once per unique message.

Parameters
messageThe message to log

Definition at line 557 of file SignalizedIntersectionManager.cpp.

557 {
558 static std::mutex log_mutex;
559
560 std::lock_guard<std::mutex> lock(log_mutex);
562 RCLCPP_WARN_STREAM(rclcpp::get_logger("carma_wm"), message);
564 }
565 }

References previous_busy_log_streams_.

Referenced by convertLaneToLaneletId(), createIntersectionFromMapMsg(), getTrafficSignal(), getTrafficSignalId(), and processSpatFromMsg().

Here is the caller graph for this function:

◆ matchSignalizedIntersection()

lanelet::Id carma_wm::SignalizedIntersectionManager::matchSignalizedIntersection ( const lanelet::Lanelets &  entry_llts,
const lanelet::Lanelets &  exit_llts 
)

Returns existing signalized intersection with same entry and exit llts if exists.

Parameters
entry_lltsof the intersection
exit_lltsof the intersection
Returns
id of the matching intersection in the map, or lanelet::InvalId if none exists

Definition at line 270 of file SignalizedIntersectionManager.cpp.

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 }

Referenced by createIntersectionFromMapMsg().

Here is the caller graph for this function:

◆ min_end_time_converter_minute_of_year()

boost::posix_time::ptime carma_wm::SignalizedIntersectionManager::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

Parameters
min_end_timeminimum end time of the spat movement event list
moy_existstells weather minute of the year exist or not
moyvalue of the minute of the year
use_real_time_spat_in_simBoolean to indicate if the incoming spat is based on wall clock. Required in edge cases where deployment in simulation is receiving SPaT messages based on wall clock.

Definition at line 693 of file SignalizedIntersectionManager.cpp.

696 {
697 double simulation_time_difference_in_seconds = 0.0;
698 double wall_time_offset_in_seconds = 0.0;
699 // NOTE: In simulation, ROS1 clock (often coming from CARLA) can have a large time ahead.
700 // 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:
701 // https://github.com/usdot-fhwa-stol/carma-platform/issues/2217
703 {
704 simulation_time_difference_in_seconds = ros1_clock_.value().seconds() - simulation_clock_.value().seconds();
705 }
706 else if (ros1_clock_ && use_real_time_spat_in_sim)
707 {
708 // NOTE: If carma-platform is running in simulation with clock synced to sim time but the incoming spat information is based on wall clock
709 // the spat signal phase time must be offset to sim time.
710 wall_time_offset_in_seconds = (std::chrono::duration<double>(std::chrono::system_clock::now().time_since_epoch()).count()) - ros1_clock_.value().seconds();
711 }
712
713 min_end_time += lanelet::time::durationFromSec(simulation_time_difference_in_seconds);
714 min_end_time -= lanelet::time::durationFromSec(wall_time_offset_in_seconds);
715
716 if (moy_exists) //account for minute of the year
717 {
718 auto inception_boost(boost::posix_time::time_from_string("1970-01-01 00:00:00.000")); // inception of epoch
719 auto duration_since_inception(lanelet::time::durationFromSec(std::chrono::duration<double>(std::chrono::system_clock::now().time_since_epoch()).count()));
720 auto curr_time_boost = inception_boost + duration_since_inception;
721
722 int curr_year = curr_time_boost.date().year();
723
724 // Force the current year to start of epoch if it is simulation
725 if (is_simulation && !use_real_time_spat_in_sim)
726 curr_year = 1970;
727
728 auto curr_year_start_boost(boost::posix_time::time_from_string(std::to_string(curr_year)+ "-01-01 00:00:00.000"));
729
730 auto curr_minute_stamp_boost = curr_year_start_boost + boost::posix_time::minutes((int)moy);
731
732 long hours_of_day = curr_minute_stamp_boost.time_of_day().hours();
733 long curr_month = curr_minute_stamp_boost.date().month();
734 long curr_day = curr_minute_stamp_boost.date().day();
735
736 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
737 auto curr_hour_boost = curr_day_boost + boost::posix_time::hours(hours_of_day);
738
739 min_end_time += lanelet::time::durationFromSec(lanelet::time::toSec(curr_hour_boost));
740 return min_end_time;
741 }
742 else
743 {
744 return min_end_time; // return unchanged
745 }
746 }

References ros1_clock_, simulation_clock_, and carma_cooperative_perception::to_string().

Referenced by extract_signal_states_from_movement_state().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ operator=()

SignalizedIntersectionManager & carma_wm::SignalizedIntersectionManager::operator= ( SignalizedIntersectionManager  other)

Assignment operator that copies everything except the traffic signal states. This is to keep the states although the map is updated or a similar event happened NOTE: The function does not update the map with new elements.

Parameters
[out]othermanager

Definition at line 459 of file SignalizedIntersectionManager.cpp.

460 {
461 this->signal_group_to_entry_lanelet_ids_ = other.signal_group_to_entry_lanelet_ids_;
462 this->signal_group_to_exit_lanelet_ids_ = other.signal_group_to_exit_lanelet_ids_;
463 this->intersection_id_to_regem_id_ = other.intersection_id_to_regem_id_;
464 this->signal_group_to_traffic_light_id_ = other.signal_group_to_traffic_light_id_;
465 this->intersection_coord_correction_ = other.intersection_coord_correction_;
466
467 return *this;
468 }

References intersection_coord_correction_, intersection_id_to_regem_id_, signal_group_to_entry_lanelet_ids_, signal_group_to_exit_lanelet_ids_, and signal_group_to_traffic_light_id_.

◆ operator==()

bool carma_wm::SignalizedIntersectionManager::operator== ( const SignalizedIntersectionManager rhs)

Equality operator that checks if every mapping are same except the traffic signal states. This is to keep the states although the map is updated or a similar event happened NOTE: The function does not update the map with new elements.

Parameters
[out]rhsmanager

Definition at line 35 of file SignalizedIntersectionManager.cpp.

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 }

References intersection_id_to_regem_id_, signal_group_to_entry_lanelet_ids_, signal_group_to_exit_lanelet_ids_, and signal_group_to_traffic_light_id_.

◆ processSpatFromMsg()

void carma_wm::SignalizedIntersectionManager::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 individual nodes through wm_listener's setWMSpatProcessingState()

Parameters
spat_msgMsg to update with
lanelet_mapto update the regulatory elements according to internal signals recorded

Definition at line 479 of file SignalizedIntersectionManager.cpp.

480 {
482 {
483 return;
484 }
485
486 if (!semantic_map)
487 {
488 RCLCPP_INFO_STREAM(rclcpp::get_logger("carma_wm"), "Map is not set yet.");
489 return;
490 }
491
492 if (spat_msg.intersection_state_list.empty())
493 {
494 logWarnOnce("Logging Once: No intersection_state_list in the newly received SPAT msg. Returning...");
495 return;
496 }
497
498 for (const auto& curr_intersection : spat_msg.intersection_state_list)
499 {
500 for (const auto& current_movement_state : curr_intersection.movement_list)
501 {
502 lanelet::Id curr_light_id = getTrafficSignalId(curr_intersection.id.id, current_movement_state.signal_group);
503
504 if (curr_light_id == lanelet::InvalId)
505 {
506 continue;
507 }
508
509 lanelet::CarmaTrafficSignalPtr curr_light =
510 getTrafficSignal(curr_light_id, semantic_map);
511
512 if (curr_light == nullptr)
513 {
514 continue;
515 }
516
517 // all maneuver types in same signal group is currently expected to share signal timing, so only 0th index is used when setting states
518 if (current_movement_state.movement_event_list.empty())
519 {
520 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);
521 continue;
522 }
523 else
524 {
525 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);
526 }
527
528 curr_light->revision_ = curr_intersection.revision; // valid SPAT msg
529
530 auto [new_end_times_and_states, new_start_times ]=
531 extract_signal_states_from_movement_state(curr_intersection, current_movement_state);
532
533 curr_light->recorded_time_stamps = new_end_times_and_states;
534 curr_light->recorded_start_time_stamps = new_start_times;
535 }
536 }
537 }
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,...
lanelet::Id getTrafficSignalId(uint16_t intersection_id, uint8_t signal_id)
helper for traffic signal Id
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

References extract_signal_states_from_movement_state(), getTrafficSignal(), getTrafficSignalId(), logWarnOnce(), carma_wm::OFF, and spat_processor_state_.

Here is the call graph for this function:

◆ setMaxLaneWidth()

void carma_wm::SignalizedIntersectionManager::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 distance to a lanelet as map msg points are guaranteed to apply to a single lane.

Definition at line 30 of file SignalizedIntersectionManager.cpp.

31 {
32 max_lane_width_ = max_lane_width;
33 }

References max_lane_width_.

◆ setTargetFrame()

void carma_wm::SignalizedIntersectionManager::setTargetFrame ( const std::string &  target_frame)

Saves the georeference string to be used for converting MAP.msg coordinates.

Parameters
target_framePROJ string of the map

Definition at line 25 of file SignalizedIntersectionManager.cpp.

26 {
27 target_frame_ = target_frame;
28 }

References target_frame_.

Member Data Documentation

◆ intersection_coord_correction_

std::unordered_map<uint16_t, std::pair<double, double> > carma_wm::SignalizedIntersectionManager::intersection_coord_correction_

◆ intersection_id_to_regem_id_

std::unordered_map<uint16_t, lanelet::Id> carma_wm::SignalizedIntersectionManager::intersection_id_to_regem_id_

◆ intersection_nodes_

std::unordered_map<uint16_t, std::vector<lanelet::Point3d> > carma_wm::SignalizedIntersectionManager::intersection_nodes_

Definition at line 211 of file SignalizedIntersectionManager.hpp.

Referenced by convertLaneToLaneletId().

◆ max_lane_width_

double carma_wm::SignalizedIntersectionManager::max_lane_width_ = 4
private

Definition at line 246 of file SignalizedIntersectionManager.hpp.

Referenced by convertLaneToLaneletId(), and setMaxLaneWidth().

◆ previous_busy_log_streams_

std::set<std::string> carma_wm::SignalizedIntersectionManager::previous_busy_log_streams_
mutable

Definition at line 240 of file SignalizedIntersectionManager.hpp.

Referenced by logInfoOnce(), and logWarnOnce().

◆ regem_id_to_intersection_id_

std::unordered_map<lanelet::Id, uint16_t> carma_wm::SignalizedIntersectionManager::regem_id_to_intersection_id_

Definition at line 220 of file SignalizedIntersectionManager.hpp.

Referenced by createIntersectionFromMapMsg().

◆ ros1_clock_

std::optional<rclcpp::Time> carma_wm::SignalizedIntersectionManager::ros1_clock_ = std::nullopt

◆ signal_group_to_entry_lanelet_ids_

std::unordered_map<uint8_t, std::unordered_set<lanelet::Id> > carma_wm::SignalizedIntersectionManager::signal_group_to_entry_lanelet_ids_

◆ signal_group_to_exit_lanelet_ids_

std::unordered_map<uint8_t, std::unordered_set<lanelet::Id> > carma_wm::SignalizedIntersectionManager::signal_group_to_exit_lanelet_ids_

◆ signal_group_to_traffic_light_id_

std::unordered_map<uint8_t, lanelet::Id> carma_wm::SignalizedIntersectionManager::signal_group_to_traffic_light_id_

◆ simulation_clock_

std::optional<rclcpp::Time> carma_wm::SignalizedIntersectionManager::simulation_clock_ = std::nullopt

◆ spat_processor_state_

SIGNAL_PHASE_PROCESSING carma_wm::SignalizedIntersectionManager::spat_processor_state_ = SIGNAL_PHASE_PROCESSING::OFF

Definition at line 236 of file SignalizedIntersectionManager.hpp.

Referenced by processSpatFromMsg().

◆ target_frame_

std::string carma_wm::SignalizedIntersectionManager::target_frame_ = ""
private

◆ use_real_time_spat_in_sim_

bool carma_wm::SignalizedIntersectionManager::use_real_time_spat_in_sim_

◆ use_sim_time_

bool carma_wm::SignalizedIntersectionManager::use_sim_time_

The documentation for this class was generated from the following files: