From 30fbc31e5368094a5df7515c13528760ddf23054 Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Fri, 26 Jul 2024 12:55:39 +0200 Subject: [PATCH] Fix deprecation warning (#2922) --- .../src/pointcloud_octomap_updater.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp b/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp index 6e2b8678d8..bce0275430 100644 --- a/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp +++ b/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp @@ -44,6 +44,7 @@ #include #include #include +#include #include @@ -96,7 +97,6 @@ void PointCloudOctomapUpdater::start() if (!ns_.empty()) prefix = ns_ + "/"; - rclcpp::QoS qos(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_sensor_data)); if (!filtered_cloud_topic_.empty()) { filtered_cloud_publisher_ = @@ -107,7 +107,11 @@ void PointCloudOctomapUpdater::start() return; /* subscribe to point cloud topic using tf filter*/ point_cloud_subscriber_ = new message_filters::Subscriber(node_, point_cloud_topic_, +#if RCLCPP_VERSION_GTE(28, 3, 0) + rclcpp::SensorDataQoS()); +#else rmw_qos_profile_sensor_data); +#endif if (tf_listener_ && tf_buffer_ && !monitor_->getMapFrame().empty()) { point_cloud_filter_ = new tf2_ros::MessageFilter(