diff --git a/nav2_amcl/include/nav2_amcl/amcl_node.hpp b/nav2_amcl/include/nav2_amcl/amcl_node.hpp index 5910181b3a6..c7341a5985a 100644 --- a/nav2_amcl/include/nav2_amcl/amcl_node.hpp +++ b/nav2_amcl/include/nav2_amcl/amcl_node.hpp @@ -28,13 +28,7 @@ #include #include -// For compatibility with Jazzy -#include "rclcpp/version.h" -#if RCLCPP_VERSION_GTE(29, 0, 0) #include "message_filters/subscriber.hpp" -#else -#include "message_filters/subscriber.h" -#endif #include "geometry_msgs/msg/pose_stamped.hpp" #include "nav2_util/lifecycle_node.hpp" diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/obstacle_layer.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/obstacle_layer.hpp index 05252015fb3..1cdec808da7 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/obstacle_layer.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/obstacle_layer.hpp @@ -49,13 +49,7 @@ #include "tf2_ros/message_filter.h" #pragma GCC diagnostic pop -// For compatibility with Jazzy -#include "rclcpp/version.h" -#if RCLCPP_VERSION_GTE(29, 0, 0) #include "message_filters/subscriber.hpp" -#else -#include "message_filters/subscriber.h" -#endif #include "nav_msgs/msg/occupancy_grid.hpp" #include "sensor_msgs/msg/laser_scan.hpp" diff --git a/nav2_costmap_2d/plugins/obstacle_layer.cpp b/nav2_costmap_2d/plugins/obstacle_layer.cpp index a05548a8cde..3bffea43fbe 100644 --- a/nav2_costmap_2d/plugins/obstacle_layer.cpp +++ b/nav2_costmap_2d/plugins/obstacle_layer.cpp @@ -46,6 +46,7 @@ #include "pluginlib/class_list_macros.hpp" #include "sensor_msgs/point_cloud2_iterator.hpp" #include "nav2_costmap_2d/costmap_math.hpp" +#include "rclcpp/version.h" PLUGINLIB_EXPORT_CLASS(nav2_costmap_2d::ObstacleLayer, nav2_costmap_2d::Layer)