Skip to content

Commit c6dae60

Browse files
authored
message_filters hpp headers have been backported (#5127)
* message_filters hpp headers have been backported Signed-off-by: Tim Clephas <[email protected]> * fixup! message_filters hpp headers have been backported Signed-off-by: Tim Clephas <[email protected]> --------- Signed-off-by: Tim Clephas <[email protected]>
1 parent 867d1c3 commit c6dae60

File tree

3 files changed

+1
-12
lines changed

3 files changed

+1
-12
lines changed

nav2_amcl/include/nav2_amcl/amcl_node.hpp

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

31-
// For compatibility with Jazzy
32-
#include "rclcpp/version.h"
33-
#if RCLCPP_VERSION_GTE(29, 0, 0)
3431
#include "message_filters/subscriber.hpp"
35-
#else
36-
#include "message_filters/subscriber.h"
37-
#endif
3832

3933
#include "geometry_msgs/msg/pose_stamped.hpp"
4034
#include "nav2_util/lifecycle_node.hpp"

nav2_costmap_2d/include/nav2_costmap_2d/obstacle_layer.hpp

Lines changed: 0 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -49,13 +49,7 @@
4949
#include "tf2_ros/message_filter.h"
5050
#pragma GCC diagnostic pop
5151

52-
// For compatibility with Jazzy
53-
#include "rclcpp/version.h"
54-
#if RCLCPP_VERSION_GTE(29, 0, 0)
5552
#include "message_filters/subscriber.hpp"
56-
#else
57-
#include "message_filters/subscriber.h"
58-
#endif
5953

6054
#include "nav_msgs/msg/occupancy_grid.hpp"
6155
#include "sensor_msgs/msg/laser_scan.hpp"

nav2_costmap_2d/plugins/obstacle_layer.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,7 @@
4646
#include "pluginlib/class_list_macros.hpp"
4747
#include "sensor_msgs/point_cloud2_iterator.hpp"
4848
#include "nav2_costmap_2d/costmap_math.hpp"
49+
#include "rclcpp/version.h"
4950

5051
PLUGINLIB_EXPORT_CLASS(nav2_costmap_2d::ObstacleLayer, nav2_costmap_2d::Layer)
5152

0 commit comments

Comments
 (0)