Skip to content

Commit 38fa921

Browse files
Fixing builds for message filters API change while retaining Jazzy, Kilted, and Rolling support (#5251)
* Update amcl_node.hpp Signed-off-by: Steve Macenski <[email protected]> * Update amcl_node.cpp Signed-off-by: Steve Macenski <[email protected]> * Working for Kilted, Jazzy Signed-off-by: Steve Macenski <[email protected]> * Update amcl_node.cpp Signed-off-by: Steve Macenski <[email protected]> * Update amcl_node.cpp Signed-off-by: Steve Macenski <[email protected]> * Update amcl_node.cpp Signed-off-by: Steve Macenski <[email protected]> --------- Signed-off-by: Steve Macenski <[email protected]>
1 parent d6fc89a commit 38fa921

File tree

4 files changed

+43
-4
lines changed

4 files changed

+43
-4
lines changed

nav2_amcl/include/nav2_amcl/amcl_node.hpp

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,7 @@
2929
#include <vector>
3030

3131
#include "message_filters/subscriber.hpp"
32+
#include "rclcpp/version.h"
3233

3334
#include "geometry_msgs/msg/pose_stamped.hpp"
3435
#include "nav2_util/lifecycle_node.hpp"
@@ -171,8 +172,14 @@ class AmclNode : public nav2_util::LifecycleNode
171172
* @brief Initialize incoming data message subscribers and filters
172173
*/
173174
void initMessageFilters();
175+
176+
// To Support Kilted and Older from Message Filters API change
177+
#if RCLCPP_VERSION_GTE(29, 6, 0)
178+
std::unique_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan>> laser_scan_sub_;
179+
#else
174180
std::unique_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
175181
rclcpp_lifecycle::LifecycleNode>> laser_scan_sub_;
182+
#endif
176183
std::unique_ptr<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>> laser_scan_filter_;
177184
message_filters::Connection laser_scan_connection_;
178185

nav2_amcl/src/amcl_node.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1523,9 +1523,15 @@ AmclNode::initMessageFilters()
15231523
{
15241524
auto sub_opt = rclcpp::SubscriptionOptions();
15251525
sub_opt.callback_group = callback_group_;
1526+
1527+
#if RCLCPP_VERSION_GTE(29, 6, 0)
1528+
laser_scan_sub_ = std::make_unique<message_filters::Subscriber<sensor_msgs::msg::LaserScan>>(
1529+
shared_from_this(), scan_topic_, rclcpp::SensorDataQoS(), sub_opt);
1530+
#else
15261531
laser_scan_sub_ = std::make_unique<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
15271532
rclcpp_lifecycle::LifecycleNode>>(
15281533
shared_from_this(), scan_topic_, rmw_qos_profile_sensor_data, sub_opt);
1534+
#endif
15291535

15301536
laser_scan_filter_ = std::make_unique<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>(
15311537
*laser_scan_sub_, *tf_buffer_, odom_frame_id_, 10,

nav2_costmap_2d/include/nav2_costmap_2d/obstacle_layer.hpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,7 @@
4343
#include <vector>
4444

4545
#include "rclcpp/rclcpp.hpp"
46+
#include "rclcpp/version.h"
4647
#include "laser_geometry/laser_geometry.hpp"
4748
#pragma GCC diagnostic push
4849
#pragma GCC diagnostic ignored "-Wreorder"
@@ -234,8 +235,13 @@ class ObstacleLayer : public CostmapLayer
234235
/// @brief Used to project laser scans into point clouds
235236
laser_geometry::LaserProjection projector_;
236237
/// @brief Used for the observation message filters
238+
#if RCLCPP_VERSION_GTE(29, 6, 0)
239+
std::vector<std::shared_ptr<message_filters::SubscriberBase>>
240+
observation_subscribers_;
241+
#else
237242
std::vector<std::shared_ptr<message_filters::SubscriberBase<rclcpp_lifecycle::LifecycleNode>>>
238243
observation_subscribers_;
244+
#endif
239245
/// @brief Used to make sure that transforms are available for each sensor
240246
std::vector<std::shared_ptr<tf2_ros::MessageFilterBase>> observation_notifiers_;
241247
/// @brief Used to store observations from various sensors

nav2_costmap_2d/plugins/obstacle_layer.cpp

Lines changed: 24 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -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

Comments
 (0)