diff --git a/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.hpp b/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.hpp index e768005753..cfe085e8c0 100644 --- a/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.hpp +++ b/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.hpp @@ -37,6 +37,7 @@ #pragma once #include +#include #include #include #include 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 74a6fcebae..31c294545d 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 @@ -114,13 +114,18 @@ void PointCloudOctomapUpdater::start() if (point_cloud_subscriber_) return; + + 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_, + auto 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 + 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(