From d2b1c51c9d4c83ad97003f93d45072eadb7c6d68 Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Fri, 19 Jul 2024 15:11:51 +0200 Subject: [PATCH 1/3] 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 6e2b8678d8..2cfb19b74a 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( From ba8a2b4033f1e2a0ce8332176240bb9f22b95ace Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Thu, 25 Jul 2024 14:12:50 +0200 Subject: [PATCH 2/3] Add compile-time switch --- .../src/pointcloud_octomap_updater.cpp | 4 ++++ 1 file changed, 4 insertions(+) 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 2cfb19b74a..56fa447338 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 @@ -106,7 +106,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( From fa37862ed7b53ec7202743d94b359446c0a8eed9 Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Fri, 26 Jul 2024 10:32:47 +0200 Subject: [PATCH 3/3] Add rclcpp/version.h --- .../src/pointcloud_octomap_updater.cpp | 1 + 1 file changed, 1 insertion(+) 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 56fa447338..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