Skip to content
Open
Changes from 1 commit
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
14 changes: 11 additions & 3 deletions pcl_ros/src/pcl_ros/filters/filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@

#include "pcl_ros/filters/filter.hpp"
#include <pcl/common/io.h>
#include <rclcpp/qos_overriding_options.hpp>
#include "pcl_ros/transforms.hpp"

/*//#include <pcl/filters/pixel_grid.h>
Expand Down Expand Up @@ -120,13 +121,17 @@ pcl_ros::Filter::computePublish(
void
pcl_ros::Filter::subscribe()
{
// Enable QoS reconfigurability via parameters
rclcpp::SubscriptionOptions sub_options;
sub_options.qos_overriding_options = rclcpp::QosOverridingOptions {{rclcpp::QosPolicyKind::History, rclcpp::QosPolicyKind::Reliability, rclcpp::QosPolicyKind::Durability, rclcpp::QosPolicyKind::Depth}};

// If we're supposed to look for PointIndices (indices)
if (use_indices_) {
// Subscribe to the input using a filter
auto sensor_qos_profile =
rclcpp::SensorDataQoS().keep_last(max_queue_size_).get_rmw_qos_profile();
sub_input_filter_.subscribe(this, "input", sensor_qos_profile);
sub_indices_filter_.subscribe(this, "indices", sensor_qos_profile);
sub_input_filter_.subscribe(this, "input", sensor_qos_profile, sub_options);
sub_indices_filter_.subscribe(this, "indices", sensor_qos_profile, sub_options);

if (approximate_sync_) {
sync_input_indices_a_ =
Expand Down Expand Up @@ -156,7 +161,7 @@ pcl_ros::Filter::subscribe()
sub_input_ =
this->create_subscription<PointCloud2>(
"input", rclcpp::SensorDataQoS().keep_last(max_queue_size_),
callback);
callback, sub_options);
}
}

Expand Down Expand Up @@ -199,6 +204,9 @@ pcl_ros::Filter::createPublishers()
}
}
};

// Enable QoS reconfigurability via parameters
pub_options.qos_overriding_options = rclcpp::QosOverridingOptions {{rclcpp::QosPolicyKind::History, rclcpp::QosPolicyKind::Reliability, rclcpp::QosPolicyKind::Durability, rclcpp::QosPolicyKind::Depth}};
pub_output_ = create_publisher<PointCloud2>("output", max_queue_size_, pub_options);
}

Expand Down