Skip to content
Open
Show file tree
Hide file tree
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
26 changes: 23 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,23 @@ 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 +167,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 +210,15 @@ 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
28 changes: 24 additions & 4 deletions pcl_ros/src/pcl_ros/filters/project_inliers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@
*/

#include "pcl_ros/filters/project_inliers.hpp"
#include <rclcpp/qos_overriding_options.hpp>

//////////////////////////////////////////////////////////////////////////////////////////////
pcl_ros::ProjectInliers::ProjectInliers(const rclcpp::NodeOptions & options)
Expand All @@ -60,7 +61,16 @@ pcl_ros::ProjectInliers::ProjectInliers(const rclcpp::NodeOptions & options)
declare_parameter("copy_all_fields", rclcpp::ParameterValue(true));
bool copy_all_fields = get_parameter("copy_all_fields").as_bool();

pub_output_ = create_publisher<PointCloud2>("output", max_queue_size_);
// Enable QoS reconfigurability via parameters
auto pub_options = rclcpp::PublisherOptions();
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);

RCLCPP_DEBUG(
this->get_logger(),
Expand Down Expand Up @@ -105,15 +115,25 @@ pcl_ros::ProjectInliers::subscribe()
if (use_indices_)
{*/

// 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
}};

auto qos_profile = rclcpp::QoS(
rclcpp::KeepLast(max_queue_size_),
rmw_qos_profile_default).get_rmw_qos_profile();
auto sensor_qos_profile = rclcpp::QoS(
rclcpp::KeepLast(max_queue_size_),
rmw_qos_profile_sensor_data).get_rmw_qos_profile();
sub_input_filter_.subscribe(this, "input", sensor_qos_profile);
sub_indices_filter_.subscribe(this, "indices", qos_profile);
sub_model_.subscribe(this, "model", qos_profile);
sub_input_filter_.subscribe(this, "input", sensor_qos_profile, sub_options);
sub_indices_filter_.subscribe(this, "indices", qos_profile, sub_options);
sub_model_.subscribe(this, "model", qos_profile, sub_options);

if (approximate_sync_) {
sync_input_indices_model_a_ = std::make_shared<
Expand Down
12 changes: 11 additions & 1 deletion pcl_ros/tools/pcd_to_pointcloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,7 @@
#include <thread>

#include <rclcpp/rclcpp.hpp>
#include <rclcpp/qos_overriding_options.hpp>
#include "rclcpp_components/register_node_macro.hpp"
#include <sensor_msgs/msg/point_cloud2.hpp>

Expand Down Expand Up @@ -95,7 +96,16 @@ class PCDPublisher : public rclcpp::Node
auto resolved_cloud_topic =
this->get_node_topics_interface()->resolve_topic_name(cloud_topic_);

pub_ = this->create_publisher<sensor_msgs::msg::PointCloud2>(cloud_topic_, 10);
// Enable QoS reconfigurability via parameters
auto pub_options = rclcpp::PublisherOptions();
pub_options.qos_overriding_options =
rclcpp::QosOverridingOptions {{
rclcpp::QosPolicyKind::History,
rclcpp::QosPolicyKind::Reliability,
rclcpp::QosPolicyKind::Durability,
rclcpp::QosPolicyKind::Depth
}};
pub_ = this->create_publisher<sensor_msgs::msg::PointCloud2>(cloud_topic_, 10, pub_options);
timer_ = this->create_wall_timer(
std::chrono::milliseconds(period_ms_),
[this]() {
Expand Down
13 changes: 12 additions & 1 deletion pcl_ros/tools/pointcloud_to_pcd.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@ Cloud Data) file format.
#include <tf2_ros/transform_listener.h>

#include <rclcpp/rclcpp.hpp>
#include <rclcpp/qos_overriding_options.hpp>
#include <rclcpp_components/register_node_macro.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <tf2_eigen/tf2_eigen.hpp>
Expand Down Expand Up @@ -189,10 +190,20 @@ class PointCloudToPCD : public rclcpp::Node
this->get_parameter("compressed", compressed_);
this->get_parameter("rgb", rgb_);

// 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
}};

auto sensor_qos = rclcpp::SensorDataQoS();
sub_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
"input", sensor_qos,
std::bind(&PointCloudToPCD::cloud_cb, this, std::placeholders::_1));
std::bind(&PointCloudToPCD::cloud_cb, this, std::placeholders::_1), sub_options);
}
};
} // namespace pcl_ros
Expand Down