Skip to content

Commit 35a0f6b

Browse files
Move nav2_behavior_tree test utils into the right folder
1 parent 2f1f9e4 commit 35a0f6b

File tree

7 files changed

+20
-18
lines changed

7 files changed

+20
-18
lines changed

nav2_behavior_tree/CMakeLists.txt

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -223,8 +223,8 @@ install(DIRECTORY include/
223223
DESTINATION include/
224224
)
225225

226-
install(DIRECTORY test/utils/
227-
DESTINATION include/utils/
226+
install(DIRECTORY test/include/
227+
DESTINATION include/
228228
)
229229

230230
install(FILES nav2_tree_nodes.xml DESTINATION share/${PROJECT_NAME})

nav2_behavior_tree/test/CMakeLists.txt

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,9 @@
11
ament_add_gtest(test_bt_conversions test_bt_conversions.cpp)
22
ament_target_dependencies(test_bt_conversions ${dependencies})
33

4-
include_directories(.)
4+
include_directories(
5+
include/nav2_behavior_tree
6+
)
57

68
add_subdirectory(plugins/condition)
79
add_subdirectory(plugins/decorator)

nav2_behavior_tree/test/utils/test_action_server.hpp renamed to nav2_behavior_tree/test/include/nav2_behavior_tree/utils/test_action_server.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef UTILS__TEST_ACTION_SERVER_HPP_
16-
#define UTILS__TEST_ACTION_SERVER_HPP_
15+
#ifndef NAV2_BEHAVIOR_TREE__UTILS__TEST_ACTION_SERVER_HPP_
16+
#define NAV2_BEHAVIOR_TREE__UTILS__TEST_ACTION_SERVER_HPP_
1717

1818
#include <string>
1919
#include <memory>
@@ -97,4 +97,4 @@ class TestActionServer : public rclcpp::Node
9797
bool goal_cancelled_ = false;
9898
};
9999

100-
#endif // UTILS__TEST_ACTION_SERVER_HPP_
100+
#endif // NAV2_BEHAVIOR_TREE__UTILS__TEST_ACTION_SERVER_HPP_

nav2_behavior_tree/test/utils/test_behavior_tree_fixture.hpp renamed to nav2_behavior_tree/test/include/nav2_behavior_tree/utils/test_behavior_tree_fixture.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -13,8 +13,8 @@
1313
// See the License for the specific language governing permissions and
1414
// limitations under the License.
1515

16-
#ifndef UTILS__TEST_BEHAVIOR_TREE_FIXTURE_HPP_
17-
#define UTILS__TEST_BEHAVIOR_TREE_FIXTURE_HPP_
16+
#ifndef NAV2_BEHAVIOR_TREE__UTILS__TEST_BEHAVIOR_TREE_FIXTURE_HPP_
17+
#define NAV2_BEHAVIOR_TREE__UTILS__TEST_BEHAVIOR_TREE_FIXTURE_HPP_
1818

1919
#include <gtest/gtest.h>
2020
#include <memory>
@@ -90,4 +90,4 @@ BT::NodeConfiguration * nav2_behavior_tree::BehaviorTreeTestFixture::config_ = n
9090
std::shared_ptr<BT::BehaviorTreeFactory>
9191
nav2_behavior_tree::BehaviorTreeTestFixture::factory_ = nullptr;
9292

93-
#endif // UTILS__TEST_BEHAVIOR_TREE_FIXTURE_HPP_
93+
#endif // NAV2_BEHAVIOR_TREE__UTILS__TEST_BEHAVIOR_TREE_FIXTURE_HPP_

nav2_behavior_tree/test/utils/test_dummy_tree_node.hpp renamed to nav2_behavior_tree/test/include/nav2_behavior_tree/utils/test_dummy_tree_node.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -13,8 +13,8 @@
1313
// See the License for the specific language governing permissions and
1414
// limitations under the License.
1515

16-
#ifndef UTILS__TEST_DUMMY_TREE_NODE_HPP_
17-
#define UTILS__TEST_DUMMY_TREE_NODE_HPP_
16+
#ifndef NAV2_BEHAVIOR_TREE__UTILS__TEST_DUMMY_TREE_NODE_HPP_
17+
#define NAV2_BEHAVIOR_TREE__UTILS__TEST_DUMMY_TREE_NODE_HPP_
1818

1919
#include <behaviortree_cpp_v3/basic_types.h>
2020
#include <behaviortree_cpp_v3/action_node.h>
@@ -56,4 +56,4 @@ class DummyNode : public BT::ActionNodeBase
5656

5757
} // namespace nav2_behavior_tree
5858

59-
#endif // UTILS__TEST_DUMMY_TREE_NODE_HPP_
59+
#endif // NAV2_BEHAVIOR_TREE__UTILS__TEST_DUMMY_TREE_NODE_HPP_

nav2_behavior_tree/test/utils/test_service.hpp renamed to nav2_behavior_tree/test/include/nav2_behavior_tree/utils/test_service.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef UTILS__TEST_SERVICE_HPP_
16-
#define UTILS__TEST_SERVICE_HPP_
15+
#ifndef NAV2_BEHAVIOR_TREE__UTILS__TEST_SERVICE_HPP_
16+
#define NAV2_BEHAVIOR_TREE__UTILS__TEST_SERVICE_HPP_
1717

1818
#include <string>
1919
#include <memory>
@@ -57,4 +57,4 @@ class TestService : public rclcpp::Node
5757
std::shared_ptr<typename ServiceT::Request> current_request_;
5858
};
5959

60-
#endif // UTILS__TEST_SERVICE_HPP_
60+
#endif // NAV2_BEHAVIOR_TREE__UTILS__TEST_SERVICE_HPP_

nav2_behavior_tree/test/utils/test_transform_handler.hpp renamed to nav2_behavior_tree/test/include/nav2_behavior_tree/utils/test_transform_handler.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -13,8 +13,8 @@
1313
// See the License for the specific language governing permissions and
1414
// limitations under the License.
1515

16-
#ifndef UTILS__TEST_TRANSFORM_HANDLER_HPP_
17-
#define UTILS__TEST_TRANSFORM_HANDLER_HPP_
16+
#ifndef NAV2_BEHAVIOR_TREE__UTILS__TEST_TRANSFORM_HANDLER_HPP_
17+
#define NAV2_BEHAVIOR_TREE__UTILS__TEST_TRANSFORM_HANDLER_HPP_
1818

1919
#include <memory>
2020
#include <string>
@@ -162,4 +162,4 @@ class TransformHandler
162162

163163
} // namespace nav2_behavior_tree
164164

165-
#endif // UTILS__TEST_TRANSFORM_HANDLER_HPP_
165+
#endif // NAV2_BEHAVIOR_TREE__UTILS__TEST_TRANSFORM_HANDLER_HPP_

0 commit comments

Comments
 (0)