Carma-platform v4.10.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.
WMBroadcasterNode.cpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2022 LEIDOS.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
5 * use this file except in compliance with the License. You may obtain a copy of
6 * the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
12 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
13 * License for the specific language governing permissions and limitations under
14 * the License.
15 */
16
17#include <carma_ros2_utils/timers/ROSTimerFactory.hpp>
19
20namespace carma_wm_ctrl
21{
22 // @SONAR_STOP@
23
24namespace std_ph = std::placeholders;
25
26
27void WMBroadcasterNode::publishMap(const autoware_lanelet2_msgs::msg::MapBin& map_msg)
28{
29 map_pub_->publish(map_msg);
30}
31
32void WMBroadcasterNode::publishMapUpdate(const autoware_lanelet2_msgs::msg::MapBin& geofence_msg) const
33{
34 map_update_pub_->publish(geofence_msg);
35}
36
37void WMBroadcasterNode::publishCtrlReq(const carma_v2x_msgs::msg::TrafficControlRequest& ctrlreq_msg) const
38{
39 control_msg_pub_->publish(ctrlreq_msg);
40}
41
42void WMBroadcasterNode::publishActiveGeofence(const carma_perception_msgs::msg::CheckActiveGeofence& active_geof_msg)
43{
44 active_pub_->publish(active_geof_msg);
45}
46
47void WMBroadcasterNode::publishTCMACK(const carma_v2x_msgs::msg::MobilityOperation& mom_msg)
48{
49 tcm_ack_pub_->publish(mom_msg);
50}
51
52WMBroadcasterNode::WMBroadcasterNode(const rclcpp::NodeOptions &options)
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_.participant = declare_parameter<double>("config_speed_limit", config_.config_limit);
65
66 declare_parameter("intersection_ids_for_correction", config_.intersection_ids_for_correction);
67 declare_parameter("intersection_coord_correction", config_.intersection_coord_correction);
68};
69
70void WMBroadcasterNode::initializeWorker(std::weak_ptr<carma_ros2_utils::CarmaLifecycleNode> weak_node_pointer)
71{
72 wmb_ = std::make_unique<carma_wm_ctrl::WMBroadcaster>(std::bind(&WMBroadcasterNode::publishMap, this, std_ph::_1), std::bind(&WMBroadcasterNode::publishMapUpdate, this, std_ph::_1),
73 std::bind(&WMBroadcasterNode::publishCtrlReq, this, std_ph::_1), std::bind(&WMBroadcasterNode::publishActiveGeofence, this, std_ph::_1),
74 std::make_unique<carma_ros2_utils::timers::ROSTimerFactory>(weak_node_pointer),
75 std::bind(&WMBroadcasterNode::publishTCMACK, this, std_ph::_1));
76}
77
78carma_ros2_utils::CallbackReturn WMBroadcasterNode::handle_on_configure(const rclcpp_lifecycle::State &)
79{
80 RCLCPP_INFO_STREAM(rclcpp::get_logger("carma_wm_ctrl"),"Starting configuration!");
81
82 // Reset config
83 config_ = Config();
84
85 initializeWorker(shared_from_this());
86
87 RCLCPP_INFO_STREAM(rclcpp::get_logger("carma_wm_ctrl"),"Done initializing worker!");
88
89 get_parameter<int>("ack_pub_times", config_.ack_pub_times);
90 get_parameter<double>("max_lane_width", config_.max_lane_width);
91 get_parameter<double>("tcr_bbox_expansion_meters", config_.tcr_bbox_expansion_meters);
92 get_parameter<double>("traffic_control_request_period", config_.traffic_control_request_period);
93 get_parameter<std::string>("vehicle_id", config_.vehicle_id);
94 get_parameter<std::string>("vehicle_participant_type", config_.participant);
95 get_parameter<double>("config_speed_limit", config_.config_limit);
96
97 wmb_->setConfigACKPubTimes(config_.ack_pub_times);
98 wmb_->setMaxLaneWidth(config_.max_lane_width);
99 wmb_->setTCRBoundBoxExpansionMeters(config_.tcr_bbox_expansion_meters);
100 wmb_->setConfigSpeedLimit(config_.config_limit);
101 wmb_->setConfigVehicleId(config_.vehicle_id);
102 wmb_->setVehicleParticipationType(config_.participant);
103
104 rclcpp::Parameter intersection_coord_correction_param = get_parameter("intersection_coord_correction");
105 config_.intersection_coord_correction = intersection_coord_correction_param.as_double_array();
106
107 rclcpp::Parameter intersection_ids_for_correction_param = get_parameter("intersection_ids_for_correction");
108 config_.intersection_ids_for_correction = intersection_ids_for_correction_param.as_integer_array();
109
111
112 RCLCPP_INFO_STREAM(rclcpp::get_logger("carma_wm_ctrl"),"Done loading parameters: " << config_);
113
115 // PUBLISHERS
117
118 // NOTE: Currently, intra-process comms must be disabled for the following two publishers that are transient_local: https://github.com/ros2/rclcpp/issues/1753
119 rclcpp::PublisherOptions intra_proc_disabled;
120 intra_proc_disabled.use_intra_process_comm = rclcpp::IntraProcessSetting::Disable; // Disable intra-process comms for this PublisherOptions object
121
122 // Create a publisher that will send all previously published messages to late-joining subscribers ONLY If the subscriber is transient_local too
123 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
124 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
125 // NOTE: The subscriber's QoS must be set to transient_local() as well for earlier messages to be resent to the later-joiner.
126
127 // Map Update Publisher
128 map_update_pub_ = create_publisher<autoware_lanelet2_msgs::msg::MapBin>("map_update", pub_qos_transient_local, intra_proc_disabled);
129
130 // Map Publisher
131 map_pub_ = create_publisher<autoware_lanelet2_msgs::msg::MapBin>("semantic_map", pub_qos_transient_local, intra_proc_disabled);
132
133 //Route Message Publisher
134 control_msg_pub_= create_publisher<carma_v2x_msgs::msg::TrafficControlRequest>("outgoing_geofence_request", 1);
135
136 //Check Active Geofence Publisher
137 active_pub_ = create_publisher<carma_perception_msgs::msg::CheckActiveGeofence>("active_geofence", 200);
138
139 //publish TCM acknowledgement after processing TCM
140 tcm_ack_pub_ = create_publisher<carma_v2x_msgs::msg::MobilityOperation>("outgoing_geofence_ack", 2 * config_.ack_pub_times );
141
142 //TCM Visualizer pub
143 tcm_visualizer_pub_= create_publisher<visualization_msgs::msg::MarkerArray>("tcm_visualizer",1);
144
145 //J2735 MAP msg Visualizer pub
146 j2735_map_msg_visualizer_pub_= create_publisher<visualization_msgs::msg::MarkerArray>("j2735_map_msg_visualizer",1);
147
148 //TCR Visualizer pub (visualized on UI)
149 tcr_visualizer_pub_ = create_publisher<carma_v2x_msgs::msg::TrafficControlRequestPolygon>("tcr_bounding_points",1);
150
151 //Upcoming intersection and group id of traffic light
152 upcoming_intersection_ids_pub_ = create_publisher<std_msgs::msg::Int32MultiArray>("intersection_signal_group_ids", 1);
153
154 // Return success if everything initialized successfully
155
156 return CallbackReturn::SUCCESS;
157}
158
159carma_ros2_utils::CallbackReturn WMBroadcasterNode::handle_on_activate(const rclcpp_lifecycle::State &prev_state)
160{
161 // Timer setup
162 timer_ = create_timer(get_clock(),
163 std::chrono::milliseconds((int)(config_.traffic_control_request_period * 1000)),
164 std::bind(&WMBroadcasterNode::spin_callback, this));
165
167 //SUBSCRIBERS
169
170 // Base Map Sub
171 base_map_sub_ = create_subscription<autoware_lanelet2_msgs::msg::MapBin>("base_map", 1, std::bind(&WMBroadcaster::baseMapCallback, wmb_.get(), std_ph::_1));
172
173 // Base Map Georeference Sub
174 georef_sub_ = create_subscription<std_msgs::msg::String>("georeference", 1, std::bind(&WMBroadcaster::geoReferenceCallback, wmb_.get(), std_ph::_1));
175
176 // Geofence Sub
177 rclcpp::SubscriptionOptions geofence_sub_options;
178 // NOTE: Currently, intra-process comms must be disabled for subscribers that are transient_local: https://github.com/ros2/rclcpp/issues/1753
179 geofence_sub_options.use_intra_process_comm = rclcpp::IntraProcessSetting::Disable;
180 auto sub_qos_transient_local = rclcpp::QoS(rclcpp::KeepAll());
181 sub_qos_transient_local.transient_local();
182 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);
183
184 // External Map Msg Sub
185 incoming_map_sub_ = create_subscription<carma_v2x_msgs::msg::MapData>("incoming_map", 20, std::bind(&WMBroadcaster::externalMapMsgCallback, wmb_.get(), std_ph::_1));
186
187 //Route Message Sub
188 route_callmsg_sub_ = create_subscription<carma_planning_msgs::msg::Route>("route", 1, std::bind(&WMBroadcaster::routeCallbackMessage, wmb_.get(), std_ph::_1));
189
190 //Current Location Sub
191 curr_location_sub_ = create_subscription<geometry_msgs::msg::PoseStamped>("current_pose", 1, std::bind(&WMBroadcaster::currentLocationCallback, wmb_.get(), std_ph::_1));
192
193
194 return CallbackReturn::SUCCESS;
195}
196
198{
199 tcm_visualizer_pub_->publish(wmb_->tcm_marker_array_);
200 j2735_map_msg_visualizer_pub_->publish(wmb_->j2735_map_msg_marker_array_);
201 tcr_visualizer_pub_->publish(wmb_->tcr_polygon_);
202 wmb_->publishLightId();
203 //updating upcoming traffic signal group id and intersection id
204 wmb_->updateUpcomingSGIntersectionIds();
205 if (wmb_->upcoming_intersection_ids_.data.size() > 0)
206 upcoming_intersection_ids_pub_->publish(wmb_->upcoming_intersection_ids_);
207 if(wmb_->getRoute().route_path_lanelet_ids.size() > 0)
208 wmb_->routeCallbackMessage(std::make_unique<carma_planning_msgs::msg::Route>(wmb_->getRoute()));
209 return true;
210}
211
212
213
214// @SONAR_START@
215
216} // namespace carma_wm_ctrl
217
218#include "rclcpp_components/register_node_macro.hpp"
219
220// Register the component with class_loader
221RCLCPP_COMPONENTS_REGISTER_NODE(carma_wm_ctrl::WMBroadcasterNode)
Node which provies exposes map publication and carma_wm update logic.
carma_ros2_utils::SubPtr< geometry_msgs::msg::PoseStamped > curr_location_sub_
WMBroadcasterNode(const rclcpp::NodeOptions &options)
Constructor.
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::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &)
void publishCtrlReq(const carma_v2x_msgs::msg::TrafficControlRequest &ctrlreq_msg) const
Callback to publish TrafficControlRequest Messages.
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::SubPtr< std_msgs::msg::String > georef_sub_
carma_ros2_utils::SubPtr< carma_v2x_msgs::msg::MapData > incoming_map_sub_
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.
carma_ros2_utils::SubPtr< carma_v2x_msgs::msg::TrafficControlMessage > geofence_sub_
carma_ros2_utils::PubPtr< visualization_msgs::msg::MarkerArray > tcm_visualizer_pub_
rclcpp::TimerBase::SharedPtr timer_
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::Route > route_callmsg_sub_
void initializeWorker(std::weak_ptr< carma_ros2_utils::CarmaLifecycleNode > weak_node_pointer)
Initializes the WMBroadcaster worker with reference to the CarmaLifecycleNode itself.
void publishMapUpdate(const autoware_lanelet2_msgs::msg::MapBin &geofence_msg) const
Callback to publish map updates (geofences)
carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &)
carma_ros2_utils::PubPtr< std_msgs::msg::Int32MultiArray > upcoming_intersection_ids_pub_
bool spin_callback()
Spin callback, which will be called frequently based on the configured spin rate.
carma_ros2_utils::PubPtr< carma_v2x_msgs::msg::TrafficControlRequestPolygon > tcr_visualizer_pub_
std::unique_ptr< carma_wm_ctrl::WMBroadcaster > wmb_
carma_ros2_utils::PubPtr< carma_v2x_msgs::msg::MobilityOperation > tcm_ack_pub_
carma_ros2_utils::SubPtr< autoware_lanelet2_msgs::msg::MapBin > base_map_sub_
void publishActiveGeofence(const carma_perception_msgs::msg::CheckActiveGeofence &active_geof_msg)
Callback to publish active geofence information.
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)
std::vector< double > intersection_coord_correction
std::vector< int64_t > intersection_ids_for_correction