19#include <rclcpp/rclcpp.hpp>
20#include <carma_v2x_msgs/msg/mobility_operation.hpp>
21#include <carma_v2x_msgs/msg/traffic_control_message_v01.hpp>
22#include <carma_v2x_msgs/msg/traffic_control_message.hpp>
23#include <std_msgs/msg/string.hpp>
34#include <lanelet2_extension/projection/local_frame_projector.h>
35#include <lanelet2_core/geometry/Lanelet.h>
36#include <lanelet2_routing/RoutingGraph.h>
38#include <std_msgs/msg/string.h>
54 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger, rclcpp::Clock::SharedPtr clock);
106 const lanelet::BasicPoint2d& start_point,
double downtrack, std::vector<std::vector<lanelet::BasicPoint2d>>* forward_lanes)
const;
116 const lanelet::BasicPoint2d& start_point,
double uptrack, std::vector<std::vector<lanelet::BasicPoint2d>>* reverse_lanes)
const;
136 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr
logger_;
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...
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