From d51a2d3e444f5a393c511f9843903d3be64f8422 Mon Sep 17 00:00:00 2001 From: Sarthak Mittal <sarthakmittal2608@gmail.com> Date: Tue, 23 Jun 2020 07:42:31 +0530 Subject: [PATCH] Fix logic in RoundRobinNode and RecoveryNode and add unit tests (#1823) * Fix recovery node test Signed-off-by: Sarthak Mittal <sarthakmittal2608@gmail.com> * Fix round robin logic and add unit tests Signed-off-by: Sarthak Mittal <sarthakmittal2608@gmail.com> --- .../plugins/control/round_robin_node.hpp | 70 ++++++++++ .../plugins/control/recovery_node.cpp | 4 +- .../plugins/control/round_robin_node.cpp | 81 ++++++----- .../test/plugins/control/CMakeLists.txt | 4 + .../plugins/control/test_recovery_node.cpp | 73 +++++----- .../plugins/control/test_round_robin_node.cpp | 130 ++++++++++++++++++ 6 files changed, 286 insertions(+), 76 deletions(-) create mode 100644 nav2_behavior_tree/include/nav2_behavior_tree/plugins/control/round_robin_node.hpp create mode 100644 nav2_behavior_tree/test/plugins/control/test_round_robin_node.cpp diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/control/round_robin_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/control/round_robin_node.hpp new file mode 100644 index 00000000..8ebc2ab2 --- /dev/null +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/control/round_robin_node.hpp @@ -0,0 +1,70 @@ +// Copyright (c) 2019 Intel Corporation +// +// 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__CONTROL__ROUND_ROBIN_NODE_HPP_ +#define NAV2_BEHAVIOR_TREE__PLUGINS__CONTROL__ROUND_ROBIN_NODE_HPP_ + +#include <string> + +#include "behaviortree_cpp_v3/control_node.h" +#include "behaviortree_cpp_v3/bt_factory.h" + +namespace nav2_behavior_tree +{ + +/** @brief Type of sequence node that ticks children in a round-robin fashion + * + * Type of Control Node | Child Returns Failure | Child Returns Running + * --------------------------------------------------------------------- + * RoundRobin | Tick Next Child | Return Running + * + * If the current child return failure, the next child is ticked and if the last child returns + * failure, the first child is ticked and the cycle continues until a child returns success + * + * As an example, let's say this node has 3 children: A, B and C. At the start, + * they are all IDLE. + * | A | B | C | + * -------------------------------- + * | IDLE | IDLE | IDLE | + * | RUNNING | IDLE | IDLE | - at first A gets ticked. Assume it returns RUNNING + * - RoundRobin returns RUNNING and no other nodes are ticked. + * | FAILURE | RUNNING | IDLE | - A returns FAILURE so B gets ticked and returns RUNNING + * - RoundRobin returns RUNNING and C is not ticked yet + * | FAILURE | SUCCESS | IDLE | - B returns SUCCESS, so RoundRobin halts all children and + * - returns SUCCESS, next iteration will tick C. + * | RUNNING | IDLE | FAILURE | - C returns FAILURE, so RoundRobin circles and ticks A. + * - A returns RUNNING, so RoundRobin returns RUNNING. + * + * If all children return FAILURE, RoundRobin will return FAILURE + * and halt all children, ending the sequence. + * + * Usage in XML: <RoundRobin> + */ +class RoundRobinNode : public BT::ControlNode +{ +public: + explicit RoundRobinNode(const std::string & name); + RoundRobinNode(const std::string & name, const BT::NodeConfiguration & config); + BT::NodeStatus tick() override; + void halt() override; + static BT::PortsList providedPorts() {return {};} + +private: + unsigned int current_child_idx_{0}; + unsigned int num_failed_children_{0}; +}; + +} // namespace nav2_behavior_tree + +#endif // NAV2_BEHAVIOR_TREE__PLUGINS__CONTROL__ROUND_ROBIN_NODE_HPP_ diff --git a/nav2_behavior_tree/plugins/control/recovery_node.cpp b/nav2_behavior_tree/plugins/control/recovery_node.cpp index 976aaeee..bfe6ac6a 100644 --- a/nav2_behavior_tree/plugins/control/recovery_node.cpp +++ b/nav2_behavior_tree/plugins/control/recovery_node.cpp @@ -39,7 +39,7 @@ BT::NodeStatus RecoveryNode::tick() setStatus(BT::NodeStatus::RUNNING); - while (current_child_idx_ < children_count && retry_count_ < number_of_retries_) { + while (current_child_idx_ < children_count && retry_count_ <= number_of_retries_) { TreeNode * child_node = children_nodes_[current_child_idx_]; const BT::NodeStatus child_status = child_node->executeTick(); @@ -55,7 +55,7 @@ BT::NodeStatus RecoveryNode::tick() case BT::NodeStatus::FAILURE: { // tick second child - if (retry_count_ <= number_of_retries_) { + if (retry_count_ < number_of_retries_) { current_child_idx_++; break; } else { diff --git a/nav2_behavior_tree/plugins/control/round_robin_node.cpp b/nav2_behavior_tree/plugins/control/round_robin_node.cpp index be85e75e..135ea09b 100644 --- a/nav2_behavior_tree/plugins/control/round_robin_node.cpp +++ b/nav2_behavior_tree/plugins/control/round_robin_node.cpp @@ -14,65 +14,76 @@ #include <string> -#include "behaviortree_cpp_v3/control_node.h" -#include "behaviortree_cpp_v3/bt_factory.h" +#include "nav2_behavior_tree/plugins/control/round_robin_node.hpp" namespace nav2_behavior_tree { -class RoundRobinNode : public BT::ControlNode +RoundRobinNode::RoundRobinNode(const std::string & name) +: BT::ControlNode::ControlNode(name, {}) { -public: - explicit RoundRobinNode(const std::string & name) - : BT::ControlNode::ControlNode(name, {}) - { - setRegistrationID("RoundRobin"); - } +} + +RoundRobinNode::RoundRobinNode( + const std::string & name, + const BT::NodeConfiguration & config) +: BT::ControlNode(name, config) +{ +} - BT::NodeStatus tick() override - { - const unsigned num_children = children_nodes_.size(); +BT::NodeStatus RoundRobinNode::tick() +{ + const auto num_children = children_nodes_.size(); - setStatus(BT::NodeStatus::RUNNING); + setStatus(BT::NodeStatus::RUNNING); + while (num_failed_children_ < num_children) { TreeNode * child_node = children_nodes_[current_child_idx_]; const BT::NodeStatus child_status = child_node->executeTick(); switch (child_status) { case BT::NodeStatus::SUCCESS: - // Wrap around to the first child - if (++current_child_idx_ == num_children) { - // TODO(mjeronimo): halt this child (not all children) - current_child_idx_ = 0; + { + // Wrap around to the first child + if (++current_child_idx_ >= num_children) { + current_child_idx_ = 0; + } + num_failed_children_ = 0; + ControlNode::haltChildren(); + return BT::NodeStatus::SUCCESS; } - ControlNode::haltChildren(); - return BT::NodeStatus::SUCCESS; - case BT::NodeStatus::FAILURE: - ControlNode::haltChildren(); - return BT::NodeStatus::FAILURE; + { + if (++current_child_idx_ >= num_children) { + current_child_idx_ = 0; + } + num_failed_children_++; + break; + } case BT::NodeStatus::RUNNING: - break; + { + return BT::NodeStatus::RUNNING; + } default: - throw BT::LogicError("Invalid status return from BT node"); - break; + { + throw BT::LogicError("Invalid status return from BT node"); + } } - - return BT::NodeStatus::RUNNING; } - void halt() override - { - ControlNode::halt(); - current_child_idx_ = 0; - } + halt(); + return BT::NodeStatus::FAILURE; +} -private: - unsigned int current_child_idx_{0}; -}; +void RoundRobinNode::halt() +{ + ControlNode::halt(); + current_child_idx_ = 0; + num_failed_children_ = 0; +} } // namespace nav2_behavior_tree diff --git a/nav2_behavior_tree/test/plugins/control/CMakeLists.txt b/nav2_behavior_tree/test/plugins/control/CMakeLists.txt index 2a54289b..16138305 100644 --- a/nav2_behavior_tree/test/plugins/control/CMakeLists.txt +++ b/nav2_behavior_tree/test/plugins/control/CMakeLists.txt @@ -5,3 +5,7 @@ ament_target_dependencies(test_control_recovery_node ${dependencies}) ament_add_gtest(test_control_pipeline_sequence test_pipeline_sequence.cpp) target_link_libraries(test_control_pipeline_sequence nav2_pipeline_sequence_bt_node) ament_target_dependencies(test_control_pipeline_sequence ${dependencies}) + +ament_add_gtest(test_control_round_robin_node test_round_robin_node.cpp) +target_link_libraries(test_control_round_robin_node nav2_round_robin_node_bt_node) +ament_target_dependencies(test_control_round_robin_node ${dependencies}) diff --git a/nav2_behavior_tree/test/plugins/control/test_recovery_node.cpp b/nav2_behavior_tree/test/plugins/control/test_recovery_node.cpp index 2307b4ec..8356a006 100644 --- a/nav2_behavior_tree/test/plugins/control/test_recovery_node.cpp +++ b/nav2_behavior_tree/test/plugins/control/test_recovery_node.cpp @@ -20,6 +20,29 @@ #include "../../test_dummy_tree_node.hpp" #include "nav2_behavior_tree/plugins/control/recovery_node.hpp" +// Changes status to SUCCESS after a specified number of failures +class RecoveryDummy : public nav2_behavior_tree::DummyNode +{ +public: + BT::NodeStatus tick() override + { + if (++ticks_ > num_failures_ && num_failures_ != -1) { + setStatus(BT::NodeStatus::SUCCESS); + } + return status(); + } + + void setMaxFailures(int max_failures) + { + num_failures_ = max_failures; + ticks_ = 0; + } + +private: + int ticks_{0}; + int num_failures_{-1}; +}; + class RecoveryNodeTestFixture : public nav2_behavior_tree::BehaviorTreeTestFixture { public: @@ -27,8 +50,8 @@ public: { bt_node_ = std::make_shared<nav2_behavior_tree::RecoveryNode>( "recovery_node", *config_); - first_child_ = std::make_shared<nav2_behavior_tree::DummyNode>(); - second_child_ = std::make_shared<nav2_behavior_tree::DummyNode>(); + first_child_ = std::make_shared<RecoveryDummy>(); + second_child_ = std::make_shared<RecoveryDummy>(); bt_node_->addChild(first_child_.get()); bt_node_->addChild(second_child_.get()); } @@ -42,13 +65,13 @@ public: protected: static std::shared_ptr<nav2_behavior_tree::RecoveryNode> bt_node_; - static std::shared_ptr<nav2_behavior_tree::DummyNode> first_child_; - static std::shared_ptr<nav2_behavior_tree::DummyNode> second_child_; + static std::shared_ptr<RecoveryDummy> first_child_; + static std::shared_ptr<RecoveryDummy> second_child_; }; std::shared_ptr<nav2_behavior_tree::RecoveryNode> RecoveryNodeTestFixture::bt_node_ = nullptr; -std::shared_ptr<nav2_behavior_tree::DummyNode> RecoveryNodeTestFixture::first_child_ = nullptr; -std::shared_ptr<nav2_behavior_tree::DummyNode> RecoveryNodeTestFixture::second_child_ = nullptr; +std::shared_ptr<RecoveryDummy> RecoveryNodeTestFixture::first_child_ = nullptr; +std::shared_ptr<RecoveryDummy> RecoveryNodeTestFixture::second_child_ = nullptr; TEST_F(RecoveryNodeTestFixture, test_only_two_children) { @@ -71,68 +94,40 @@ TEST_F(RecoveryNodeTestFixture, test_failure_on_idle_child) first_child_->changeStatus(BT::NodeStatus::IDLE); EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::FAILURE); first_child_->changeStatus(BT::NodeStatus::FAILURE); - EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::FAILURE); second_child_->changeStatus(BT::NodeStatus::IDLE); EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::FAILURE); } -TEST_F(RecoveryNodeTestFixture, test_success) +TEST_F(RecoveryNodeTestFixture, test_success_one_retry) { // first child returns success right away first_child_->changeStatus(BT::NodeStatus::SUCCESS); EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::SUCCESS); - // first child fails, second child succeeds, then first child succeeds - first_child_->changeStatus(BT::NodeStatus::FAILURE); - EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::FAILURE); - second_child_->changeStatus(BT::NodeStatus::SUCCESS); - EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::FAILURE); - first_child_->changeStatus(BT::NodeStatus::SUCCESS); - EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::SUCCESS); - EXPECT_EQ(bt_node_->status(), BT::NodeStatus::SUCCESS); - EXPECT_EQ(first_child_->status(), BT::NodeStatus::IDLE); - EXPECT_EQ(second_child_->status(), BT::NodeStatus::IDLE); - - // first child fails, second child succeeds, then first child fails, - // second child succeeds, and first child succeeds (one retry) + // first child fails, second child succeeds, then first child succeeds (one retry) + first_child_->setMaxFailures(1); first_child_->changeStatus(BT::NodeStatus::FAILURE); - EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::FAILURE); second_child_->changeStatus(BT::NodeStatus::SUCCESS); - EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::FAILURE); - first_child_->changeStatus(BT::NodeStatus::FAILURE); - EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::FAILURE); - second_child_->changeStatus(BT::NodeStatus::SUCCESS); - EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::FAILURE); - first_child_->changeStatus(BT::NodeStatus::SUCCESS); EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::SUCCESS); EXPECT_EQ(bt_node_->status(), BT::NodeStatus::SUCCESS); EXPECT_EQ(first_child_->status(), BT::NodeStatus::IDLE); EXPECT_EQ(second_child_->status(), BT::NodeStatus::IDLE); } -TEST_F(RecoveryNodeTestFixture, test_failure) +TEST_F(RecoveryNodeTestFixture, test_failure_one_retry) { // first child fails, second child fails first_child_->changeStatus(BT::NodeStatus::FAILURE); - EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::FAILURE); second_child_->changeStatus(BT::NodeStatus::FAILURE); EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::FAILURE); EXPECT_EQ(bt_node_->status(), BT::NodeStatus::FAILURE); EXPECT_EQ(first_child_->status(), BT::NodeStatus::IDLE); EXPECT_EQ(second_child_->status(), BT::NodeStatus::IDLE); - // first child fails, second child succeeds, then first child fails, - // second child succeeds, and first child fails again (one retry) + // first child fails, second child succeeds, then first child fails (one retry) first_child_->changeStatus(BT::NodeStatus::FAILURE); - EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::FAILURE); second_child_->changeStatus(BT::NodeStatus::SUCCESS); EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::FAILURE); - first_child_->changeStatus(BT::NodeStatus::FAILURE); - EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::FAILURE); - second_child_->changeStatus(BT::NodeStatus::SUCCESS); - EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::FAILURE); - first_child_->changeStatus(BT::NodeStatus::FAILURE); - EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::FAILURE); EXPECT_EQ(bt_node_->status(), BT::NodeStatus::FAILURE); EXPECT_EQ(first_child_->status(), BT::NodeStatus::IDLE); EXPECT_EQ(second_child_->status(), BT::NodeStatus::IDLE); diff --git a/nav2_behavior_tree/test/plugins/control/test_round_robin_node.cpp b/nav2_behavior_tree/test/plugins/control/test_round_robin_node.cpp new file mode 100644 index 00000000..6baa425b --- /dev/null +++ b/nav2_behavior_tree/test/plugins/control/test_round_robin_node.cpp @@ -0,0 +1,130 @@ +// Copyright (c) 2018 Intel Corporation +// 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. + +#include <gtest/gtest.h> +#include <memory> + +#include "../../test_behavior_tree_fixture.hpp" +#include "../../test_dummy_tree_node.hpp" +#include "nav2_behavior_tree/plugins/control/round_robin_node.hpp" + +class RoundRobinNodeTestFixture : public nav2_behavior_tree::BehaviorTreeTestFixture +{ +public: + void SetUp() override + { + bt_node_ = std::make_shared<nav2_behavior_tree::RoundRobinNode>( + "round_robin", *config_); + first_child_ = std::make_shared<nav2_behavior_tree::DummyNode>(); + second_child_ = std::make_shared<nav2_behavior_tree::DummyNode>(); + third_child_ = std::make_shared<nav2_behavior_tree::DummyNode>(); + bt_node_->addChild(first_child_.get()); + bt_node_->addChild(second_child_.get()); + bt_node_->addChild(third_child_.get()); + } + + void TearDown() override + { + first_child_.reset(); + second_child_.reset(); + third_child_.reset(); + bt_node_.reset(); + } + +protected: + static std::shared_ptr<nav2_behavior_tree::RoundRobinNode> bt_node_; + static std::shared_ptr<nav2_behavior_tree::DummyNode> first_child_; + static std::shared_ptr<nav2_behavior_tree::DummyNode> second_child_; + static std::shared_ptr<nav2_behavior_tree::DummyNode> third_child_; +}; + +std::shared_ptr<nav2_behavior_tree::RoundRobinNode> RoundRobinNodeTestFixture::bt_node_ = nullptr; +std::shared_ptr<nav2_behavior_tree::DummyNode> RoundRobinNodeTestFixture::first_child_ = nullptr; +std::shared_ptr<nav2_behavior_tree::DummyNode> RoundRobinNodeTestFixture::second_child_ = nullptr; +std::shared_ptr<nav2_behavior_tree::DummyNode> RoundRobinNodeTestFixture::third_child_ = nullptr; + +TEST_F(RoundRobinNodeTestFixture, test_failure_on_idle_child) +{ + first_child_->changeStatus(BT::NodeStatus::IDLE); + EXPECT_THROW(bt_node_->executeTick(), BT::LogicError); +} + +TEST_F(RoundRobinNodeTestFixture, test_failure) +{ + first_child_->changeStatus(BT::NodeStatus::FAILURE); + second_child_->changeStatus(BT::NodeStatus::RUNNING); + EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::RUNNING); + + second_child_->changeStatus(BT::NodeStatus::FAILURE); + third_child_->changeStatus(BT::NodeStatus::RUNNING); + EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::RUNNING); + + third_child_->changeStatus(BT::NodeStatus::FAILURE); + EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::FAILURE); + EXPECT_EQ(first_child_->status(), BT::NodeStatus::IDLE); + EXPECT_EQ(second_child_->status(), BT::NodeStatus::IDLE); + EXPECT_EQ(third_child_->status(), BT::NodeStatus::IDLE); +} + +TEST_F(RoundRobinNodeTestFixture, test_behavior) +{ + first_child_->changeStatus(BT::NodeStatus::RUNNING); + second_child_->changeStatus(BT::NodeStatus::IDLE); + third_child_->changeStatus(BT::NodeStatus::IDLE); + EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::RUNNING); + + first_child_->changeStatus(BT::NodeStatus::FAILURE); + second_child_->changeStatus(BT::NodeStatus::RUNNING); + third_child_->changeStatus(BT::NodeStatus::IDLE); + EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::RUNNING); + + first_child_->changeStatus(BT::NodeStatus::FAILURE); + second_child_->changeStatus(BT::NodeStatus::SUCCESS); + third_child_->changeStatus(BT::NodeStatus::IDLE); + EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::SUCCESS); + + first_child_->changeStatus(BT::NodeStatus::IDLE); + second_child_->changeStatus(BT::NodeStatus::IDLE); + third_child_->changeStatus(BT::NodeStatus::RUNNING); + EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::RUNNING); + + first_child_->changeStatus(BT::NodeStatus::RUNNING); + second_child_->changeStatus(BT::NodeStatus::IDLE); + third_child_->changeStatus(BT::NodeStatus::FAILURE); + EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::RUNNING); + + first_child_->changeStatus(BT::NodeStatus::FAILURE); + second_child_->changeStatus(BT::NodeStatus::SUCCESS); + third_child_->changeStatus(BT::NodeStatus::FAILURE); + EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::SUCCESS); + EXPECT_EQ(first_child_->status(), BT::NodeStatus::IDLE); + EXPECT_EQ(second_child_->status(), BT::NodeStatus::IDLE); + EXPECT_EQ(third_child_->status(), BT::NodeStatus::IDLE); +} + +int main(int argc, char ** argv) +{ + ::testing::InitGoogleTest(&argc, argv); + + // initialize ROS + rclcpp::init(argc, argv); + + int all_successful = RUN_ALL_TESTS(); + + // shutdown ROS + rclcpp::shutdown(); + + return all_successful; +} -- GitLab