Skip to content

Commit 396a9ce

Browse files
authored
Deprecate c headers (#25)
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 <[email protected]>
1 parent 5eba63c commit 396a9ce

File tree

2 files changed

+2
-2
lines changed

2 files changed

+2
-2
lines changed

imu_transformer/include/imu_transformer/tf2_sensor_msgs.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@
3232
#ifndef TF2_SENSOR_MSGS_H
3333
#define TF2_SENSOR_MSGS_H
3434

35-
#include <tf2/convert.h>
35+
#include <tf2/convert.hpp>
3636
#include <sensor_msgs/msg/imu.hpp>
3737
#include <sensor_msgs/msg/magnetic_field.hpp>
3838
#include <Eigen/Eigen>

imu_transformer/test/test_imu_transforms.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,7 @@
99
#include "gtest/gtest.h"
1010

1111

12-
#include <tf2/LinearMath/Quaternion.h>
12+
#include <tf2/LinearMath/Quaternion.hpp>
1313
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
1414

1515
#include <Eigen/Eigen>

0 commit comments

Comments
 (0)