Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix deprecation warning #2922

Merged
merged 4 commits into from
Jul 26, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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
Loading