Carma-platform v4.11.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_ctrl::WMBroadcasterNode Class Reference

Node which provies exposes map publication and carma_wm update logic. More...

#include <WMBroadcasterNode.hpp>

Inheritance diagram for carma_wm_ctrl::WMBroadcasterNode:
Inheritance graph
Collaboration diagram for carma_wm_ctrl::WMBroadcasterNode:
Collaboration graph

Public Member Functions

 WMBroadcasterNode (const rclcpp::NodeOptions &options)
 Constructor. More...
 
carma_ros2_utils::CallbackReturn handle_on_configure (const rclcpp_lifecycle::State &)
 
carma_ros2_utils::CallbackReturn handle_on_activate (const rclcpp_lifecycle::State &)
 
void publishMap (const autoware_lanelet2_msgs::msg::MapBin &map_msg)
 Callback to publish a map. More...
 
void initializeWorker (std::weak_ptr< carma_ros2_utils::CarmaLifecycleNode > weak_node_pointer)
 Initializes the WMBroadcaster worker with reference to the CarmaLifecycleNode itself. More...
 
void publishCtrlReq (const carma_v2x_msgs::msg::TrafficControlRequest &ctrlreq_msg) const
 Callback to publish TrafficControlRequest Messages. More...
 
void publishMapUpdate (const autoware_lanelet2_msgs::msg::MapBin &geofence_msg) const
 Callback to publish map updates (geofences) More...
 
void publishActiveGeofence (const carma_perception_msgs::msg::CheckActiveGeofence &active_geof_msg)
 Callback to publish active geofence information. More...
 
void publishTCMACK (const carma_v2x_msgs::msg::MobilityOperation &mom_msg)
 Callback to publish traffic control acknowledgement information. More...
 

Private Member Functions

bool spin_callback ()
 Spin callback, which will be called frequently based on the configured spin rate. More...
 

Private Attributes

Config config_
 
carma_ros2_utils::PubPtr< autoware_lanelet2_msgs::msg::MapBin > map_pub_
 
carma_ros2_utils::PubPtr< autoware_lanelet2_msgs::msg::MapBin > map_update_pub_
 
carma_ros2_utils::PubPtr< carma_v2x_msgs::msg::TrafficControlRequest > control_msg_pub_
 
carma_ros2_utils::PubPtr< visualization_msgs::msg::MarkerArray > tcm_visualizer_pub_
 
carma_ros2_utils::PubPtr< visualization_msgs::msg::MarkerArray > j2735_map_msg_visualizer_pub_
 
carma_ros2_utils::PubPtr< carma_v2x_msgs::msg::TrafficControlRequestPolygon > tcr_visualizer_pub_
 
carma_ros2_utils::PubPtr< std_msgs::msg::Int32MultiArray > upcoming_intersection_ids_pub_
 
carma_ros2_utils::PubPtr< carma_perception_msgs::msg::CheckActiveGeofence > active_pub_
 
carma_ros2_utils::PubPtr< carma_v2x_msgs::msg::MobilityOperation > tcm_ack_pub_
 
carma_ros2_utils::SubPtr< autoware_lanelet2_msgs::msg::MapBin > base_map_sub_
 
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::Route > route_callmsg_sub_
 
carma_ros2_utils::SubPtr< std_msgs::msg::String > georef_sub_
 
carma_ros2_utils::SubPtr< carma_v2x_msgs::msg::TrafficControlMessage > geofence_sub_
 
carma_ros2_utils::SubPtr< carma_v2x_msgs::msg::MapData > incoming_map_sub_
 
carma_ros2_utils::SubPtr< geometry_msgs::msg::PoseStamped > curr_location_sub_
 
rclcpp::TimerBase::SharedPtr timer_
 
std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > ptr_
 
std::unique_ptr< carma_wm_ctrl::WMBroadcasterwmb_
 

Detailed Description

Node which provies exposes map publication and carma_wm update logic.

The WMBroadcasterNode handles updating the lanelet2 base map and publishing the new versions to the rest of the CARMA Platform ROS network. The broadcaster also provides functions for adding or removing geofences from the map and notifying the rest of the system.

Definition at line 45 of file WMBroadcasterNode.hpp.

Constructor & Destructor Documentation

◆ WMBroadcasterNode()

carma_wm_ctrl::WMBroadcasterNode::WMBroadcasterNode ( const rclcpp::NodeOptions &  options)
explicit

Constructor.

Definition at line 52 of file WMBroadcasterNode.cpp.

53 : carma_ros2_utils::CarmaLifecycleNode(options)
54{
55 // Create initial config
56 config_ = Config();
57
58 config_.ack_pub_times = declare_parameter<int>("ack_pub_times", config_.ack_pub_times);
59 config_.max_lane_width = declare_parameter<double>("max_lane_width", config_.max_lane_width);
60 config_.tcr_bbox_expansion_meters = declare_parameter<double>("tcr_bbox_expansion_meters", config_.tcr_bbox_expansion_meters);
61 config_.traffic_control_request_period = declare_parameter<double>("traffic_control_request_period", config_.traffic_control_request_period);
62 config_.vehicle_id = declare_parameter<std::string>("vehicle_id", config_.vehicle_id);
63 config_.participant = declare_parameter<std::string>("vehicle_participant_type", config_.participant);
64 config_.config_limit = declare_parameter<double>("config_speed_limit", config_.config_limit);
65 config_.tim_icon_path = declare_parameter<std::string>("tim_icon_path", config_.tim_icon_path);
66 config_.tim_icon_scale = declare_parameter<double>("tim_icon_scale", config_.tim_icon_scale);
67
68 declare_parameter("intersection_ids_for_correction", config_.intersection_ids_for_correction);
69 declare_parameter("intersection_coord_correction", config_.intersection_coord_correction);
70};
std::vector< double > intersection_coord_correction
std::vector< int64_t > intersection_ids_for_correction

References carma_wm_ctrl::Config::ack_pub_times, config_, carma_wm_ctrl::Config::config_limit, carma_wm_ctrl::Config::intersection_coord_correction, carma_wm_ctrl::Config::intersection_ids_for_correction, carma_wm_ctrl::Config::max_lane_width, carma_wm_ctrl::Config::participant, carma_wm_ctrl::Config::tcr_bbox_expansion_meters, carma_wm_ctrl::Config::tim_icon_path, carma_wm_ctrl::Config::tim_icon_scale, carma_wm_ctrl::Config::traffic_control_request_period, and carma_wm_ctrl::Config::vehicle_id.

Member Function Documentation

◆ handle_on_activate()

carma_ros2_utils::CallbackReturn carma_wm_ctrl::WMBroadcasterNode::handle_on_activate ( const rclcpp_lifecycle::State &  prev_state)

Definition at line 165 of file WMBroadcasterNode.cpp.

166{
167 // Timer setup
168 timer_ = create_timer(get_clock(),
169 std::chrono::milliseconds((int)(config_.traffic_control_request_period * 1000)),
170 std::bind(&WMBroadcasterNode::spin_callback, this));
171
173 //SUBSCRIBERS
175
176 // Base Map Sub
177 base_map_sub_ = create_subscription<autoware_lanelet2_msgs::msg::MapBin>("base_map", 1, std::bind(&WMBroadcaster::baseMapCallback, wmb_.get(), std_ph::_1));
178
179 // Base Map Georeference Sub
180 georef_sub_ = create_subscription<std_msgs::msg::String>("georeference", 1, std::bind(&WMBroadcaster::geoReferenceCallback, wmb_.get(), std_ph::_1));
181
182 // Geofence Sub
183 rclcpp::SubscriptionOptions geofence_sub_options;
184 // NOTE: Currently, intra-process comms must be disabled for subscribers that are transient_local: https://github.com/ros2/rclcpp/issues/1753
185 geofence_sub_options.use_intra_process_comm = rclcpp::IntraProcessSetting::Disable;
186 auto sub_qos_transient_local = rclcpp::QoS(rclcpp::KeepAll());
187 sub_qos_transient_local.transient_local();
188 geofence_sub_ = create_subscription<carma_v2x_msgs::msg::TrafficControlMessage>("geofence", sub_qos_transient_local, std::bind(&WMBroadcaster::geofenceCallback, wmb_.get(), std_ph::_1), geofence_sub_options);
189
190 // External Map Msg Sub
191 incoming_map_sub_ = create_subscription<carma_v2x_msgs::msg::MapData>("incoming_map", 20, std::bind(&WMBroadcaster::externalMapMsgCallback, wmb_.get(), std_ph::_1));
192
193 //Route Message Sub
194 route_callmsg_sub_ = create_subscription<carma_planning_msgs::msg::Route>("route", 1, std::bind(&WMBroadcaster::routeCallbackMessage, wmb_.get(), std_ph::_1));
195
196 //Current Location Sub
197 curr_location_sub_ = create_subscription<geometry_msgs::msg::PoseStamped>("current_pose", 1, std::bind(&WMBroadcaster::currentLocationCallback, wmb_.get(), std_ph::_1));
198
199
200 return CallbackReturn::SUCCESS;
201}
carma_ros2_utils::SubPtr< geometry_msgs::msg::PoseStamped > curr_location_sub_
carma_ros2_utils::SubPtr< std_msgs::msg::String > georef_sub_
carma_ros2_utils::SubPtr< carma_v2x_msgs::msg::MapData > incoming_map_sub_
carma_ros2_utils::SubPtr< carma_v2x_msgs::msg::TrafficControlMessage > geofence_sub_
rclcpp::TimerBase::SharedPtr timer_
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::Route > route_callmsg_sub_
bool spin_callback()
Spin callback, which will be called frequently based on the configured spin rate.
std::unique_ptr< carma_wm_ctrl::WMBroadcaster > wmb_
carma_ros2_utils::SubPtr< autoware_lanelet2_msgs::msg::MapBin > base_map_sub_
void baseMapCallback(autoware_lanelet2_msgs::msg::MapBin::UniquePtr map_msg)
Callback to set the base map when it has been loaded.
void geofenceCallback(carma_v2x_msgs::msg::TrafficControlMessage::UniquePtr geofence_msg)
Callback to add a geofence to the map. Currently only supports version 1 TrafficControlMessage.
void currentLocationCallback(geometry_msgs::msg::PoseStamped::UniquePtr current_pos)
void routeCallbackMessage(carma_planning_msgs::msg::Route::UniquePtr route_msg)
Calls controlRequestFromRoute() and publishes the TrafficControlRequest Message returned after the co...
void externalMapMsgCallback(carma_v2x_msgs::msg::MapData::UniquePtr map_msg)
Callback to MAP.msg which contains intersections' static info such geometry and lane ids.
void geoReferenceCallback(std_msgs::msg::String::UniquePtr geo_ref)
Callback to set the base map georeference (proj string)

References base_map_sub_, carma_wm_ctrl::WMBroadcaster::baseMapCallback(), config_, curr_location_sub_, carma_wm_ctrl::WMBroadcaster::currentLocationCallback(), carma_wm_ctrl::WMBroadcaster::externalMapMsgCallback(), geofence_sub_, carma_wm_ctrl::WMBroadcaster::geofenceCallback(), georef_sub_, carma_wm_ctrl::WMBroadcaster::geoReferenceCallback(), incoming_map_sub_, route_callmsg_sub_, carma_wm_ctrl::WMBroadcaster::routeCallbackMessage(), spin_callback(), timer_, carma_wm_ctrl::Config::traffic_control_request_period, and wmb_.

Here is the call graph for this function:

◆ handle_on_configure()

carma_ros2_utils::CallbackReturn carma_wm_ctrl::WMBroadcasterNode::handle_on_configure ( const rclcpp_lifecycle::State &  )

Definition at line 80 of file WMBroadcasterNode.cpp.

81{
82 RCLCPP_INFO_STREAM(rclcpp::get_logger("carma_wm_ctrl"),"Starting configuration!");
83
84 // Reset config
85 config_ = Config();
86
87 initializeWorker(shared_from_this());
88
89 RCLCPP_INFO_STREAM(rclcpp::get_logger("carma_wm_ctrl"),"Done initializing worker!");
90
91 get_parameter<int>("ack_pub_times", config_.ack_pub_times);
92 get_parameter<double>("max_lane_width", config_.max_lane_width);
93 get_parameter<double>("tcr_bbox_expansion_meters", config_.tcr_bbox_expansion_meters);
94 get_parameter<double>("traffic_control_request_period", config_.traffic_control_request_period);
95 get_parameter<std::string>("vehicle_id", config_.vehicle_id);
96 get_parameter<std::string>("vehicle_participant_type", config_.participant);
97 get_parameter<double>("config_speed_limit", config_.config_limit);
98 get_parameter<std::string>("tim_icon_path", config_.tim_icon_path);
99 get_parameter<double>("tim_icon_scale", config_.tim_icon_scale);
100
101
102 wmb_->setConfigACKPubTimes(config_.ack_pub_times);
103 wmb_->setMaxLaneWidth(config_.max_lane_width);
104 wmb_->setTCRBoundBoxExpansionMeters(config_.tcr_bbox_expansion_meters);
105 wmb_->setConfigSpeedLimit(config_.config_limit);
106 wmb_->setConfigVehicleId(config_.vehicle_id);
107 wmb_->setVehicleParticipationType(config_.participant);
108 wmb_->setVisualizationInfo(config_.tim_icon_path, config_.tim_icon_scale);
109
110 rclcpp::Parameter intersection_coord_correction_param = get_parameter("intersection_coord_correction");
111 config_.intersection_coord_correction = intersection_coord_correction_param.as_double_array();
112
113 rclcpp::Parameter intersection_ids_for_correction_param = get_parameter("intersection_ids_for_correction");
114 config_.intersection_ids_for_correction = intersection_ids_for_correction_param.as_integer_array();
115
117
118 RCLCPP_INFO_STREAM(rclcpp::get_logger("carma_wm_ctrl"),"Done loading parameters: " << config_);
119
121 // PUBLISHERS
123
124 // NOTE: Currently, intra-process comms must be disabled for the following two publishers that are transient_local: https://github.com/ros2/rclcpp/issues/1753
125 rclcpp::PublisherOptions intra_proc_disabled;
126 intra_proc_disabled.use_intra_process_comm = rclcpp::IntraProcessSetting::Disable; // Disable intra-process comms for this PublisherOptions object
127
128 // Create a publisher that will send all previously published messages to late-joining subscribers ONLY If the subscriber is transient_local too
129 auto pub_qos_transient_local = rclcpp::QoS(rclcpp::KeepAll()); // A publisher with this QoS will store all messages that it has sent on the topic
130 pub_qos_transient_local.transient_local(); // A publisher with this QoS will re-send all (when KeepAll is used) messages to all late-joining subscribers
131 // NOTE: The subscriber's QoS must be set to transient_local() as well for earlier messages to be resent to the later-joiner.
132
133 // Map Update Publisher
134 map_update_pub_ = create_publisher<autoware_lanelet2_msgs::msg::MapBin>("map_update", pub_qos_transient_local, intra_proc_disabled);
135
136 // Map Publisher
137 map_pub_ = create_publisher<autoware_lanelet2_msgs::msg::MapBin>("semantic_map", pub_qos_transient_local, intra_proc_disabled);
138
139 //Route Message Publisher
140 control_msg_pub_= create_publisher<carma_v2x_msgs::msg::TrafficControlRequest>("outgoing_geofence_request", 1);
141
142 //Check Active Geofence Publisher
143 active_pub_ = create_publisher<carma_perception_msgs::msg::CheckActiveGeofence>("active_geofence", 200);
144
145 //publish TCM acknowledgement after processing TCM
146 tcm_ack_pub_ = create_publisher<carma_v2x_msgs::msg::MobilityOperation>("outgoing_geofence_ack", 2 * config_.ack_pub_times );
147
148 //TCM Visualizer pub
149 tcm_visualizer_pub_= create_publisher<visualization_msgs::msg::MarkerArray>("tcm_visualizer",10);
150
151 //J2735 MAP msg Visualizer pub
152 j2735_map_msg_visualizer_pub_= create_publisher<visualization_msgs::msg::MarkerArray>("j2735_map_msg_visualizer",1);
153
154 //TCR Visualizer pub (visualized on UI)
155 tcr_visualizer_pub_ = create_publisher<carma_v2x_msgs::msg::TrafficControlRequestPolygon>("tcr_bounding_points",1);
156
157 //Upcoming intersection and group id of traffic light
158 upcoming_intersection_ids_pub_ = create_publisher<std_msgs::msg::Int32MultiArray>("intersection_signal_group_ids", 1);
159
160 // Return success if everything initialized successfully
161
162 return CallbackReturn::SUCCESS;
163}
carma_ros2_utils::PubPtr< carma_v2x_msgs::msg::TrafficControlRequest > control_msg_pub_
carma_ros2_utils::PubPtr< carma_perception_msgs::msg::CheckActiveGeofence > active_pub_
carma_ros2_utils::PubPtr< visualization_msgs::msg::MarkerArray > j2735_map_msg_visualizer_pub_
carma_ros2_utils::PubPtr< autoware_lanelet2_msgs::msg::MapBin > map_pub_
carma_ros2_utils::PubPtr< autoware_lanelet2_msgs::msg::MapBin > map_update_pub_
carma_ros2_utils::PubPtr< visualization_msgs::msg::MarkerArray > tcm_visualizer_pub_
void initializeWorker(std::weak_ptr< carma_ros2_utils::CarmaLifecycleNode > weak_node_pointer)
Initializes the WMBroadcaster worker with reference to the CarmaLifecycleNode itself.
carma_ros2_utils::PubPtr< std_msgs::msg::Int32MultiArray > upcoming_intersection_ids_pub_
carma_ros2_utils::PubPtr< carma_v2x_msgs::msg::TrafficControlRequestPolygon > tcr_visualizer_pub_
carma_ros2_utils::PubPtr< carma_v2x_msgs::msg::MobilityOperation > tcm_ack_pub_

References carma_wm_ctrl::Config::ack_pub_times, active_pub_, config_, carma_wm_ctrl::Config::config_limit, control_msg_pub_, initializeWorker(), carma_wm_ctrl::Config::intersection_coord_correction, carma_wm_ctrl::Config::intersection_ids_for_correction, j2735_map_msg_visualizer_pub_, map_pub_, map_update_pub_, carma_wm_ctrl::Config::max_lane_width, carma_wm_ctrl::Config::participant, tcm_ack_pub_, tcm_visualizer_pub_, carma_wm_ctrl::Config::tcr_bbox_expansion_meters, tcr_visualizer_pub_, carma_wm_ctrl::Config::tim_icon_path, carma_wm_ctrl::Config::tim_icon_scale, carma_wm_ctrl::Config::traffic_control_request_period, upcoming_intersection_ids_pub_, carma_wm_ctrl::Config::vehicle_id, and wmb_.

Here is the call graph for this function:

◆ initializeWorker()

void carma_wm_ctrl::WMBroadcasterNode::initializeWorker ( std::weak_ptr< carma_ros2_utils::CarmaLifecycleNode >  weak_node_pointer)

Initializes the WMBroadcaster worker with reference to the CarmaLifecycleNode itself.

Parameters
weak_ptrto the node of type CarmaLifecycleNode that owns this worker

Definition at line 72 of file WMBroadcasterNode.cpp.

73{
74 wmb_ = std::make_unique<carma_wm_ctrl::WMBroadcaster>(std::bind(&WMBroadcasterNode::publishMap, this, std_ph::_1), std::bind(&WMBroadcasterNode::publishMapUpdate, this, std_ph::_1),
75 std::bind(&WMBroadcasterNode::publishCtrlReq, this, std_ph::_1), std::bind(&WMBroadcasterNode::publishActiveGeofence, this, std_ph::_1),
76 std::make_unique<carma_ros2_utils::timers::ROSTimerFactory>(weak_node_pointer),
77 std::bind(&WMBroadcasterNode::publishTCMACK, this, std_ph::_1));
78}
void publishCtrlReq(const carma_v2x_msgs::msg::TrafficControlRequest &ctrlreq_msg) const
Callback to publish TrafficControlRequest Messages.
void publishTCMACK(const carma_v2x_msgs::msg::MobilityOperation &mom_msg)
Callback to publish traffic control acknowledgement information.
void publishMap(const autoware_lanelet2_msgs::msg::MapBin &map_msg)
Callback to publish a map.
void publishMapUpdate(const autoware_lanelet2_msgs::msg::MapBin &geofence_msg) const
Callback to publish map updates (geofences)
void publishActiveGeofence(const carma_perception_msgs::msg::CheckActiveGeofence &active_geof_msg)
Callback to publish active geofence information.

References publishActiveGeofence(), publishCtrlReq(), publishMap(), publishMapUpdate(), publishTCMACK(), and wmb_.

Referenced by handle_on_configure().

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

◆ publishActiveGeofence()

void carma_wm_ctrl::WMBroadcasterNode::publishActiveGeofence ( const carma_perception_msgs::msg::CheckActiveGeofence &  active_geof_msg)

Callback to publish active geofence information.

Parameters
active_geof_msgThe geofence information to publish

Definition at line 42 of file WMBroadcasterNode.cpp.

43{
44 active_pub_->publish(active_geof_msg);
45}

References active_pub_.

Referenced by initializeWorker().

Here is the caller graph for this function:

◆ publishCtrlReq()

void carma_wm_ctrl::WMBroadcasterNode::publishCtrlReq ( const carma_v2x_msgs::msg::TrafficControlRequest &  ctrlreq_msg) const

Callback to publish TrafficControlRequest Messages.

Parameters
route_msgThe TrafficControlRequest message to publish

Definition at line 37 of file WMBroadcasterNode.cpp.

38{
39 control_msg_pub_->publish(ctrlreq_msg);
40}

References control_msg_pub_.

Referenced by initializeWorker().

Here is the caller graph for this function:

◆ publishMap()

void carma_wm_ctrl::WMBroadcasterNode::publishMap ( const autoware_lanelet2_msgs::msg::MapBin &  map_msg)

Callback to publish a map.

Parameters
map_msgThe map message to publish

Definition at line 27 of file WMBroadcasterNode.cpp.

28{
29 map_pub_->publish(map_msg);
30}

References map_pub_.

Referenced by initializeWorker().

Here is the caller graph for this function:

◆ publishMapUpdate()

void carma_wm_ctrl::WMBroadcasterNode::publishMapUpdate ( const autoware_lanelet2_msgs::msg::MapBin &  geofence_msg) const

Callback to publish map updates (geofences)

Parameters
geofence_msgThe geofence message to publish

Definition at line 32 of file WMBroadcasterNode.cpp.

33{
34 map_update_pub_->publish(geofence_msg);
35}

References map_update_pub_.

Referenced by initializeWorker().

Here is the caller graph for this function:

◆ publishTCMACK()

void carma_wm_ctrl::WMBroadcasterNode::publishTCMACK ( const carma_v2x_msgs::msg::MobilityOperation &  mom_msg)

Callback to publish traffic control acknowledgement information.

Parameters
mom_msgThe acknowledgement information to publish

Definition at line 47 of file WMBroadcasterNode.cpp.

48{
49 tcm_ack_pub_->publish(mom_msg);
50}

References tcm_ack_pub_.

Referenced by initializeWorker().

Here is the caller graph for this function:

◆ spin_callback()

bool carma_wm_ctrl::WMBroadcasterNode::spin_callback ( )
private

Spin callback, which will be called frequently based on the configured spin rate.

Definition at line 203 of file WMBroadcasterNode.cpp.

204{
205 tcm_visualizer_pub_->publish(wmb_->tcm_marker_array_);
206 j2735_map_msg_visualizer_pub_->publish(wmb_->j2735_map_msg_marker_array_);
207 tcr_visualizer_pub_->publish(wmb_->tcr_polygon_);
208 wmb_->publishLightId();
209 //updating upcoming traffic signal group id and intersection id
210 wmb_->updateUpcomingSGIntersectionIds();
211 if (wmb_->upcoming_intersection_ids_.data.size() > 0)
212 upcoming_intersection_ids_pub_->publish(wmb_->upcoming_intersection_ids_);
213 if(wmb_->getRoute().route_path_lanelet_ids.size() > 0)
214 wmb_->routeCallbackMessage(std::make_unique<carma_planning_msgs::msg::Route>(wmb_->getRoute()));
215 return true;
216}

References j2735_map_msg_visualizer_pub_, tcm_visualizer_pub_, tcr_visualizer_pub_, upcoming_intersection_ids_pub_, and wmb_.

Referenced by handle_on_activate().

Here is the caller graph for this function:

Member Data Documentation

◆ active_pub_

carma_ros2_utils::PubPtr<carma_perception_msgs::msg::CheckActiveGeofence> carma_wm_ctrl::WMBroadcasterNode::active_pub_
private

Definition at line 118 of file WMBroadcasterNode.hpp.

Referenced by handle_on_configure(), and publishActiveGeofence().

◆ base_map_sub_

carma_ros2_utils::SubPtr<autoware_lanelet2_msgs::msg::MapBin> carma_wm_ctrl::WMBroadcasterNode::base_map_sub_
private

Definition at line 121 of file WMBroadcasterNode.hpp.

Referenced by handle_on_activate().

◆ config_

Config carma_wm_ctrl::WMBroadcasterNode::config_
private

◆ control_msg_pub_

carma_ros2_utils::PubPtr<carma_v2x_msgs::msg::TrafficControlRequest> carma_wm_ctrl::WMBroadcasterNode::control_msg_pub_
private

Definition at line 113 of file WMBroadcasterNode.hpp.

Referenced by handle_on_configure(), and publishCtrlReq().

◆ curr_location_sub_

carma_ros2_utils::SubPtr<geometry_msgs::msg::PoseStamped> carma_wm_ctrl::WMBroadcasterNode::curr_location_sub_
private

Definition at line 126 of file WMBroadcasterNode.hpp.

Referenced by handle_on_activate().

◆ geofence_sub_

carma_ros2_utils::SubPtr<carma_v2x_msgs::msg::TrafficControlMessage> carma_wm_ctrl::WMBroadcasterNode::geofence_sub_
private

Definition at line 124 of file WMBroadcasterNode.hpp.

Referenced by handle_on_activate().

◆ georef_sub_

carma_ros2_utils::SubPtr<std_msgs::msg::String> carma_wm_ctrl::WMBroadcasterNode::georef_sub_
private

Definition at line 123 of file WMBroadcasterNode.hpp.

Referenced by handle_on_activate().

◆ incoming_map_sub_

carma_ros2_utils::SubPtr<carma_v2x_msgs::msg::MapData> carma_wm_ctrl::WMBroadcasterNode::incoming_map_sub_
private

Definition at line 125 of file WMBroadcasterNode.hpp.

Referenced by handle_on_activate().

◆ j2735_map_msg_visualizer_pub_

carma_ros2_utils::PubPtr<visualization_msgs::msg::MarkerArray> carma_wm_ctrl::WMBroadcasterNode::j2735_map_msg_visualizer_pub_
private

Definition at line 115 of file WMBroadcasterNode.hpp.

Referenced by handle_on_configure(), and spin_callback().

◆ map_pub_

carma_ros2_utils::PubPtr<autoware_lanelet2_msgs::msg::MapBin> carma_wm_ctrl::WMBroadcasterNode::map_pub_
private

Definition at line 111 of file WMBroadcasterNode.hpp.

Referenced by handle_on_configure(), and publishMap().

◆ map_update_pub_

carma_ros2_utils::PubPtr<autoware_lanelet2_msgs::msg::MapBin> carma_wm_ctrl::WMBroadcasterNode::map_update_pub_
private

Definition at line 112 of file WMBroadcasterNode.hpp.

Referenced by handle_on_configure(), and publishMapUpdate().

◆ ptr_

std::shared_ptr<carma_ros2_utils::CarmaLifecycleNode> carma_wm_ctrl::WMBroadcasterNode::ptr_
private

Definition at line 131 of file WMBroadcasterNode.hpp.

◆ route_callmsg_sub_

carma_ros2_utils::SubPtr<carma_planning_msgs::msg::Route> carma_wm_ctrl::WMBroadcasterNode::route_callmsg_sub_
private

Definition at line 122 of file WMBroadcasterNode.hpp.

Referenced by handle_on_activate().

◆ tcm_ack_pub_

carma_ros2_utils::PubPtr<carma_v2x_msgs::msg::MobilityOperation> carma_wm_ctrl::WMBroadcasterNode::tcm_ack_pub_
private

Definition at line 119 of file WMBroadcasterNode.hpp.

Referenced by handle_on_configure(), and publishTCMACK().

◆ tcm_visualizer_pub_

carma_ros2_utils::PubPtr<visualization_msgs::msg::MarkerArray> carma_wm_ctrl::WMBroadcasterNode::tcm_visualizer_pub_
private

Definition at line 114 of file WMBroadcasterNode.hpp.

Referenced by handle_on_configure(), and spin_callback().

◆ tcr_visualizer_pub_

carma_ros2_utils::PubPtr<carma_v2x_msgs::msg::TrafficControlRequestPolygon> carma_wm_ctrl::WMBroadcasterNode::tcr_visualizer_pub_
private

Definition at line 116 of file WMBroadcasterNode.hpp.

Referenced by handle_on_configure(), and spin_callback().

◆ timer_

rclcpp::TimerBase::SharedPtr carma_wm_ctrl::WMBroadcasterNode::timer_
private

Definition at line 129 of file WMBroadcasterNode.hpp.

Referenced by handle_on_activate().

◆ upcoming_intersection_ids_pub_

carma_ros2_utils::PubPtr<std_msgs::msg::Int32MultiArray> carma_wm_ctrl::WMBroadcasterNode::upcoming_intersection_ids_pub_
private

Definition at line 117 of file WMBroadcasterNode.hpp.

Referenced by handle_on_configure(), and spin_callback().

◆ wmb_

std::unique_ptr<carma_wm_ctrl::WMBroadcaster> carma_wm_ctrl::WMBroadcasterNode::wmb_
private

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