From 9492dc06e078d0cf843ca4d988c8a78696194470 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Sun, 7 Jul 2024 19:05:34 +0200 Subject: [PATCH] Make #4525 compile on humble (#4526) * Make it compile on humble Signed-off-by: Christoph Froehlich * Remove formatting Signed-off-by: Christoph Froehlich --------- Signed-off-by: Christoph Froehlich --- .../plugins/action/get_pose_from_path_action.hpp | 2 +- .../plugins/action/get_pose_from_path_action.cpp | 2 +- .../test/plugins/action/test_get_pose_from_path_action.cpp | 6 +++--- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/get_pose_from_path_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/get_pose_from_path_action.hpp index 091360b4795..4715b0eb226 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/get_pose_from_path_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/get_pose_from_path_action.hpp @@ -22,7 +22,7 @@ #include "geometry_msgs/msg/pose_stamped.hpp" #include "nav2_util/geometry_utils.hpp" #include "nav2_util/robot_utils.hpp" -#include "behaviortree_cpp/action_node.h" +#include "behaviortree_cpp_v3/action_node.h" #include "nav_msgs/msg/path.h" namespace nav2_behavior_tree diff --git a/nav2_behavior_tree/plugins/action/get_pose_from_path_action.cpp b/nav2_behavior_tree/plugins/action/get_pose_from_path_action.cpp index cab0311a37a..13b2da31405 100644 --- a/nav2_behavior_tree/plugins/action/get_pose_from_path_action.cpp +++ b/nav2_behavior_tree/plugins/action/get_pose_from_path_action.cpp @@ -72,7 +72,7 @@ inline BT::NodeStatus GetPoseFromPath::tick() } // namespace nav2_behavior_tree -#include "behaviortree_cpp/bt_factory.h" +#include "behaviortree_cpp_v3/bt_factory.h" BT_REGISTER_NODES(factory) { factory.registerNodeType("GetPoseFromPath"); diff --git a/nav2_behavior_tree/test/plugins/action/test_get_pose_from_path_action.cpp b/nav2_behavior_tree/test/plugins/action/test_get_pose_from_path_action.cpp index 39f6df2a3c9..497a138f32e 100644 --- a/nav2_behavior_tree/test/plugins/action/test_get_pose_from_path_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_get_pose_from_path_action.cpp @@ -23,11 +23,11 @@ #include "nav_msgs/msg/path.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" -#include "behaviortree_cpp/bt_factory.h" +#include "behaviortree_cpp_v3/bt_factory.h" -#include "utils/test_action_server.hpp" +#include "../../test_action_server.hpp" #include "nav2_behavior_tree/plugins/action/get_pose_from_path_action.hpp" -#include "utils/test_behavior_tree_fixture.hpp" +#include "../../test_behavior_tree_fixture.hpp" class GetPoseFromPathTestFixture : public ::testing::Test {