Skip to content

Commit 5546b2e

Browse files
authored
Fix Deprecated tf2 headers (#1289)
Signed-off-by: CursedRock17 <[email protected]>
1 parent 2dbce10 commit 5546b2e

File tree

9 files changed

+12
-12
lines changed

9 files changed

+12
-12
lines changed

rviz_common/include/rviz_common/transformation/frame_transformer.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -36,8 +36,8 @@
3636
#include <string>
3737
#include <vector>
3838

39-
#include "tf2/buffer_core_interface.h"
40-
#include "tf2/exceptions.h"
39+
#include "tf2/buffer_core_interface.hpp"
40+
#include "tf2/exceptions.hpp"
4141
#include "tf2_ros/async_buffer_interface.h"
4242

4343
#include <QString> // NOLINT

rviz_default_plugins/include/rviz_default_plugins/displays/tf/frame_info.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@
3434

3535
#include <string>
3636

37-
#include "tf2/time.h"
37+
#include "tf2/time.hpp"
3838

3939
#include "rviz_default_plugins/displays/tf/tf_display.hpp"
4040
#include "rviz_default_plugins/visibility_control.hpp"

rviz_default_plugins/include/rviz_default_plugins/displays/tf/tf_display.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -42,9 +42,9 @@
4242
#include <OgreVector.h>
4343

4444
#include "geometry_msgs/msg/transform_stamped.hpp"
45-
#include "tf2/exceptions.h"
46-
#include "tf2/buffer_core.h"
47-
#include "tf2/time.h"
45+
#include "tf2/exceptions.hpp"
46+
#include "tf2/buffer_core.hpp"
47+
#include "tf2/time.hpp"
4848

4949
#include "rviz_common/interaction/forwards.hpp"
5050
#include "rviz_common/display.hpp"

rviz_default_plugins/test/rviz_default_plugins/publishers/laser_scan_publisher.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@
3838
#include "rclcpp/rclcpp.hpp"
3939
#include "sensor_msgs/msg/laser_scan.hpp"
4040
#include "std_msgs/msg/header.hpp"
41-
#include "tf2/LinearMath/Quaternion.h"
41+
#include "tf2/LinearMath/Quaternion.hpp"
4242

4343
using namespace std::chrono_literals; // NOLINT
4444

rviz_default_plugins/test/rviz_default_plugins/publishers/point_cloud2_publisher.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,7 @@
3535
#include <vector>
3636

3737
#include "geometry_msgs/msg/transform_stamped.hpp"
38-
#include "tf2/LinearMath/Quaternion.h"
38+
#include "tf2/LinearMath/Quaternion.hpp"
3939
#include "rclcpp/rclcpp.hpp"
4040
#include "sensor_msgs/msg/point_cloud2.hpp"
4141
#include "std_msgs/msg/header.hpp"

rviz_default_plugins/test/rviz_default_plugins/publishers/point_cloud_publisher.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@
3434
#include <vector>
3535

3636
#include "geometry_msgs/msg/transform_stamped.hpp"
37-
#include "tf2/LinearMath/Quaternion.h"
37+
#include "tf2/LinearMath/Quaternion.hpp"
3838
#include "rclcpp/rclcpp.hpp"
3939
#include "std_msgs/msg/header.hpp"
4040
#include "sensor_msgs/msg/point_cloud.hpp"

rviz_visual_testing_framework/include/rviz_visual_testing_framework/visual_test_fixture.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@
3838
#include "rclcpp/clock.hpp"
3939
#include "std_msgs/msg/header.hpp"
4040
#include "geometry_msgs/msg/transform_stamped.hpp"
41-
#include "tf2/LinearMath/Quaternion.h"
41+
#include "tf2/LinearMath/Quaternion.hpp"
4242
#include "tf2_ros/static_transform_broadcaster.h"
4343

4444
#include "rviz_visual_testing_framework/internal/display_handler.hpp"

rviz_visual_testing_framework/include/rviz_visual_testing_framework/visual_test_publisher.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@
4040
#include "rclcpp/clock.hpp"
4141
#include "std_msgs/msg/header.hpp"
4242
#include "geometry_msgs/msg/transform_stamped.hpp"
43-
#include "tf2/LinearMath/Quaternion.h"
43+
#include "tf2/LinearMath/Quaternion.hpp"
4444
#include "tf2_ros/static_transform_broadcaster.h"
4545
#include "internal/transform_message_creator.hpp"
4646

rviz_visual_testing_framework/src/internal/transform_message_creator.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@
3333

3434
#include "rclcpp/rclcpp.hpp"
3535
#include "rclcpp/clock.hpp"
36-
#include "tf2/LinearMath/Quaternion.h"
36+
#include "tf2/LinearMath/Quaternion.hpp"
3737

3838
geometry_msgs::msg::TransformStamped createStaticTransformMessageFor(
3939
std::string header_frame_id, std::string child_frame_id)

0 commit comments

Comments
 (0)