From 0924bdd50a89326ea0e68bd95f3fce4c42842640 Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Fri, 19 Jul 2024 15:11:51 +0200 Subject: [PATCH] Fix deprecation warning --- .../src/pointcloud_octomap_updater.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) 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 6e2b8678d87..2cfb19b74ae 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 @@ -96,7 +96,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 +106,7 @@ void PointCloudOctomapUpdater::start() return; /* subscribe to point cloud topic using tf filter*/ point_cloud_subscriber_ = new message_filters::Subscriber(node_, point_cloud_topic_, - rmw_qos_profile_sensor_data); + rclcpp::SensorDataQoS()); if (tf_listener_ && tf_buffer_ && !monitor_->getMapFrame().empty()) { point_cloud_filter_ = new tf2_ros::MessageFilter(