Skip to content

Commit 3359a6e

Browse files
Deprecating tf2 C Headers (#1039)
Related to this [pull request](ros2/geometry2#720) in `geometry2` in which we deprecated the `.h` style headers in favor of `.hpp`. Signed-off-by: CursedRock17 <mtglucas1@gmail.com> Co-authored-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
1 parent afc34b4 commit 3359a6e

File tree

1 file changed

+2
-2
lines changed

1 file changed

+2
-2
lines changed

image_rotate/src/image_rotate_node.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -48,8 +48,8 @@
4848
#include <vector>
4949

5050
#include "cv_bridge/cv_bridge.hpp"
51-
#include "tf2/LinearMath/Vector3.h"
52-
#include "tf2/LinearMath/Quaternion.h"
51+
#include "tf2/LinearMath/Vector3.hpp"
52+
#include "tf2/LinearMath/Quaternion.hpp"
5353
#include "tf2_ros/buffer.h"
5454
#include "tf2_ros/transform_listener.h"
5555
#include "tf2_ros/transform_broadcaster.h"

0 commit comments

Comments
 (0)