@@ -289,8 +289,32 @@ void ObstacleLayer::onInitialize()
289
289
tf_filter_tolerance));
290
290
291
291
} else {
292
- auto sub = std::make_shared<point_cloud_transport::SubscriberFilter>(
292
+ // For Kilted and Older Support from Message Filters API change
293
+ #if RCLCPP_VERSION_GTE(29, 6, 0)
294
+ std::shared_ptr<point_cloud_transport::SubscriberFilter> sub;
295
+ #else
296
+ std::shared_ptr<message_filters::Subscriber<sensor_msgs::msg::PointCloud2,
297
+ rclcpp_lifecycle::LifecycleNode>> sub;
298
+ #endif
299
+
300
+ // For Kilted compatibility in Message Filters API change
301
+ #if RCLCPP_VERSION_GTE(29, 6, 0)
302
+ sub = std::make_shared<point_cloud_transport::SubscriberFilter>(
293
303
*node, topic, transport_type, custom_qos_profile, sub_opt);
304
+ // For Jazzy compatibility in Message Filters API change
305
+ #elif RCLCPP_VERSION_GTE(29, 0, 0)
306
+ sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::PointCloud2,
307
+ rclcpp_lifecycle::LifecycleNode>>(
308
+ std::static_pointer_cast<rclcpp_lifecycle::LifecycleNode>(node),
309
+ topic, custom_qos_profile, sub_opt);
310
+ // For Humble and Older compatibility in Message Filters API change
311
+ #else
312
+ sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::PointCloud2,
313
+ rclcpp_lifecycle::LifecycleNode>>(
314
+ std::static_pointer_cast<rclcpp_lifecycle::LifecycleNode>(node),
315
+ topic, custom_qos_profile.get_rmw_qos_profile (), sub_opt);
316
+ #endif
317
+
294
318
sub->unsubscribe ();
295
319
296
320
if (inf_is_valid) {
0 commit comments