17#include <carma_ros2_utils/timers/ROSTimerFactory.hpp>
24namespace std_ph = std::placeholders;
53 : carma_ros2_utils::CarmaLifecycleNode(options)
65 declare_parameter(
"intersection_ids_for_correction");
66 declare_parameter(
"intersection_coord_correction");
73 std::make_unique<carma_ros2_utils::timers::ROSTimerFactory>(weak_node_pointer),
79 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"carma_mw_ctrl"),
"Starting configuration!");
86 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"carma_mw_ctrl"),
"Done initializing worker!");
101 rclcpp::Parameter intersection_coord_correction_param = get_parameter(
"intersection_coord_correction");
104 rclcpp::Parameter intersection_ids_for_correction_param = get_parameter(
"intersection_ids_for_correction");
109 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"carma_mw_ctrl"),
"Done loading parameters: " <<
config_);
116 rclcpp::PublisherOptions intra_proc_disabled;
117 intra_proc_disabled.use_intra_process_comm = rclcpp::IntraProcessSetting::Disable;
120 auto pub_qos_transient_local = rclcpp::QoS(rclcpp::KeepAll());
121 pub_qos_transient_local.transient_local();
125 map_update_pub_ = create_publisher<autoware_lanelet2_msgs::msg::MapBin>(
"map_update", pub_qos_transient_local, intra_proc_disabled);
128 map_pub_ = create_publisher<autoware_lanelet2_msgs::msg::MapBin>(
"semantic_map", pub_qos_transient_local, intra_proc_disabled);
131 control_msg_pub_= create_publisher<carma_v2x_msgs::msg::TrafficControlRequest>(
"outgoing_geofence_request", 1);
134 active_pub_ = create_publisher<carma_perception_msgs::msg::CheckActiveGeofence>(
"active_geofence", 200);
140 tcm_visualizer_pub_= create_publisher<visualization_msgs::msg::MarkerArray>(
"tcm_visualizer",1);
143 tcr_visualizer_pub_ = create_publisher<carma_v2x_msgs::msg::TrafficControlRequestPolygon>(
"tcr_bounding_points",1);
150 return CallbackReturn::SUCCESS;
156 timer_ = create_timer(get_clock(),
171 rclcpp::SubscriptionOptions geofence_sub_options;
173 geofence_sub_options.use_intra_process_comm = rclcpp::IntraProcessSetting::Disable;
174 auto sub_qos_transient_local = rclcpp::QoS(rclcpp::KeepAll());
175 sub_qos_transient_local.transient_local();
188 return CallbackReturn::SUCCESS;
195 wmb_->publishLightId();
197 wmb_->updateUpcomingSGIntersectionIds();
198 if (
wmb_->upcoming_intersection_ids_.data.size() > 0)
200 if(
wmb_->getRoute().route_path_lanelet_ids.size() > 0)
201 wmb_->routeCallbackMessage(std::make_unique<carma_planning_msgs::msg::Route>(
wmb_->getRoute()));
212#include "rclcpp_components/register_node_macro.hpp"
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_
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
double traffic_control_request_period