diff --git a/nav2_amcl/include/nav2_amcl/amcl_node.hpp b/nav2_amcl/include/nav2_amcl/amcl_node.hpp index 0be08c39db6..65787e82b00 100644 --- a/nav2_amcl/include/nav2_amcl/amcl_node.hpp +++ b/nav2_amcl/include/nav2_amcl/amcl_node.hpp @@ -44,9 +44,9 @@ #include "sensor_msgs/msg/laser_scan.hpp" #include "nav2_ros_common/service_server.hpp" #include "std_srvs/srv/empty.hpp" -#include "tf2_ros/message_filter.h" -#include "tf2_ros/transform_broadcaster.h" -#include "tf2_ros/transform_listener.h" +#include "tf2_ros/message_filter.hpp" +#include "tf2_ros/transform_broadcaster.hpp" +#include "tf2_ros/transform_listener.hpp" #define NEW_UNIFORM_SAMPLING 1 diff --git a/nav2_amcl/src/amcl_node.cpp b/nav2_amcl/src/amcl_node.cpp index a8cbfd197d4..b3b21631a59 100644 --- a/nav2_amcl/src/amcl_node.cpp +++ b/nav2_amcl/src/amcl_node.cpp @@ -38,11 +38,11 @@ #include "tf2/utils.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" #include "tf2/LinearMath/Transform.hpp" -#include "tf2_ros/buffer.h" -#include "tf2_ros/message_filter.h" -#include "tf2_ros/transform_broadcaster.h" -#include "tf2_ros/transform_listener.h" -#include "tf2_ros/create_timer_ros.h" +#include "tf2_ros/buffer.hpp" +#include "tf2_ros/message_filter.hpp" +#include "tf2_ros/transform_broadcaster.hpp" +#include "tf2_ros/transform_listener.hpp" +#include "tf2_ros/create_timer_ros.hpp" #include "nav2_amcl/portable_utils.hpp" #include "nav2_ros_common/validate_messages.hpp" diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/truncate_path_local_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/truncate_path_local_action.hpp index 6ce8a76fd64..9ffc5aa773f 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/truncate_path_local_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/truncate_path_local_action.hpp @@ -25,7 +25,7 @@ #include "nav_msgs/msg/path.hpp" #include "nav2_behavior_tree/bt_utils.hpp" #include "nav2_behavior_tree/json_utils.hpp" -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" #include "nav2_ros_common/lifecycle_node.hpp" diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/are_poses_near_condition.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/are_poses_near_condition.hpp index db615c06181..eb099f329b0 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/are_poses_near_condition.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/are_poses_near_condition.hpp @@ -20,7 +20,7 @@ #include "nav2_ros_common/lifecycle_node.hpp" #include "behaviortree_cpp/condition_node.h" -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" #include "nav2_behavior_tree/bt_utils.hpp" namespace nav2_behavior_tree diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/distance_traveled_condition.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/distance_traveled_condition.hpp index abcf722b872..c75f8b78d98 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/distance_traveled_condition.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/distance_traveled_condition.hpp @@ -23,7 +23,7 @@ #include "nav2_ros_common/lifecycle_node.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" #include "nav2_behavior_tree/bt_utils.hpp" namespace nav2_behavior_tree diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/goal_reached_condition.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/goal_reached_condition.hpp index aeebfcb3634..db3c56f24b7 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/goal_reached_condition.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/goal_reached_condition.hpp @@ -23,7 +23,7 @@ #include "behaviortree_cpp/json_export.h" #include "nav2_behavior_tree/bt_utils.hpp" #include "nav2_behavior_tree/json_utils.hpp" -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" namespace nav2_behavior_tree diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/transform_available_condition.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/transform_available_condition.hpp index 41a86ee813d..be1bcd6ee18 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/transform_available_condition.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/transform_available_condition.hpp @@ -21,7 +21,7 @@ #include "nav2_ros_common/lifecycle_node.hpp" #include "behaviortree_cpp/condition_node.h" -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/distance_controller.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/distance_controller.hpp index 64e4a7c4a75..782e89a8f89 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/distance_controller.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/distance_controller.hpp @@ -20,7 +20,7 @@ #include #include "geometry_msgs/msg/pose_stamped.hpp" -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" #include "behaviortree_cpp/decorator_node.h" #include "nav2_behavior_tree/bt_utils.hpp" diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/ros_topic_logger.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/ros_topic_logger.hpp index a8d27ecd96f..57ca3d4ffc3 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/ros_topic_logger.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/ros_topic_logger.hpp @@ -24,7 +24,7 @@ #include "nav2_msgs/msg/behavior_tree_log.hpp" #include "nav2_msgs/msg/behavior_tree_status_change.hpp" #include "tf2/time.hpp" -#include "tf2_ros/buffer_interface.h" +#include "tf2_ros/buffer_interface.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/plugins/action/truncate_path_local_action.cpp b/nav2_behavior_tree/plugins/action/truncate_path_local_action.cpp index bf8e58b9184..7cae783bb9f 100644 --- a/nav2_behavior_tree/plugins/action/truncate_path_local_action.cpp +++ b/nav2_behavior_tree/plugins/action/truncate_path_local_action.cpp @@ -25,8 +25,8 @@ #include "nav_msgs/msg/path.hpp" #include "rclcpp/rclcpp.hpp" #include "tf2/LinearMath/Quaternion.hpp" -#include "tf2_ros/buffer.h" -#include "tf2_ros/create_timer_ros.h" +#include "tf2_ros/buffer.hpp" +#include "tf2_ros/create_timer_ros.hpp" #include "nav2_behavior_tree/plugins/action/truncate_path_local_action.hpp" diff --git a/nav2_behavior_tree/plugins/condition/transform_available_condition.cpp b/nav2_behavior_tree/plugins/condition/transform_available_condition.cpp index b377d47c585..914a2be547a 100644 --- a/nav2_behavior_tree/plugins/condition/transform_available_condition.cpp +++ b/nav2_behavior_tree/plugins/condition/transform_available_condition.cpp @@ -18,7 +18,7 @@ #include "rclcpp/rclcpp.hpp" #include "tf2/time.hpp" -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" #include "nav2_behavior_tree/plugins/condition/transform_available_condition.hpp" diff --git a/nav2_behavior_tree/plugins/decorator/distance_controller.cpp b/nav2_behavior_tree/plugins/decorator/distance_controller.cpp index 0fdd47e7ffb..b560cddf2e7 100644 --- a/nav2_behavior_tree/plugins/decorator/distance_controller.cpp +++ b/nav2_behavior_tree/plugins/decorator/distance_controller.cpp @@ -21,7 +21,7 @@ #include "nav2_util/robot_utils.hpp" #include "nav2_util/geometry_utils.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" #include "behaviortree_cpp/decorator_node.h" diff --git a/nav2_behavior_tree/test/utils/test_transform_handler.hpp b/nav2_behavior_tree/test/utils/test_transform_handler.hpp index 19cfcdfa222..cf272d132cd 100644 --- a/nav2_behavior_tree/test/utils/test_transform_handler.hpp +++ b/nav2_behavior_tree/test/utils/test_transform_handler.hpp @@ -29,9 +29,9 @@ #include "geometry_msgs/msg/pose.hpp" #include "geometry_msgs/msg/transform_stamped.hpp" #include "tf2_msgs/msg/tf_message.hpp" -#include "tf2_ros/transform_broadcaster.h" -#include "tf2_ros/transform_listener.h" -#include "tf2_ros/buffer.h" +#include "tf2_ros/transform_broadcaster.hpp" +#include "tf2_ros/transform_listener.hpp" +#include "tf2_ros/buffer.hpp" using namespace std::chrono_literals; // NOLINT using namespace std::chrono; // NOLINT diff --git a/nav2_behaviors/include/nav2_behaviors/behavior_server.hpp b/nav2_behaviors/include/nav2_behaviors/behavior_server.hpp index 7301cef3836..82b55c0786f 100644 --- a/nav2_behaviors/include/nav2_behaviors/behavior_server.hpp +++ b/nav2_behaviors/include/nav2_behaviors/behavior_server.hpp @@ -19,8 +19,8 @@ #include #include "nav2_ros_common/lifecycle_node.hpp" -#include "tf2_ros/transform_listener.h" -#include "tf2_ros/create_timer_ros.h" +#include "tf2_ros/transform_listener.hpp" +#include "tf2_ros/create_timer_ros.hpp" #include "pluginlib/class_loader.hpp" #include "pluginlib/class_list_macros.hpp" #include "nav2_core/behavior.hpp" diff --git a/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp b/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp index 70d0f30fa30..22db8701700 100644 --- a/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp +++ b/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp @@ -26,8 +26,8 @@ #include #include "rclcpp/rclcpp.hpp" -#include "tf2_ros/transform_listener.h" -#include "tf2_ros/create_timer_ros.h" +#include "tf2_ros/transform_listener.hpp" +#include "tf2_ros/create_timer_ros.hpp" #include "geometry_msgs/msg/twist.hpp" #include "nav2_util/robot_utils.hpp" #include "nav2_util/twist_publisher.hpp" diff --git a/nav2_bt_navigator/include/nav2_bt_navigator/bt_navigator.hpp b/nav2_bt_navigator/include/nav2_bt_navigator/bt_navigator.hpp index 8a25e5a2c8d..adea1aba20f 100644 --- a/nav2_bt_navigator/include/nav2_bt_navigator/bt_navigator.hpp +++ b/nav2_bt_navigator/include/nav2_bt_navigator/bt_navigator.hpp @@ -23,9 +23,9 @@ #include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_util/odometry_utils.hpp" #include "rclcpp_action/rclcpp_action.hpp" -#include "tf2_ros/buffer.h" -#include "tf2_ros/transform_listener.h" -#include "tf2_ros/create_timer_ros.h" +#include "tf2_ros/buffer.hpp" +#include "tf2_ros/transform_listener.hpp" +#include "tf2_ros/create_timer_ros.hpp" #include "nav2_core/behavior_tree_navigator.hpp" #include "pluginlib/class_loader.hpp" diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/collision_detector_node.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/collision_detector_node.hpp index 59b807f562e..450e97c8078 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/collision_detector_node.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/collision_detector_node.hpp @@ -23,8 +23,8 @@ #include "rclcpp/rclcpp.hpp" #include "tf2/time.hpp" -#include "tf2_ros/buffer.h" -#include "tf2_ros/transform_listener.h" +#include "tf2_ros/buffer.hpp" +#include "tf2_ros/transform_listener.hpp" #include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_msgs/msg/collision_detector_state.hpp" diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/collision_monitor_node.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/collision_monitor_node.hpp index d73804cb827..c53540089d7 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/collision_monitor_node.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/collision_monitor_node.hpp @@ -26,8 +26,8 @@ #include "geometry_msgs/msg/twist_stamped.hpp" #include "tf2/time.hpp" -#include "tf2_ros/buffer.h" -#include "tf2_ros/transform_listener.h" +#include "tf2_ros/buffer.hpp" +#include "tf2_ros/transform_listener.hpp" #include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_util/twist_publisher.hpp" diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/polygon.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/polygon.hpp index 12d64259993..3191de1727e 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/polygon.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/polygon.hpp @@ -24,7 +24,7 @@ #include "geometry_msgs/msg/polygon_stamped.hpp" #include "tf2/time.hpp" -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" #include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_costmap_2d/footprint_subscriber.hpp" diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/source.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/source.hpp index 312c13ea577..4e91dab13c7 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/source.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/source.hpp @@ -22,7 +22,7 @@ #include "rclcpp/rclcpp.hpp" #include "tf2/time.hpp" -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" #include "nav2_collision_monitor/types.hpp" #include "nav2_ros_common/lifecycle_node.hpp" diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/velocity_polygon.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/velocity_polygon.hpp index 55f894d87c5..8056973ddf9 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/velocity_polygon.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/velocity_polygon.hpp @@ -24,7 +24,7 @@ #include "nav2_collision_monitor/types.hpp" #include "nav2_ros_common/lifecycle_node.hpp" #include "rclcpp/rclcpp.hpp" -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" namespace nav2_collision_monitor { diff --git a/nav2_collision_monitor/src/collision_detector_node.cpp b/nav2_collision_monitor/src/collision_detector_node.cpp index 15bbca37c6c..91023afae4f 100644 --- a/nav2_collision_monitor/src/collision_detector_node.cpp +++ b/nav2_collision_monitor/src/collision_detector_node.cpp @@ -19,7 +19,7 @@ #include #include -#include "tf2_ros/create_timer_ros.h" +#include "tf2_ros/create_timer_ros.hpp" #include "nav2_ros_common/node_utils.hpp" diff --git a/nav2_collision_monitor/src/collision_monitor_node.cpp b/nav2_collision_monitor/src/collision_monitor_node.cpp index 0a7f16a8ce2..d7ec6131220 100644 --- a/nav2_collision_monitor/src/collision_monitor_node.cpp +++ b/nav2_collision_monitor/src/collision_monitor_node.cpp @@ -18,7 +18,7 @@ #include #include -#include "tf2_ros/create_timer_ros.h" +#include "tf2_ros/create_timer_ros.hpp" #include "nav2_ros_common/node_utils.hpp" #include "nav2_util/robot_utils.hpp" diff --git a/nav2_collision_monitor/test/collision_detector_node_test.cpp b/nav2_collision_monitor/test/collision_detector_node_test.cpp index 1bd2eb0ca0c..4bbd37bc4e9 100644 --- a/nav2_collision_monitor/test/collision_detector_node_test.cpp +++ b/nav2_collision_monitor/test/collision_detector_node_test.cpp @@ -34,7 +34,7 @@ #include "geometry_msgs/msg/polygon_stamped.hpp" #include "visualization_msgs/msg/marker_array.hpp" -#include "tf2_ros/transform_broadcaster.h" +#include "tf2_ros/transform_broadcaster.hpp" #include "nav2_collision_monitor/types.hpp" #include "nav2_collision_monitor/collision_detector_node.hpp" diff --git a/nav2_collision_monitor/test/collision_monitor_node_test.cpp b/nav2_collision_monitor/test/collision_monitor_node_test.cpp index d64f0bd71e8..ea0213f468c 100644 --- a/nav2_collision_monitor/test/collision_monitor_node_test.cpp +++ b/nav2_collision_monitor/test/collision_monitor_node_test.cpp @@ -34,7 +34,7 @@ #include "geometry_msgs/msg/polygon_stamped.hpp" #include "visualization_msgs/msg/marker_array.hpp" -#include "tf2_ros/transform_broadcaster.h" +#include "tf2_ros/transform_broadcaster.hpp" #include "nav2_collision_monitor/types.hpp" #include "nav2_collision_monitor/collision_monitor_node.hpp" diff --git a/nav2_collision_monitor/test/polygons_test.cpp b/nav2_collision_monitor/test/polygons_test.cpp index 52eff3c650b..86f393febfa 100644 --- a/nav2_collision_monitor/test/polygons_test.cpp +++ b/nav2_collision_monitor/test/polygons_test.cpp @@ -27,9 +27,9 @@ #include "geometry_msgs/msg/point32.hpp" #include "geometry_msgs/msg/polygon_stamped.hpp" -#include "tf2_ros/buffer.h" -#include "tf2_ros/transform_listener.h" -#include "tf2_ros/transform_broadcaster.h" +#include "tf2_ros/buffer.hpp" +#include "tf2_ros/transform_listener.hpp" +#include "tf2_ros/transform_broadcaster.hpp" #include "nav2_collision_monitor/types.hpp" #include "nav2_collision_monitor/polygon.hpp" diff --git a/nav2_collision_monitor/test/sources_test.cpp b/nav2_collision_monitor/test/sources_test.cpp index 04929bd339c..034cdd40d96 100644 --- a/nav2_collision_monitor/test/sources_test.cpp +++ b/nav2_collision_monitor/test/sources_test.cpp @@ -30,9 +30,9 @@ #include "sensor_msgs/msg/range.hpp" #include "sensor_msgs/point_cloud2_iterator.hpp" -#include "tf2_ros/buffer.h" -#include "tf2_ros/transform_listener.h" -#include "tf2_ros/transform_broadcaster.h" +#include "tf2_ros/buffer.hpp" +#include "tf2_ros/transform_listener.hpp" +#include "tf2_ros/transform_broadcaster.hpp" #include "nav2_collision_monitor/types.hpp" #include "nav2_collision_monitor/scan.hpp" diff --git a/nav2_collision_monitor/test/velocity_polygons_test.cpp b/nav2_collision_monitor/test/velocity_polygons_test.cpp index d13fc873340..88024dd723b 100644 --- a/nav2_collision_monitor/test/velocity_polygons_test.cpp +++ b/nav2_collision_monitor/test/velocity_polygons_test.cpp @@ -27,9 +27,9 @@ #include "geometry_msgs/msg/point32.hpp" #include "geometry_msgs/msg/polygon_stamped.hpp" -#include "tf2_ros/buffer.h" -#include "tf2_ros/transform_listener.h" -#include "tf2_ros/transform_broadcaster.h" +#include "tf2_ros/buffer.hpp" +#include "tf2_ros/transform_listener.hpp" +#include "tf2_ros/transform_broadcaster.hpp" #include "nav2_collision_monitor/types.hpp" #include "nav2_collision_monitor/polygon.hpp" diff --git a/nav2_constrained_smoother/test/test_constrained_smoother.cpp b/nav2_constrained_smoother/test/test_constrained_smoother.cpp index b9285fa9240..6e4e3d4bc90 100644 --- a/nav2_constrained_smoother/test/test_constrained_smoother.cpp +++ b/nav2_constrained_smoother/test/test_constrained_smoother.cpp @@ -23,7 +23,7 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" -#include "tf2_ros/create_timer_ros.h" +#include "tf2_ros/create_timer_ros.hpp" #include "nav2_util/geometry_utils.hpp" #include "nav2_costmap_2d/inflation_layer.hpp" #include "nav2_costmap_2d/footprint_collision_checker.hpp" diff --git a/nav2_controller/include/nav2_controller/controller_server.hpp b/nav2_controller/include/nav2_controller/controller_server.hpp index da8b80c39f0..b68c8e5bb94 100644 --- a/nav2_controller/include/nav2_controller/controller_server.hpp +++ b/nav2_controller/include/nav2_controller/controller_server.hpp @@ -26,7 +26,7 @@ #include "nav2_core/progress_checker.hpp" #include "nav2_core/goal_checker.hpp" #include "nav2_costmap_2d/costmap_2d_ros.hpp" -#include "tf2_ros/transform_listener.h" +#include "tf2_ros/transform_listener.hpp" #include "nav2_msgs/action/follow_path.hpp" #include "nav2_msgs/msg/speed_limit.hpp" #include "nav2_ros_common/lifecycle_node.hpp" diff --git a/nav2_core/include/nav2_core/behavior.hpp b/nav2_core/include/nav2_core/behavior.hpp index b2e00e8cf53..7a58d3aa2a0 100644 --- a/nav2_core/include/nav2_core/behavior.hpp +++ b/nav2_core/include/nav2_core/behavior.hpp @@ -20,7 +20,7 @@ #include "rclcpp/rclcpp.hpp" #include "nav2_ros_common/lifecycle_node.hpp" -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" #include "nav2_costmap_2d/costmap_topic_collision_checker.hpp" namespace nav2_core diff --git a/nav2_core/include/nav2_core/behavior_tree_navigator.hpp b/nav2_core/include/nav2_core/behavior_tree_navigator.hpp index 87824c7fd31..fda64cec974 100644 --- a/nav2_core/include/nav2_core/behavior_tree_navigator.hpp +++ b/nav2_core/include/nav2_core/behavior_tree_navigator.hpp @@ -21,7 +21,7 @@ #include #include "nav2_util/odometry_utils.hpp" -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" #include "rclcpp/rclcpp.hpp" #include "nav2_ros_common/lifecycle_node.hpp" #include "pluginlib/class_loader.hpp" diff --git a/nav2_core/include/nav2_core/controller.hpp b/nav2_core/include/nav2_core/controller.hpp index 261eec22436..d24e84d6680 100644 --- a/nav2_core/include/nav2_core/controller.hpp +++ b/nav2_core/include/nav2_core/controller.hpp @@ -41,7 +41,7 @@ #include "nav2_costmap_2d/costmap_2d_ros.hpp" #include "nav2_ros_common/lifecycle_node.hpp" -#include "tf2_ros/transform_listener.h" +#include "tf2_ros/transform_listener.hpp" #include "pluginlib/class_loader.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "geometry_msgs/msg/twist_stamped.hpp" diff --git a/nav2_core/include/nav2_core/global_planner.hpp b/nav2_core/include/nav2_core/global_planner.hpp index bcf65da6d4f..fa63d2e519e 100644 --- a/nav2_core/include/nav2_core/global_planner.hpp +++ b/nav2_core/include/nav2_core/global_planner.hpp @@ -18,7 +18,7 @@ #include #include #include "nav2_costmap_2d/costmap_2d_ros.hpp" -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" #include "nav_msgs/msg/path.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "nav2_ros_common/lifecycle_node.hpp" diff --git a/nav2_core/include/nav2_core/smoother.hpp b/nav2_core/include/nav2_core/smoother.hpp index 7705106177d..deb4a6107ec 100644 --- a/nav2_core/include/nav2_core/smoother.hpp +++ b/nav2_core/include/nav2_core/smoother.hpp @@ -20,8 +20,8 @@ #include "nav2_costmap_2d/costmap_subscriber.hpp" #include "nav2_costmap_2d/footprint_subscriber.hpp" -#include "tf2_ros/buffer.h" -#include "tf2_ros/transform_listener.h" +#include "tf2_ros/buffer.hpp" +#include "tf2_ros/transform_listener.hpp" #include "nav2_ros_common/lifecycle_node.hpp" #include "pluginlib/class_loader.hpp" #include "nav_msgs/msg/path.hpp" diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index b18938352a3..5b1fa01591b 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -56,8 +56,8 @@ #include "pluginlib/class_loader.hpp" #include "tf2/convert.hpp" #include "tf2/LinearMath/Transform.hpp" -#include "tf2_ros/buffer.h" -#include "tf2_ros/transform_listener.h" +#include "tf2_ros/buffer.hpp" +#include "tf2_ros/transform_listener.hpp" #include "tf2/time.hpp" #include "tf2/transform_datatypes.hpp" #include "nav2_ros_common/service_server.hpp" diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/layer.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/layer.hpp index 2136db7c856..571df68c9d3 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/layer.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/layer.hpp @@ -41,7 +41,7 @@ #include #include -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" #include "rclcpp/rclcpp.hpp" #include "nav2_costmap_2d/costmap_2d.hpp" #include "nav2_costmap_2d/layered_costmap.hpp" diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/observation_buffer.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/observation_buffer.hpp index c54d586b729..09f0e79c114 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/observation_buffer.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/observation_buffer.hpp @@ -43,7 +43,7 @@ #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" #include "rclcpp/time.hpp" -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" #include "tf2_sensor_msgs/tf2_sensor_msgs.hpp" #include "sensor_msgs/msg/point_cloud2.hpp" #include "nav2_costmap_2d/observation.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 ec0fbb1cbf3..32b17ca5d5b 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/obstacle_layer.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/obstacle_layer.hpp @@ -47,7 +47,7 @@ #include "laser_geometry/laser_geometry.hpp" #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wreorder" -#include "tf2_ros/message_filter.h" +#include "tf2_ros/message_filter.hpp" #pragma GCC diagnostic pop #include "message_filters/subscriber.hpp" diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/plugin_container_layer.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/plugin_container_layer.hpp index 2e00a412637..8a9aeb29623 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/plugin_container_layer.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/plugin_container_layer.hpp @@ -27,7 +27,7 @@ #include "nav2_costmap_2d/costmap_layer.hpp" #include "nav2_costmap_2d/observation_buffer.hpp" #include "nav2_costmap_2d/inflation_layer.hpp" -#include "tf2_ros/message_filter.h" +#include "tf2_ros/message_filter.hpp" #include "pluginlib/class_loader.hpp" using nav2_costmap_2d::LETHAL_OBSTACLE; diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index 49dd1885fea..f43373d286b 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -48,7 +48,7 @@ #include "nav2_util/execution_timer.hpp" #include "nav2_ros_common/node_utils.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" -#include "tf2_ros/create_timer_ros.h" +#include "tf2_ros/create_timer_ros.hpp" #include "nav2_util/robot_utils.hpp" #include "rcl_interfaces/msg/set_parameters_result.hpp" diff --git a/nav2_costmap_2d/test/integration/costmap_tester.cpp b/nav2_costmap_2d/test/integration/costmap_tester.cpp index c7d44e6e70c..8569cae54e3 100644 --- a/nav2_costmap_2d/test/integration/costmap_tester.cpp +++ b/nav2_costmap_2d/test/integration/costmap_tester.cpp @@ -38,7 +38,7 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" -#include "tf2_ros/transform_listener.h" +#include "tf2_ros/transform_listener.hpp" #include "nav2_costmap_2d/costmap_2d_ros.hpp" #include "nav2_costmap_2d/cost_values.hpp" diff --git a/nav2_costmap_2d/test/integration/dyn_params_tests.cpp b/nav2_costmap_2d/test/integration/dyn_params_tests.cpp index a543dda02ae..94e0f72ea77 100644 --- a/nav2_costmap_2d/test/integration/dyn_params_tests.cpp +++ b/nav2_costmap_2d/test/integration/dyn_params_tests.cpp @@ -19,7 +19,7 @@ #include "rclcpp/rclcpp.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" #include "nav2_costmap_2d/costmap_2d_ros.hpp" -#include "tf2_ros/transform_broadcaster.h" +#include "tf2_ros/transform_broadcaster.hpp" class DynParamTestNode { diff --git a/nav2_costmap_2d/test/integration/footprint_tests.cpp b/nav2_costmap_2d/test/integration/footprint_tests.cpp index 2f527b5faac..0bde175ce0a 100644 --- a/nav2_costmap_2d/test/integration/footprint_tests.cpp +++ b/nav2_costmap_2d/test/integration/footprint_tests.cpp @@ -41,7 +41,7 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" -#include "tf2_ros/transform_listener.h" +#include "tf2_ros/transform_listener.hpp" #include "nav2_costmap_2d/footprint.hpp" class FootprintTestNode diff --git a/nav2_costmap_2d/test/integration/test_costmap_2d_publisher.cpp b/nav2_costmap_2d/test/integration/test_costmap_2d_publisher.cpp index c0616176647..a365cdc9a7d 100644 --- a/nav2_costmap_2d/test/integration/test_costmap_2d_publisher.cpp +++ b/nav2_costmap_2d/test/integration/test_costmap_2d_publisher.cpp @@ -19,7 +19,7 @@ #include "nav2_costmap_2d/costmap_2d.hpp" #include "nav2_costmap_2d/costmap_subscriber.hpp" #include "nav2_costmap_2d/cost_values.hpp" -#include "tf2_ros/transform_listener.h" +#include "tf2_ros/transform_listener.hpp" #include "nav2_costmap_2d/costmap_2d_ros.hpp" class CostmapRosLifecycleNode : public nav2::LifecycleNode diff --git a/nav2_costmap_2d/test/integration/test_costmap_topic_collision_checker.cpp b/nav2_costmap_2d/test/integration/test_costmap_topic_collision_checker.cpp index 1543060ccca..e5b73e4b5cc 100644 --- a/nav2_costmap_2d/test/integration/test_costmap_topic_collision_checker.cpp +++ b/nav2_costmap_2d/test/integration/test_costmap_topic_collision_checker.cpp @@ -29,10 +29,10 @@ #include "nav2_util/robot_utils.hpp" #include "nav2_ros_common/node_utils.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" -#include "tf2_ros/buffer.h" -#include "tf2_ros/transform_listener.h" -#include "tf2_ros/create_timer_ros.h" -#include "tf2_ros/transform_broadcaster.h" +#include "tf2_ros/buffer.hpp" +#include "tf2_ros/transform_listener.hpp" +#include "tf2_ros/create_timer_ros.hpp" +#include "tf2_ros/transform_broadcaster.hpp" #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wpedantic" #include "tf2/utils.hpp" diff --git a/nav2_costmap_2d/test/unit/binary_filter_test.cpp b/nav2_costmap_2d/test/unit/binary_filter_test.cpp index befb8d00e1e..e0061e91e88 100644 --- a/nav2_costmap_2d/test/unit/binary_filter_test.cpp +++ b/nav2_costmap_2d/test/unit/binary_filter_test.cpp @@ -24,9 +24,9 @@ #include "rclcpp/rclcpp.hpp" #include "nav2_ros_common/lifecycle_node.hpp" -#include "tf2_ros/buffer.h" -#include "tf2_ros/transform_listener.h" -#include "tf2_ros/transform_broadcaster.h" +#include "tf2_ros/buffer.hpp" +#include "tf2_ros/transform_listener.hpp" +#include "tf2_ros/transform_broadcaster.hpp" #include "nav2_util/geometry_utils.hpp" #include "nav2_util/occ_grid_values.hpp" #include "nav2_costmap_2d/cost_values.hpp" diff --git a/nav2_costmap_2d/test/unit/keepout_filter_test.cpp b/nav2_costmap_2d/test/unit/keepout_filter_test.cpp index c75acf2b7dc..37a5a683299 100644 --- a/nav2_costmap_2d/test/unit/keepout_filter_test.cpp +++ b/nav2_costmap_2d/test/unit/keepout_filter_test.cpp @@ -22,9 +22,9 @@ #include "rclcpp/rclcpp.hpp" #include "nav2_ros_common/lifecycle_node.hpp" -#include "tf2_ros/buffer.h" -#include "tf2_ros/transform_listener.h" -#include "tf2_ros/transform_broadcaster.h" +#include "tf2_ros/buffer.hpp" +#include "tf2_ros/transform_listener.hpp" +#include "tf2_ros/transform_broadcaster.hpp" #include "nav2_util/occ_grid_values.hpp" #include "nav2_costmap_2d/cost_values.hpp" #include "nav_msgs/msg/occupancy_grid.hpp" diff --git a/nav2_costmap_2d/test/unit/speed_filter_test.cpp b/nav2_costmap_2d/test/unit/speed_filter_test.cpp index 76e96187924..5d3eebb6db5 100644 --- a/nav2_costmap_2d/test/unit/speed_filter_test.cpp +++ b/nav2_costmap_2d/test/unit/speed_filter_test.cpp @@ -24,9 +24,9 @@ #include "rclcpp/rclcpp.hpp" #include "nav2_ros_common/lifecycle_node.hpp" -#include "tf2_ros/buffer.h" -#include "tf2_ros/transform_listener.h" -#include "tf2_ros/transform_broadcaster.h" +#include "tf2_ros/buffer.hpp" +#include "tf2_ros/transform_listener.hpp" +#include "tf2_ros/transform_broadcaster.hpp" #include "nav2_util/occ_grid_values.hpp" #include "nav2_costmap_2d/cost_values.hpp" #include "nav_msgs/msg/occupancy_grid.hpp" diff --git a/nav2_docking/opennav_docking/include/opennav_docking/docking_server.hpp b/nav2_docking/opennav_docking/include/opennav_docking/docking_server.hpp index 0b478cba72d..4538b2e447d 100644 --- a/nav2_docking/opennav_docking/include/opennav_docking/docking_server.hpp +++ b/nav2_docking/opennav_docking/include/opennav_docking/docking_server.hpp @@ -34,7 +34,7 @@ #include "opennav_docking/dock_database.hpp" #include "opennav_docking/navigator.hpp" #include "opennav_docking_core/charging_dock.hpp" -#include "tf2_ros/transform_listener.h" +#include "tf2_ros/transform_listener.hpp" namespace opennav_docking { diff --git a/nav2_docking/opennav_docking/test/test_controller.cpp b/nav2_docking/opennav_docking/test/test_controller.cpp index f0e982a919b..8708b31428d 100644 --- a/nav2_docking/opennav_docking/test/test_controller.cpp +++ b/nav2_docking/opennav_docking/test/test_controller.cpp @@ -21,7 +21,7 @@ #include "nav2_costmap_2d/costmap_2d_ros.hpp" #include "nav2_util/geometry_utils.hpp" #include "nav2_ros_common/node_utils.hpp" -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" #include "ament_index_cpp/get_package_share_directory.hpp" // Testing the controller at high level; the nav2_graceful_controller diff --git a/nav2_docking/opennav_docking_core/include/opennav_docking_core/charging_dock.hpp b/nav2_docking/opennav_docking_core/include/opennav_docking_core/charging_dock.hpp index a923cc98d26..67e599405d7 100644 --- a/nav2_docking/opennav_docking_core/include/opennav_docking_core/charging_dock.hpp +++ b/nav2_docking/opennav_docking_core/include/opennav_docking_core/charging_dock.hpp @@ -20,7 +20,7 @@ #include "nav2_ros_common/lifecycle_node.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" namespace opennav_docking_core diff --git a/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/tf_help.hpp b/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/tf_help.hpp deleted file mode 100644 index 9bed6cd6810..00000000000 --- a/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/tf_help.hpp +++ /dev/null @@ -1,85 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2017, Locus Robotics - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the copyright holder nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - */ - -#ifndef NAV_2D_UTILS__TF_HELP_HPP_ -#define NAV_2D_UTILS__TF_HELP_HPP_ - -#include -#include -#include "tf2_ros/buffer.h" -#include "nav_2d_utils/conversions.hpp" -#include "geometry_msgs/msg/pose_stamped.hpp" -#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" - -namespace nav_2d_utils -{ -/** - * @brief Transform a PoseStamped from one frame to another while catching exceptions - * - * Also returns immediately if the frames are equal. - * @param tf Smart pointer to TFListener - * @param frame Frame to transform the pose into - * @param in_pose Pose to transform - * @param out_pose Place to store the resulting transformed pose - * @return True if successful transform - */ -bool transformPose( - const std::shared_ptr tf, - const std::string frame, - const geometry_msgs::msg::PoseStamped & in_pose, - geometry_msgs::msg::PoseStamped & out_pose, - rclcpp::Duration & transform_tolerance -); - -/** - * @brief Transform a PoseStamped from one frame to another while catching exceptions - * - * Also returns immediately if the frames are equal. - * @param tf Smart pointer to TFListener - * @param frame Frame to transform the pose into - * @param in_pose Pose to transform - * @param out_pose Place to store the resulting transformed pose - * @return True if successful transform - */ -bool transformPose( - const std::shared_ptr tf, - const std::string frame, - const geometry_msgs::msg::PoseStamped & in_pose, - geometry_msgs::msg::PoseStamped & out_pose, - rclcpp::Duration & transform_tolerance -); - -} // namespace nav_2d_utils - -#endif // NAV_2D_UTILS__TF_HELP_HPP_ diff --git a/nav2_mppi_controller/benchmark/optimizer_benchmark.cpp b/nav2_mppi_controller/benchmark/optimizer_benchmark.cpp index c59f28e2fad..afe8e83eea9 100644 --- a/nav2_mppi_controller/benchmark/optimizer_benchmark.cpp +++ b/nav2_mppi_controller/benchmark/optimizer_benchmark.cpp @@ -28,7 +28,7 @@ #include #include #include -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" #include "nav2_mppi_controller/optimizer.hpp" #include "nav2_mppi_controller/motion_models.hpp" diff --git a/nav2_mppi_controller/include/nav2_mppi_controller/optimal_trajectory_validator.hpp b/nav2_mppi_controller/include/nav2_mppi_controller/optimal_trajectory_validator.hpp index b5d88008ab1..b3f7b03faab 100644 --- a/nav2_mppi_controller/include/nav2_mppi_controller/optimal_trajectory_validator.hpp +++ b/nav2_mppi_controller/include/nav2_mppi_controller/optimal_trajectory_validator.hpp @@ -21,7 +21,7 @@ #include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_costmap_2d/costmap_2d_ros.hpp" -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" #include "geometry_msgs/msg/twist.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "nav_msgs/msg/path.hpp" diff --git a/nav2_mppi_controller/include/nav2_mppi_controller/optimizer.hpp b/nav2_mppi_controller/include/nav2_mppi_controller/optimizer.hpp index 5eba18b9d5d..e70cfcab786 100644 --- a/nav2_mppi_controller/include/nav2_mppi_controller/optimizer.hpp +++ b/nav2_mppi_controller/include/nav2_mppi_controller/optimizer.hpp @@ -26,7 +26,7 @@ #include "nav2_costmap_2d/costmap_2d_ros.hpp" #include "nav2_core/goal_checker.hpp" #include "nav2_core/controller_exceptions.hpp" -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" #include "pluginlib/class_loader.hpp" #include "geometry_msgs/msg/twist.hpp" diff --git a/nav2_mppi_controller/include/nav2_mppi_controller/tools/path_handler.hpp b/nav2_mppi_controller/include/nav2_mppi_controller/tools/path_handler.hpp index 1c9e52b8e3d..4233c91ef28 100644 --- a/nav2_mppi_controller/include/nav2_mppi_controller/tools/path_handler.hpp +++ b/nav2_mppi_controller/include/nav2_mppi_controller/tools/path_handler.hpp @@ -23,7 +23,7 @@ #include #include "nav2_ros_common/lifecycle_node.hpp" -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "nav_msgs/msg/path.hpp" #include "builtin_interfaces/msg/time.hpp" diff --git a/nav2_mppi_controller/test/optimizer_smoke_test.cpp b/nav2_mppi_controller/test/optimizer_smoke_test.cpp index d201e20eeb8..733229b77df 100644 --- a/nav2_mppi_controller/test/optimizer_smoke_test.cpp +++ b/nav2_mppi_controller/test/optimizer_smoke_test.cpp @@ -21,7 +21,7 @@ #include #include #include -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" #include "nav2_mppi_controller/optimizer.hpp" #include "nav2_mppi_controller/tools/parameters_handler.hpp" diff --git a/nav2_mppi_controller/test/optimizer_unit_tests.cpp b/nav2_mppi_controller/test/optimizer_unit_tests.cpp index 510d9ef300b..eec9ea0ec57 100644 --- a/nav2_mppi_controller/test/optimizer_unit_tests.cpp +++ b/nav2_mppi_controller/test/optimizer_unit_tests.cpp @@ -18,7 +18,7 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" #include "nav2_mppi_controller/optimizer.hpp" -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" // Tests main optimizer functions diff --git a/nav2_mppi_controller/test/path_handler_test.cpp b/nav2_mppi_controller/test/path_handler_test.cpp index 58e2739f4c7..e0f17e48411 100644 --- a/nav2_mppi_controller/test/path_handler_test.cpp +++ b/nav2_mppi_controller/test/path_handler_test.cpp @@ -18,7 +18,7 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" #include "nav2_mppi_controller/tools/path_handler.hpp" -#include "tf2_ros/transform_broadcaster.h" +#include "tf2_ros/transform_broadcaster.hpp" // Tests path handling diff --git a/nav2_mppi_controller/test/utils/utils.hpp b/nav2_mppi_controller/test/utils/utils.hpp index b0185ce7cfe..2772ea9a858 100644 --- a/nav2_mppi_controller/test/utils/utils.hpp +++ b/nav2_mppi_controller/test/utils/utils.hpp @@ -22,7 +22,7 @@ #include -#include "tf2_ros/transform_broadcaster.h" +#include "tf2_ros/transform_broadcaster.hpp" #include "nav2_costmap_2d/costmap_2d.hpp" #include "nav2_costmap_2d/costmap_2d_ros.hpp" diff --git a/nav2_planner/include/nav2_planner/planner_server.hpp b/nav2_planner/include/nav2_planner/planner_server.hpp index c9fc2a46dd6..372f4c7c2f9 100644 --- a/nav2_planner/include/nav2_planner/planner_server.hpp +++ b/nav2_planner/include/nav2_planner/planner_server.hpp @@ -32,8 +32,8 @@ #include "nav2_util/robot_utils.hpp" #include "nav2_ros_common/simple_action_server.hpp" #include "nav2_ros_common/service_server.hpp" -#include "tf2_ros/transform_listener.h" -#include "tf2_ros/create_timer_ros.h" +#include "tf2_ros/transform_listener.hpp" +#include "tf2_ros/create_timer_ros.hpp" #include "nav2_costmap_2d/costmap_2d_ros.hpp" #include "pluginlib/class_loader.hpp" #include "pluginlib/class_list_macros.hpp" diff --git a/nav2_rotation_shim_controller/test/test_shim_controller.cpp b/nav2_rotation_shim_controller/test/test_shim_controller.cpp index 0b97876182f..ee87908d827 100644 --- a/nav2_rotation_shim_controller/test/test_shim_controller.cpp +++ b/nav2_rotation_shim_controller/test/test_shim_controller.cpp @@ -24,7 +24,7 @@ #include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_controller/plugins/simple_goal_checker.hpp" #include "nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp" -#include "tf2_ros/transform_broadcaster.h" +#include "tf2_ros/transform_broadcaster.hpp" class RotationShimShim : public nav2_rotation_shim_controller::RotationShimController { diff --git a/nav2_route/include/nav2_route/edge_scorer.hpp b/nav2_route/include/nav2_route/edge_scorer.hpp index c294ac47e43..7b6534b50c4 100644 --- a/nav2_route/include/nav2_route/edge_scorer.hpp +++ b/nav2_route/include/nav2_route/edge_scorer.hpp @@ -19,7 +19,7 @@ #include #include -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" #include "pluginlib/class_loader.hpp" #include "pluginlib/class_list_macros.hpp" #include "nav2_ros_common/node_utils.hpp" diff --git a/nav2_route/include/nav2_route/goal_intent_extractor.hpp b/nav2_route/include/nav2_route/goal_intent_extractor.hpp index db26121fcef..8e407d66c91 100644 --- a/nav2_route/include/nav2_route/goal_intent_extractor.hpp +++ b/nav2_route/include/nav2_route/goal_intent_extractor.hpp @@ -19,7 +19,7 @@ #include #include -#include "tf2_ros/transform_listener.h" +#include "tf2_ros/transform_listener.hpp" #include "nav2_core/route_exceptions.hpp" #include "nav2_util/robot_utils.hpp" #include "nav2_ros_common/node_utils.hpp" diff --git a/nav2_route/include/nav2_route/graph_loader.hpp b/nav2_route/include/nav2_route/graph_loader.hpp index 2a39da1bee1..c2235e5e914 100644 --- a/nav2_route/include/nav2_route/graph_loader.hpp +++ b/nav2_route/include/nav2_route/graph_loader.hpp @@ -23,8 +23,8 @@ #include #include "nav2_ros_common/lifecycle_node.hpp" -#include "tf2_ros/buffer.h" -#include "tf2_ros/transform_listener.h" +#include "tf2_ros/buffer.hpp" +#include "tf2_ros/transform_listener.hpp" #include "nav2_ros_common/node_utils.hpp" #include "nav2_util/robot_utils.hpp" #include "nav2_route/types.hpp" diff --git a/nav2_route/include/nav2_route/graph_saver.hpp b/nav2_route/include/nav2_route/graph_saver.hpp index 7cc25d83c04..8155689df55 100644 --- a/nav2_route/include/nav2_route/graph_saver.hpp +++ b/nav2_route/include/nav2_route/graph_saver.hpp @@ -23,8 +23,8 @@ #include #include "nav2_ros_common/lifecycle_node.hpp" -#include "tf2_ros/buffer.h" -#include "tf2_ros/transform_listener.h" +#include "tf2_ros/buffer.hpp" +#include "tf2_ros/transform_listener.hpp" #include "nav2_ros_common/node_utils.hpp" #include "nav2_util/robot_utils.hpp" #include "nav2_route/types.hpp" diff --git a/nav2_route/include/nav2_route/interfaces/edge_cost_function.hpp b/nav2_route/include/nav2_route/interfaces/edge_cost_function.hpp index e20bade1070..e45980f3a45 100644 --- a/nav2_route/include/nav2_route/interfaces/edge_cost_function.hpp +++ b/nav2_route/include/nav2_route/interfaces/edge_cost_function.hpp @@ -18,7 +18,7 @@ #include #include -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" #include "nav2_ros_common/lifecycle_node.hpp" #include "pluginlib/class_loader.hpp" #include "nav2_route/types.hpp" diff --git a/nav2_route/include/nav2_route/route_planner.hpp b/nav2_route/include/nav2_route/route_planner.hpp index bdadc6c9dd0..cd0c978bc90 100644 --- a/nav2_route/include/nav2_route/route_planner.hpp +++ b/nav2_route/include/nav2_route/route_planner.hpp @@ -22,8 +22,8 @@ #include #include -#include "tf2_ros/buffer.h" -#include "tf2_ros/transform_listener.h" +#include "tf2_ros/buffer.hpp" +#include "tf2_ros/transform_listener.hpp" #include "nav2_route/types.hpp" #include "nav2_route/utils.hpp" #include "nav2_route/edge_scorer.hpp" diff --git a/nav2_route/include/nav2_route/route_server.hpp b/nav2_route/include/nav2_route/route_server.hpp index 3d384e93c0b..ce52c07e750 100644 --- a/nav2_route/include/nav2_route/route_server.hpp +++ b/nav2_route/include/nav2_route/route_server.hpp @@ -23,8 +23,8 @@ #include #include "nav2_ros_common/lifecycle_node.hpp" -#include "tf2_ros/transform_listener.h" -#include "tf2_ros/create_timer_ros.h" +#include "tf2_ros/transform_listener.hpp" +#include "tf2_ros/create_timer_ros.hpp" #include "nav2_ros_common/simple_action_server.hpp" #include "nav2_ros_common/node_utils.hpp" #include "nav2_util/robot_utils.hpp" diff --git a/nav2_route/include/nav2_route/route_tracker.hpp b/nav2_route/include/nav2_route/route_tracker.hpp index 9c2e7058aec..a2a3d4e897c 100644 --- a/nav2_route/include/nav2_route/route_tracker.hpp +++ b/nav2_route/include/nav2_route/route_tracker.hpp @@ -16,7 +16,7 @@ #include #include -#include "tf2_ros/transform_listener.h" +#include "tf2_ros/transform_listener.hpp" #include "nav2_util/robot_utils.hpp" #include "nav2_ros_common/simple_action_server.hpp" #include "nav2_msgs/action/compute_and_track_route.hpp" diff --git a/nav2_route/test/test_edge_scorers.cpp b/nav2_route/test/test_edge_scorers.cpp index 07af4293d0b..8c16ced8306 100644 --- a/nav2_route/test/test_edge_scorers.cpp +++ b/nav2_route/test/test_edge_scorers.cpp @@ -27,8 +27,8 @@ #include "nav2_costmap_2d/costmap_2d.hpp" #include "nav2_costmap_2d/costmap_2d_publisher.hpp" #include "nav2_core/route_exceptions.hpp" -#include "tf2_ros/static_transform_broadcaster.h" -#include "tf2_ros/transform_listener.h" +#include "tf2_ros/static_transform_broadcaster.hpp" +#include "tf2_ros/transform_listener.hpp" class RclCppFixture { diff --git a/nav2_route/test/test_goal_intent_extractor.cpp b/nav2_route/test/test_goal_intent_extractor.cpp index c3ac8d176cc..21c49708193 100644 --- a/nav2_route/test/test_goal_intent_extractor.cpp +++ b/nav2_route/test/test_goal_intent_extractor.cpp @@ -19,9 +19,9 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" -#include "tf2_ros/transform_broadcaster.h" -#include "tf2_ros/create_timer_ros.h" -#include "tf2_ros/transform_listener.h" +#include "tf2_ros/transform_broadcaster.hpp" +#include "tf2_ros/create_timer_ros.hpp" +#include "tf2_ros/transform_listener.hpp" #include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_ros_common/service_client.hpp" #include "nav2_ros_common/node_thread.hpp" diff --git a/nav2_route/test/test_goal_intent_search.cpp b/nav2_route/test/test_goal_intent_search.cpp index a829af0370f..1f3e8fd4b1e 100644 --- a/nav2_route/test/test_goal_intent_search.cpp +++ b/nav2_route/test/test_goal_intent_search.cpp @@ -19,9 +19,9 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" -#include "tf2_ros/transform_broadcaster.h" -#include "tf2_ros/create_timer_ros.h" -#include "tf2_ros/transform_listener.h" +#include "tf2_ros/transform_broadcaster.hpp" +#include "tf2_ros/create_timer_ros.hpp" +#include "tf2_ros/transform_listener.hpp" #include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_ros_common/service_client.hpp" #include "nav2_ros_common/node_thread.hpp" diff --git a/nav2_route/test/test_graph_loader.cpp b/nav2_route/test/test_graph_loader.cpp index 99341852f78..e76fe863314 100644 --- a/nav2_route/test/test_graph_loader.cpp +++ b/nav2_route/test/test_graph_loader.cpp @@ -20,7 +20,7 @@ #include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_ros_common/node_utils.hpp" #include "nav2_route/graph_loader.hpp" -#include "tf2_ros/static_transform_broadcaster.h" +#include "tf2_ros/static_transform_broadcaster.hpp" class RclCppFixture { diff --git a/nav2_route/test/test_graph_saver.cpp b/nav2_route/test/test_graph_saver.cpp index a6897f11602..4abdc0b74d3 100644 --- a/nav2_route/test/test_graph_saver.cpp +++ b/nav2_route/test/test_graph_saver.cpp @@ -22,7 +22,7 @@ #include "nav2_ros_common/node_utils.hpp" #include "nav2_route/graph_loader.hpp" #include "nav2_route/graph_saver.hpp" -#include "tf2_ros/static_transform_broadcaster.h" +#include "tf2_ros/static_transform_broadcaster.hpp" class RclCppFixture { diff --git a/nav2_route/test/test_route_server.cpp b/nav2_route/test/test_route_server.cpp index f8906529d31..5fb73b4ce0f 100644 --- a/nav2_route/test/test_route_server.cpp +++ b/nav2_route/test/test_route_server.cpp @@ -19,9 +19,9 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" -#include "tf2_ros/transform_broadcaster.h" -#include "tf2_ros/create_timer_ros.h" -#include "tf2_ros/transform_listener.h" +#include "tf2_ros/transform_broadcaster.hpp" +#include "tf2_ros/create_timer_ros.hpp" +#include "tf2_ros/transform_listener.hpp" #include "nav2_ros_common/lifecycle_node.hpp" #include "std_srvs/srv/trigger.hpp" #include "nav2_ros_common/service_client.hpp" diff --git a/nav2_route/test/test_route_tracker.cpp b/nav2_route/test/test_route_tracker.cpp index 9d874a1dc5a..07ca24a4e91 100644 --- a/nav2_route/test/test_route_tracker.cpp +++ b/nav2_route/test/test_route_tracker.cpp @@ -19,9 +19,9 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" -#include "tf2_ros/transform_broadcaster.h" -#include "tf2_ros/create_timer_ros.h" -#include "tf2_ros/transform_listener.h" +#include "tf2_ros/transform_broadcaster.hpp" +#include "tf2_ros/create_timer_ros.hpp" +#include "tf2_ros/transform_listener.hpp" #include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_core/route_exceptions.hpp" #include "nav2_route/route_tracker.hpp" diff --git a/nav2_rviz_plugins/include/nav2_rviz_plugins/nav2_panel.hpp b/nav2_rviz_plugins/include/nav2_rviz_plugins/nav2_panel.hpp index 3a4cdd9e50f..44ad28d279e 100644 --- a/nav2_rviz_plugins/include/nav2_rviz_plugins/nav2_panel.hpp +++ b/nav2_rviz_plugins/include/nav2_rviz_plugins/nav2_panel.hpp @@ -35,9 +35,9 @@ #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" #include "visualization_msgs/msg/marker_array.hpp" #include "nav2_util/geometry_utils.hpp" -#include "tf2_ros/transform_listener.h" -#include "tf2_ros/create_timer_ros.h" -#include "tf2_ros/buffer.h" +#include "tf2_ros/transform_listener.hpp" +#include "tf2_ros/create_timer_ros.hpp" +#include "tf2_ros/buffer.hpp" class QPushButton; diff --git a/nav2_smoother/src/nav2_smoother.cpp b/nav2_smoother/src/nav2_smoother.cpp index 52fa10f8985..74714bafb81 100644 --- a/nav2_smoother/src/nav2_smoother.cpp +++ b/nav2_smoother/src/nav2_smoother.cpp @@ -23,7 +23,7 @@ #include "nav2_core/smoother_exceptions.hpp" #include "nav2_smoother/nav2_smoother.hpp" #include "nav2_ros_common/node_utils.hpp" -#include "tf2_ros/create_timer_ros.h" +#include "tf2_ros/create_timer_ros.hpp" using namespace std::chrono_literals; diff --git a/nav2_system_tests/src/behavior_tree/test_behavior_tree_node.cpp b/nav2_system_tests/src/behavior_tree/test_behavior_tree_node.cpp index 2f62894abb7..d36535924e0 100644 --- a/nav2_system_tests/src/behavior_tree/test_behavior_tree_node.cpp +++ b/nav2_system_tests/src/behavior_tree/test_behavior_tree_node.cpp @@ -26,9 +26,9 @@ #include "behaviortree_cpp/bt_factory.h" #include "behaviortree_cpp/utils/shared_library.h" -#include "tf2_ros/buffer.h" -#include "tf2_ros/transform_listener.h" -#include "tf2_ros/create_timer_ros.h" +#include "tf2_ros/buffer.hpp" +#include "tf2_ros/transform_listener.hpp" +#include "tf2_ros/create_timer_ros.hpp" #include "nav2_util/odometry_utils.hpp" #include "nav2_util/string_utils.hpp" diff --git a/nav2_system_tests/src/behaviors/assisted_teleop/assisted_teleop_behavior_tester.hpp b/nav2_system_tests/src/behaviors/assisted_teleop/assisted_teleop_behavior_tester.hpp index bb3f3b18159..40e2aa9a754 100644 --- a/nav2_system_tests/src/behaviors/assisted_teleop/assisted_teleop_behavior_tester.hpp +++ b/nav2_system_tests/src/behaviors/assisted_teleop/assisted_teleop_behavior_tester.hpp @@ -35,8 +35,8 @@ #include "std_msgs/msg/empty.hpp" #include "tf2/utils.hpp" -#include "tf2_ros/buffer.h" -#include "tf2_ros/transform_listener.h" +#include "tf2_ros/buffer.hpp" +#include "tf2_ros/transform_listener.hpp" namespace nav2_system_tests { diff --git a/nav2_system_tests/src/behaviors/wait/wait_behavior_tester.hpp b/nav2_system_tests/src/behaviors/wait/wait_behavior_tester.hpp index 5a7313c0cd5..bea4506e68e 100644 --- a/nav2_system_tests/src/behaviors/wait/wait_behavior_tester.hpp +++ b/nav2_system_tests/src/behaviors/wait/wait_behavior_tester.hpp @@ -33,8 +33,8 @@ #include "geometry_msgs/msg/pose_with_covariance_stamped.hpp" #include "tf2/utils.hpp" -#include "tf2_ros/buffer.h" -#include "tf2_ros/transform_listener.h" +#include "tf2_ros/buffer.hpp" +#include "tf2_ros/transform_listener.hpp" namespace nav2_system_tests { diff --git a/nav2_system_tests/src/planning/planner_tester.hpp b/nav2_system_tests/src/planning/planner_tester.hpp index d878bc49f22..3c14f795d4f 100644 --- a/nav2_system_tests/src/planning/planner_tester.hpp +++ b/nav2_system_tests/src/planning/planner_tester.hpp @@ -32,7 +32,7 @@ #include "geometry_msgs/msg/pose_stamped.hpp" #include "geometry_msgs/msg/transform_stamped.hpp" #include "nav2_planner/planner_server.hpp" -#include "tf2_ros/transform_broadcaster.h" +#include "tf2_ros/transform_broadcaster.hpp" namespace nav2_system_tests { diff --git a/nav2_util/include/nav2_util/robot_utils.hpp b/nav2_util/include/nav2_util/robot_utils.hpp index cffbe80a26b..faca6d301dc 100644 --- a/nav2_util/include/nav2_util/robot_utils.hpp +++ b/nav2_util/include/nav2_util/robot_utils.hpp @@ -26,7 +26,7 @@ #include "geometry_msgs/msg/transform_stamped.hpp" #include "tf2/time.hpp" #include "tf2/transform_datatypes.hpp" -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" #include "rclcpp/rclcpp.hpp" diff --git a/nav2_util/src/base_footprint_publisher.hpp b/nav2_util/src/base_footprint_publisher.hpp index 67f50625101..15b16037bed 100644 --- a/nav2_util/src/base_footprint_publisher.hpp +++ b/nav2_util/src/base_footprint_publisher.hpp @@ -21,10 +21,10 @@ #include "rclcpp/rclcpp.hpp" #include "tf2_msgs/msg/tf_message.hpp" #include "geometry_msgs/msg/transform_stamped.hpp" -#include "tf2_ros/create_timer_ros.h" -#include "tf2_ros/transform_listener.h" -#include "tf2_ros/transform_broadcaster.h" -#include "tf2_ros/buffer.h" +#include "tf2_ros/create_timer_ros.hpp" +#include "tf2_ros/transform_listener.hpp" +#include "tf2_ros/transform_broadcaster.hpp" +#include "tf2_ros/buffer.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" #include "tf2/utils.hpp" diff --git a/nav2_util/test/test_robot_utils.cpp b/nav2_util/test/test_robot_utils.cpp index 119addc9355..33c55aa2a3b 100644 --- a/nav2_util/test/test_robot_utils.cpp +++ b/nav2_util/test/test_robot_utils.cpp @@ -16,11 +16,11 @@ #include #include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_util/robot_utils.hpp" -#include "tf2_ros/transform_listener.h" -#include "tf2_ros/transform_broadcaster.h" +#include "tf2_ros/transform_listener.hpp" +#include "tf2_ros/transform_broadcaster.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "gtest/gtest.h" -#include "tf2_ros/create_timer_ros.h" +#include "tf2_ros/create_timer_ros.hpp" TEST(RobotUtils, LookupExceptionError) { diff --git a/nav2_waypoint_follower/include/nav2_waypoint_follower/waypoint_follower.hpp b/nav2_waypoint_follower/include/nav2_waypoint_follower/waypoint_follower.hpp index 83edf012880..816feb9eca3 100644 --- a/nav2_waypoint_follower/include/nav2_waypoint_follower/waypoint_follower.hpp +++ b/nav2_waypoint_follower/include/nav2_waypoint_follower/waypoint_follower.hpp @@ -37,9 +37,9 @@ #include "nav2_core/waypoint_task_executor.hpp" #include "robot_localization/srv/from_ll.hpp" -#include "tf2_ros/buffer.h" +#include "tf2_ros/buffer.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" -#include "tf2_ros/transform_listener.h" +#include "tf2_ros/transform_listener.hpp" namespace nav2_waypoint_follower {