Skip to content

Commit

Permalink
Deprecating tf2 C Headers
Browse files Browse the repository at this point in the history
Signed-off-by: CursedRock17 <[email protected]>
  • Loading branch information
CursedRock17 committed Oct 29, 2024
1 parent 44a69cc commit 884bc9b
Show file tree
Hide file tree
Showing 54 changed files with 64 additions and 64 deletions.
6 changes: 3 additions & 3 deletions nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,10 +35,10 @@
#include "nav2_util/string_utils.hpp"
#include "nav2_amcl/sensors/laser/laser.hpp"
#include "rclcpp/node_options.hpp"
#include "tf2/convert.h"
#include "tf2/utils.h"
#include "tf2/convert.hpp"
#include "tf2/utils.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "tf2/LinearMath/Transform.h"
#include "tf2/LinearMath/Transform.hpp"
#include "tf2_ros/buffer.h"
#include "tf2_ros/message_filter.h"
#include "tf2_ros/transform_broadcaster.h"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
#include "rclcpp/rclcpp.hpp"
#include "nav2_msgs/msg/behavior_tree_log.hpp"
#include "nav2_msgs/msg/behavior_tree_status_change.h"
#include "tf2/time.h"
#include "tf2/time.hpp"
#include "tf2_ros/buffer_interface.h"

namespace nav2_behavior_tree
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@

#include "nav2_behavior_tree/plugins/action/remove_in_collision_goals_action.hpp"
#include "nav2_behavior_tree/bt_utils.hpp"
#include "tf2/utils.h"
#include "tf2/utils.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"

namespace nav2_behavior_tree
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#include "nav2_util/robot_utils.hpp"
#include "nav_msgs/msg/path.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tf2/LinearMath/Quaternion.h"
#include "tf2/LinearMath/Quaternion.hpp"
#include "tf2_ros/buffer.h"
#include "tf2_ros/create_timer_ros.h"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
#include <string>

#include "rclcpp/rclcpp.hpp"
#include "tf2/time.h"
#include "tf2/time.hpp"
#include "tf2_ros/buffer.h"

#include "nav2_behavior_tree/plugins/condition/transform_available_condition.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,8 @@
#include "nav_msgs/msg/path.hpp"
#include "nav2_util/geometry_utils.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tf2/LinearMath/Matrix3x3.h"
#include "tf2/LinearMath/Quaternion.h"
#include "tf2/LinearMath/Matrix3x3.hpp"
#include "tf2/LinearMath/Quaternion.hpp"

#include "behaviortree_cpp/bt_factory.h"

Expand Down
2 changes: 1 addition & 1 deletion nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
#include "nav2_core/behavior.hpp"
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wpedantic"
#include "tf2/utils.h"
#include "tf2/utils.hpp"
#pragma GCC diagnostic pop


Expand Down
2 changes: 1 addition & 1 deletion nav2_behaviors/plugins/spin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
#include <utility>

#include "nav2_behaviors/plugins/spin.hpp"
#include "tf2/utils.h"
#include "tf2/utils.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "nav2_util/node_utils.hpp"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@

#include "rclcpp/rclcpp.hpp"

#include "tf2/time.h"
#include "tf2/time.hpp"
#include "tf2_ros/buffer.h"
#include "tf2_ros/transform_listener.h"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include "visualization_msgs/msg/marker_array.hpp"
#include "geometry_msgs/msg/twist_stamped.hpp"

#include "tf2/time.h"
#include "tf2/time.hpp"
#include "tf2_ros/buffer.h"
#include "tf2_ros/transform_listener.h"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
#include "rclcpp/rclcpp.hpp"
#include "geometry_msgs/msg/polygon_stamped.hpp"

#include "tf2/time.h"
#include "tf2/time.hpp"
#include "tf2_ros/buffer.h"

#include "nav2_util/lifecycle_node.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@

#include "rclcpp/rclcpp.hpp"

#include "tf2/time.h"
#include "tf2/time.hpp"
#include "tf2_ros/buffer.h"

#include "nav2_collision_monitor/types.hpp"
Expand Down
2 changes: 1 addition & 1 deletion nav2_collision_monitor/src/pointcloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
#include <functional>

#include "sensor_msgs/point_cloud2_iterator.hpp"
#include "tf2/transform_datatypes.h"
#include "tf2/transform_datatypes.hpp"

#include "nav2_util/node_utils.hpp"
#include "nav2_util/robot_utils.hpp"
Expand Down
2 changes: 1 addition & 1 deletion nav2_collision_monitor/src/polygon.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

#include "geometry_msgs/msg/point.hpp"
#include "geometry_msgs/msg/point32.hpp"
#include "tf2/transform_datatypes.h"
#include "tf2/transform_datatypes.hpp"

#include "nav2_util/node_utils.hpp"
#include "nav2_util/robot_utils.hpp"
Expand Down
2 changes: 1 addition & 1 deletion nav2_collision_monitor/src/polygon_source.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include <functional>

#include "geometry_msgs/msg/polygon_stamped.hpp"
#include "tf2/transform_datatypes.h"
#include "tf2/transform_datatypes.hpp"

#include "nav2_util/node_utils.hpp"
#include "nav2_util/robot_utils.hpp"
Expand Down
2 changes: 1 addition & 1 deletion nav2_collision_monitor/src/range.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include <cmath>
#include <functional>

#include "tf2/transform_datatypes.h"
#include "tf2/transform_datatypes.hpp"

#include "nav2_util/node_utils.hpp"
#include "nav2_util/robot_utils.hpp"
Expand Down
2 changes: 1 addition & 1 deletion nav2_collision_monitor/src/scan.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
#include <cmath>
#include <functional>

#include "tf2/transform_datatypes.h"
#include "tf2/transform_datatypes.hpp"

#include "nav2_util/robot_utils.hpp"

Expand Down
2 changes: 1 addition & 1 deletion nav2_constrained_smoother/src/constrained_smoother.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@
#include "pluginlib/class_loader.hpp"
#include "pluginlib/class_list_macros.hpp"

#include "tf2/utils.h"
#include "tf2/utils.hpp"

using nav2_util::declare_parameter_if_not_declared;
using nav2_util::geometry_utils::euclidean_distance;
Expand Down
2 changes: 1 addition & 1 deletion nav2_controller/plugins/simple_goal_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@
#include "nav2_util/geometry_utils.hpp"
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wpedantic"
#include "tf2/utils.h"
#include "tf2/utils.hpp"
#pragma GCC diagnostic pop

using rcl_interfaces::msg::ParameterType;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,9 +50,9 @@
#include "nav2_msgs/msg/costmap.hpp"
#include "nav2_msgs/msg/costmap_update.hpp"
#include "nav2_msgs/srv/get_costmap.hpp"
#include "tf2/transform_datatypes.h"
#include "tf2/transform_datatypes.hpp"
#include "nav2_util/lifecycle_node.hpp"
#include "tf2/LinearMath/Quaternion.h"
#include "tf2/LinearMath/Quaternion.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"

namespace nav2_costmap_2d
Expand Down
10 changes: 5 additions & 5 deletions nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,16 +54,16 @@
#include "nav2_util/lifecycle_node.hpp"
#include "nav2_msgs/srv/get_costs.hpp"
#include "pluginlib/class_loader.hpp"
#include "tf2/convert.h"
#include "tf2/LinearMath/Transform.h"
#include "tf2/convert.hpp"
#include "tf2/LinearMath/Transform.hpp"
#include "tf2_ros/buffer.h"
#include "tf2_ros/transform_listener.h"
#include "tf2/time.h"
#include "tf2/transform_datatypes.h"
#include "tf2/time.hpp"
#include "tf2/transform_datatypes.hpp"

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wpedantic"
#include "tf2/utils.h"
#include "tf2/utils.hpp"
#pragma GCC diagnostic pop

namespace nav2_costmap_2d
Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/plugins/costmap_filters/keepout_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@
#include <string>
#include <memory>
#include <algorithm>
#include "tf2/convert.h"
#include "tf2/convert.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"

#include "nav2_costmap_2d/costmap_filters/keepout_filter.hpp"
Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/plugins/static_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@
#include <string>

#include "pluginlib/class_list_macros.hpp"
#include "tf2/convert.h"
#include "tf2/convert.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "nav2_util/validate_messages.hpp"

Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/src/footprint_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
#include "nav2_costmap_2d/footprint_subscriber.hpp"
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wpedantic"
#include "tf2/utils.h"
#include "tf2/utils.hpp"
#pragma GCC diagnostic pop

namespace nav2_costmap_2d
Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/src/observation_buffer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@
#include <vector>
#include <chrono>

#include "tf2/convert.h"
#include "tf2/convert.hpp"
#include "sensor_msgs/point_cloud2_iterator.hpp"
using namespace std::chrono_literals;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
#include "tf2_ros/transform_broadcaster.h"
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wpedantic"
#include "tf2/utils.h"
#include "tf2/utils.hpp"
#pragma GCC diagnostic pop
#include "nav2_util/geometry_utils.hpp"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
#include "sensor_msgs/msg/battery_state.hpp"
#include "sensor_msgs/msg/joint_state.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "tf2/utils.h"
#include "tf2/utils.hpp"

#include "opennav_docking_core/charging_dock.hpp"
#include "opennav_docking/pose_filter.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
#include "sensor_msgs/msg/battery_state.hpp"
#include "sensor_msgs/msg/joint_state.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "tf2/utils.h"
#include "tf2/utils.hpp"

#include "opennav_docking_core/non_charging_dock.hpp"
#include "opennav_docking/pose_filter.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#include "nav2_util/geometry_utils.hpp"
#include "angles/angles.h"
#include "opennav_docking/types.hpp"
#include "tf2/utils.h"
#include "tf2/utils.hpp"

namespace utils
{
Expand Down
2 changes: 1 addition & 1 deletion nav2_docking/opennav_docking/src/docking_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#include "angles/angles.h"
#include "opennav_docking/docking_server.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "tf2/utils.h"
#include "tf2/utils.hpp"

using namespace std::chrono_literals;
using rcl_interfaces::msg::ParameterType;
Expand Down
2 changes: 1 addition & 1 deletion nav2_docking/opennav_docking/test/test_pose_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include "rclcpp/rclcpp.hpp"
#include "opennav_docking/pose_filter.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "tf2/utils.h"
#include "tf2/utils.hpp"

// Testing the pose filter

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
#include "opennav_docking/simple_charging_dock.hpp"
#include "ament_index_cpp/get_package_share_directory.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "tf2/utils.h"
#include "tf2/utils.hpp"

// Testing the simple charging dock plugin

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
#include "opennav_docking/simple_non_charging_dock.hpp"
#include "ament_index_cpp/get_package_share_directory.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "tf2/utils.h"
#include "tf2/utils.hpp"

// Testing the simple non-charging dock plugin

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@
#include "nav_2d_msgs/msg/pose2_d_stamped.hpp"
#include "nav_msgs/msg/path.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tf2/convert.h"
#include "tf2/convert.hpp"

namespace nav_2d_utils
{
Expand Down
2 changes: 1 addition & 1 deletion nav2_dwb_controller/nav_2d_utils/src/conversions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wpedantic"
#include "tf2/utils.h"
#include "tf2/utils.hpp"
#pragma GCC diagnostic pop

#include "nav2_util/geometry_utils.hpp"
Expand Down
2 changes: 1 addition & 1 deletion nav2_dwb_controller/nav_2d_utils/test/2d_utils_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@
*/

#include <math.h>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2/LinearMath/Quaternion.hpp>
#include <vector>

#include "gtest/gtest.h"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

#include "angles/angles.h"
#include "geometry_msgs/msg/pose.hpp"
#include "tf2/utils.h"
#include "tf2/utils.hpp"

namespace nav2_graceful_controller
{
Expand Down
4 changes: 2 additions & 2 deletions nav2_map_server/src/map_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,8 +46,8 @@

#include "yaml-cpp/yaml.h"

#include "tf2/LinearMath/Matrix3x3.h"
#include "tf2/LinearMath/Quaternion.h"
#include "tf2/LinearMath/Matrix3x3.hpp"
#include "tf2/LinearMath/Quaternion.hpp"
#include "nav2_util/occ_grid_values.hpp"

#ifdef _WIN32
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@

#include "angles/angles.h"

#include "tf2/utils.h"
#include "tf2/utils.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"

#include "geometry_msgs/msg/twist_stamped.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "nav2_util/lifecycle_node.hpp"
#include "nav2_util/node_utils.hpp"
#include "tf2/utils.h"
#include "tf2/utils.hpp"
#include "rcl_interfaces/msg/set_parameters_result.hpp"

namespace nav2_smac_planner
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@
#include "geometry_msgs/msg/pose_array.hpp"
#include "nav2_util/lifecycle_node.hpp"
#include "nav2_util/node_utils.hpp"
#include "tf2/utils.h"
#include "tf2/utils.hpp"

namespace nav2_smac_planner
{
Expand Down
Loading

0 comments on commit 884bc9b

Please sign in to comment.