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>
64 void publishMap(
const autoware_lanelet2_msgs::msg::MapBin& map_msg);
71 void initializeWorker(std::weak_ptr<carma_ros2_utils::CarmaLifecycleNode> weak_node_pointer);
78 void publishCtrlReq(
const carma_v2x_msgs::msg::TrafficControlRequest& ctrlreq_msg)
const;
85 void publishMapUpdate(
const autoware_lanelet2_msgs::msg::MapBin& geofence_msg)
const;
99 void publishTCMACK(
const carma_v2x_msgs::msg::MobilityOperation& mom_msg);
111 carma_ros2_utils::PubPtr<autoware_lanelet2_msgs::msg::MapBin>
map_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_;
120 carma_ros2_utils::SubPtr<autoware_lanelet2_msgs::msg::MapBin>
base_map_sub_;
123 carma_ros2_utils::SubPtr<carma_v2x_msgs::msg::TrafficControlMessage>
geofence_sub_;
130 std::shared_ptr<carma_ros2_utils::CarmaLifecycleNode>
ptr_;
131 std::unique_ptr<carma_wm_ctrl::WMBroadcaster>
wmb_;
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.