Skip to content

Commit b0f9a6f

Browse files
authored
tf2 uses hpp headers in rolling (and is backported) (#5180)
Signed-off-by: Tim Clephas <tim.clephas@nobleo.nl>
1 parent fda475c commit b0f9a6f

File tree

2 files changed

+2
-2
lines changed

2 files changed

+2
-2
lines changed

nav2_route/include/nav2_route/plugins/edge_cost_functions/goal_orientation_scorer.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@
2626
#include "nav2_util/node_utils.hpp"
2727
#include "nav2_costmap_2d/costmap_subscriber.hpp"
2828
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
29-
#include "tf2/utils.h"
29+
#include "tf2/utils.hpp"
3030
#include "angles/angles.h"
3131

3232
namespace nav2_route

nav2_route/include/nav2_route/plugins/edge_cost_functions/start_pose_orientation_scorer.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@
2727
#include "nav2_util/robot_utils.hpp"
2828
#include "nav2_costmap_2d/costmap_subscriber.hpp"
2929
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
30-
#include "tf2/utils.h"
30+
#include "tf2/utils.hpp"
3131
#include "angles/angles.h"
3232

3333
namespace nav2_route

0 commit comments

Comments
 (0)