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.
WMBroadcasterNode.hpp
Go to the documentation of this file.
1#pragma once
2
3/*
4 * Copyright (C) 2022 LEIDOS.
5 *
6 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
7 * use this file except in compliance with the License. You may obtain a copy of
8 * the License at
9 *
10 * http://www.apache.org/licenses/LICENSE-2.0
11 *
12 * Unless required by applicable law or agreed to in writing, software
13 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
14 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
15 * License for the specific language governing permissions and limitations under
16 * the License.
17 */
18
19#include <functional>
20#include <autoware_lanelet2_msgs/msg/map_bin.hpp>
21#include <carma_v2x_msgs/msg/traffic_control_request.hpp>
22#include <carma_ros2_utils/carma_ros2_utils.hpp>
23#include <visualization_msgs/msg/marker_array.hpp>
26#include <std_msgs/msg/int32_multi_array.hpp>
27#include <rclcpp/rclcpp.hpp>
28#include <carma_ros2_utils/carma_lifecycle_node.hpp>
29
30#include <memory>
31
32namespace carma_wm_ctrl
33{
34
35class WMBroadcaster;
36
45class WMBroadcasterNode : public carma_ros2_utils::CarmaLifecycleNode
46{
47public:
51 explicit WMBroadcasterNode(const rclcpp::NodeOptions& options);
52
54 // Overrides
56 carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &);
57 carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &);
58
64 void publishMap(const autoware_lanelet2_msgs::msg::MapBin& map_msg);
65
71 void initializeWorker(std::weak_ptr<carma_ros2_utils::CarmaLifecycleNode> weak_node_pointer);
72
78 void publishCtrlReq(const carma_v2x_msgs::msg::TrafficControlRequest& ctrlreq_msg) const;
79
85 void publishMapUpdate(const autoware_lanelet2_msgs::msg::MapBin& geofence_msg) const;
86
92 void publishActiveGeofence(const carma_perception_msgs::msg::CheckActiveGeofence& active_geof_msg);
93
99 void publishTCMACK(const carma_v2x_msgs::msg::MobilityOperation& mom_msg);
100
101private:
102
106 bool spin_callback();
107
108 // Node configuration
110
111 carma_ros2_utils::PubPtr<autoware_lanelet2_msgs::msg::MapBin> map_pub_;
112 carma_ros2_utils::PubPtr<autoware_lanelet2_msgs::msg::MapBin> map_update_pub_;
113 carma_ros2_utils::PubPtr<carma_v2x_msgs::msg::TrafficControlRequest> control_msg_pub_;
114 carma_ros2_utils::PubPtr<visualization_msgs::msg::MarkerArray> tcm_visualizer_pub_;
115 carma_ros2_utils::PubPtr<carma_v2x_msgs::msg::TrafficControlRequestPolygon> tcr_visualizer_pub_;
116 carma_ros2_utils::PubPtr<std_msgs::msg::Int32MultiArray> upcoming_intersection_ids_pub_;
117 carma_ros2_utils::PubPtr<carma_perception_msgs::msg::CheckActiveGeofence> active_pub_;
118 carma_ros2_utils::PubPtr<carma_v2x_msgs::msg::MobilityOperation> tcm_ack_pub_;
119
120 carma_ros2_utils::SubPtr<autoware_lanelet2_msgs::msg::MapBin> base_map_sub_;
121 carma_ros2_utils::SubPtr<carma_planning_msgs::msg::Route> route_callmsg_sub_;
122 carma_ros2_utils::SubPtr<std_msgs::msg::String> georef_sub_;
123 carma_ros2_utils::SubPtr<carma_v2x_msgs::msg::TrafficControlMessage> geofence_sub_;
124 carma_ros2_utils::SubPtr<carma_v2x_msgs::msg::MapData> incoming_map_sub_;
125 carma_ros2_utils::SubPtr<geometry_msgs::msg::PoseStamped> curr_location_sub_;
126
127 // Timer for publishing TCR and SignalGroup/IntersectionID
128 rclcpp::TimerBase::SharedPtr timer_;
129
130 std::shared_ptr<carma_ros2_utils::CarmaLifecycleNode> ptr_;
131 std::unique_ptr<carma_wm_ctrl::WMBroadcaster> wmb_;
132};
133} // namespace carma_wm_ctrl
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< 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_
std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > ptr_
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.