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.
traffic_incident_parser::TrafficIncidentParserNode Class Reference

The class responsible for processing incoming MobilityOperation messages with strategy "carma3/Incident_Use_Case". More...

#include <traffic_incident_parser_node.hpp>

Inheritance diagram for traffic_incident_parser::TrafficIncidentParserNode:
Inheritance graph
Collaboration diagram for traffic_incident_parser::TrafficIncidentParserNode:
Collaboration graph

Public Member Functions

 TrafficIncidentParserNode (const rclcpp::NodeOptions &)
 TrafficIncidentParserNode constructor. More...
 
carma_ros2_utils::CallbackReturn handle_on_configure (const rclcpp_lifecycle::State &)
 
void publishTrafficControlMessage (const carma_v2x_msgs::msg::TrafficControlMessage &traffic_control_msg) const
 Publish traffic control message. More...
 

Private Attributes

carma_ros2_utils::SubPtr< std_msgs::msg::String > projection_sub_
 
carma_ros2_utils::SubPtr< carma_v2x_msgs::msg::MobilityOperation > mobility_operation_sub_
 
carma_ros2_utils::PubPtr< carma_v2x_msgs::msg::TrafficControlMessage > traffic_control_msg_pub_
 
std::shared_ptr< carma_wm::WMListenerwm_listener_
 
std::shared_ptr< TrafficIncidentParserWorkertraffic_parser_worker_
 

Detailed Description

The class responsible for processing incoming MobilityOperation messages with strategy "carma3/Incident_Use_Case".

Definition at line 37 of file traffic_incident_parser_node.hpp.

Constructor & Destructor Documentation

◆ TrafficIncidentParserNode()

traffic_incident_parser::TrafficIncidentParserNode::TrafficIncidentParserNode ( const rclcpp::NodeOptions &  options)
explicit

TrafficIncidentParserNode constructor.

Definition at line 22 of file traffic_incident_parser_node.cpp.

23 : carma_ros2_utils::CarmaLifecycleNode(options)
24 {
25 }

Member Function Documentation

◆ handle_on_configure()

carma_ros2_utils::CallbackReturn traffic_incident_parser::TrafficIncidentParserNode::handle_on_configure ( const rclcpp_lifecycle::State &  )

Definition at line 27 of file traffic_incident_parser_node.cpp.

28 {
29
30 wm_listener_ = std::make_shared<carma_wm::WMListener>(get_node_base_interface(), get_node_logging_interface(),
31 get_node_topics_interface(), get_node_parameters_interface());
32
33 traffic_parser_worker_ = std::make_shared<TrafficIncidentParserWorker>(wm_listener_->getWorldModel(), std::bind(&TrafficIncidentParserNode::publishTrafficControlMessage, this, std_ph::_1), get_node_logging_interface(), get_clock());
34
35
36 // Setup subscribers
37 projection_sub_ = create_subscription<std_msgs::msg::String>("georeference", 1,
39 mobility_operation_sub_ = create_subscription<carma_v2x_msgs::msg::MobilityOperation>("incoming_mobility_operation", 1,
41
42 // Setup publishers
43
44 // NOTE: Currently, intra-process comms must be disabled for publishers that are transient_local: https://github.com/ros2/rclcpp/issues/1753
45 rclcpp::PublisherOptions traffic_control_msg_pub_options;
46 traffic_control_msg_pub_options.use_intra_process_comm = rclcpp::IntraProcessSetting::Disable; // Disable intra-process comms for this PublisherOptions object
47
48 auto traffic_control_msg_pub_qos = rclcpp::QoS(rclcpp::KeepAll()); // A publisher with this QoS will store all messages that it has sent on the topic
49 traffic_control_msg_pub_qos.transient_local(); // A publisher with this QoS will re-send all (when KeepAll is used) messages to all late-joining subscribers
50 // NOTE: The subscriber's QoS must be set to transient_local() as well for earlier messages to be resent to the later-joiner.
51
52
53 // Create a publisher that will send all previously published messages to late-joining subscribers ONLY If the subscriber is transient_local too
54 traffic_control_msg_pub_ = create_publisher<carma_v2x_msgs::msg::TrafficControlMessage>("geofence", traffic_control_msg_pub_qos, traffic_control_msg_pub_options);
55
56 // Return success if everthing initialized successfully
57 return CallbackReturn::SUCCESS;
58 }
carma_ros2_utils::SubPtr< std_msgs::msg::String > projection_sub_
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_
carma_ros2_utils::SubPtr< carma_v2x_msgs::msg::MobilityOperation > mobility_operation_sub_
void georeferenceCallback(std_msgs::msg::String::UniquePtr projection_msg)
Callback for the georeference subscriber used to set the map projection.
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...

References traffic_incident_parser::TrafficIncidentParserWorker::georeferenceCallback(), mobility_operation_sub_, traffic_incident_parser::TrafficIncidentParserWorker::mobilityOperationCallback(), projection_sub_, publishTrafficControlMessage(), traffic_control_msg_pub_, traffic_parser_worker_, and wm_listener_.

Here is the call graph for this function:

◆ publishTrafficControlMessage()

void traffic_incident_parser::TrafficIncidentParserNode::publishTrafficControlMessage ( const carma_v2x_msgs::msg::TrafficControlMessage &  traffic_control_msg) const

Publish traffic control message.

Definition at line 60 of file traffic_incident_parser_node.cpp.

61 {
62 traffic_control_msg_pub_->publish(traffic_control_msg);
63 }

References traffic_control_msg_pub_.

Referenced by handle_on_configure().

Here is the caller graph for this function:

Member Data Documentation

◆ mobility_operation_sub_

carma_ros2_utils::SubPtr<carma_v2x_msgs::msg::MobilityOperation> traffic_incident_parser::TrafficIncidentParserNode::mobility_operation_sub_
private

Definition at line 43 of file traffic_incident_parser_node.hpp.

Referenced by handle_on_configure().

◆ projection_sub_

carma_ros2_utils::SubPtr<std_msgs::msg::String> traffic_incident_parser::TrafficIncidentParserNode::projection_sub_
private

Definition at line 42 of file traffic_incident_parser_node.hpp.

Referenced by handle_on_configure().

◆ traffic_control_msg_pub_

carma_ros2_utils::PubPtr<carma_v2x_msgs::msg::TrafficControlMessage> traffic_incident_parser::TrafficIncidentParserNode::traffic_control_msg_pub_
private

◆ traffic_parser_worker_

std::shared_ptr<TrafficIncidentParserWorker> traffic_incident_parser::TrafficIncidentParserNode::traffic_parser_worker_
private

Definition at line 52 of file traffic_incident_parser_node.hpp.

Referenced by handle_on_configure().

◆ wm_listener_

std::shared_ptr<carma_wm::WMListener> traffic_incident_parser::TrafficIncidentParserNode::wm_listener_
private

Definition at line 49 of file traffic_incident_parser_node.hpp.

Referenced by handle_on_configure().


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