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

Fixed message filter api #457

Open
wants to merge 2 commits into
base: ros2
Choose a base branch
from
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
14 changes: 10 additions & 4 deletions pcl_ros/include/pcl_ros/filters/filter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -137,11 +137,17 @@ class Filter : public PCLNode<sensor_msgs::msg::PointCloud2>
/** \brief Pointer to parameters callback handle. */
OnSetParametersCallbackHandle::SharedPtr callback_handle_;

typedef message_filters::sync_policies::ApproximateTime<
PointCloud2, PointIndices> SyncApproxPolInputIndices;
typedef message_filters::Synchronizer<SyncApproxPolInputIndices> SynchronizerApproxInputIndices;

typedef message_filters::sync_policies::ExactTime<
PointCloud2, PointIndices> SyncExactPolInputIndices;
typedef message_filters::Synchronizer<SyncExactPolInputIndices> SynchronizerExactInputIndices;

/** \brief Synchronized input, and indices.*/
std::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloud2,
PointIndices>>> sync_input_indices_e_;
std::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud2,
PointIndices>>> sync_input_indices_a_;
std::shared_ptr<SynchronizerExactInputIndices> sync_input_indices_e_;
std::shared_ptr<SynchronizerApproxInputIndices> sync_input_indices_a_;

/** \brief Parameter callback
* \param params parameter values to set
Expand Down
17 changes: 13 additions & 4 deletions pcl_ros/include/pcl_ros/filters/project_inliers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,11 +77,20 @@ class ProjectInliers : public Filter
/** \brief The message filter subscriber for model coefficients. */
message_filters::Subscriber<ModelCoefficients> sub_model_;

typedef message_filters::sync_policies::ApproximateTime<
PointCloud2, PointIndices, ModelCoefficients> SyncApproxPolInputIndicesModel;
typedef message_filters::Synchronizer<SyncApproxPolInputIndicesModel>
SynchronizerApproxInputIndicesModel;

typedef message_filters::sync_policies::ExactTime<
PointCloud2, PointIndices, ModelCoefficients> SyncExactPolInputIndicesModel;
typedef message_filters::Synchronizer<SyncExactPolInputIndicesModel>
SynchronizerExactInputIndicesModel;

/** \brief Synchronized input, indices, and model coefficients.*/
std::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloud2,
PointIndices, ModelCoefficients>>> sync_input_indices_model_e_;
std::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud2,
PointIndices, ModelCoefficients>>> sync_input_indices_model_a_;
std::shared_ptr<SynchronizerExactInputIndicesModel> sync_input_indices_model_e_;
std::shared_ptr<SynchronizerApproxInputIndicesModel> sync_input_indices_model_a_;

/** \brief The PCL filter implementation used. */
pcl::ProjectInliers<pcl::PCLPointCloud2> impl_;

Expand Down
10 changes: 5 additions & 5 deletions pcl_ros/src/pcl_ros/filters/filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -119,23 +119,23 @@ pcl_ros::Filter::subscribe()
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();
rclcpp::SensorDataQoS().keep_last(max_queue_size_);
sub_input_filter_.subscribe(this, "input", sensor_qos_profile);
sub_indices_filter_.subscribe(this, "indices", sensor_qos_profile);

if (approximate_sync_) {
sync_input_indices_a_ =
std::make_shared<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud2,
pcl_msgs::msg::PointIndices>>>(max_queue_size_);
std::make_shared<SynchronizerApproxInputIndices>(SyncApproxPolInputIndices(
max_queue_size_));
sync_input_indices_a_->connectInput(sub_input_filter_, sub_indices_filter_);
sync_input_indices_a_->registerCallback(
std::bind(
&Filter::input_indices_callback, this,
std::placeholders::_1, std::placeholders::_2));
} else {
sync_input_indices_e_ =
std::make_shared<message_filters::Synchronizer<sync_policies::ExactTime<PointCloud2,
pcl_msgs::msg::PointIndices>>>(max_queue_size_);
std::make_shared<SynchronizerExactInputIndices>(SyncExactPolInputIndices(
max_queue_size_));
sync_input_indices_e_->connectInput(sub_input_filter_, sub_indices_filter_);
sync_input_indices_e_->registerCallback(
std::bind(
Expand Down
16 changes: 6 additions & 10 deletions pcl_ros/src/pcl_ros/filters/project_inliers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,29 +108,25 @@ pcl_ros::ProjectInliers::subscribe()

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

if (approximate_sync_) {
sync_input_indices_model_a_ = std::make_shared<
message_filters::Synchronizer<
message_filters::sync_policies::ApproximateTime<
PointCloud2, PointIndices, ModelCoefficients>>>(max_queue_size_);
sync_input_indices_model_a_ = std::make_shared<SynchronizerApproxInputIndicesModel>(
SyncApproxPolInputIndicesModel(max_queue_size_));
sync_input_indices_model_a_->connectInput(sub_input_filter_, sub_indices_filter_, sub_model_);
sync_input_indices_model_a_->registerCallback(
std::bind(
&ProjectInliers::input_indices_model_callback, this,
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
} else {
sync_input_indices_model_e_ = std::make_shared<
message_filters::Synchronizer<
message_filters::sync_policies::ExactTime<
PointCloud2, PointIndices, ModelCoefficients>>>(max_queue_size_);
sync_input_indices_model_e_ = std::make_shared<SynchronizerExactInputIndicesModel>(
SyncExactPolInputIndicesModel(max_queue_size_));
sync_input_indices_model_e_->connectInput(sub_input_filter_, sub_indices_filter_, sub_model_);
sync_input_indices_model_e_->registerCallback(
std::bind(
Expand Down