18#include <boost/uuid/uuid.hpp>
19#include <boost/uuid/uuid_generators.hpp>
20#include <carma_ros2_utils/containers/containers.hpp>
21#include <lanelet2_core/Attribute.h>
22#include <lanelet2_core/geometry/LineString.h>
23#include <lanelet2_core/primitives/Traits.h>
29 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger, rclcpp::Clock::SharedPtr clock)
30 : traffic_control_pub_(traffic_control_pub), wm_(wm), logger_(logger), clock_(clock) {}
36 RCLCPP_WARN_STREAM(
logger_->get_logger(),
"The map is not loaded yet, ignoring the Traffic Incident Mobility Message");
41 RCLCPP_WARN_STREAM(
logger_->get_logger(),
"The georeference is not loaded yet, ignoring the Traffic Incident Mobility Message");
46 RCLCPP_WARN_STREAM(
logger_->get_logger(),
"The route is not loaded yet, ignoring the Traffic Incident Mobility Message");
50 if(mobility_msg->strategy==
"carma3/Incident_Use_Case")
58 carma_v2x_msgs::msg::TrafficControlMessage traffic_control_msg;
59 traffic_control_msg.choice = carma_v2x_msgs::msg::TrafficControlMessage::TCMV01;
62 traffic_control_msg.tcm_v01=traffic_msg;
82 std::vector<std::string> vec={};
83 std::string delimiter =
",";
86 while ((pos = mobility_strategy_params.find(delimiter)) != std::string::npos)
88 token = mobility_strategy_params.substr(0, pos);
90 mobility_strategy_params.erase(0, pos + delimiter.length());
92 vec.push_back(mobility_strategy_params);
96 RCLCPP_ERROR_STREAM(
logger_->get_logger(),
"Given mobility strategy params are not correctly formatted.");
100 std::string lat_str=vec[0];
101 std::string lon_str=vec[1];
102 std::string downtrack_str=vec[2];
103 std::string uptrack_str=vec[3];
104 std::string min_gap_str=vec[4];
105 std::string speed_advisory_str=vec[5];
106 std::string event_reason_str=vec[6];
107 std::string event_type_str=vec[7];
113 double constexpr APPROXIMATE_DEG_PER_5M = 0.00005;
114 double delta_lat = temp_lat -
latitude;
116 double approximate_degree_delta = sqrt(delta_lat*delta_lat + delta_lon*delta_lon);
118 double temp_down_track=stod(
stringParserHelper(downtrack_str,downtrack_str.find_last_of(
"down_track:")));
119 double temp_up_track=stod(
stringParserHelper(uptrack_str,uptrack_str.find_last_of(
"up_track:")));
120 double temp_min_gap=stod(
stringParserHelper(min_gap_str,min_gap_str.find_last_of(
"min_gap:")));
122 std::string temp_event_reason=
stringParserHelper(event_reason_str,event_reason_str.find_last_of(
"event_reason:"));
123 std::string temp_event_type=
stringParserHelper(event_type_str,event_type_str.find_last_of(
"event_type:"));
125 if ( approximate_degree_delta < APPROXIMATE_DEG_PER_5M
133 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"Strategy params are unchanged so ignoring new message: " << mobility_strategy_params
134 <<
" degree_delta: " << approximate_degree_delta
156 std::string str_temp=
"";
157 for(
size_t i=str_index+1;
i<
str.length();
i++)
166 lanelet::projection::LocalFrameProjector projector(
projection_msg_.c_str());
167 lanelet::GPSPoint gps_point;
171 auto local_point3d = projector.forward(gps_point);
172 return {local_point3d.x(), local_point3d.y()};
179 const lanelet::BasicPoint2d&
point)
181 double min_distance = std::numeric_limits<double>::max();
183 size_t best_index = 0;
184 for (
const auto& p : points)
186 double distance = lanelet::geometry::distance2d(p,
point);
187 if (distance < min_distance)
190 min_distance = distance;
199 const lanelet::BasicPoint2d& start_point,
double downtrack, std::vector<std::vector<lanelet::BasicPoint2d>>* forward_lanes)
const
201 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"getAdjacentForwardCenterlines");
202 for (
const auto& ll : adjacentSet) {
203 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"Processing adjacent lanelet: " << ll.id());
204 std::vector<lanelet::BasicPoint2d> following_lane;
212 lanelet::BasicPoint2d prev_point = cur_ll.centerline()[p_idx].basicPoint2d();
214 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"nearest point" << cur_ll.centerline()[p_idx].id() <<
" : " << prev_point.x() <<
", " << prev_point.y());
216 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"p_idx: " << p_idx);
219 while (dist < downtrack) {
220 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"Accumulating lanelet: " << cur_ll.id());
221 if (p_idx == cur_ll.centerline().size()) {
222 auto next_lls =
wm_->getMapRoutingGraph()->following(cur_ll,
false);
223 if (next_lls.empty()) {
224 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"No followers");
227 const auto& next = next_lls[0];
228 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"Getting next lanelet: " << next.id());
232 if (p_idx != 0 || dist == 0) {
233 following_lane.push_back(lanelet::traits::to2D(cur_ll.centerline()[p_idx]));
234 dist += lanelet::geometry::distance2d(prev_point, following_lane.back());
236 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"distance " << dist);
237 prev_point = lanelet::traits::to2D(cur_ll.centerline()[p_idx]);
240 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"Adding lane with size: " << following_lane.size());
241 forward_lanes->emplace_back(following_lane);
246 const lanelet::BasicPoint2d& start_point,
double uptrack, std::vector<std::vector<lanelet::BasicPoint2d>>* reverse_lanes)
const
248 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"getAdjacentReverseCenterlines");
249 for (
const auto& ll : adjacentSet) {
250 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"Processing adjacent lanelet: " << ll.id());
251 std::vector<lanelet::BasicPoint2d> previous_lane;
258 lanelet::BasicPoint2d prev_point = cur_ll.centerline()[p_idx].basicPoint2d();
260 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"nearest point" << cur_ll.centerline()[p_idx].id() <<
" : " << prev_point.x() <<
", " << prev_point.y());
262 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"p_idx: " << p_idx);
265 while (dist < uptrack) {
266 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"Accumulating lanelet: " << cur_ll.id());
268 auto next_lls =
wm_->getMapRoutingGraph()->previous(cur_ll,
false);
269 if (next_lls.empty()) {
270 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"No previous lanelets");
273 const auto& next = next_lls[0];
274 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"Getting next lanelet: " << next.id());
276 p_idx = cur_ll.centerline().size() - 1;
278 if (p_idx != cur_ll.centerline().size() - 1 || dist == 0) {
280 previous_lane.push_back(lanelet::traits::to2D(cur_ll.centerline()[p_idx]));
281 dist += lanelet::geometry::distance2d(prev_point, previous_lane.back());
283 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"distance " << dist);
284 prev_point = lanelet::traits::to2D(cur_ll.centerline()[p_idx]);
287 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"Adding lane with size: " << previous_lane.size());
288 reverse_lanes->emplace_back(previous_lane);
294 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"In composeTrafficControlMesssages");
298 auto current_lanelets = lanelet::geometry::findNearest(
wm_->getMap()->laneletLayer,
local_point_, 1);
299 if (current_lanelets.empty()) {
304 lanelet::ConstLanelet current_lanelet = current_lanelets[0].second;
306 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"Nearest Lanelet: " << current_lanelet.id());
308 lanelet::ConstLanelets lefts = { current_lanelet };
309 for (
const auto& l :
wm_->getMapRoutingGraph()->lefts(current_lanelet)) {
310 lefts.emplace_back(l);
311 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"Left lanelet: " << l.id());
314 lanelet::ConstLanelets rights =
wm_->getMapRoutingGraph()->rights(current_lanelet);
315 for (
const auto& l : rights) {
316 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"Right lanelet: " << l.id());
320 std::vector<std::vector<lanelet::BasicPoint2d>> forward_lanes;
321 std::vector<std::vector<lanelet::BasicPoint2d>> reverse_lanes;
323 if (lefts.size() >= rights.size()) {
324 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"Emergency vehicle on the right ");
328 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"Emergency vehicle on the left ");
333 for (
auto& lane : reverse_lanes) {
334 std::reverse(lane.begin(), lane.end());
338 for (
size_t i = 0;
i < reverse_lanes.size();
i++) {
339 if (forward_lanes[
i].size() > 1) {
340 reverse_lanes[
i].insert(reverse_lanes[
i].end(), forward_lanes[
i].begin() + 1, forward_lanes[
i].end());
344 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"Constructing message for lanes: " << reverse_lanes.size());
345 std::vector<carma_v2x_msgs::msg::TrafficControlMessageV01> output_msg;
347 carma_v2x_msgs::msg::TrafficControlMessageV01 traffic_mobility_msg;
349 traffic_mobility_msg.geometry_exists=
true;
350 traffic_mobility_msg.params_exists=
true;
351 traffic_mobility_msg.package_exists=
true;
352 j2735_v2x_msgs::msg::TrafficControlVehClass veh_type;
353 veh_type.vehicle_class = j2735_v2x_msgs::msg::TrafficControlVehClass::ANY;
354 traffic_mobility_msg.params.vclasses.push_back(veh_type);
355 traffic_mobility_msg.params.schedule.start=
clock_->now();
356 traffic_mobility_msg.params.schedule.end_exists=
false;
357 traffic_mobility_msg.params.schedule.dow_exists=
false;
358 traffic_mobility_msg.params.schedule.between_exists=
false;
359 traffic_mobility_msg.params.schedule.repeat_exists =
false;
366 std::string common_frame =
"WGS84";
368 PJ* common_to_map_proj = proj_create_crs_to_crs(PJ_DEFAULT_CTX, common_frame.c_str(),
projection_msg_.c_str() ,
nullptr);
370 if (common_to_map_proj ==
nullptr) {
372 RCLCPP_ERROR_STREAM(
logger_->get_logger(),
"Failed to generate projection between map georeference and common frame with error number: " << proj_context_errno(PJ_DEFAULT_CTX)
373 <<
" projection_msg_: " <<
projection_msg_ <<
" common_frame: " << common_frame);
378 PJ_COORD map_origin_map_frame{{0.0, 0.0, 0.0, 0.0}};
379 PJ_COORD map_origin_in_common_frame;
381 map_origin_in_common_frame = proj_trans(common_to_map_proj, PJ_INV, map_origin_map_frame);
383 traffic_mobility_msg.geometry.datum =
"WGS84";
384 traffic_mobility_msg.geometry.reflat = map_origin_in_common_frame.lpz.lam;
385 traffic_mobility_msg.geometry.reflon = map_origin_in_common_frame.lpz.phi;
387 std::ostringstream lat_string;
388 std::ostringstream lon_string;
390 lat_string.precision(14);
391 lat_string << std::fixed << traffic_mobility_msg.geometry.reflat;
393 lon_string.precision(14);
394 lon_string << std::fixed << traffic_mobility_msg.geometry.reflon;
398 std::string local_tmerc_enu_proj =
"+proj=tmerc +datum=WGS84 +h_0=0 +lat_0=" + lat_string.str() +
" +lon_0=" + lon_string.str() +
" +k=1 +x_0=0 +y_0=0 +units=m +vunits=m +no_defs";
400 PJ* map_to_tmerc_proj = proj_create_crs_to_crs(PJ_DEFAULT_CTX,
projection_msg_.c_str(), local_tmerc_enu_proj.c_str() ,
nullptr);
402 if (map_to_tmerc_proj ==
nullptr) {
404 RCLCPP_ERROR_STREAM(
logger_->get_logger(),
"Failed to generate projection between map georeference and tmerc frame with error number: " << proj_context_errno(PJ_DEFAULT_CTX)
405 <<
" projection_msg_: " <<
projection_msg_ <<
" local_tmerc_enu_proj: " << local_tmerc_enu_proj);
410 traffic_mobility_msg.geometry.proj = local_tmerc_enu_proj;
412 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"Projection in message: " << traffic_mobility_msg.geometry.proj);
418 for (
size_t i = 0;
i < reverse_lanes.size();
i++) {
420 traffic_mobility_msg.geometry.nodes.clear();
421 if (reverse_lanes[
i].size() == 0) {
422 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"Skipping empty lane");
427 PJ_COORD map_pt{{reverse_lanes[
i].front().x(), reverse_lanes[
i].front().y(), 0.0, 0.0}};
429 PJ_COORD tmerc_pt = proj_trans(map_to_tmerc_proj, PJ_FWD, map_pt);
431 carma_v2x_msgs::msg::PathNode prev_point;
432 prev_point.x = tmerc_pt.xyz.x;
433 prev_point.y = tmerc_pt.xyz.y;
435 for(
const auto& p : carma_ros2_utils::containers::downsample_vector(reverse_lanes[
i], 8))
437 carma_v2x_msgs::msg::PathNode delta;
439 map_pt = PJ_COORD({p.x(), p.y(), 0.0, 0.0});
440 tmerc_pt = proj_trans(map_to_tmerc_proj, PJ_FWD, map_pt);
442 delta.x=tmerc_pt.xyz.x - prev_point.x;
443 delta.y=tmerc_pt.xyz.y - prev_point.y;
445 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"prev_point x" << prev_point.x <<
", prev_point y " << prev_point.y);
446 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"tmerc_pt.xyz.x" << tmerc_pt.xyz.x <<
", tmerc_pt.xyz.y " << tmerc_pt.xyz.y);
447 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"map_pt x" << p.x() <<
", map_pt y " << p.y());
449 RCLCPP_DEBUG_STREAM(
logger_->get_logger(),
"calculated diff x" << delta.x <<
", diff y" << delta.y);
452 traffic_mobility_msg.geometry.nodes.push_back(prev_point);
457 traffic_mobility_msg.geometry.nodes.push_back(delta);
460 prev_point.x = p.x();
461 prev_point.y = p.y();
465 boost::uuids::uuid closure_id = boost::uuids::random_generator()();
466 std::copy(closure_id.begin(), closure_id.end(), traffic_mobility_msg.id.id.begin());
467 traffic_mobility_msg.params.detail.choice=carma_v2x_msgs::msg::TrafficControlDetail::CLOSED_CHOICE;
468 traffic_mobility_msg.params.detail.closed=carma_v2x_msgs::msg::TrafficControlDetail::CLOSED;
470 output_msg.push_back(traffic_mobility_msg);
473 boost::uuids::uuid headway_id = boost::uuids::random_generator()();
474 std::copy(headway_id.begin(), headway_id.end(), traffic_mobility_msg.id.id.begin());
475 traffic_mobility_msg.params.detail.choice=carma_v2x_msgs::msg::TrafficControlDetail::MINHDWY_CHOICE;
476 traffic_mobility_msg.params.detail.minhdwy=
min_gap;
477 output_msg.push_back(traffic_mobility_msg);
479 boost::uuids::uuid speed_id = boost::uuids::random_generator()();
480 std::copy(speed_id.begin(), speed_id.end(), traffic_mobility_msg.id.id.begin());
481 traffic_mobility_msg.params.detail.choice=carma_v2x_msgs::msg::TrafficControlDetail::MAXSPEED_CHOICE;
483 output_msg.push_back(traffic_mobility_msg);
std::function< void(const carma_v2x_msgs::msg::TrafficControlMessage &)> PublishTrafficControlCallback
carma_wm::WorldModelConstPtr wm_
std::string stringParserHelper(std::string str, unsigned long str_index) const
Function to help convert string to double data type.
std::string previous_strategy_params
TrafficIncidentParserWorker(carma_wm::WorldModelConstPtr wm, const PublishTrafficControlCallback &traffic_control_pub, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger, rclcpp::Clock::SharedPtr clock)
TrafficIncidentParserWorker constructor.
lanelet::BasicPoint2d getIncidentOriginPoint() const
Function to convert internally saved incident origin point from lat/lon to local map frame.
PublishTrafficControlCallback traffic_control_pub_
std::string projection_msg_
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_
std::vector< carma_v2x_msgs::msg::TrafficControlMessageV01 > composeTrafficControlMesssages()
Algorithm for extracting the closed lanelet from internally saved mobility message (or geofence) para...
const double MphToMetersPerSec
bool mobilityMessageParser(std::string mobility_strategy_params)
Function to help parse incoming mobility operation messages to required format.
void georeferenceCallback(std_msgs::msg::String::UniquePtr projection_msg)
Callback for the georeference subscriber used to set the map projection.
void getAdjacentForwardCenterlines(const lanelet::ConstLanelets &adjacentSet, const lanelet::BasicPoint2d &start_point, double downtrack, std::vector< std::vector< lanelet::BasicPoint2d > > *forward_lanes) const
Helper method to compute the concatenated centerlines of the lanes in front of the emergency vehicle ...
void mobilityOperationCallback(carma_v2x_msgs::msg::MobilityOperation::UniquePtr mobility_msg)
Function to receive the incoming mobility operation message from the message node and publish the geo...
rclcpp::Clock::SharedPtr clock_
void getAdjacentReverseCenterlines(const lanelet::ConstLanelets &adjacentSet, const lanelet::BasicPoint2d &start_point, double uptrack, std::vector< std::vector< lanelet::BasicPoint2d > > *reverse_lanes) const
Helper method that is identical to getAdjacentForwardCenterlines except it works in reverse using upt...
lanelet::BasicPoint2d local_point_
std::shared_ptr< const WorldModel > WorldModelConstPtr
size_t getNearestPointIndex(const lanelet::ConstLineString3d &points, const lanelet::BasicPoint2d &point)
Helper method to get the nearest point index of a point and a linestring.