diff --git a/.gitignore b/.gitignore index 173558e8c0e..88c775d303c 100644 --- a/.gitignore +++ b/.gitignore @@ -46,3 +46,7 @@ __pycache__/ *.py[cod] sphinx_doc/_build + +# CLion artifacts +.idea +cmake-build-debug/ diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp index de94e697e6e..99c0e249a7d 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp @@ -49,6 +49,8 @@ class BtActionNode : public BT::ActionNodeBase node_ = config().blackboard->template get("node"); // Get the required items from the blackboard + bt_loop_duration_ = + config().blackboard->template get("bt_loop_duration"); server_timeout_ = config().blackboard->template get("server_timeout"); getInput("server_timeout", server_timeout_); @@ -174,7 +176,26 @@ class BtActionNode : public BT::ActionNodeBase // user defined callback on_tick(); - on_new_goal_received(); + send_new_goal(); + } + + // if new goal was sent and action server has not yet responded + // check the future goal handle + if (future_goal_handle_) { + auto elapsed = (node_->now() - time_goal_sent_).to_chrono(); + if (!is_future_goal_handle_complete(elapsed)) { + // return RUNNING if there is still some time before timeout happens + if (elapsed < server_timeout_) { + return BT::NodeStatus::RUNNING; + } + // if server has taken more time to respond than the specified timeout value return FAILURE + RCLCPP_WARN( + node_->get_logger(), + "Timed out while waiting for action server to acknowledge goal request for %s", + action_name_.c_str()); + future_goal_handle_.reset(); + return BT::NodeStatus::FAILURE; + } } // The following code corresponds to the "RUNNING" loop @@ -187,7 +208,19 @@ class BtActionNode : public BT::ActionNodeBase goal_status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED)) { goal_updated_ = false; - on_new_goal_received(); + send_new_goal(); + auto elapsed = (node_->now() - time_goal_sent_).to_chrono(); + if (!is_future_goal_handle_complete(elapsed)) { + if (elapsed < server_timeout_) { + return BT::NodeStatus::RUNNING; + } + RCLCPP_WARN( + node_->get_logger(), + "Timed out while waiting for action server to acknowledge goal request for %s", + action_name_.c_str()); + future_goal_handle_.reset(); + return BT::NodeStatus::FAILURE; + } } rclcpp::spin_some(node_); @@ -199,19 +232,26 @@ class BtActionNode : public BT::ActionNodeBase } } + BT::NodeStatus status; switch (result_.code) { case rclcpp_action::ResultCode::SUCCEEDED: - return on_success(); + status = on_success(); + break; case rclcpp_action::ResultCode::ABORTED: - return on_aborted(); + status = on_aborted(); + break; case rclcpp_action::ResultCode::CANCELED: - return on_cancelled(); + status = on_cancelled(); + break; default: throw std::logic_error("BtActionNode::Tick: invalid status value"); } + + goal_handle_.reset(); + return status; } /** @@ -246,6 +286,11 @@ class BtActionNode : public BT::ActionNodeBase return false; } + // No need to cancel the goal if goal handle is invalid + if (!goal_handle_) { + return false; + } + rclcpp::spin_some(node_); auto status = goal_handle_->get_status(); @@ -257,7 +302,7 @@ class BtActionNode : public BT::ActionNodeBase /** * @brief Function to send new goal to action server */ - void on_new_goal_received() + void send_new_goal() { goal_result_available_ = false; auto send_goal_options = typename rclcpp_action::Client::SendGoalOptions(); @@ -272,18 +317,47 @@ class BtActionNode : public BT::ActionNodeBase } }; - auto future_goal_handle = action_client_->async_send_goal(goal_, send_goal_options); + future_goal_handle_ = std::make_shared< + std::shared_future::SharedPtr>>( + action_client_->async_send_goal(goal_, send_goal_options)); + time_goal_sent_ = node_->now(); + } - if (rclcpp::spin_until_future_complete(node_, future_goal_handle, server_timeout_) != - rclcpp::FutureReturnCode::SUCCESS) - { + /** + * @brief Function to check if the action server acknowledged a new goal + * @param elapsed Duration since the last goal was sent and future goal handle has not completed. + * After waiting for the future to complete, this value is incremented with the timeout value. + * @return boolean True if future_goal_handle_ returns SUCCESS, False otherwise + */ + bool is_future_goal_handle_complete(std::chrono::milliseconds & elapsed) + { + auto remaining = server_timeout_ - elapsed; + + // server has already timed out, no need to sleep + if (remaining <= std::chrono::milliseconds(0)) { + future_goal_handle_.reset(); + return false; + } + + auto timeout = remaining > bt_loop_duration_ ? bt_loop_duration_ : remaining; + auto result = rclcpp::spin_until_future_complete(node_, *future_goal_handle_, timeout); + elapsed += timeout; + + if (result == rclcpp::FutureReturnCode::INTERRUPTED) { + future_goal_handle_.reset(); throw std::runtime_error("send_goal failed"); } - goal_handle_ = future_goal_handle.get(); - if (!goal_handle_) { - throw std::runtime_error("Goal was rejected by the action server"); + if (result == rclcpp::FutureReturnCode::SUCCESS) { + goal_handle_ = future_goal_handle_->get(); + future_goal_handle_.reset(); + if (!goal_handle_) { + throw std::runtime_error("Goal was rejected by the action server"); + } + return true; } + + return false; } /** @@ -313,6 +387,14 @@ class BtActionNode : public BT::ActionNodeBase // The timeout value while waiting for response from a server when a // new action goal is sent or canceled std::chrono::milliseconds server_timeout_; + + // The timeout value for BT loop execution + std::chrono::milliseconds bt_loop_duration_; + + // To track the action server acknowledgement when a new goal is sent + std::shared_ptr::SharedPtr>> + future_goal_handle_; + rclcpp::Time time_goal_sent_; }; } // namespace nav2_behavior_tree diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server.hpp index 857df122be4..ec977944418 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server.hpp @@ -225,6 +225,12 @@ class BtActionServer // To publish BT logs std::unique_ptr topic_logger_; + // Duration for each iteration of BT execution + std::chrono::milliseconds bt_loop_duration_; + + // Default timeout value while waiting for response from a server + std::chrono::milliseconds default_server_timeout_; + // Parameters for Groot monitoring bool enable_groot_monitoring_; int groot_zmq_publisher_port_; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp index 82cb5b565a8..8a0faaa93b8 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp @@ -53,6 +53,12 @@ BtActionServer::BtActionServer( clock_ = node->get_clock(); // Declare this node's parameters + if (!node->has_parameter("bt_loop_duration")) { + node->declare_parameter("bt_loop_duration", 10); + } + if (!node->has_parameter("default_server_timeout")) { + node->declare_parameter("default_server_timeout", 20); + } if (!node->has_parameter("enable_groot_monitoring")) { node->declare_parameter("enable_groot_monitoring", true); } @@ -91,6 +97,18 @@ bool BtActionServer::on_configure() node->get_node_waitables_interface(), action_name_, std::bind(&BtActionServer::executeCallback, this)); + // Get parameter for monitoring with Groot via ZMQ Publisher + node->get_parameter("enable_groot_monitoring", enable_groot_monitoring_); + node->get_parameter("groot_zmq_publisher_port", groot_zmq_publisher_port_); + node->get_parameter("groot_zmq_server_port", groot_zmq_server_port_); + + // Get parameters for BT timeouts + int timeout; + node->get_parameter("bt_loop_duration", timeout); + bt_loop_duration_ = std::chrono::milliseconds(timeout); + node->get_parameter("default_server_timeout", timeout); + default_server_timeout_ = std::chrono::milliseconds(timeout); + // Create the class that registers our custom nodes and executes the BT bt_ = std::make_unique(plugin_lib_names_); @@ -99,12 +117,8 @@ bool BtActionServer::on_configure() // Put items on the blackboard blackboard_->set("node", client_node_); // NOLINT - blackboard_->set("server_timeout", std::chrono::milliseconds(10)); // NOLINT - - // Get parameter for monitoring with Groot via ZMQ Publisher - node->get_parameter("enable_groot_monitoring", enable_groot_monitoring_); - node->get_parameter("groot_zmq_publisher_port", groot_zmq_publisher_port_); - node->get_parameter("groot_zmq_server_port", groot_zmq_server_port_); + blackboard_->set("server_timeout", default_server_timeout_); // NOLINT + blackboard_->set("bt_loop_duration", bt_loop_duration_); // NOLINT return true; } @@ -217,7 +231,7 @@ void BtActionServer::executeCallback() }; // Execute the BT that was previously created in the configure step - nav2_behavior_tree::BtStatus rc = bt_->run(&tree_, on_loop, is_canceling); + nav2_behavior_tree::BtStatus rc = bt_->run(&tree_, on_loop, is_canceling, bt_loop_duration_); // Make sure that the Bt is not in a running state from a previous execution // note: if all the ControlNodes are implemented correctly, this is not needed. diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp index c8c3d24637f..366ce0f87b9 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp @@ -31,7 +31,7 @@ namespace nav2_behavior_tree * @tparam ServiceT Type of service */ template -class BtServiceNode : public BT::SyncActionNode +class BtServiceNode : public BT::ActionNodeBase { public: /** @@ -42,11 +42,13 @@ class BtServiceNode : public BT::SyncActionNode BtServiceNode( const std::string & service_node_name, const BT::NodeConfiguration & conf) - : BT::SyncActionNode(service_node_name, conf), service_node_name_(service_node_name) + : BT::ActionNodeBase(service_node_name, conf), service_node_name_(service_node_name) { node_ = config().blackboard->template get("node"); // Get the required items from the blackboard + bt_loop_duration_ = + config().blackboard->template get("bt_loop_duration"); server_timeout_ = config().blackboard->template get("server_timeout"); getInput("server_timeout", server_timeout_); @@ -107,9 +109,22 @@ class BtServiceNode : public BT::SyncActionNode */ BT::NodeStatus tick() override { - on_tick(); - auto future_result = service_client_->async_send_request(request_); - return check_future(future_result); + if (!request_sent_) { + on_tick(); + future_result_ = service_client_->async_send_request(request_); + sent_time_ = node_->now(); + request_sent_ = true; + } + return check_future(); + } + + /** + * @brief The other (optional) override required by a BT service. + */ + void halt() override + { + request_sent_ = false; + setStatus(BT::NodeStatus::IDLE); } /** @@ -122,24 +137,35 @@ class BtServiceNode : public BT::SyncActionNode /** * @brief Check the future and decide the status of BT - * @param future_result shared_future of service response * @return BT::NodeStatus SUCCESS if future complete before timeout, FAILURE otherwise */ - virtual BT::NodeStatus check_future( - std::shared_future future_result) + virtual BT::NodeStatus check_future() { - rclcpp::FutureReturnCode rc; - rc = rclcpp::spin_until_future_complete( - node_, - future_result, server_timeout_); - if (rc == rclcpp::FutureReturnCode::SUCCESS) { - return BT::NodeStatus::SUCCESS; - } else if (rc == rclcpp::FutureReturnCode::TIMEOUT) { - RCLCPP_WARN( - node_->get_logger(), - "Node timed out while executing service call to %s.", service_name_.c_str()); - on_wait_for_result(); + auto elapsed = (node_->now() - sent_time_).to_chrono(); + auto remaining = server_timeout_ - elapsed; + + if (remaining > std::chrono::milliseconds(0)) { + auto timeout = remaining > bt_loop_duration_ ? bt_loop_duration_ : remaining; + + auto rc = rclcpp::spin_until_future_complete(node_, future_result_, timeout); + if (rc == rclcpp::FutureReturnCode::SUCCESS) { + request_sent_ = false; + return BT::NodeStatus::SUCCESS; + } + + if (rc == rclcpp::FutureReturnCode::TIMEOUT) { + on_wait_for_result(); + elapsed = (node_->now() - sent_time_).to_chrono(); + if (elapsed < server_timeout_) { + return BT::NodeStatus::RUNNING; + } + } } + + RCLCPP_WARN( + node_->get_logger(), + "Node timed out while executing service call to %s.", service_name_.c_str()); + request_sent_ = false; return BT::NodeStatus::FAILURE; } @@ -173,6 +199,14 @@ class BtServiceNode : public BT::SyncActionNode // The timeout value while to use in the tick loop while waiting for // a result from the server std::chrono::milliseconds server_timeout_; + + // The timeout value for BT loop execution + std::chrono::milliseconds bt_loop_duration_; + + // To track the server response when a new request is sent + std::shared_future future_result_; + bool request_sent_{false}; + rclcpp::Time sent_time_; }; } // namespace nav2_behavior_tree diff --git a/nav2_behavior_tree/test/plugins/action/CMakeLists.txt b/nav2_behavior_tree/test/plugins/action/CMakeLists.txt index e4ab440d33b..53c5f974fd8 100644 --- a/nav2_behavior_tree/test/plugins/action/CMakeLists.txt +++ b/nav2_behavior_tree/test/plugins/action/CMakeLists.txt @@ -1,3 +1,6 @@ +ament_add_gtest(test_bt_action_node test_bt_action_node.cpp) +ament_target_dependencies(test_bt_action_node ${dependencies}) + ament_add_gtest(test_action_spin_action test_spin_action.cpp) target_link_libraries(test_action_spin_action nav2_spin_action_bt_node) ament_target_dependencies(test_action_spin_action ${dependencies}) diff --git a/nav2_behavior_tree/test/plugins/action/test_back_up_action.cpp b/nav2_behavior_tree/test/plugins/action/test_back_up_action.cpp index 3671fb02f8c..db970202128 100644 --- a/nav2_behavior_tree/test/plugins/action/test_back_up_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_back_up_action.cpp @@ -64,6 +64,9 @@ class BackUpActionTestFixture : public ::testing::Test node_); config_->blackboard->set( "server_timeout", + std::chrono::milliseconds(20)); + config_->blackboard->set( + "bt_loop_duration", std::chrono::milliseconds(10)); config_->blackboard->set("initial_pose_received", false); config_->blackboard->set("number_recoveries", 0); diff --git a/nav2_behavior_tree/test/plugins/action/test_bt_action_node.cpp b/nav2_behavior_tree/test/plugins/action/test_bt_action_node.cpp new file mode 100644 index 00000000000..d95cbd4a848 --- /dev/null +++ b/nav2_behavior_tree/test/plugins/action/test_bt_action_node.cpp @@ -0,0 +1,364 @@ +// 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 +#include +#include +#include +#include +#include + +#include "rclcpp/rclcpp.hpp" +#include "rclcpp_action/rclcpp_action.hpp" + +#include "behaviortree_cpp_v3/bt_factory.h" +#include "nav2_behavior_tree/bt_action_node.hpp" + +#include "test_msgs/action/fibonacci.hpp" + +using namespace std::chrono_literals; // NOLINT +using namespace std::placeholders; // NOLINT + +class FibonacciActionServer : public rclcpp::Node +{ +public: + FibonacciActionServer() + : rclcpp::Node("fibonacci_node", rclcpp::NodeOptions()), + sleep_duration_(0ms) + { + this->action_server_ = rclcpp_action::create_server( + this->get_node_base_interface(), + this->get_node_clock_interface(), + this->get_node_logging_interface(), + this->get_node_waitables_interface(), + "fibonacci", + std::bind(&FibonacciActionServer::handle_goal, this, _1, _2), + std::bind(&FibonacciActionServer::handle_cancel, this, _1), + std::bind(&FibonacciActionServer::handle_accepted, this, _1)); + } + + void setHandleGoalSleepDuration(std::chrono::milliseconds sleep_duration) + { + sleep_duration_ = sleep_duration; + } + +protected: + rclcpp_action::GoalResponse handle_goal( + const rclcpp_action::GoalUUID &, + std::shared_ptr) + { + if (sleep_duration_ > 0ms) { + std::this_thread::sleep_for(sleep_duration_); + } + return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; + } + + rclcpp_action::CancelResponse handle_cancel( + const std::shared_ptr>) + { + return rclcpp_action::CancelResponse::ACCEPT; + } + + void handle_accepted( + const std::shared_ptr> handle) + { + // this needs to return quickly to avoid blocking the executor, so spin up a new thread + if (handle) { + const auto goal = handle->get_goal(); + auto result = std::make_shared(); + + if (goal->order < 0) { + handle->abort(result); + return; + } + + auto & sequence = result->sequence; + sequence.push_back(0); + sequence.push_back(1); + + for (int i = 1; (i < goal->order) && rclcpp::ok(); ++i) { + sequence.push_back(sequence[i] + sequence[i - 1]); + } + + handle->succeed(result); + } + } + +protected: + rclcpp_action::Server::SharedPtr action_server_; + std::chrono::milliseconds sleep_duration_; +}; + +class FibonacciAction : public nav2_behavior_tree::BtActionNode +{ +public: + FibonacciAction( + const std::string & xml_tag_name, + const BT::NodeConfiguration & conf) + : nav2_behavior_tree::BtActionNode(xml_tag_name, "fibonacci", conf) + {} + + void on_tick() override + { + getInput("order", goal_.order); + } + + BT::NodeStatus on_success() override + { + config().blackboard->set>("sequence", result_.result->sequence); + return BT::NodeStatus::SUCCESS; + } + + static BT::PortsList providedPorts() + { + return providedBasicPorts({BT::InputPort("order", "Fibonacci order")}); + } +}; + +class BTActionNodeTestFixture : public ::testing::Test +{ +public: + static void SetUpTestCase() + { + node_ = std::make_shared("bt_action_node_test_fixture"); + factory_ = std::make_shared(); + + config_ = new BT::NodeConfiguration(); + + // Create the blackboard that will be shared by all of the nodes in the tree + config_->blackboard = BT::Blackboard::create(); + // Put items on the blackboard + config_->blackboard->set("node", node_); + config_->blackboard->set("server_timeout", 20ms); + config_->blackboard->set("bt_loop_duration", 10ms); + config_->blackboard->set("initial_pose_received", false); + + BT::NodeBuilder builder = + [](const std::string & name, const BT::NodeConfiguration & config) + { + return std::make_unique(name, config); + }; + + factory_->registerBuilder("Fibonacci", builder); + } + + static void TearDownTestCase() + { + delete config_; + config_ = nullptr; + node_.reset(); + action_server_.reset(); + factory_.reset(); + } + + void SetUp() override + { + // initialize action server and spin on new thread + action_server_ = std::make_shared(); + server_thread_ = std::make_shared( + []() { + while (rclcpp::ok() && BTActionNodeTestFixture::action_server_ != nullptr) { + rclcpp::spin_some(BTActionNodeTestFixture::action_server_); + std::this_thread::sleep_for(100ns); + } + }); + } + + void TearDown() override + { + action_server_.reset(); + tree_.reset(); + server_thread_->join(); + server_thread_.reset(); + } + + static std::shared_ptr action_server_; + +protected: + static rclcpp::Node::SharedPtr node_; + static BT::NodeConfiguration * config_; + static std::shared_ptr factory_; + static std::shared_ptr tree_; + static std::shared_ptr server_thread_; +}; + +rclcpp::Node::SharedPtr BTActionNodeTestFixture::node_ = nullptr; +std::shared_ptr BTActionNodeTestFixture::action_server_ = nullptr; +BT::NodeConfiguration * BTActionNodeTestFixture::config_ = nullptr; +std::shared_ptr BTActionNodeTestFixture::factory_ = nullptr; +std::shared_ptr BTActionNodeTestFixture::tree_ = nullptr; +std::shared_ptr BTActionNodeTestFixture::server_thread_ = nullptr; + +TEST_F(BTActionNodeTestFixture, test_server_timeout_success) +{ + // create tree + std::string xml_txt = + R"( + + + + + )"; + + // the server timeout is larger than the goal handling duration + config_->blackboard->set("server_timeout", 20ms); + config_->blackboard->set("bt_loop_duration", 10ms); + + tree_ = std::make_shared(factory_->createTreeFromText(xml_txt, config_->blackboard)); + + // setting a small action server goal handling duration + action_server_->setHandleGoalSleepDuration(2ms); + + // to keep track of the number of ticks it took to reach a terminal result + int ticks = 0; + + BT::NodeStatus result = BT::NodeStatus::RUNNING; + + // BT loop execution rate + rclcpp::WallRate loopRate(10ms); + + // main BT execution loop + while (rclcpp::ok() && result == BT::NodeStatus::RUNNING) { + result = tree_->tickRoot(); + ticks++; + loopRate.sleep(); + } + + // get calculated fibonacci sequence from blackboard + auto sequence = config_->blackboard->get>("sequence"); + + // expected fibonacci sequence for order 5 + std::vector expected = {0, 1, 1, 2, 3, 5}; + + // since the server timeout was larger than the action server goal handling duration + // the BT should have succeeded + EXPECT_EQ(result, BT::NodeStatus::SUCCESS); + + // checking the output fibonacci sequence + EXPECT_EQ(sequence.size(), expected.size()); + for (size_t i = 0; i < expected.size(); ++i) { + EXPECT_EQ(sequence[i], expected[i]); + } + + // start a new execution cycle with the previous BT to ensure previous state doesn't leak into + // the new cycle + + // halt BT for a new execution cycle + tree_->haltTree(); + + // setting a large action server goal handling duration + action_server_->setHandleGoalSleepDuration(100ms); + + // reset state variables + ticks = 0; + result = BT::NodeStatus::RUNNING; + + // main BT execution loop + while (rclcpp::ok() && result == BT::NodeStatus::RUNNING) { + result = tree_->tickRoot(); + ticks++; + loopRate.sleep(); + } + + // since the server timeout was smaller than the action server goal handling duration + // the BT should have failed + EXPECT_EQ(result, BT::NodeStatus::FAILURE); + + // since the server timeout is 20ms and bt loop duration is 10ms, number of ticks should be 2 + EXPECT_EQ(ticks, 2); +} + +TEST_F(BTActionNodeTestFixture, test_server_timeout_failure) +{ + // create tree + std::string xml_txt = + R"( + + + + + )"; + + // setting a server timeout smaller than the time the action server will take to accept the goal + // to simulate a server timeout scenario + config_->blackboard->set("server_timeout", 90ms); + config_->blackboard->set("bt_loop_duration", 10ms); + + tree_ = std::make_shared(factory_->createTreeFromText(xml_txt, config_->blackboard)); + + // the action server will take 100ms before accepting the goal + action_server_->setHandleGoalSleepDuration(100ms); + + // to keep track of the number of ticks it took to reach a terminal result + int ticks = 0; + + BT::NodeStatus result = BT::NodeStatus::RUNNING; + + // BT loop execution rate + rclcpp::WallRate loopRate(10ms); + + // main BT execution loop + while (rclcpp::ok() && result == BT::NodeStatus::RUNNING) { + result = tree_->tickRoot(); + ticks++; + loopRate.sleep(); + } + + // since the server timeout was smaller than the action server goal handling duration + // the BT should have failed + EXPECT_EQ(result, BT::NodeStatus::FAILURE); + + // since the server timeout is 90ms and bt loop duration is 10ms, number of ticks should be 9 + EXPECT_EQ(ticks, 9); + + // start a new execution cycle with the previous BT to ensure previous state doesn't leak into + // the new cycle + + // halt BT for a new execution cycle + tree_->haltTree(); + + // setting a small action server goal handling duration + action_server_->setHandleGoalSleepDuration(25ms); + + // reset state variables + ticks = 0; + result = BT::NodeStatus::RUNNING; + + // main BT execution loop + while (rclcpp::ok() && result == BT::NodeStatus::RUNNING) { + result = tree_->tickRoot(); + ticks++; + loopRate.sleep(); + } + + // since the server timeout was smaller than the action server goal handling duration + // the BT should have failed + EXPECT_EQ(result, BT::NodeStatus::SUCCESS); +} + +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; +} diff --git a/nav2_behavior_tree/test/plugins/action/test_clear_costmap_service.cpp b/nav2_behavior_tree/test/plugins/action/test_clear_costmap_service.cpp index 17cd7cbb44e..f10177ecffb 100644 --- a/nav2_behavior_tree/test/plugins/action/test_clear_costmap_service.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_clear_costmap_service.cpp @@ -49,6 +49,9 @@ class ClearEntireCostmapServiceTestFixture : public ::testing::Test node_); config_->blackboard->set( "server_timeout", + std::chrono::milliseconds(20)); + config_->blackboard->set( + "bt_loop_duration", std::chrono::milliseconds(10)); config_->blackboard->set("initial_pose_received", false); config_->blackboard->set("number_recoveries", 0); @@ -133,6 +136,9 @@ class ClearCostmapExceptRegionServiceTestFixture : public ::testing::Test config_->blackboard->set( "server_timeout", std::chrono::milliseconds(10)); + config_->blackboard->set( + "bt_loop_duration", + std::chrono::milliseconds(10)); config_->blackboard->set("initial_pose_received", false); config_->blackboard->set("number_recoveries", 0); @@ -222,6 +228,9 @@ class ClearCostmapAroundRobotServiceTestFixture : public ::testing::Test config_->blackboard->set( "server_timeout", std::chrono::milliseconds(10)); + config_->blackboard->set( + "bt_loop_duration", + std::chrono::milliseconds(10)); config_->blackboard->set("initial_pose_received", false); config_->blackboard->set("number_recoveries", 0); diff --git a/nav2_behavior_tree/test/plugins/action/test_compute_path_through_poses_action.cpp b/nav2_behavior_tree/test/plugins/action/test_compute_path_through_poses_action.cpp index fc7cfe36160..122c7646212 100644 --- a/nav2_behavior_tree/test/plugins/action/test_compute_path_through_poses_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_compute_path_through_poses_action.cpp @@ -72,6 +72,9 @@ class ComputePathThroughPosesActionTestFixture : public ::testing::Test node_); config_->blackboard->set( "server_timeout", + std::chrono::milliseconds(20)); + config_->blackboard->set( + "bt_loop_duration", std::chrono::milliseconds(10)); config_->blackboard->set("initial_pose_received", false); diff --git a/nav2_behavior_tree/test/plugins/action/test_compute_path_to_pose_action.cpp b/nav2_behavior_tree/test/plugins/action/test_compute_path_to_pose_action.cpp index 595f88e0e34..5e35a1981de 100644 --- a/nav2_behavior_tree/test/plugins/action/test_compute_path_to_pose_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_compute_path_to_pose_action.cpp @@ -70,6 +70,9 @@ class ComputePathToPoseActionTestFixture : public ::testing::Test node_); config_->blackboard->set( "server_timeout", + std::chrono::milliseconds(20)); + config_->blackboard->set( + "bt_loop_duration", std::chrono::milliseconds(10)); config_->blackboard->set("initial_pose_received", false); diff --git a/nav2_behavior_tree/test/plugins/action/test_follow_path_action.cpp b/nav2_behavior_tree/test/plugins/action/test_follow_path_action.cpp index 9c3c67fe4e7..1325070e000 100644 --- a/nav2_behavior_tree/test/plugins/action/test_follow_path_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_follow_path_action.cpp @@ -63,6 +63,9 @@ class FollowPathActionTestFixture : public ::testing::Test node_); config_->blackboard->set( "server_timeout", + std::chrono::milliseconds(20)); + config_->blackboard->set( + "bt_loop_duration", std::chrono::milliseconds(10)); config_->blackboard->set("initial_pose_received", false); diff --git a/nav2_behavior_tree/test/plugins/action/test_navigate_through_poses_action.cpp b/nav2_behavior_tree/test/plugins/action/test_navigate_through_poses_action.cpp index 0aa3500ff24..c62e15798e2 100644 --- a/nav2_behavior_tree/test/plugins/action/test_navigate_through_poses_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_navigate_through_poses_action.cpp @@ -66,6 +66,9 @@ class NavigateThroughPosesActionTestFixture : public ::testing::Test node_); config_->blackboard->set( "server_timeout", + std::chrono::milliseconds(20)); + config_->blackboard->set( + "bt_loop_duration", std::chrono::milliseconds(10)); config_->blackboard->set("initial_pose_received", false); std::vector poses; diff --git a/nav2_behavior_tree/test/plugins/action/test_navigate_to_pose_action.cpp b/nav2_behavior_tree/test/plugins/action/test_navigate_to_pose_action.cpp index 7ea3e858f8d..19b96d6f682 100644 --- a/nav2_behavior_tree/test/plugins/action/test_navigate_to_pose_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_navigate_to_pose_action.cpp @@ -64,6 +64,9 @@ class NavigateToPoseActionTestFixture : public ::testing::Test node_); config_->blackboard->set( "server_timeout", + std::chrono::milliseconds(20)); + config_->blackboard->set( + "bt_loop_duration", std::chrono::milliseconds(10)); config_->blackboard->set("initial_pose_received", false); diff --git a/nav2_behavior_tree/test/plugins/action/test_reinitialize_global_localization_service.cpp b/nav2_behavior_tree/test/plugins/action/test_reinitialize_global_localization_service.cpp index 0ce10e229f4..1dbf1a7e6d1 100644 --- a/nav2_behavior_tree/test/plugins/action/test_reinitialize_global_localization_service.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_reinitialize_global_localization_service.cpp @@ -49,6 +49,9 @@ class ReinitializeGlobalLocalizationServiceTestFixture : public ::testing::Test node_); config_->blackboard->set( "server_timeout", + std::chrono::milliseconds(20)); + config_->blackboard->set( + "bt_loop_duration", std::chrono::milliseconds(10)); config_->blackboard->set("initial_pose_received", false); diff --git a/nav2_behavior_tree/test/plugins/action/test_spin_action.cpp b/nav2_behavior_tree/test/plugins/action/test_spin_action.cpp index 432a3c55bd4..332d5149417 100644 --- a/nav2_behavior_tree/test/plugins/action/test_spin_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_spin_action.cpp @@ -64,6 +64,9 @@ class SpinActionTestFixture : public ::testing::Test node_); config_->blackboard->set( "server_timeout", + std::chrono::milliseconds(20)); + config_->blackboard->set( + "bt_loop_duration", std::chrono::milliseconds(10)); config_->blackboard->set("initial_pose_received", false); config_->blackboard->set("number_recoveries", 0); diff --git a/nav2_behavior_tree/test/plugins/action/test_wait_action.cpp b/nav2_behavior_tree/test/plugins/action/test_wait_action.cpp index 193395f9401..05cd388d7a6 100644 --- a/nav2_behavior_tree/test/plugins/action/test_wait_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_wait_action.cpp @@ -55,6 +55,9 @@ class WaitActionTestFixture : public ::testing::Test node_); config_->blackboard->set( "server_timeout", + std::chrono::milliseconds(20)); + config_->blackboard->set( + "bt_loop_duration", std::chrono::milliseconds(10)); config_->blackboard->set("initial_pose_received", false); config_->blackboard->set("number_recoveries", 0); diff --git a/nav2_behavior_tree/test/plugins/condition/test_transform_available.cpp b/nav2_behavior_tree/test/plugins/condition/test_transform_available.cpp index 37dfc32809b..a24dcbf530d 100644 --- a/nav2_behavior_tree/test/plugins/condition/test_transform_available.cpp +++ b/nav2_behavior_tree/test/plugins/condition/test_transform_available.cpp @@ -44,6 +44,9 @@ class TransformAvailableConditionTestFixture : public ::testing::Test transform_handler_->getBuffer()); config_->blackboard->set( "server_timeout", + std::chrono::milliseconds(20)); + config_->blackboard->set( + "bt_loop_duration", std::chrono::milliseconds(10)); config_->blackboard->set("initial_pose_received", false); } diff --git a/nav2_behavior_tree/test/test_behavior_tree_fixture.hpp b/nav2_behavior_tree/test/test_behavior_tree_fixture.hpp index 20c9ace7bf9..2a377f9caad 100644 --- a/nav2_behavior_tree/test/test_behavior_tree_fixture.hpp +++ b/nav2_behavior_tree/test/test_behavior_tree_fixture.hpp @@ -51,6 +51,9 @@ class BehaviorTreeTestFixture : public ::testing::Test transform_handler_->getBuffer()); config_->blackboard->set( "server_timeout", + std::chrono::milliseconds(20)); + config_->blackboard->set( + "bt_loop_duration", std::chrono::milliseconds(10)); config_->blackboard->set("initial_pose_received", false); diff --git a/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml b/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml index 37c2532818e..0c19287576a 100644 --- a/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml +++ b/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml @@ -53,6 +53,8 @@ bt_navigator: global_frame: map robot_base_frame: base_link odom_topic: /odom + bt_loop_duration: 10 + default_server_timeout: 20 # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults: # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml diff --git a/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml b/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml index f07e5858467..07b069faf72 100644 --- a/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml +++ b/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml @@ -53,6 +53,8 @@ bt_navigator: global_frame: map robot_base_frame: base_link odom_topic: /odom + bt_loop_duration: 10 + default_server_timeout: 20 # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults: # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml diff --git a/nav2_bringup/bringup/params/nav2_params.yaml b/nav2_bringup/bringup/params/nav2_params.yaml index f6a32378125..b643828cfd2 100644 --- a/nav2_bringup/bringup/params/nav2_params.yaml +++ b/nav2_bringup/bringup/params/nav2_params.yaml @@ -53,6 +53,8 @@ bt_navigator: global_frame: map robot_base_frame: base_link odom_topic: /odom + bt_loop_duration: 10 + default_server_timeout: 20 enable_groot_monitoring: True groot_zmq_publisher_port: 1666 groot_zmq_server_port: 1667 diff --git a/nav2_rviz_plugins/src/nav2_panel.cpp b/nav2_rviz_plugins/src/nav2_panel.cpp index 5c1b163bf3f..8fb4a481df5 100644 --- a/nav2_rviz_plugins/src/nav2_panel.cpp +++ b/nav2_rviz_plugins/src/nav2_panel.cpp @@ -38,7 +38,7 @@ GoalPoseUpdater GoalUpdater; Nav2Panel::Nav2Panel(QWidget * parent) : Panel(parent), - server_timeout_(10), + server_timeout_(20), client_nav_("lifecycle_manager_navigation"), client_loc_("lifecycle_manager_localization") { 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 56210581722..9b9ad869fe9 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 @@ -109,7 +109,9 @@ class BehaviorTreeHandler // Put items on the blackboard blackboard->set("node", node_); // NOLINT blackboard->set( - "server_timeout", std::chrono::milliseconds(10)); // NOLINT + "server_timeout", std::chrono::milliseconds(20)); // NOLINT + blackboard->set( + "bt_loop_duration", std::chrono::milliseconds(10)); // NOLINT blackboard->set>("tf_buffer", tf_); // NOLINT blackboard->set("initial_pose_received", false); // NOLINT blackboard->set("number_recoveries", 0); // NOLINT