@@ -231,13 +231,23 @@ void ObstacleLayer::onInitialize()
231231
232232 // create a callback for the topic
233233 if (data_type == " LaserScan" ) {
234+ // For Kilted and Older Support from Message Filters API change
235+ #if RCLCPP_VERSION_GTE(29, 6, 0)
236+ std::shared_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan>> sub;
237+ #else
234238 std::shared_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
235239 rclcpp_lifecycle::LifecycleNode>> sub;
240+ #endif
236241
237- // For Jazzy compatibility
238- #if RCLCPP_VERSION_GTE(29, 0, 0)
242+ // For Kilted compatibility in Message Filters API change
243+ #if RCLCPP_VERSION_GTE(29, 6, 0)
244+ sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::LaserScan>>(
245+ node, topic, custom_qos_profile, sub_opt);
246+ // For Jazzy compatibility in Message Filters API change
247+ #elif RCLCPP_VERSION_GTE(29, 0, 0)
239248 sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
240249 rclcpp_lifecycle::LifecycleNode>>(node, topic, custom_qos_profile, sub_opt);
250+ // For Humble and Older compatibility in Message Filters API change
241251 #else
242252 sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
243253 rclcpp_lifecycle::LifecycleNode>>(
@@ -271,13 +281,23 @@ void ObstacleLayer::onInitialize()
271281 observation_notifiers_.back ()->setTolerance (rclcpp::Duration::from_seconds (0.05 ));
272282
273283 } else {
284+ // For Kilted and Older Support from Message Filters API change
285+ #if RCLCPP_VERSION_GTE(29, 6, 0)
286+ std::shared_ptr<message_filters::Subscriber<sensor_msgs::msg::PointCloud2>> sub;
287+ #else
274288 std::shared_ptr<message_filters::Subscriber<sensor_msgs::msg::PointCloud2,
275289 rclcpp_lifecycle::LifecycleNode>> sub;
290+ #endif
276291
277- // For Jazzy compatibility
278- #if RCLCPP_VERSION_GTE(29, 0, 0)
292+ // For Kilted compatibility in Message Filters API change
293+ #if RCLCPP_VERSION_GTE(29, 6, 0)
294+ sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::PointCloud2>>(
295+ node, topic, custom_qos_profile, sub_opt);
296+ // For Jazzy compatibility in Message Filters API change
297+ #elif RCLCPP_VERSION_GTE(29, 0, 0)
279298 sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::PointCloud2,
280299 rclcpp_lifecycle::LifecycleNode>>(node, topic, custom_qos_profile, sub_opt);
300+ // For Humble and Older compatibility in Message Filters API change
281301 #else
282302 sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::PointCloud2,
283303 rclcpp_lifecycle::LifecycleNode>>(
0 commit comments