Skip to content

Commit

Permalink
Set sensor data QoS to filter subscribers (#419)
Browse files Browse the repository at this point in the history
* Set sensor data QoS to filter subscribers

* Fix format for consistency

* Fix type

* Fix style format
  • Loading branch information
Tacha-S authored Jun 12, 2023
1 parent b2dcad2 commit daee50f
Showing 1 changed file with 3 additions and 4 deletions.
7 changes: 3 additions & 4 deletions pcl_ros/src/pcl_ros/filters/filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,9 +118,8 @@ pcl_ros::Filter::subscribe()
// If we're supposed to look for PointIndices (indices)
if (use_indices_) {
// Subscribe to the input using a filter
auto sensor_qos_profile = rclcpp::QoS(
rclcpp::KeepLast(max_queue_size_),
rmw_qos_profile_sensor_data).get_rmw_qos_profile();
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);

Expand Down Expand Up @@ -151,7 +150,7 @@ pcl_ros::Filter::subscribe()
// Subscribe in an old fashion to input only (no filters)
sub_input_ =
this->create_subscription<PointCloud2>(
"input", max_queue_size_,
"input", rclcpp::SensorDataQoS().keep_last(max_queue_size_),
callback);
}
}
Expand Down

0 comments on commit daee50f

Please sign in to comment.