19#include <rclcpp/rclcpp.hpp>
26#include <carma_ros2_utils/carma_lifecycle_node.hpp>
The class responsible for processing incoming MobilityOperation messages with strategy "carma3/Incide...
carma_ros2_utils::SubPtr< std_msgs::msg::String > projection_sub_
std::shared_ptr< carma_wm::WMListener > wm_listener_
void publishTrafficControlMessage(const carma_v2x_msgs::msg::TrafficControlMessage &traffic_control_msg) const
Publish traffic control message.
carma_ros2_utils::PubPtr< carma_v2x_msgs::msg::TrafficControlMessage > traffic_control_msg_pub_
std::shared_ptr< TrafficIncidentParserWorker > traffic_parser_worker_
TrafficIncidentParserNode(const rclcpp::NodeOptions &)
TrafficIncidentParserNode constructor.
carma_ros2_utils::SubPtr< carma_v2x_msgs::msg::MobilityOperation > mobility_operation_sub_
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &)