diff --git a/nav2_behavior_tree/CMakeLists.txt b/nav2_behavior_tree/CMakeLists.txt index 1767bdcf329..7a73c2da59a 100644 --- a/nav2_behavior_tree/CMakeLists.txt +++ b/nav2_behavior_tree/CMakeLists.txt @@ -132,6 +132,18 @@ list(APPEND plugin_libs nav2_initial_pose_received_condition_bt_node) add_library(nav2_is_battery_low_condition_bt_node SHARED plugins/condition/is_battery_low_condition.cpp) list(APPEND plugin_libs nav2_is_battery_low_condition_bt_node) +add_library(nav2_are_error_codes_active_condition_bt_node SHARED plugins/condition/are_error_codes_present_condition.cpp) +list(APPEND plugin_libs nav2_are_error_codes_active_condition_bt_node) + +add_library(nav2_would_a_controller_recovery_help_condition_bt_node SHARED plugins/condition/would_a_controller_recovery_help_condition.cpp) +list(APPEND plugin_libs nav2_would_a_controller_recovery_help_condition_bt_node) + +add_library(nav2_would_a_planner_recovery_help_condition_bt_node SHARED plugins/condition/would_a_planner_recovery_help_condition.cpp) +list(APPEND plugin_libs nav2_would_a_planner_recovery_help_condition_bt_node) + +add_library(nav2_would_a_smoother_recovery_help_condition_bt_node SHARED plugins/condition/would_a_smoother_recovery_help_condition.cpp) +list(APPEND plugin_libs nav2_would_a_smoother_recovery_help_condition_bt_node) + add_library(nav2_reinitialize_global_localization_service_bt_node SHARED plugins/action/reinitialize_global_localization_service.cpp) list(APPEND plugin_libs nav2_reinitialize_global_localization_service_bt_node) diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_conversions.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_conversions.hpp index c109c4f0e29..4e9f8437ed6 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_conversions.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_conversions.hpp @@ -16,6 +16,7 @@ #define NAV2_BEHAVIOR_TREE__BT_CONVERSIONS_HPP_ #include +#include #include "rclcpp/time.hpp" #include "behaviortree_cpp_v3/behavior_tree.h" @@ -111,6 +112,24 @@ inline std::chrono::milliseconds convertFromString(co return std::chrono::milliseconds(std::stoul(key.data())); } +/** + * @brief Parse XML string to std::set + * @param key XML string + * @return std::set + */ +template<> +inline std::set convertFromString(StringView key) +{ + // Real numbers separated by semicolons + auto parts = splitString(key, ';'); + + std::set set; + for (const auto part : parts) { + set.insert(convertFromString(part)); + } + return set; +} + } // namespace BT #endif // NAV2_BEHAVIOR_TREE__BT_CONVERSIONS_HPP_ diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/are_error_codes_present_condition.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/are_error_codes_present_condition.hpp new file mode 100644 index 00000000000..4bb8ec46f71 --- /dev/null +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/are_error_codes_present_condition.hpp @@ -0,0 +1,69 @@ +// Copyright (c) 2022 Joshua Wallace +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__ARE_ERROR_CODES_PRESENT_CONDITION_HPP_ +#define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__ARE_ERROR_CODES_PRESENT_CONDITION_HPP_ + +#include +#include +#include +#include + +#include "rclcpp/rclcpp.hpp" +#include "behaviortree_cpp_v3/condition_node.h" + +namespace nav2_behavior_tree +{ + +class AreErrorCodesPresent : public BT::ConditionNode +{ +public: + AreErrorCodesPresent( + const std::string & condition_name, + const BT::NodeConfiguration & conf) + : BT::ConditionNode(condition_name, conf) + { + getInput>("error_codes_to_check", error_codes_to_check_); //NOLINT + } + + AreErrorCodesPresent() = delete; + + BT::NodeStatus tick() + { + getInput("error_code", error_code_); //NOLINT + + if (error_codes_to_check_.find(error_code_) != error_codes_to_check_.end()) { + return BT::NodeStatus::SUCCESS; + } + + return BT::NodeStatus::FAILURE; + } + + static BT::PortsList providedPorts() + { + return + { + BT::InputPort("error_code", "The active error codes"), //NOLINT + BT::InputPort>("error_codes_to_check", "Error codes to check")//NOLINT + }; + } + +protected: + unsigned short error_code_; //NOLINT + std::set error_codes_to_check_; //NOLINT +}; + +} // namespace nav2_behavior_tree + +#endif // NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__ARE_ERROR_CODES_PRESENT_CONDITION_HPP_ diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/would_a_controller_recovery_help_condition.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/would_a_controller_recovery_help_condition.hpp new file mode 100644 index 00000000000..6c5b4f3982e --- /dev/null +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/would_a_controller_recovery_help_condition.hpp @@ -0,0 +1,40 @@ +// Copyright (c) 2022 Joshua Wallace +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__WOULD_A_CONTROLLER_RECOVERY_HELP_CONDITION_HPP_ +#define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__WOULD_A_CONTROLLER_RECOVERY_HELP_CONDITION_HPP_ + +#include + +#include "nav2_msgs/action/follow_path.hpp" +#include "nav2_behavior_tree/plugins/condition/are_error_codes_present_condition.hpp" + +namespace nav2_behavior_tree +{ + +class WouldAControllerRecoveryHelp : public AreErrorCodesPresent +{ + using Action = nav2_msgs::action::FollowPath; + using ActionGoal = Action::Goal; + +public: + WouldAControllerRecoveryHelp( + const std::string & condition_name, + const BT::NodeConfiguration & conf); + + WouldAControllerRecoveryHelp() = delete; +}; + +} // namespace nav2_behavior_tree +#endif // NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__WOULD_A_CONTROLLER_RECOVERY_HELP_CONDITION_HPP_ diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/would_a_planner_recovery_help_condition.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/would_a_planner_recovery_help_condition.hpp new file mode 100644 index 00000000000..4c37893bc4b --- /dev/null +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/would_a_planner_recovery_help_condition.hpp @@ -0,0 +1,40 @@ +// Copyright (c) 2022 Joshua Wallace +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__WOULD_A_PLANNER_RECOVERY_HELP_CONDITION_HPP_ +#define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__WOULD_A_PLANNER_RECOVERY_HELP_CONDITION_HPP_ + +#include + +#include "nav2_msgs/action/compute_path_to_pose.hpp" +#include "nav2_behavior_tree/plugins/condition/are_error_codes_present_condition.hpp" + +namespace nav2_behavior_tree +{ + +class WouldAPlannerRecoveryHelp : public AreErrorCodesPresent +{ + using Action = nav2_msgs::action::ComputePathToPose; + using ActionGoal = Action::Goal; + +public: + WouldAPlannerRecoveryHelp( + const std::string & condition_name, + const BT::NodeConfiguration & conf); + + WouldAPlannerRecoveryHelp() = delete; +}; + +} // namespace nav2_behavior_tree +#endif // NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__WOULD_A_PLANNER_RECOVERY_HELP_CONDITION_HPP_ diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/would_a_smoother_recovery_help_condition.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/would_a_smoother_recovery_help_condition.hpp new file mode 100644 index 00000000000..a13a6c76eb9 --- /dev/null +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/would_a_smoother_recovery_help_condition.hpp @@ -0,0 +1,42 @@ +// Copyright (c) 2023 Joshua Wallace +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__WOULD_A_SMOOTHER_RECOVERY_HELP_CONDITION_HPP_ +#define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__WOULD_A_SMOOTHER_RECOVERY_HELP_CONDITION_HPP_ + + +#include + +#include "nav2_msgs/action/smooth_path.hpp" +#include "nav2_behavior_tree/plugins/condition/are_error_codes_present_condition.hpp" + +namespace nav2_behavior_tree +{ + +class WouldASmootherRecoveryHelp : public AreErrorCodesPresent +{ + using Action = nav2_msgs::action::SmoothPath; + using ActionGoal = Action::Goal; + +public: + WouldASmootherRecoveryHelp( + const std::string & condition_name, + const BT::NodeConfiguration & conf); + + WouldASmootherRecoveryHelp() = delete; +}; + +} // namespace nav2_behavior_tree + +#endif // NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__WOULD_A_SMOOTHER_RECOVERY_HELP_CONDITION_HPP_ diff --git a/nav2_behavior_tree/plugins/condition/are_error_codes_present_condition.cpp b/nav2_behavior_tree/plugins/condition/are_error_codes_present_condition.cpp new file mode 100644 index 00000000000..6764cccd116 --- /dev/null +++ b/nav2_behavior_tree/plugins/condition/are_error_codes_present_condition.cpp @@ -0,0 +1,22 @@ +// Copyright (c) 2023 Joshua Wallace +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "nav2_behavior_tree/plugins/condition/are_error_codes_present_condition.hpp" + +#include "behaviortree_cpp_v3/bt_factory.h" +BT_REGISTER_NODES(factory) +{ + factory.registerNodeType( + "AreErrorCodesPresent"); +} diff --git a/nav2_behavior_tree/plugins/condition/would_a_controller_recovery_help_condition.cpp b/nav2_behavior_tree/plugins/condition/would_a_controller_recovery_help_condition.cpp new file mode 100644 index 00000000000..f299f4b7b42 --- /dev/null +++ b/nav2_behavior_tree/plugins/condition/would_a_controller_recovery_help_condition.cpp @@ -0,0 +1,41 @@ +// Copyright (c) 2022 Joshua Wallace +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "nav2_behavior_tree/plugins/condition/would_a_controller_recovery_help_condition.hpp" +#include + +namespace nav2_behavior_tree +{ + +WouldAControllerRecoveryHelp::WouldAControllerRecoveryHelp( + const std::string & condition_name, + const BT::NodeConfiguration & conf) +: AreErrorCodesPresent(condition_name, conf) +{ + error_codes_to_check_ = { + ActionGoal::UNKNOWN, + ActionGoal::PATIENCE_EXCEEDED, + ActionGoal::FAILED_TO_MAKE_PROGRESS, + ActionGoal::NO_VALID_CONTROL + }; +} + +} // namespace nav2_behavior_tree + +#include "behaviortree_cpp_v3/bt_factory.h" +BT_REGISTER_NODES(factory) +{ + factory.registerNodeType( + "WouldAControllerRecoveryHelp"); +} diff --git a/nav2_behavior_tree/plugins/condition/would_a_planner_recovery_help_condition.cpp b/nav2_behavior_tree/plugins/condition/would_a_planner_recovery_help_condition.cpp new file mode 100644 index 00000000000..2420c1ea025 --- /dev/null +++ b/nav2_behavior_tree/plugins/condition/would_a_planner_recovery_help_condition.cpp @@ -0,0 +1,40 @@ +// Copyright (c) 2022 Joshua Wallace +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "nav2_behavior_tree/plugins/condition/would_a_planner_recovery_help_condition.hpp" +#include + +namespace nav2_behavior_tree +{ + +WouldAPlannerRecoveryHelp::WouldAPlannerRecoveryHelp( + const std::string & condition_name, + const BT::NodeConfiguration & conf) +: AreErrorCodesPresent(condition_name, conf) +{ + error_codes_to_check_ = { + ActionGoal::UNKNOWN, + ActionGoal::NO_VALID_PATH, + ActionGoal::TIMEOUT + }; +} + +} // namespace nav2_behavior_tree + +#include "behaviortree_cpp_v3/bt_factory.h" +BT_REGISTER_NODES(factory) +{ + factory.registerNodeType( + "WouldAPlannerRecoveryHelp"); +} diff --git a/nav2_behavior_tree/plugins/condition/would_a_smoother_recovery_help_condition.cpp b/nav2_behavior_tree/plugins/condition/would_a_smoother_recovery_help_condition.cpp new file mode 100644 index 00000000000..7bcf01f0915 --- /dev/null +++ b/nav2_behavior_tree/plugins/condition/would_a_smoother_recovery_help_condition.cpp @@ -0,0 +1,41 @@ +// Copyright (c) 2023 Joshua Wallace +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "nav2_behavior_tree/plugins/condition/would_a_smoother_recovery_help_condition.hpp" +#include + +namespace nav2_behavior_tree +{ + +WouldASmootherRecoveryHelp::WouldASmootherRecoveryHelp( + const std::string & condition_name, + const BT::NodeConfiguration & conf) +: AreErrorCodesPresent(condition_name, conf) +{ + error_codes_to_check_ = { + ActionGoal::UNKNOWN, + ActionGoal::TIMEOUT, + ActionGoal::FAILED_TO_SMOOTH_PATH, + ActionGoal::SMOOTHED_PATH_IN_COLLISION + }; +} + +} // namespace nav2_behavior_tree + +#include "behaviortree_cpp_v3/bt_factory.h" +BT_REGISTER_NODES(factory) +{ + factory.registerNodeType( + "WouldASmootherRecoveryHelp"); +} diff --git a/nav2_behavior_tree/test/plugins/condition/CMakeLists.txt b/nav2_behavior_tree/test/plugins/condition/CMakeLists.txt index 21fd0b29409..c6edc8dcd7e 100644 --- a/nav2_behavior_tree/test/plugins/condition/CMakeLists.txt +++ b/nav2_behavior_tree/test/plugins/condition/CMakeLists.txt @@ -41,3 +41,20 @@ ament_target_dependencies(test_condition_is_battery_low ${dependencies}) ament_add_gtest(test_condition_is_path_valid test_is_path_valid.cpp) target_link_libraries(test_condition_is_path_valid nav2_is_path_valid_condition_bt_node) ament_target_dependencies(test_condition_is_path_valid ${dependencies}) + +ament_add_gtest(test_are_error_codes_present test_are_error_codes_present.cpp) +target_link_libraries(test_are_error_codes_present nav2_would_a_controller_recovery_help_condition_bt_node) +ament_target_dependencies(test_are_error_codes_present ${dependencies}) + +ament_add_gtest(test_would_a_controller_recovery_help test_would_a_controller_recovery_help.cpp) +target_link_libraries(test_would_a_controller_recovery_help nav2_would_a_controller_recovery_help_condition_bt_node) +ament_target_dependencies(test_would_a_controller_recovery_help ${dependencies}) + +ament_add_gtest(test_would_a_planner_recovery_help test_would_a_planner_recovery_help.cpp) +target_link_libraries(test_would_a_planner_recovery_help nav2_would_a_planner_recovery_help_condition_bt_node) +ament_target_dependencies(test_would_a_planner_recovery_help ${dependencies}) + +ament_add_gtest(test_would_a_smoother_recovery_help test_would_a_smoother_recovery_help.cpp) +target_link_libraries(test_would_a_smoother_recovery_help nav2_would_a_smoother_recovery_help_condition_bt_node) +ament_target_dependencies(test_would_a_smoother_recovery_help ${dependencies}) + diff --git a/nav2_behavior_tree/test/plugins/condition/test_are_error_codes_present.cpp b/nav2_behavior_tree/test/plugins/condition/test_are_error_codes_present.cpp new file mode 100644 index 00000000000..057d393f382 --- /dev/null +++ b/nav2_behavior_tree/test/plugins/condition/test_are_error_codes_present.cpp @@ -0,0 +1,85 @@ +// Copyright (c) 2022 Joshua Wallace +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include + +#include "../../test_behavior_tree_fixture.hpp" +#include "nav2_behavior_tree/plugins/condition/are_error_codes_present_condition.hpp" +#include "nav2_msgs/action/follow_path.hpp" + +class AreErrorCodesPresentFixture : public nav2_behavior_tree::BehaviorTreeTestFixture +{ +public: + using Action = nav2_msgs::action::FollowPath; + using ActionGoal = Action::Goal; + void SetUp() + { + int error_code = ActionGoal::NONE; + std::set error_codes_to_check = {ActionGoal::UNKNOWN}; //NOLINT + config_->blackboard->set("error_code", error_code); + config_->blackboard->set("error_codes_to_check", error_codes_to_check); + + std::string xml_txt = + R"( + + + + + )"; + + factory_->registerNodeType( + "AreErrorCodesPresent"); + tree_ = std::make_shared(factory_->createTreeFromText(xml_txt, config_->blackboard)); + } + + void TearDown() + { + tree_.reset(); + } + +protected: + static std::shared_ptr tree_; +}; + +std::shared_ptr AreErrorCodesPresentFixture::tree_ = nullptr; + +TEST_F(AreErrorCodesPresentFixture, test_condition) +{ + std::map error_to_status_map = { + {ActionGoal::NONE, BT::NodeStatus::FAILURE}, + {ActionGoal::UNKNOWN, BT::NodeStatus::SUCCESS}, + }; + + for (const auto & error_to_status : error_to_status_map) { + config_->blackboard->set("error_code", error_to_status.first); + EXPECT_EQ(tree_->tickRoot(), error_to_status.second); + } +} + +int main(int argc, char ** argv) +{ + ::testing::InitGoogleTest(&argc, argv); + + // initialize ROS + rclcpp::init(argc, argv); + + bool all_successful = RUN_ALL_TESTS(); + + // shutdown ROS + rclcpp::shutdown(); + + return all_successful; +} diff --git a/nav2_behavior_tree/test/plugins/condition/test_would_a_controller_recovery_help.cpp b/nav2_behavior_tree/test/plugins/condition/test_would_a_controller_recovery_help.cpp new file mode 100644 index 00000000000..be28a2d2ba7 --- /dev/null +++ b/nav2_behavior_tree/test/plugins/condition/test_would_a_controller_recovery_help.cpp @@ -0,0 +1,89 @@ +// Copyright (c) 2022 Joshua Wallace +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include + +#include "../../test_behavior_tree_fixture.hpp" +#include "nav2_behavior_tree/plugins/condition/would_a_controller_recovery_help_condition.hpp" +#include "nav2_msgs/action/follow_path.hpp" + +class WouldAControllerRecoveryHelpFixture : public nav2_behavior_tree::BehaviorTreeTestFixture +{ +public: + using Action = nav2_msgs::action::FollowPath; + using ActionGoal = Action::Goal; + void SetUp() + { + int error_code = ActionGoal::NONE; + config_->blackboard->set("error_code", error_code); + + std::string xml_txt = + R"( + + + + + )"; + + factory_->registerNodeType( + "WouldAControllerRecoveryHelp"); + tree_ = std::make_shared(factory_->createTreeFromText(xml_txt, config_->blackboard)); + } + + void TearDown() + { + tree_.reset(); + } + +protected: + static std::shared_ptr tree_; +}; + +std::shared_ptr WouldAControllerRecoveryHelpFixture::tree_ = nullptr; + +TEST_F(WouldAControllerRecoveryHelpFixture, test_condition) +{ + std::map error_to_status_map = { + {ActionGoal::NONE, BT::NodeStatus::FAILURE}, + {ActionGoal::UNKNOWN, BT::NodeStatus::SUCCESS}, + {ActionGoal::INVALID_CONTROLLER, BT::NodeStatus::FAILURE}, + {ActionGoal::TF_ERROR, BT::NodeStatus::FAILURE}, + {ActionGoal::INVALID_PATH, BT::NodeStatus::FAILURE}, + {ActionGoal::PATIENCE_EXCEEDED, BT::NodeStatus::SUCCESS}, + {ActionGoal::FAILED_TO_MAKE_PROGRESS, BT::NodeStatus::SUCCESS}, + {ActionGoal::NO_VALID_CONTROL, BT::NodeStatus::SUCCESS}, + }; + + for (const auto & error_to_status : error_to_status_map) { + config_->blackboard->set("error_code", error_to_status.first); + EXPECT_EQ(tree_->tickRoot(), error_to_status.second); + } +} + +int main(int argc, char ** argv) +{ + ::testing::InitGoogleTest(&argc, argv); + + // initialize ROS + rclcpp::init(argc, argv); + + bool all_successful = RUN_ALL_TESTS(); + + // shutdown ROS + rclcpp::shutdown(); + + return all_successful; +} diff --git a/nav2_behavior_tree/test/plugins/condition/test_would_a_planner_recovery_help.cpp b/nav2_behavior_tree/test/plugins/condition/test_would_a_planner_recovery_help.cpp new file mode 100644 index 00000000000..768745a85f6 --- /dev/null +++ b/nav2_behavior_tree/test/plugins/condition/test_would_a_planner_recovery_help.cpp @@ -0,0 +1,84 @@ +// Copyright (c) 2022 Joshua Wallace +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include + +#include "../../test_behavior_tree_fixture.hpp" +#include "nav2_behavior_tree/plugins/condition/would_a_planner_recovery_help_condition.hpp" +#include "nav2_msgs/action/compute_path_to_pose.hpp" + +class WouldAPlannerRecoveryHelpFixture : public nav2_behavior_tree::BehaviorTreeTestFixture +{ +public: + using Action = nav2_msgs::action::ComputePathToPose; + using ActionGoal = Action::Goal; + void SetUp() + { + int error_code = ActionGoal::NONE; + config_->blackboard->set("error_code", error_code); + + std::string xml_txt = + R"( + + + + + )"; + + factory_->registerNodeType( + "WouldAPlannerRecoveryHelp"); + tree_ = std::make_shared(factory_->createTreeFromText(xml_txt, config_->blackboard)); + } + + void TearDown() + { + tree_.reset(); + } + +protected: + static std::shared_ptr tree_; +}; + +std::shared_ptr WouldAPlannerRecoveryHelpFixture::tree_ = nullptr; + +TEST_F(WouldAPlannerRecoveryHelpFixture, test_condition) +{ + std::map error_to_status_map = { + {ActionGoal::NONE, BT::NodeStatus::FAILURE}, + {ActionGoal::UNKNOWN, BT::NodeStatus::SUCCESS}, + {ActionGoal::NO_VALID_PATH, BT::NodeStatus::SUCCESS}, + }; + + for (const auto & error_to_status : error_to_status_map) { + config_->blackboard->set("error_code", error_to_status.first); + EXPECT_EQ(tree_->tickRoot(), error_to_status.second); + } +} + +int main(int argc, char ** argv) +{ + ::testing::InitGoogleTest(&argc, argv); + + // initialize ROS + rclcpp::init(argc, argv); + + bool all_successful = RUN_ALL_TESTS(); + + // shutdown ROS + rclcpp::shutdown(); + + return all_successful; +} diff --git a/nav2_behavior_tree/test/plugins/condition/test_would_a_smoother_recovery_help.cpp b/nav2_behavior_tree/test/plugins/condition/test_would_a_smoother_recovery_help.cpp new file mode 100644 index 00000000000..272b3b651ac --- /dev/null +++ b/nav2_behavior_tree/test/plugins/condition/test_would_a_smoother_recovery_help.cpp @@ -0,0 +1,86 @@ +// Copyright (c) 2023 Joshua Wallace +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include + +#include "../../test_behavior_tree_fixture.hpp" +#include "nav2_behavior_tree/plugins/condition/would_a_smoother_recovery_help_condition.hpp" +#include "nav2_msgs/action/smooth_path.hpp" + +class WouldASmootherRecoveryHelpFixture : public nav2_behavior_tree::BehaviorTreeTestFixture +{ +public: + using Action = nav2_msgs::action::SmoothPath; + using ActionGoal = Action::Goal; + void SetUp() + { + int error_code = ActionGoal::NONE; + config_->blackboard->set("error_code", error_code); + + std::string xml_txt = + R"( + + + + + )"; + + factory_->registerNodeType( + "WouldASmootherRecoveryHelp"); + tree_ = std::make_shared(factory_->createTreeFromText(xml_txt, config_->blackboard)); + } + + void TearDown() + { + tree_.reset(); + } + +protected: + static std::shared_ptr tree_; +}; + +std::shared_ptr WouldASmootherRecoveryHelpFixture::tree_ = nullptr; + +TEST_F(WouldASmootherRecoveryHelpFixture, test_condition) +{ + std::map error_to_status_map = { + {ActionGoal::NONE, BT::NodeStatus::FAILURE}, + {ActionGoal::UNKNOWN, BT::NodeStatus::SUCCESS}, + {ActionGoal::TIMEOUT, BT::NodeStatus::SUCCESS}, + {ActionGoal::FAILED_TO_SMOOTH_PATH, BT::NodeStatus::SUCCESS}, + {ActionGoal::SMOOTHED_PATH_IN_COLLISION, BT::NodeStatus::SUCCESS} + }; + + for (const auto & error_to_status : error_to_status_map) { + config_->blackboard->set("error_code", error_to_status.first); + EXPECT_EQ(tree_->tickRoot(), error_to_status.second); + } +} + +int main(int argc, char ** argv) +{ + ::testing::InitGoogleTest(&argc, argv); + + // initialize ROS + rclcpp::init(argc, argv); + + bool all_successful = RUN_ALL_TESTS(); + + // shutdown ROS + rclcpp::shutdown(); + + return all_successful; +} diff --git a/nav2_behavior_tree/test/test_bt_conversions.cpp b/nav2_behavior_tree/test/test_bt_conversions.cpp index ab67d5e52f5..1c5c01cf673 100644 --- a/nav2_behavior_tree/test/test_bt_conversions.cpp +++ b/nav2_behavior_tree/test/test_bt_conversions.cpp @@ -16,7 +16,7 @@ #include #include #include -#include +#include #include "geometry_msgs/msg/point.hpp" #include "geometry_msgs/msg/quaternion.hpp" @@ -267,3 +267,26 @@ TEST(MillisecondsPortTest, test_correct_syntax) tree.rootNode()->getInput("test", value); EXPECT_EQ(value.count(), 123); } + +TEST(ErrorCodePortTest, test_correct_syntax) +{ + std::string xml_txt = + R"( + + + + + )"; + + BT::BehaviorTreeFactory factory; + factory.registerNodeType>>("ErrorCodePort"); + auto tree = factory.createTreeFromText(xml_txt); + + tree = factory.createTreeFromText(xml_txt); + std::set value; + tree.rootNode()->getInput("test", value); + + EXPECT_TRUE(value.find(100) != value.end()); + EXPECT_TRUE(value.find(204) != value.end()); + EXPECT_TRUE(value.find(212) != value.end()); +} diff --git a/nav2_bringup/params/nav2_params.yaml b/nav2_bringup/params/nav2_params.yaml index 4d8412a61e8..019bbb3946c 100644 --- a/nav2_bringup/params/nav2_params.yaml +++ b/nav2_bringup/params/nav2_params.yaml @@ -70,6 +70,10 @@ bt_navigator: - nav2_goal_updated_condition_bt_node - nav2_globally_updated_goal_condition_bt_node - nav2_is_path_valid_condition_bt_node + - nav2_are_error_codes_active_condition_bt_node + - nav2_would_a_controller_recovery_help_condition_bt_node + - nav2_would_a_planner_recovery_help_condition_bt_node + - nav2_would_a_smoother_recovery_help_condition_bt_node - nav2_initial_pose_received_condition_bt_node - nav2_reinitialize_global_localization_service_bt_node - nav2_rate_controller_bt_node diff --git a/nav2_bt_navigator/behavior_trees/navigate_to_pose_w_replanning_and_recovery.xml b/nav2_bt_navigator/behavior_trees/navigate_to_pose_w_replanning_and_recovery.xml index d50bd7fe5df..07d3a363989 100644 --- a/nav2_bt_navigator/behavior_trees/navigate_to_pose_w_replanning_and_recovery.xml +++ b/nav2_bt_navigator/behavior_trees/navigate_to_pose_w_replanning_and_recovery.xml @@ -11,26 +11,38 @@ - + + + + - + + + + - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + diff --git a/nav2_bt_navigator/src/bt_navigator.cpp b/nav2_bt_navigator/src/bt_navigator.cpp index 206c3965636..4d9fcfec7c2 100644 --- a/nav2_bt_navigator/src/bt_navigator.cpp +++ b/nav2_bt_navigator/src/bt_navigator.cpp @@ -49,6 +49,10 @@ BtNavigator::BtNavigator(const rclcpp::NodeOptions & options) "nav2_goal_updated_condition_bt_node", "nav2_globally_updated_goal_condition_bt_node", "nav2_is_path_valid_condition_bt_node", + "nav2_are_error_codes_active_condition_bt_node", + "nav2_would_a_controller_recovery_help_condition_bt_node", + "nav2_would_a_planner_recovery_help_condition_bt_node", + "nav2_would_a_smoother_recovery_help_condition_bt_node", "nav2_reinitialize_global_localization_service_bt_node", "nav2_rate_controller_bt_node", "nav2_distance_controller_bt_node", diff --git a/nav2_msgs/action/ComputePathToPose.action b/nav2_msgs/action/ComputePathToPose.action index 5abf2e6826b..920bcf5ff24 100644 --- a/nav2_msgs/action/ComputePathToPose.action +++ b/nav2_msgs/action/ComputePathToPose.action @@ -3,7 +3,7 @@ uint16 NONE=0 uint16 UNKNOWN=200 uint16 INVALID_PLANNER=201 -uint16 TF_ERROR=2002 +uint16 TF_ERROR=202 uint16 START_OUTSIDE_MAP=203 uint16 GOAL_OUTSIDE_MAP=204 uint16 START_OCCUPIED=205 diff --git a/nav2_system_tests/src/behavior_tree/dummy_servers.hpp b/nav2_system_tests/src/behavior_tree/dummy_action_server.hpp similarity index 66% rename from nav2_system_tests/src/behavior_tree/dummy_servers.hpp rename to nav2_system_tests/src/behavior_tree/dummy_action_server.hpp index ce8d26599e1..d478885eaf2 100644 --- a/nav2_system_tests/src/behavior_tree/dummy_servers.hpp +++ b/nav2_system_tests/src/behavior_tree/dummy_action_server.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. Reserved. -#ifndef BEHAVIOR_TREE__DUMMY_SERVERS_HPP_ -#define BEHAVIOR_TREE__DUMMY_SERVERS_HPP_ +#ifndef BEHAVIOR_TREE__DUMMY_ACTION_SERVER_HPP_ +#define BEHAVIOR_TREE__DUMMY_ACTION_SERVER_HPP_ #include #include @@ -24,75 +24,15 @@ #include "rclcpp_action/rclcpp_action.hpp" #include "rclcpp/rclcpp.hpp" +namespace nav2_system_tests +{ + using namespace std::chrono_literals; // NOLINT using namespace std::chrono; // NOLINT using namespace std::placeholders; // NOLINT -template -class DummyService -{ -public: - explicit DummyService( - const rclcpp::Node::SharedPtr & node, - std::string service_name) - : node_(node), - service_name_(service_name), - request_count_(0), - disabled_(false) - { - server_ = node->create_service( - service_name, - std::bind(&DummyService::handle_service, this, _1, _2, _3)); - } - - void disable() - { - server_.reset(); - disabled_ = true; - } - - void enable() - { - if (disabled_) { - server_ = node_->create_service( - service_name_, - std::bind(&DummyService::handle_service, this, _1, _2, _3)); - disabled_ = false; - } - } - - void reset() - { - enable(); - request_count_ = 0; - } - - int getRequestCount() const - { - return request_count_; - } - -protected: - virtual void fillResponse( - const std::shared_ptr/*request*/, - const std::shared_ptr/*response*/) {} - - void handle_service( - const std::shared_ptr/*request_header*/, - const std::shared_ptr request, - const std::shared_ptr response) - { - request_count_++; - fillResponse(request, response); - } - -private: - rclcpp::Node::SharedPtr node_; - typename rclcpp::Service::SharedPtr server_; - std::string service_name_; - int request_count_; - bool disabled_; -}; +using Range = std::pair; +using Ranges = std::vector; template class DummyActionServer @@ -104,7 +44,7 @@ class DummyActionServer : action_name_(action_name), goal_count_(0) { - this->action_server_ = rclcpp_action::create_server( + action_server_ = rclcpp_action::create_server( node->get_node_base_interface(), node->get_node_clock_interface(), node->get_node_logging_interface(), @@ -115,12 +55,12 @@ class DummyActionServer std::bind(&DummyActionServer::handle_accepted, this, _1)); } - void setFailureRanges(const std::vector> & failureRanges) + void setFailureRanges(const Ranges & failureRanges) { failure_ranges_ = failureRanges; } - void setRunningRanges(const std::vector> & runningRanges) + void setRunningRanges(const Ranges & runningRanges) { running_ranges_ = runningRanges; } @@ -143,6 +83,14 @@ class DummyActionServer return std::make_shared(); } + virtual void updateResultForFailure(std::shared_ptr &) + { + } + + virtual void updateResultForSuccess(std::shared_ptr &) + { + } + virtual rclcpp_action::GoalResponse handle_goal( const rclcpp_action::GoalUUID &, std::shared_ptr/*goal*/) @@ -174,12 +122,14 @@ class DummyActionServer // if current goal index exists in failure range, the goal will be aborted for (auto & index : failure_ranges_) { if (goal_count_ >= index.first && goal_count_ <= index.second) { + updateResultForFailure(result); goal_handle->abort(result); return; } } // goal succeeds for all other indices + updateResultForSuccess(result); goal_handle->succeed(result); } @@ -198,10 +148,11 @@ class DummyActionServer // contains pairs of indices which define a range for which the // requested action goal will return running for 1s or be aborted // for all other indices, the action server will return success - std::vector> failure_ranges_; - std::vector> running_ranges_; + Ranges failure_ranges_; + Ranges running_ranges_; - int goal_count_; + unsigned int goal_count_; }; +} // namespace nav2_system_tests -#endif // BEHAVIOR_TREE__DUMMY_SERVERS_HPP_ +#endif // BEHAVIOR_TREE__DUMMY_ACTION_SERVER_HPP_ diff --git a/nav2_system_tests/src/behavior_tree/dummy_service.hpp b/nav2_system_tests/src/behavior_tree/dummy_service.hpp new file mode 100644 index 00000000000..ff5d742dd9b --- /dev/null +++ b/nav2_system_tests/src/behavior_tree/dummy_service.hpp @@ -0,0 +1,98 @@ +// Copyright (c) 2020 Sarthak Mittal +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. Reserved. + +#ifndef BEHAVIOR_TREE__DUMMY_SERVICE_HPP_ +#define BEHAVIOR_TREE__DUMMY_SERVICE_HPP_ + +#include +#include +#include +#include +#include + +#include "rclcpp_action/rclcpp_action.hpp" +#include "rclcpp/rclcpp.hpp" + +namespace nav2_system_tests +{ + +template +class DummyService +{ +public: + explicit DummyService( + const rclcpp::Node::SharedPtr & node, + std::string service_name) + : node_(node), + service_name_(service_name), + request_count_(0), + disabled_(false) + { + service_ = node->create_service( + service_name, + std::bind(&DummyService::handle_service, this, _1, _2, _3)); + } + + void disable() + { + service_.reset(); + disabled_ = true; + } + + void enable() + { + if (disabled_) { + service_ = node_->create_service( + service_name_, + std::bind(&DummyService::handle_service, this, _1, _2, _3)); + disabled_ = false; + } + } + + void reset() + { + enable(); + request_count_ = 0; + } + + int getRequestCount() const + { + return request_count_; + } + +protected: + virtual void fillResponse( + const std::shared_ptr/*request*/, + const std::shared_ptr/*response*/) {} + + void handle_service( + const std::shared_ptr/*request_header*/, + const std::shared_ptr request, + const std::shared_ptr response) + { + request_count_++; + fillResponse(request, response); + } + +private: + rclcpp::Node::SharedPtr node_; + typename rclcpp::Service::SharedPtr service_; + std::string service_name_; + int request_count_; + bool disabled_; +}; + +} // namespace nav2_system_tests + +#endif // BEHAVIOR_TREE__DUMMY_SERVICE_HPP_ diff --git a/nav2_system_tests/src/behavior_tree/server_handler.cpp b/nav2_system_tests/src/behavior_tree/server_handler.cpp index 2108f37d58f..b457fa6736f 100644 --- a/nav2_system_tests/src/behavior_tree/server_handler.cpp +++ b/nav2_system_tests/src/behavior_tree/server_handler.cpp @@ -22,6 +22,10 @@ using namespace std::chrono_literals; // NOLINT using namespace std::chrono; // NOLINT +namespace nav2_system_tests +{ + + ServerHandler::ServerHandler() : is_active_(false) { @@ -31,9 +35,8 @@ ServerHandler::ServerHandler() node_, "local_costmap/clear_entirely_local_costmap"); clear_global_costmap_server = std::make_unique>( node_, "global_costmap/clear_entirely_global_costmap"); - compute_path_to_pose_server = std::make_unique(node_); - follow_path_server = std::make_unique>( - node_, "follow_path"); + compute_path_to_pose_server = std::make_unique(node_); + follow_path_server = std::make_unique(node_); spin_server = std::make_unique>( node_, "spin"); wait_server = std::make_unique>( @@ -94,3 +97,5 @@ void ServerHandler::spinThread() { rclcpp::spin(node_); } + +} // namespace nav2_system_tests diff --git a/nav2_system_tests/src/behavior_tree/server_handler.hpp b/nav2_system_tests/src/behavior_tree/server_handler.hpp index f8869ea0374..a85134d4109 100644 --- a/nav2_system_tests/src/behavior_tree/server_handler.hpp +++ b/nav2_system_tests/src/behavior_tree/server_handler.hpp @@ -36,13 +36,17 @@ #include "rclcpp/rclcpp.hpp" -#include "dummy_servers.hpp" +#include "dummy_action_server.hpp" +#include "dummy_service.hpp" -class ComputePathToPoseActionServer +namespace nav2_system_tests +{ + +class DummyComputePathToPoseActionServer : public DummyActionServer { public: - explicit ComputePathToPoseActionServer(const rclcpp::Node::SharedPtr & node) + explicit DummyComputePathToPoseActionServer(const rclcpp::Node::SharedPtr & node) : DummyActionServer(node, "compute_path_to_pose") { result_ = std::make_shared(); @@ -65,10 +69,34 @@ class ComputePathToPoseActionServer return result_; } +protected: + void updateResultForFailure( + std::shared_ptr + & result) override + { + result->error_code = nav2_msgs::action::ComputePathToPose::Goal::TIMEOUT; + } + private: std::shared_ptr result_; }; +class DummyFollowPathActionServer : public DummyActionServer +{ +public: + explicit DummyFollowPathActionServer(const rclcpp::Node::SharedPtr & node) + : DummyActionServer(node, "follow_path") {} + +protected: + void updateResultForFailure( + std::shared_ptr + & result) override + { + result->error_code = nav2_msgs::action::FollowPath::Goal::NO_VALID_CONTROL; + } +}; + + class ServerHandler { public: @@ -89,8 +117,8 @@ class ServerHandler public: std::unique_ptr> clear_local_costmap_server; std::unique_ptr> clear_global_costmap_server; - std::unique_ptr compute_path_to_pose_server; - std::unique_ptr> follow_path_server; + std::unique_ptr compute_path_to_pose_server; + std::unique_ptr follow_path_server; std::unique_ptr> spin_server; std::unique_ptr> wait_server; std::unique_ptr> backup_server; @@ -105,4 +133,6 @@ class ServerHandler std::shared_ptr server_thread_; }; +} // namespace nav2_system_tests + #endif // BEHAVIOR_TREE__SERVER_HANDLER_HPP_ diff --git a/nav2_system_tests/src/behavior_tree/test_behavior_tree_node.cpp b/nav2_system_tests/src/behavior_tree/test_behavior_tree_node.cpp index d7ede55cd18..6be412753f6 100644 --- a/nav2_system_tests/src/behavior_tree/test_behavior_tree_node.cpp +++ b/nav2_system_tests/src/behavior_tree/test_behavior_tree_node.cpp @@ -37,6 +37,9 @@ using namespace std::chrono_literals; namespace fs = boost::filesystem; +namespace nav2_system_tests +{ + class BehaviorTreeHandler { public: @@ -68,6 +71,10 @@ class BehaviorTreeHandler "nav2_goal_updated_condition_bt_node", "nav2_globally_updated_goal_condition_bt_node", "nav2_is_path_valid_condition_bt_node", + "nav2_are_error_codes_active_condition_bt_node", + "nav2_would_a_controller_recovery_help_condition_bt_node", + "nav2_would_a_planner_recovery_help_condition_bt_node", + "nav2_would_a_smoother_recovery_help_condition_bt_node", "nav2_reinitialize_global_localization_service_bt_node", "nav2_rate_controller_bt_node", "nav2_distance_controller_bt_node", @@ -156,6 +163,17 @@ class BehaviorTreeHandler return true; } + std::string generateBTLogFileName() + { + auto end = std::chrono::system_clock::now(); + std::time_t end_time = std::chrono::system_clock::to_time_t(end); + std::string time_str = std::ctime(&end_time); + std::replace(time_str.begin(), time_str.end(), ' ', '_'); + time_str.erase(std::remove(time_str.begin(), time_str.end(), '\n'), time_str.end()); + std::string file_name = "bt_trace_" + time_str + "_.fbl"; + return file_name; + } + public: BT::Blackboard::Ptr blackboard; BT::Tree tree; @@ -272,7 +290,7 @@ TEST_F(BehaviorTreeTestFixture, TestAllSuccess) * RoundRobin triggers Spin, Wait, and BackUp which return FAILURE * RoundRobin returns FAILURE hence RecoveryCallbackk returns FAILURE * Finally NavigateRecovery returns FAILURE - * The behavior tree should also return FAILURE + * The behavior tree should return FAILURE */ TEST_F(BehaviorTreeTestFixture, TestAllFailure) { @@ -283,18 +301,14 @@ TEST_F(BehaviorTreeTestFixture, TestAllFailure) EXPECT_EQ(bt_handler->loadBehaviorTree(bt_file.string()), true); // Set all action server to fail the first 100 times - std::vector> failureRange; - failureRange.emplace_back(std::pair(0, 100)); + Ranges failureRange; + failureRange.emplace_back(Range(0, 100)); server_handler->compute_path_to_pose_server->setFailureRanges(failureRange); server_handler->follow_path_server->setFailureRanges(failureRange); server_handler->spin_server->setFailureRanges(failureRange); server_handler->wait_server->setFailureRanges(failureRange); server_handler->backup_server->setFailureRanges(failureRange); - // Disable services - server_handler->clear_global_costmap_server->disable(); - server_handler->clear_local_costmap_server->disable(); - BT::NodeStatus result = BT::NodeStatus::RUNNING; while (result == BT::NodeStatus::RUNNING) { @@ -305,20 +319,20 @@ TEST_F(BehaviorTreeTestFixture, TestAllFailure) // The final result should be failure EXPECT_EQ(result, BT::NodeStatus::FAILURE); - // Goal count should be 1 since only one goal is sent to ComputePathToPose - EXPECT_EQ(server_handler->compute_path_to_pose_server->getGoalCount(), 1); + // Goal count should be 2 since only two goals are sent to ComputePathToPose + EXPECT_EQ(server_handler->compute_path_to_pose_server->getGoalCount(), 14); // Goal count should be 0 since no goal is sent to FollowPath action server EXPECT_EQ(server_handler->follow_path_server->getGoalCount(), 0); - // All recovery action servers were sent 1 goal - EXPECT_EQ(server_handler->spin_server->getGoalCount(), 1); - EXPECT_EQ(server_handler->wait_server->getGoalCount(), 1); - EXPECT_EQ(server_handler->backup_server->getGoalCount(), 1); + EXPECT_EQ(server_handler->spin_server->getGoalCount(), 5); + EXPECT_EQ(server_handler->wait_server->getGoalCount(), 5); + EXPECT_EQ(server_handler->backup_server->getGoalCount(), 5); - // Service count is 0 since the server was disabled - EXPECT_EQ(server_handler->clear_local_costmap_server->getRequestCount(), 0); - EXPECT_EQ(server_handler->clear_global_costmap_server->getRequestCount(), 0); + // Service count is 1 to try and resolve global planner error + EXPECT_EQ(server_handler->clear_global_costmap_server->getRequestCount(), 13); + + EXPECT_EQ(server_handler->clear_local_costmap_server->getRequestCount(), 6); } /** @@ -339,8 +353,8 @@ TEST_F(BehaviorTreeTestFixture, TestNavigateSubtreeRecoveries) EXPECT_EQ(bt_handler->loadBehaviorTree(bt_file.string()), true); // Set ComputePathToPose and FollowPath action servers to fail for the first action - std::vector> failureRange; - failureRange.emplace_back(std::pair(0, 1)); + Ranges failureRange; + failureRange.emplace_back(Range(0, 1)); server_handler->compute_path_to_pose_server->setFailureRanges(failureRange); server_handler->follow_path_server->setFailureRanges(failureRange); @@ -393,13 +407,13 @@ TEST_F(BehaviorTreeTestFixture, TestNavigateRecoverySimple) EXPECT_EQ(bt_handler->loadBehaviorTree(bt_file.string()), true); // Set ComputePathToPose action server to fail for the first action - std::vector> plannerFailureRange; - plannerFailureRange.emplace_back(std::pair(0, 1)); + Ranges plannerFailureRange; + plannerFailureRange.emplace_back(Range(0, 1)); server_handler->compute_path_to_pose_server->setFailureRanges(plannerFailureRange); // Set FollowPath action server to fail for the first 3 actions - std::vector> controllerFailureRange; - controllerFailureRange.emplace_back(std::pair(0, 3)); + Ranges controllerFailureRange; + controllerFailureRange.emplace_back(Range(0, 3)); server_handler->follow_path_server->setFailureRanges(controllerFailureRange); BT::NodeStatus result = BT::NodeStatus::RUNNING; @@ -431,56 +445,52 @@ TEST_F(BehaviorTreeTestFixture, TestNavigateRecoverySimple) } /** - * Test scenario: + * Test Scenario: * - * ComputePathToPose returns FAILURE on the first try triggering the planner recovery - * ClearGlobalCostmap-Context returns SUCCESS and ComputePathToPose returns FAILURE when retried - * PipelineSequence returns FAILURE and NavigateRecovery triggers RecoveryFallback + * PipelineSequence returns FAILURE and triggers the Recovery subtree + * NavigateRecovery ticks the recovery subtree, WouldAControllerRecoveryHelp returns SUCCESS * GoalUpdated returns FAILURE, RoundRobin triggers ClearingActions Sequence which returns SUCCESS - * RoundRobin returns SUCCESS and RecoveryFallback returns SUCCESS + * RoundRobin returns SUCCESS and the recovery subtree returns SUCCESS * - * PipelineSequence is triggered again and ComputePathToPose returns SUCCESS (retry #1) - * FollowPath returns FAILURE on the first try triggering the controller recovery - * ClearLocalCostmap-Context returns SUCCESS and FollowPath is retried - * FollowPath returns FAILURE again and PipelineSequence returns FAILURE - * NavigateRecovery triggers RecoveryFallback and GoalUpdated returns FAILURE - * RoundRobin triggers Spin which returns FAILURE + * RETRY 1 + * PipelineSequence returns FAILURE and triggers the Recovery subtree + * NavigateRecovery ticks the recovery subtree, WouldAControllerRecoveryHelp returns SUCCESS + * GoalUpdated returns FAILURE, RoundRobin triggers Spin which returns FAILURE * RoundRobin triggers Wait which returns SUCCESS * RoundRobin returns SUCCESS and RecoveryFallback returns SUCCESS * - * PipelineSequence is triggered again and ComputePathToPose returns FAILURE (retry #2) - * ClearGlobalCostmap-Context returns SUCCESS and ComputePathToPose returns FAILURE when retried - * PipelineSequence returns FAILURE NavigateRecovery triggers RecoveryFallback + * RETRY 2 + * PipelineSequence returns FAILURE and triggers the Recovery subtree + * NavigateRecovery ticks the recovery subtree, WouldAControllerRecoveryHelp returns SUCCESS * GoalUpdated returns FAILURE and RoundRobin triggers BackUp which returns FAILURE * RoundRobin triggers ClearingActions Sequence which returns SUCCESS * RoundRobin returns SUCCESS and RecoveryFallback returns SUCCESS * - * PipelineSequence is triggered again and ComputePathToPose returns FAILURE (retry #3) - * ClearGlobalCostmap-Context returns SUCCESS and ComputePathToPose returns FAILURE when retried - * PipelineSequence returns FAILURE NavigateRecovery triggers RecoveryFallback - * GoalUpdated returns FAILURE and RoundRobin triggers Spin which returns SUCCESS + * RETRY 3 + * PipelineSequence returns FAILURE and triggers the Recovery subtree + * NavigateRecovery ticks the recovery subtree, WouldAControllerRecoveryHelp returns SUCCESS + * GoalUpdated returns FAILURE and RoundRobin triggers ClearingActions which returns SUCCESS * RoundRobin returns SUCCESS and RecoveryFallback returns SUCCESS * - * PipelineSequence is triggered again and ComputePathToPose returns FAILURE (retry #4) - * ClearGlobalCostmap-Context returns SUCCESS and ComputePathToPose returns FAILURE when retried - * PipelineSequence returns FAILURE NavigateRecovery triggers RecoveryFallback - * GoalUpdated returns FAILURE and RoundRobin triggers Wait which returns FAILURE - * RoundRobin triggers BackUp which returns SUCCESS - * RoundRobin returns SUCCESS and RecoveryFallback returns SUCCESS + * RETRY 4 + * PipelineSequence returns FAILURE and triggers the Recovery subtree + * NavigateRecovery ticks the recovery subtree, WouldAControllerRecoveryHelp returns SUCCESS + * WouldAControllerRecoveryHelp returns SUCCESS + * GoalUpdated returns FAILURE and RoundRobin triggers Spin which returns SUCCESS * - * PipelineSequence is triggered again and ComputePathToPose returns SUCCESS (retry #5) - * FollowPath returns FAILURE on the first try triggering the controller recovery - * ClearLocalCostmap-Context returns SUCCESS and FollowPath is retried - * FollowPath returns FAILURE again and PipelineSequence returns FAILURE - * NavigateRecovery triggers RecoveryFallback and GoalUpdated returns FAILURE - * RoundRobin triggers ClearingActions Sequence which returns SUCCESS - * RoundRobin returns SUCCESS and RecoveryFallback returns SUCCESS + * RETRY 5 + * PipelineSequence returns FAILURE and triggers the Recovery subtree + * NavigateRecovery ticks the recovery subtree, WouldAControllerRecoveryHelp returns SUCCESS + * GoalUpdated returns FAILURE and RoundRobin triggers Wait which returns SUCCESS + * RoundRobin triggers BackUp which returns SUCCESS * - * PipelineSequence is triggered again and ComputePathToPose returns FAILURE (retry #6) + * RETRY 6 + * ComputePathToPose returns FAILURE on the first try triggering the planner recovery * ClearGlobalCostmap-Context returns SUCCESS and ComputePathToPose returns FAILURE when retried * PipelineSequence returns FAILURE and NavigateRecovery finally also returns FAILURE * * The behavior tree should return FAILURE + * */ TEST_F(BehaviorTreeTestFixture, TestNavigateRecoveryComplex) { @@ -490,33 +500,16 @@ TEST_F(BehaviorTreeTestFixture, TestNavigateRecoveryComplex) bt_file /= "navigate_to_pose_w_replanning_and_recovery.xml"; EXPECT_EQ(bt_handler->loadBehaviorTree(bt_file.string()), true); - // Set ComputePathToPose action server to fail for the first 2 actions - std::vector> plannerFailureRange; - plannerFailureRange.emplace_back(std::pair(0, 2)); - plannerFailureRange.emplace_back(std::pair(4, 9)); - plannerFailureRange.emplace_back(std::pair(11, 12)); - server_handler->compute_path_to_pose_server->setFailureRanges(plannerFailureRange); - // Set FollowPath action server to fail for the first 2 actions - std::vector> controllerFailureRange; - controllerFailureRange.emplace_back(std::pair(0, 4)); + Ranges controllerFailureRange; + controllerFailureRange.emplace_back(Range(0, 14)); server_handler->follow_path_server->setFailureRanges(controllerFailureRange); // Set Spin action server to fail for the first action - std::vector> spinFailureRange; - spinFailureRange.emplace_back(std::pair(0, 1)); + Ranges spinFailureRange; + spinFailureRange.emplace_back(Range(0, 1)); server_handler->spin_server->setFailureRanges(spinFailureRange); - // Set Wait action server to fail for the first action - std::vector> waitFailureRange; - waitFailureRange.emplace_back(std::pair(2, 2)); - server_handler->wait_server->setFailureRanges(waitFailureRange); - - // Set BackUp action server to fail for the first action - std::vector> backupFailureRange; - backupFailureRange.emplace_back(std::pair(0, 1)); - server_handler->backup_server->setFailureRanges(backupFailureRange); - BT::NodeStatus result = BT::NodeStatus::RUNNING; while (result == BT::NodeStatus::RUNNING) { @@ -528,38 +521,30 @@ TEST_F(BehaviorTreeTestFixture, TestNavigateRecoveryComplex) EXPECT_EQ(result, BT::NodeStatus::FAILURE); // ComputePathToPose is called 12 times - EXPECT_EQ(server_handler->compute_path_to_pose_server->getGoalCount(), 12); + EXPECT_EQ(server_handler->compute_path_to_pose_server->getGoalCount(), 7); // FollowPath is called 4 times - EXPECT_EQ(server_handler->follow_path_server->getGoalCount(), 4); + EXPECT_EQ(server_handler->follow_path_server->getGoalCount(), 14); // Local costmap is cleared 5 times - EXPECT_EQ(server_handler->clear_local_costmap_server->getRequestCount(), 5); + EXPECT_EQ(server_handler->clear_local_costmap_server->getRequestCount(), 9); // Global costmap is cleared 8 times - EXPECT_EQ(server_handler->clear_global_costmap_server->getRequestCount(), 8); + EXPECT_EQ(server_handler->clear_global_costmap_server->getRequestCount(), 2); // All recovery action servers receive 2 goals EXPECT_EQ(server_handler->spin_server->getGoalCount(), 2); EXPECT_EQ(server_handler->wait_server->getGoalCount(), 2); - EXPECT_EQ(server_handler->backup_server->getGoalCount(), 2); + EXPECT_EQ(server_handler->backup_server->getGoalCount(), 1); } /** * Test scenario: * - * ComputePathToPose returns FAILURE on the first try triggering the planner recovery - * ClearGlobalCostmap-Context returns SUCCESS and ComputePathToPose returns FAILURE when retried - * PipelineSequence returns FAILURE and NavigateRecovery triggers RecoveryFallback - * GoalUpdated returns FAILURE, RoundRobin triggers ClearingActions Sequence which returns SUCCESS - * RoundRobin returns SUCCESS and RecoveryFallback returns SUCCESS - * PipelineSequence is triggered again and ComputePathToPose returns SUCCESS - * FollowPath returns FAILURE on the first try triggering the controller recovery - * ClearLocalCostmap-Context returns SUCCESS and FollowPath is retried - * FollowPath returns FAILURE and PipelineSequence returns FAILURE - * NavigateRecovery triggers RecoveryFallback which triggers GoalUpdated - * GoalUpdated returns FAILURE and RecoveryFallback triggers RoundRobin - * RoundRobin triggers Spin which returns RUNNING + * The PipelineSequence return FAILURE due to FollowPath returning FAILURE + * The NavigateRecovery triggers the recovery sub tree which returns SUCCESS + * The PipelineSequence return FAILURE due to FollowPath returning FAILURE + * The NavigateRecovery triggers the recovery sub tree which ticks the Spin recovery * * At this point a new goal is updated on the blackboard * @@ -579,19 +564,14 @@ TEST_F(BehaviorTreeTestFixture, TestRecoverySubtreeGoalUpdated) bt_file /= "navigate_to_pose_w_replanning_and_recovery.xml"; EXPECT_EQ(bt_handler->loadBehaviorTree(bt_file.string()), true); - // Set ComputePathToPose action server to fail for the first 2 actions - std::vector> plannerFailureRange; - plannerFailureRange.emplace_back(std::pair(0, 2)); - server_handler->compute_path_to_pose_server->setFailureRanges(plannerFailureRange); - // Set FollowPath action server to fail for the first 2 actions - std::vector> controllerFailureRange; - controllerFailureRange.emplace_back(std::pair(0, 2)); + Ranges controllerFailureRange; + controllerFailureRange.emplace_back(Range(0, 4)); server_handler->follow_path_server->setFailureRanges(controllerFailureRange); // Set Spin action server to return running for the first action - std::vector> spinRunningRange; - spinRunningRange.emplace_back(std::pair(1, 1)); + Ranges spinRunningRange; + spinRunningRange.emplace_back(Range(1, 1)); server_handler->spin_server->setRunningRanges(spinRunningRange); BT::NodeStatus result = BT::NodeStatus::RUNNING; @@ -620,16 +600,16 @@ TEST_F(BehaviorTreeTestFixture, TestRecoverySubtreeGoalUpdated) EXPECT_EQ(result, BT::NodeStatus::SUCCESS); // ComputePathToPose is called 4 times - EXPECT_EQ(server_handler->compute_path_to_pose_server->getGoalCount(), 4); + EXPECT_EQ(server_handler->compute_path_to_pose_server->getGoalCount(), 3); // FollowPath is called 3 times - EXPECT_EQ(server_handler->follow_path_server->getGoalCount(), 3); + EXPECT_EQ(server_handler->follow_path_server->getGoalCount(), 5); // Local costmap is cleared 2 times - EXPECT_EQ(server_handler->clear_local_costmap_server->getRequestCount(), 2); + EXPECT_EQ(server_handler->clear_local_costmap_server->getRequestCount(), 3); // Global costmap is cleared 2 times - EXPECT_EQ(server_handler->clear_global_costmap_server->getRequestCount(), 2); + EXPECT_EQ(server_handler->clear_global_costmap_server->getRequestCount(), 1); // Spin server receives 1 action EXPECT_EQ(server_handler->spin_server->getGoalCount(), 1); @@ -639,6 +619,8 @@ TEST_F(BehaviorTreeTestFixture, TestRecoverySubtreeGoalUpdated) EXPECT_EQ(server_handler->backup_server->getGoalCount(), 0); } +} // namespace nav2_system_tests + int main(int argc, char ** argv) { ::testing::InitGoogleTest(&argc, argv); diff --git a/nav2_system_tests/src/costmap_filters/keepout_params.yaml b/nav2_system_tests/src/costmap_filters/keepout_params.yaml index 94cd7553e03..2b05867ac4b 100644 --- a/nav2_system_tests/src/costmap_filters/keepout_params.yaml +++ b/nav2_system_tests/src/costmap_filters/keepout_params.yaml @@ -59,6 +59,9 @@ bt_navigator: - nav2_drive_on_heading_bt_node - nav2_clear_costmap_service_bt_node - nav2_is_stuck_condition_bt_node + - nav2_are_error_codes_active_condition_bt_node + - nav2_would_a_controller_recovery_help_condition_bt_node + - nav2_would_a_planner_recovery_help_condition_bt_node - nav2_goal_reached_condition_bt_node - nav2_goal_updated_condition_bt_node - nav2_is_path_valid_condition_bt_node diff --git a/nav2_system_tests/src/costmap_filters/speed_global_params.yaml b/nav2_system_tests/src/costmap_filters/speed_global_params.yaml index e9e0c4550b4..b50098a88af 100644 --- a/nav2_system_tests/src/costmap_filters/speed_global_params.yaml +++ b/nav2_system_tests/src/costmap_filters/speed_global_params.yaml @@ -59,6 +59,9 @@ bt_navigator: - nav2_drive_on_heading_bt_node - nav2_clear_costmap_service_bt_node - nav2_is_stuck_condition_bt_node + - nav2_are_error_codes_active_condition_bt_node + - nav2_would_a_controller_recovery_help_condition_bt_node + - nav2_would_a_planner_recovery_help_condition_bt_node - nav2_goal_reached_condition_bt_node - nav2_goal_updated_condition_bt_node - nav2_globally_updated_goal_condition_bt_node diff --git a/nav2_system_tests/src/costmap_filters/speed_local_params.yaml b/nav2_system_tests/src/costmap_filters/speed_local_params.yaml index b2a8f82eb29..d87990bde1d 100644 --- a/nav2_system_tests/src/costmap_filters/speed_local_params.yaml +++ b/nav2_system_tests/src/costmap_filters/speed_local_params.yaml @@ -59,6 +59,9 @@ bt_navigator: - nav2_drive_on_heading_bt_node - nav2_clear_costmap_service_bt_node - nav2_is_stuck_condition_bt_node + - nav2_are_error_codes_active_condition_bt_node + - nav2_would_a_controller_recovery_help_condition_bt_node + - nav2_would_a_planner_recovery_help_condition_bt_node - nav2_goal_reached_condition_bt_node - nav2_goal_updated_condition_bt_node - nav2_globally_updated_goal_condition_bt_node