Skip to content

Commit

Permalink
Fix deprecation warning (#2922)
Browse files Browse the repository at this point in the history
  • Loading branch information
rhaschke authored Jul 26, 2024
1 parent bc07edf commit 30fbc31
Showing 1 changed file with 5 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
#include <tf2_ros/create_timer_interface.h>
#include <tf2_ros/create_timer_ros.h>
#include <moveit/utils/logger.hpp>
#include <rclcpp/version.h>

#include <memory>

Expand Down Expand Up @@ -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_ =
Expand All @@ -107,7 +107,11 @@ void PointCloudOctomapUpdater::start()
return;
/* subscribe to point cloud topic using tf filter*/
point_cloud_subscriber_ = new message_filters::Subscriber<sensor_msgs::msg::PointCloud2>(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<sensor_msgs::msg::PointCloud2>(
Expand Down

0 comments on commit 30fbc31

Please sign in to comment.