Skip to content

Commit

Permalink
Update deprecated tf2 imports from .h to .hpp (#3197)
Browse files Browse the repository at this point in the history
* Update deprecated tf2 imports from .h to .hpp

* make the imports conditional

* Update all the files
  • Loading branch information
sea-bass authored Jan 6, 2025
1 parent 3268f16 commit 7390ebc
Show file tree
Hide file tree
Showing 18 changed files with 103 additions and 3 deletions.
5 changes: 5 additions & 0 deletions moveit_core/robot_state/test/test_aabb.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,12 @@
#include <string>
#include <gtest/gtest.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
// TODO: Remove conditional include when released to all active distros.
#if __has_include(<tf2/LinearMath/Vector3.hpp>)
#include <tf2/LinearMath/Vector3.hpp>
#else
#include <tf2/LinearMath/Vector3.h>
#endif
#include <moveit/utils/robot_model_test_utils.hpp>

// To visualize bbox of the PR2, set this to 1.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,17 @@
#include <moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.hpp>
#include <moveit/kinematics_base/kinematics_base.hpp>
#include <moveit/robot_model/robot_model.hpp>
// TODO: Remove conditional includes when released to all active distros.
#if __has_include(<tf2/LinearMath/Quaternion.hpp>)
#include <tf2/LinearMath/Quaternion.hpp>
#else
#include <tf2/LinearMath/Quaternion.h>
#endif
#if __has_include(<tf2/LinearMath/Vector3.hpp>)
#include <tf2/LinearMath/Vector3.hpp>
#else
#include <tf2/LinearMath/Vector3.h>
#endif
#include <mutex>
#include <unordered_map>
#include <utility>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,12 @@
#include <moveit/utils/logger.hpp>

#include <tf2_kdl/tf2_kdl.hpp>
// TODO: Remove conditional include when released to all active distros.
#if __has_include(<tf2/transform_datatypes.hpp>)
#include <tf2/transform_datatypes.hpp>
#else
#include <tf2/transform_datatypes.h>
#endif

#include <kdl_parser/kdl_parser.hpp>
#include <kdl/chainfksolverpos_recursive.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,12 @@
#include <chomp_motion_planner/chomp_planner.hpp>
#include <chomp_motion_planner/chomp_trajectory.hpp>
#include <moveit/robot_state/conversions.hpp>
// TODO: Remove conditional include when released to all active distros.
#if __has_include(<tf2/LinearMath/Quaternion.hpp>)
#include <tf2/LinearMath/Quaternion.hpp>
#else
#include <tf2/LinearMath/Quaternion.h>
#endif
#include <tf2_eigen/tf2_eigen.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include <moveit/utils/logger.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,12 @@
#include <moveit/robot_model/robot_model.hpp>
#include <moveit/robot_state/robot_state.hpp>
#include <moveit/robot_trajectory/robot_trajectory.hpp>
// TODO: Remove conditional include when released to all active distros.
#if __has_include(<tf2/transform_datatypes.hpp>)
#include <tf2/transform_datatypes.hpp>
#else
#include <tf2/transform_datatypes.h>
#endif
#include <trajectory_msgs/msg/multi_dof_joint_trajectory.hpp>
#include <moveit/planning_scene/planning_scene.hpp>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,12 @@
#include <pilz_industrial_motion_planner/trajectory_functions.hpp>

#include <moveit/planning_scene/planning_scene.hpp>
// TODO: Remove conditional include when released to all active distros.
#if __has_include(<tf2/LinearMath/Quaternion.hpp>)
#include <tf2/LinearMath/Quaternion.hpp>
#else
#include <tf2/LinearMath/Quaternion.h>
#endif
#include <tf2_eigen_kdl/tf2_eigen_kdl.hpp>
#include <tf2_eigen/tf2_eigen.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,10 +43,10 @@
#include <kdl/utilities/error.h>
#include <kdl/utilities/utility.h>
#include <moveit/robot_state/conversions.hpp>
#include <tf2_eigen_kdl/tf2_eigen_kdl.hpp>
#include <rclcpp/logger.hpp>
#include <rclcpp/logging.hpp>
#include <tf2_eigen/tf2_eigen.hpp>
#include <tf2_eigen_kdl/tf2_eigen_kdl.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include <moveit/utils/logger.hpp>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,11 +43,16 @@
#include <kdl/path_line.hpp>
#include <kdl/trajectory_segment.hpp>
#include <kdl/utilities/error.h>
// TODO: Remove conditional include when released to all active distros.
#if __has_include(<tf2/convert.hpp>)
#include <tf2/convert.hpp>
#else
#include <tf2/convert.h>
#include <tf2_eigen_kdl/tf2_eigen_kdl.hpp>
#endif
#include <rclcpp/logger.hpp>
#include <rclcpp/logging.hpp>
#include <tf2_eigen/tf2_eigen.hpp>
#include <tf2_eigen_kdl/tf2_eigen_kdl.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include <moveit/utils/logger.hpp>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,8 +56,17 @@
#include <moveit_msgs/action/move_group.hpp>
#include <sensor_msgs/msg/joint_state.hpp>
#include <string>
// TODO: Remove conditional include swhen released to all active distros.
#if __has_include(<tf2/LinearMath/Quaternion.hpp>)
#include <tf2/LinearMath/Quaternion.hpp>
#else
#include <tf2/LinearMath/Quaternion.h>
#endif
#if __has_include(<tf2/convert.hpp>)
#include <tf2/convert.hpp>
#else
#include <tf2/convert.h>
#endif
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include <utility>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,12 +43,12 @@


#include <Eigen/Geometry>
#include <tf2_eigen_kdl/tf2_eigen_kdl.hpp>
#include <rclcpp/logger.hpp>
#include <rclcpp/logging.hpp>
#include <rclcpp/node.hpp>
#include <rclcpp/parameter_value.hpp>
#include <tf2_eigen/tf2_eigen.hpp>
#include <tf2_eigen_kdl/tf2_eigen_kdl.hpp>
#include <tf2_kdl/tf2_kdl.hpp>
#include <moveit/kinematics_base/kinematics_base.hpp>
#include <moveit/robot_state/robot_state.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,17 @@
#include <moveit/occupancy_map_monitor/occupancy_map_monitor.hpp>
#include <cmath>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
// TODO: Remove conditional includes when released to all active distros.
#if __has_include(<tf2/LinearMath/Vector3.hpp>)
#include <tf2/LinearMath/Vector3.hpp>
#else
#include <tf2/LinearMath/Vector3.h>
#endif
#if __has_include(<tf2/LinearMath/Transform.hpp>)
#include <tf2/LinearMath/Transform.hpp>
#else
#include <tf2/LinearMath/Transform.h>
#endif
#include <geometric_shapes/shape_operations.h>
#include <sensor_msgs/image_encodings.hpp>
#include <stdint.h>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,17 @@
#include <moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.hpp>
#include <moveit/occupancy_map_monitor/occupancy_map_monitor.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
// TODO: Remove conditional includes when released to all active distros.
#if __has_include(<tf2/LinearMath/Vector3.hpp>)
#include <tf2/LinearMath/Vector3.hpp>
#else
#include <tf2/LinearMath/Vector3.h>
#endif
#if __has_include(<tf2/LinearMath/Transform.hpp>)
#include <tf2/LinearMath/Transform.hpp>
#else
#include <tf2/LinearMath/Transform.h>
#endif
#include <sensor_msgs/point_cloud2_iterator.hpp>
#include <tf2_ros/create_timer_interface.h>
#include <tf2_ros/create_timer_ros.h>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,8 +41,17 @@
#include <moveit_msgs/srv/get_planning_scene.hpp>
#include <moveit/utils/logger.hpp>

// TODO: Remove conditional includes when released to all active distros.
#if __has_include(<tf2/exceptions.hpp>)
#include <tf2/exceptions.hpp>
#else
#include <tf2/exceptions.h>
#endif
#if __has_include(<tf2/LinearMath/Transform.hpp>)
#include <tf2/LinearMath/Transform.hpp>
#else
#include <tf2/LinearMath/Transform.h>
#endif
#include <tf2_eigen/tf2_eigen.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>

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

#include <std_msgs/msg/string.hpp>
#include <geometry_msgs/msg/transform_stamped.hpp>
// TODO: Remove conditional include when released to all active distros.
#if __has_include(<tf2/utils.hpp>)
#include <tf2/utils.hpp>
#else
#include <tf2/utils.h>
#endif
#include <tf2_eigen/tf2_eigen.hpp>
#include <tf2_ros/transform_listener.h>
#include <rclcpp/rclcpp.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,12 @@

// ROS
#include <rclcpp/rclcpp.hpp>
// TODO: Remove conditional include when released to all active distros.
#if __has_include(<tf2/LinearMath/Quaternion.hpp>)
#include <tf2/LinearMath/Quaternion.hpp>
#else
#include <tf2/LinearMath/Quaternion.h>
#endif
#include <tf2_eigen/tf2_eigen.hpp>

// MoveIt
Expand Down
5 changes: 5 additions & 0 deletions moveit_ros/robot_interaction/src/interaction_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,12 @@
#include <moveit/transforms/transforms.hpp>
#include <interactive_markers/interactive_marker_server.hpp>
#include <interactive_markers/menu_handler.hpp>
// TODO: Remove conditional include when released to all active distros.
#if __has_include(<tf2/LinearMath/Transform.hpp>)
#include <tf2/LinearMath/Transform.hpp>
#else
#include <tf2/LinearMath/Transform.h>
#endif
#include <tf2_eigen/tf2_eigen.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include <moveit/utils/logger.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,12 @@

#include <math.h>
#include <moveit/robot_interaction/interactive_marker_helpers.hpp>
// TODO: Remove conditional include when released to all active distros.
#if __has_include(<tf2/LinearMath/Quaternion.hpp>)
#include <tf2/LinearMath/Quaternion.hpp>
#else
#include <tf2/LinearMath/Quaternion.h>
#endif
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>

namespace robot_interaction
Expand Down
5 changes: 5 additions & 0 deletions moveit_ros/robot_interaction/src/robot_interaction.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,12 @@
#include <interactive_markers/menu_handler.hpp>
#include <tf2_eigen/tf2_eigen.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
// TODO: Remove conditional include when released to all active distros.
#if __has_include(<tf2/LinearMath/Transform.hpp>)
#include <tf2/LinearMath/Transform.hpp>
#else
#include <tf2/LinearMath/Transform.h>
#endif
#include <moveit/utils/logger.hpp>

#include <algorithm>
Expand Down

0 comments on commit 7390ebc

Please sign in to comment.