Skip to content

Commit

Permalink
No need for conditionals on humble
Browse files Browse the repository at this point in the history
  • Loading branch information
sea-bass committed Jan 10, 2025
1 parent dcdc12d commit b1adae1
Showing 1 changed file with 2 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -119,14 +119,8 @@ void PointCloudOctomapUpdater::start()
rclcpp::SubscriptionOptions options;
options.callback_group = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
/* subscribe to point cloud topic using tf filter*/
auto qos_profile =
#if RCLCPP_VERSION_GTE(28, 3, 0)
rclcpp::SensorDataQoS();
#else
rmw_qos_profile_sensor_data;
#endif
point_cloud_subscriber_ =
new message_filters::Subscriber<sensor_msgs::msg::PointCloud2>(node_, point_cloud_topic_, qos_profile, options);
point_cloud_subscriber_ = new message_filters::Subscriber<sensor_msgs::msg::PointCloud2>(
node_, point_cloud_topic_, rmw_qos_profile_sensor_data, options);
if (tf_listener_ && tf_buffer_ && !monitor_->getMapFrame().empty())
{
point_cloud_filter_ = new tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>(
Expand Down

0 comments on commit b1adae1

Please sign in to comment.