From d6f6c38fd5d516cc708f5385a02a801cb1a73481 Mon Sep 17 00:00:00 2001 From: Marco Magri Date: Wed, 8 Jan 2025 13:46:31 +0100 Subject: [PATCH] refactor: adjust macro for readability --- .../src/pointcloud_octomap_updater.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 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 6462a6df71..47aa4b30f5 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 @@ -118,13 +118,14 @@ void PointCloudOctomapUpdater::start() rclcpp::SubscriptionOptions options; options.callback_group = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); /* subscribe to point cloud topic using tf filter*/ - point_cloud_subscriber_ = new message_filters::Subscriber(node_, point_cloud_topic_, + rclcpp::QoS qos_profile = #if RCLCPP_VERSION_GTE(28, 3, 0) - rclcpp::SensorDataQoS(), + rclcpp::SensorDataQoS(); #else - rmw_qos_profile_sensor_data, + rmw_qos_profile_sensor_data; #endif - options); + point_cloud_subscriber_ = + new message_filters::Subscriber(node_, point_cloud_topic_, qos_profile, options); if (tf_listener_ && tf_buffer_ && !monitor_->getMapFrame().empty()) { point_cloud_filter_ = new tf2_ros::MessageFilter(