diff --git a/doc/parameters/param_list.md b/doc/parameters/param_list.md index dec94bf61a339b63684ee72f7e137bbd7bbdb5ae..3bbacfa09029bba118315b0ae2f1471e531cc376 100644 --- a/doc/parameters/param_list.md +++ b/doc/parameters/param_list.md @@ -400,6 +400,7 @@ When `controller_plugins`\`progress_checker_plugin`\`goal_checker_plugin` parame | ----------| --------| ------------| | node_names | N/A | Ordered list of node names to bringup through lifecycle transition | | autostart | false | Whether to transition nodes to active state on startup | +| bond_timeout_ms | 4000 | Timeout for bond to fail if no heartbeat can be found, in milliseconds. If set to 0, it will be disabled. Must be larger than 300ms for stable bringup. | # map_server diff --git a/nav2_amcl/src/amcl_node.cpp b/nav2_amcl/src/amcl_node.cpp index e90d48a4ffc7d475d201832569151bd72186e7c2..e4e4c37e9f114d97f1e569572d852a8e89939dc5 100644 --- a/nav2_amcl/src/amcl_node.cpp +++ b/nav2_amcl/src/amcl_node.cpp @@ -300,6 +300,9 @@ AmclNode::on_activate(const rclcpp_lifecycle::State & /*state*/) handleInitialPose(last_published_pose_); } + // create bond connection + createBond(); + return nav2_util::CallbackReturn::SUCCESS; } @@ -315,6 +318,9 @@ AmclNode::on_deactivate(const rclcpp_lifecycle::State & /*state*/) particlecloud_pub_->on_deactivate(); particle_cloud_pub_->on_deactivate(); + // destroy bond connection + destroyBond(); + return nav2_util::CallbackReturn::SUCCESS; } diff --git a/nav2_bt_navigator/src/bt_navigator.cpp b/nav2_bt_navigator/src/bt_navigator.cpp index c660a25765ff3dc4a621388e7b325e0f2622834c..69bee0ff5f5cb1d128e33cee400d9d15286467e6 100644 --- a/nav2_bt_navigator/src/bt_navigator.cpp +++ b/nav2_bt_navigator/src/bt_navigator.cpp @@ -108,7 +108,7 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & /*state*/) get_node_clock_interface(), get_node_logging_interface(), get_node_waitables_interface(), - "navigate_to_pose", std::bind(&BtNavigator::navigateToPose, this), false); + "navigate_to_pose", std::bind(&BtNavigator::navigateToPose, this)); // Get the libraries to pull plugins from plugin_lib_names_ = get_parameter("plugin_lib_names").as_string_array(); @@ -133,11 +133,6 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & /*state*/) // Get the BT filename to use from the node parameter get_parameter("default_bt_xml_filename", default_bt_xml_filename_); - if (!loadBehaviorTree(default_bt_xml_filename_)) { - RCLCPP_ERROR(get_logger(), "Error loading XML file: %s", default_bt_xml_filename_.c_str()); - return nav2_util::CallbackReturn::FAILURE; - } - return nav2_util::CallbackReturn::SUCCESS; } @@ -176,8 +171,16 @@ BtNavigator::on_activate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Activating"); + if (!loadBehaviorTree(default_bt_xml_filename_)) { + RCLCPP_ERROR(get_logger(), "Error loading XML file: %s", default_bt_xml_filename_.c_str()); + return nav2_util::CallbackReturn::FAILURE; + } + action_server_->activate(); + // create bond connection + createBond(); + return nav2_util::CallbackReturn::SUCCESS; } @@ -188,6 +191,9 @@ BtNavigator::on_deactivate(const rclcpp_lifecycle::State & /*state*/) action_server_->deactivate(); + // destroy bond connection + destroyBond(); + return nav2_util::CallbackReturn::SUCCESS; } @@ -332,7 +338,7 @@ BtNavigator::initializeGoalPose() blackboard_->set<int>("number_recoveries", 0); // NOLINT // Update the goal pose on the blackboard - blackboard_->set("goal", goal->pose); + blackboard_->set<geometry_msgs::msg::PoseStamped>("goal", goal->pose); } void diff --git a/nav2_controller/src/nav2_controller.cpp b/nav2_controller/src/nav2_controller.cpp index a01df102fadc6e9ce236f151a82d3a7039e8a582..6527b71e8298dd89f97a6aab3ff1a9e3ac330dd8 100644 --- a/nav2_controller/src/nav2_controller.cpp +++ b/nav2_controller/src/nav2_controller.cpp @@ -72,6 +72,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state) RCLCPP_INFO(get_logger(), "Configuring controller interface"); + get_parameter("progress_checker_plugin", progress_checker_id_); if (progress_checker_id_ == default_progress_checker_id_) { nav2_util::declare_parameter_if_not_declared( @@ -93,6 +94,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state) rclcpp::ParameterValue(default_types_[i])); } } + controller_types_.resize(controller_ids_.size()); get_parameter("controller_frequency", controller_frequency_); @@ -172,6 +174,9 @@ ControllerServer::on_activate(const rclcpp_lifecycle::State & state) vel_publisher_->on_activate(); action_server_->activate(); + // create bond connection + createBond(); + return nav2_util::CallbackReturn::SUCCESS; } @@ -190,6 +195,9 @@ ControllerServer::on_deactivate(const rclcpp_lifecycle::State & state) publishZeroVelocity(); vel_publisher_->on_deactivate(); + // destroy bond connection + destroyBond(); + return nav2_util::CallbackReturn::SUCCESS; } diff --git a/nav2_lifecycle_manager/CMakeLists.txt b/nav2_lifecycle_manager/CMakeLists.txt index ff06d31cc5391f5eb43565e0aea3598b732c482b..6d812c358342429b4f9f360d185bed78df6f629b 100644 --- a/nav2_lifecycle_manager/CMakeLists.txt +++ b/nav2_lifecycle_manager/CMakeLists.txt @@ -13,6 +13,7 @@ find_package(rclcpp REQUIRED) find_package(std_msgs REQUIRED) find_package(std_srvs REQUIRED) find_package(tf2_geometry_msgs REQUIRED) +find_package(bondcpp REQUIRED) nav2_package() @@ -38,6 +39,7 @@ set(dependencies std_msgs std_srvs tf2_geometry_msgs + bondcpp ) ament_target_dependencies(${library_name} diff --git a/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager.hpp b/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager.hpp index 384f33e01820b4915516dd23b8f51ae554a9f279..dc58026f2dc2ac9cd510cdb1ffa39edd8321b908 100644 --- a/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager.hpp +++ b/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager.hpp @@ -22,10 +22,12 @@ #include <vector> #include "nav2_util/lifecycle_service_client.hpp" +#include "nav2_util/node_thread.hpp" #include "rclcpp/rclcpp.hpp" #include "std_srvs/srv/empty.hpp" #include "nav2_msgs/srv/manage_lifecycle_nodes.hpp" #include "std_srvs/srv/trigger.hpp" +#include "bondcpp/bond.hpp" namespace nav2_lifecycle_manager { @@ -52,6 +54,8 @@ public: protected: // The ROS node to use when calling lifecycle services rclcpp::Node::SharedPtr service_client_node_; + rclcpp::Node::SharedPtr bond_client_node_; + std::unique_ptr<nav2_util::NodeThread> bond_node_thread_; // The services provided by this node rclcpp::Service<ManageLifecycleNodes>::SharedPtr manager_srv_; @@ -121,10 +125,37 @@ protected: */ void destroyLifecycleServiceClients(); + // Support function for creating bond timer + /** + * @brief Support function for creating bond timer + */ + void createBondTimer(); + + // Support function for creating bond connection + /** + * @brief Support function for creating bond connections + */ + bool createBondConnection(const std::string & node_name); + + // Support function for killing bond connections + /** + * @brief Support function for killing bond connections + */ + void destroyBondTimer(); + + // Support function for checking on bond connections + /** + * @ brief Support function for checking on bond connections + * will take down system if there's something non-responsive + */ + void checkBondConnections(); + /** * @brief For a node, transition to the new target state */ - bool changeStateForNode(const std::string & node_name, std::uint8_t transition); + bool changeStateForNode( + const std::string & node_name, + std::uint8_t transition); /** * @brief For each node in the map, transition to the new target state @@ -137,6 +168,13 @@ protected: */ void message(const std::string & msg); + // Timer thread to look at bond connections + rclcpp::TimerBase::SharedPtr bond_timer_; + std::chrono::milliseconds bond_timeout_; + + // A map of all nodes to check bond connection + std::map<std::string, std::shared_ptr<bond::Bond>> bond_map_; + // A map of all nodes to be controlled std::map<std::string, std::shared_ptr<nav2_util::LifecycleServiceClient>> node_map_; diff --git a/nav2_lifecycle_manager/package.xml b/nav2_lifecycle_manager/package.xml index a9b16bd48676c89b4b33a2f56c4dc31b63549eed..f796d640ed0cb254c49faaf1dfbc20827926d991 100644 --- a/nav2_lifecycle_manager/package.xml +++ b/nav2_lifecycle_manager/package.xml @@ -18,6 +18,7 @@ <build_depend>std_msgs</build_depend> <build_depend>std_srvs</build_depend> <build_depend>tf2_geometry_msgs</build_depend> + <build_depend>bondcpp</build_depend> <build_depend>nav2_common</build_depend> <exec_depend>geometry_msgs</exec_depend> @@ -28,6 +29,7 @@ <exec_depend>rclcpp_lifecycle</exec_depend> <exec_depend>std_msgs</exec_depend> <exec_depend>std_srvs</exec_depend> + <exec_depend>bondcpp</exec_depend> <exec_depend>tf2_geometry_msgs</exec_depend> <test_depend>ament_lint_auto</test_depend> diff --git a/nav2_lifecycle_manager/src/lifecycle_manager.cpp b/nav2_lifecycle_manager/src/lifecycle_manager.cpp index ccd9faaeab46a9fe9ec548255c6d1f72e08f0607..92a6279cb02270407b595a61eae30adb55f96b32 100644 --- a/nav2_lifecycle_manager/src/lifecycle_manager.cpp +++ b/nav2_lifecycle_manager/src/lifecycle_manager.cpp @@ -40,9 +40,13 @@ LifecycleManager::LifecycleManager() // of nodes declare_parameter("node_names"); declare_parameter("autostart", rclcpp::ParameterValue(false)); + declare_parameter("bond_timeout_ms", 4000); node_names_ = get_parameter("node_names").as_string_array(); get_parameter("autostart", autostart_); + int bond_timeout_int; + get_parameter("bond_timeout_ms", bond_timeout_int); + bond_timeout_ = std::chrono::milliseconds(bond_timeout_int); manager_srv_ = create_service<ManageLifecycleNodes>( get_name() + std::string("/manage_nodes"), @@ -52,9 +56,13 @@ LifecycleManager::LifecycleManager() get_name() + std::string("/is_active"), std::bind(&LifecycleManager::isActiveCallback, this, _1, _2, _3)); - auto options = rclcpp::NodeOptions().arguments( + auto service_options = rclcpp::NodeOptions().arguments( {"--ros-args", "-r", std::string("__node:=") + get_name() + "_service_client", "--"}); - service_client_node_ = std::make_shared<rclcpp::Node>("_", options); + auto bond_options = rclcpp::NodeOptions().arguments( + {"--ros-args", "-r", std::string("__node:=") + get_name() + "_bond_client", "--"}); + service_client_node_ = std::make_shared<rclcpp::Node>("_", service_options); + bond_client_node_ = std::make_shared<rclcpp::Node>("_", bond_options); + bond_node_thread_ = std::make_unique<nav2_util::NodeThread>(bond_client_node_); transition_state_map_[Transition::TRANSITION_CONFIGURE] = State::PRIMARY_STATE_INACTIVE; transition_state_map_[Transition::TRANSITION_CLEANUP] = State::PRIMARY_STATE_UNCONFIGURED; @@ -79,7 +87,7 @@ LifecycleManager::LifecycleManager() LifecycleManager::~LifecycleManager() { - RCLCPP_INFO(get_logger(), "Destroying"); + RCLCPP_INFO(get_logger(), "Destroying %s", get_name()); } void @@ -135,10 +143,38 @@ LifecycleManager::destroyLifecycleServiceClients() } } +bool +LifecycleManager::createBondConnection(const std::string & node_name) +{ + const double timeout_ns = + std::chrono::duration_cast<std::chrono::nanoseconds>(bond_timeout_).count(); + const double timeout_s = timeout_ns / 1e9; + + if (bond_map_.find(node_name) == bond_map_.end() && bond_timeout_.count() > 0.0) { + bond_map_[node_name] = + std::make_shared<bond::Bond>("bond", node_name, bond_client_node_); + bond_map_[node_name]->setHeartbeatTimeout(timeout_s); + bond_map_[node_name]->setHeartbeatPeriod(0.10); + bond_map_[node_name]->start(); + if (!bond_map_[node_name]->waitUntilFormed(rclcpp::Duration(timeout_ns / 2))) { + RCLCPP_ERROR( + get_logger(), + "Server %s was unable to be reached after %0.2fs by bond. " + "This server may be misconfigured.", + node_name.c_str(), timeout_s); + return false; + } + RCLCPP_INFO(get_logger(), "Server %s connected with bond.", node_name.c_str()); + } + + return true; +} + bool LifecycleManager::changeStateForNode(const std::string & node_name, std::uint8_t transition) { message(transition_label_map_[transition] + node_name); + if (!node_map_[node_name]->change_state(transition) || !(node_map_[node_name]->get_state() == transition_state_map_[transition])) { @@ -146,6 +182,12 @@ LifecycleManager::changeStateForNode(const std::string & node_name, std::uint8_t return false; } + if (transition == Transition::TRANSITION_ACTIVATE) { + return createBondConnection(node_name); + } else if (transition == Transition::TRANSITION_DEACTIVATE) { + bond_map_.erase(node_name); + } + return true; } @@ -192,23 +234,29 @@ LifecycleManager::startup() } message("Managed nodes are active"); system_active_ = true; + createBondTimer(); return true; } bool LifecycleManager::shutdown() { + system_active_ = false; + destroyBondTimer(); + message("Shutting down managed nodes..."); shutdownAllNodes(); destroyLifecycleServiceClients(); message("Managed nodes have been shut down"); - system_active_ = false; return true; } bool LifecycleManager::reset() { + system_active_ = false; + destroyBondTimer(); + message("Resetting managed nodes..."); // Should transition in reverse order if (!changeStateForAllNodes(Transition::TRANSITION_DEACTIVATE) || @@ -217,21 +265,25 @@ LifecycleManager::reset() RCLCPP_ERROR(get_logger(), "Failed to reset nodes: aborting reset"); return false; } + message("Managed nodes have been reset"); - system_active_ = false; + return true; } bool LifecycleManager::pause() { + system_active_ = false; + destroyBondTimer(); + message("Pausing managed nodes..."); if (!changeStateForAllNodes(Transition::TRANSITION_DEACTIVATE)) { RCLCPP_ERROR(get_logger(), "Failed to pause nodes: aborting pause"); return false; } message("Managed nodes have been paused"); - system_active_ = false; + return true; } @@ -245,12 +297,62 @@ LifecycleManager::resume() } message("Managed nodes are active"); system_active_ = true; + createBondTimer(); return true; } -// TODO(mjeronimo): This is used to emphasize the major events during system bring-up and -// shutdown so that the messgaes can be easily seen among the log output. We should replace -// this with a ROS2-supported way of highlighting console output, if possible. +void +LifecycleManager::createBondTimer() +{ + if (bond_timeout_.count() <= 0) { + return; + } + + message("Creating bond timer..."); + + bond_timer_ = this->create_wall_timer( + 200ms, + std::bind(&LifecycleManager::checkBondConnections, this)); +} + +void +LifecycleManager::destroyBondTimer() +{ + if (bond_timer_) { + message("Terminating bond timer..."); + bond_timer_->cancel(); + bond_timer_.reset(); + } +} + +void +LifecycleManager::checkBondConnections() +{ + if (!system_active_ || !rclcpp::ok() || bond_map_.empty()) { + return; + } + + for (auto & node_name : node_names_) { + if (!rclcpp::ok()) { + return; + } + + if (bond_map_[node_name]->isBroken()) { + message( + std::string( + "Have not received a heartbeat from " + node_name + ".")); + + // if one is down, bring them all down + RCLCPP_ERROR( + get_logger(), + "CRITICAL FAILURE: SERVER %s IS DOWN after not receiving a heartbeat for %i ms." + " Shutting down related nodes.", + node_name.c_str(), static_cast<int>(bond_timeout_.count())); + reset(); + return; + } + } +} #define ANSI_COLOR_RESET "\x1b[0m" #define ANSI_COLOR_BLUE "\x1b[34m" diff --git a/nav2_lifecycle_manager/test/CMakeLists.txt b/nav2_lifecycle_manager/test/CMakeLists.txt index e931a5ce1915b151a9eaab05e3068b7b858434d0..96cbaa5f7ad92e232e6ec025dd0f15610f0aaf4b 100644 --- a/nav2_lifecycle_manager/test/CMakeLists.txt +++ b/nav2_lifecycle_manager/test/CMakeLists.txt @@ -14,7 +14,28 @@ ament_add_test(test_lifecycle GENERATE_RESULT_FOR_RETURN_CODE_ZERO COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/launch_lifecycle_test.py" WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}" - TIMEOUT 180 + TIMEOUT 20 ENV TEST_EXECUTABLE=$<TARGET_FILE:test_lifecycle_gtest> ) + +ament_add_gtest_executable(test_bond_gtest + test_bond.cpp +) + +target_link_libraries(test_bond_gtest + ${library_name} +) + +ament_target_dependencies(test_bond_gtest + ${dependencies} +) + +ament_add_test(test_bond + GENERATE_RESULT_FOR_RETURN_CODE_ZERO + COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/launch_bond_test.py" + WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}" + TIMEOUT 20 + ENV + TEST_EXECUTABLE=$<TARGET_FILE:test_bond_gtest> +) diff --git a/nav2_lifecycle_manager/test/launch_bond_test.py b/nav2_lifecycle_manager/test/launch_bond_test.py new file mode 100755 index 0000000000000000000000000000000000000000..061375db45247a4a17b84beb79b9b0fbdb7a64ea --- /dev/null +++ b/nav2_lifecycle_manager/test/launch_bond_test.py @@ -0,0 +1,57 @@ +#! /usr/bin/env python3 +# Copyright (c) 2020 Samsung Research America +# +# 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. + +import os +import sys + +from launch import LaunchDescription +from launch import LaunchService +from launch.actions import ExecuteProcess +from launch_ros.actions import Node +from launch_testing.legacy import LaunchTestService + + +def generate_launch_description(): + return LaunchDescription([ + Node( + package='nav2_lifecycle_manager', + executable='lifecycle_manager', + name='lifecycle_manager_test', + output='screen', + parameters=[{'use_sim_time': False}, + {'autostart': False}, + {'node_names': ['bond_tester']}]), + ]) + + +def main(argv=sys.argv[1:]): + ld = generate_launch_description() + + testExecutable = os.getenv('TEST_EXECUTABLE') + + test1_action = ExecuteProcess( + cmd=[testExecutable], + name='test_bond_gtest', + output='screen') + + lts = LaunchTestService() + lts.add_test_action(ld, test1_action) + ls = LaunchService(argv=argv) + ls.include_launch_description(ld) + return lts.run(ls) + + +if __name__ == '__main__': + sys.exit(main()) diff --git a/nav2_lifecycle_manager/test/launch_lifecycle_test.py b/nav2_lifecycle_manager/test/launch_lifecycle_test.py index 822a4423579c483df1a6595e489c32d29dae08d2..88b267ea1d527524cb901a4808575d2e0e168ea3 100755 --- a/nav2_lifecycle_manager/test/launch_lifecycle_test.py +++ b/nav2_lifecycle_manager/test/launch_lifecycle_test.py @@ -32,6 +32,7 @@ def generate_launch_description(): output='screen', parameters=[{'use_sim_time': False}, {'autostart': False}, + {'bond_timeout_ms': 0}, {'node_names': ['lifecycle_node_test']}]), ]) diff --git a/nav2_lifecycle_manager/test/test_bond.cpp b/nav2_lifecycle_manager/test/test_bond.cpp new file mode 100644 index 0000000000000000000000000000000000000000..96d0b324f6ccf195a2f05d4deb17fd985c15b2a8 --- /dev/null +++ b/nav2_lifecycle_manager/test/test_bond.cpp @@ -0,0 +1,197 @@ +// Copyright (c) 2020 Samsung Research America +// +// 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 <chrono> +#include <string> +#include "rclcpp/rclcpp.hpp" +#include "nav2_util/lifecycle_node.hpp" +#include "nav2_util/node_thread.hpp" +#include "nav2_lifecycle_manager/lifecycle_manager.hpp" +#include "nav2_lifecycle_manager/lifecycle_manager_client.hpp" + +using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn; + +// minimal lifecycle node implementing bond as in rest of navigation servers +class TestLifecycleNode : public nav2_util::LifecycleNode +{ +public: + TestLifecycleNode(bool bond, std::string name) + : nav2_util::LifecycleNode(name) + { + state = ""; + enable_bond = bond; + } + + CallbackReturn on_configure(const rclcpp_lifecycle::State & /*state*/) override + { + RCLCPP_INFO(get_logger(), "Lifecycle Test node is Configured!"); + state = "configured"; + return CallbackReturn::SUCCESS; + } + + CallbackReturn on_activate(const rclcpp_lifecycle::State & /*state*/) override + { + RCLCPP_INFO(get_logger(), "Lifecycle Test node is Activated!"); + state = "activated"; + if (enable_bond) { + createBond(); + } + return CallbackReturn::SUCCESS; + } + + CallbackReturn on_deactivate(const rclcpp_lifecycle::State & /*state*/) override + { + RCLCPP_INFO(get_logger(), "Lifecycle Test node is Deactivated!"); + state = "deactivated"; + if (enable_bond) { + destroyBond(); + } + return CallbackReturn::SUCCESS; + } + + CallbackReturn on_cleanup(const rclcpp_lifecycle::State & /*state*/) override + { + RCLCPP_INFO(get_logger(), "Lifecycle Test node is Cleanup!"); + state = "cleaned up"; + return CallbackReturn::SUCCESS; + } + + CallbackReturn on_shutdown(const rclcpp_lifecycle::State & /*state*/) override + { + RCLCPP_INFO(get_logger(), "Lifecycle Test node is Shutdown!"); + state = "shut down"; + return CallbackReturn::SUCCESS; + } + + CallbackReturn on_error(const rclcpp_lifecycle::State & /*state*/) override + { + RCLCPP_INFO(get_logger(), "Lifecycle Test node is encountered an error!"); + state = "errored"; + return CallbackReturn::SUCCESS; + } + + bool bondAllocated() + { + return bond_ ? true : false; + } + + void breakBond() + { + bond_->breakBond(); + } + + std::string getState() + { + return state; + } + + bool isBondEnabled() + { + return enable_bond; + } + + bool isBondConnected() + { + return bondAllocated() ? !bond_->isBroken() : false; + } + + std::string state; + bool enable_bond; +}; + +class TestFixture +{ +public: + TestFixture(bool bond, std::string node_name) + { + lf_node_ = std::make_shared<TestLifecycleNode>(bond, node_name); + lf_thread_ = std::make_unique<nav2_util::NodeThread>(lf_node_->get_node_base_interface()); + } + + std::shared_ptr<TestLifecycleNode> lf_node_; + std::unique_ptr<nav2_util::NodeThread> lf_thread_; +}; + +TEST(LifecycleBondTest, POSITIVE) +{ + // let the lifecycle server come up + rclcpp::Rate(1).sleep(); + + nav2_lifecycle_manager::LifecycleManagerClient client("lifecycle_manager_test"); + + // create node, should be up now + auto fixture = TestFixture(true, "bond_tester"); + auto bond_tester = fixture.lf_node_; + + EXPECT_TRUE(client.startup()); + + // check if bond is connected after being activated + rclcpp::Rate(5).sleep(); + EXPECT_TRUE(bond_tester->isBondConnected()); + EXPECT_EQ(bond_tester->getState(), "activated"); + + bond_tester->breakBond(); + + // bond should be disconnected now and lifecycle manager should know and react to reset + rclcpp::Rate(5).sleep(); + EXPECT_EQ( + nav2_lifecycle_manager::SystemStatus::INACTIVE, + client.is_active(std::chrono::nanoseconds(1000000000))); + EXPECT_FALSE(bond_tester->isBondConnected()); + EXPECT_EQ(bond_tester->getState(), "cleaned up"); + + // check that bringing up again is OK + EXPECT_TRUE(client.startup()); + EXPECT_EQ(bond_tester->getState(), "activated"); + EXPECT_TRUE(bond_tester->isBondConnected()); + EXPECT_EQ( + nav2_lifecycle_manager::SystemStatus::ACTIVE, + client.is_active(std::chrono::nanoseconds(1000000000))); + + // clean state for next test. + EXPECT_TRUE(client.reset()); + EXPECT_FALSE(bond_tester->isBondConnected()); + EXPECT_EQ(bond_tester->getState(), "cleaned up"); +} + +TEST(LifecycleBondTest, NEGATIVE) +{ + nav2_lifecycle_manager::LifecycleManagerClient client("lifecycle_manager_test"); + + // create node, now without bond setup to connect to. Should fail because no bond + auto fixture = TestFixture(false, "bond_tester"); + auto bond_tester = fixture.lf_node_; + EXPECT_FALSE(client.startup()); + EXPECT_FALSE(bond_tester->isBondEnabled()); + EXPECT_EQ( + nav2_lifecycle_manager::SystemStatus::INACTIVE, + client.is_active(std::chrono::nanoseconds(1000000000))); +} + +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_map_server/src/map_server/map_server.cpp b/nav2_map_server/src/map_server/map_server.cpp index 2c2e174f9c91c9d44f894de37b605c9bac82e00a..490049e4b9ebbd80e00f1591e1e1735087dffd82 100644 --- a/nav2_map_server/src/map_server/map_server.cpp +++ b/nav2_map_server/src/map_server/map_server.cpp @@ -129,6 +129,9 @@ MapServer::on_activate(const rclcpp_lifecycle::State & /*state*/) auto occ_grid = std::make_unique<nav_msgs::msg::OccupancyGrid>(msg_); occ_pub_->publish(std::move(occ_grid)); + // create bond connection + createBond(); + return nav2_util::CallbackReturn::SUCCESS; } @@ -139,6 +142,9 @@ MapServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) occ_pub_->on_deactivate(); + // destroy bond connection + destroyBond(); + return nav2_util::CallbackReturn::SUCCESS; } diff --git a/nav2_planner/src/planner_server.cpp b/nav2_planner/src/planner_server.cpp index edf273e87fe97f3fe34d45b098ed3d5c22966f69..6e42c131b7988fdbb7d14d017affbd35fd3e344c 100644 --- a/nav2_planner/src/planner_server.cpp +++ b/nav2_planner/src/planner_server.cpp @@ -48,6 +48,13 @@ PlannerServer::PlannerServer() declare_parameter("planner_plugins", default_ids_); declare_parameter("expected_planner_frequency", 20.0); + get_parameter("planner_plugins", planner_ids_); + if (planner_ids_ == default_ids_) { + for (size_t i = 0; i < default_ids_.size(); ++i) { + declare_parameter(default_ids_[i] + ".plugin", default_types_[i]); + } + } + // Setup the global costmap costmap_ros_ = std::make_shared<nav2_costmap_2d::Costmap2DROS>( "global_costmap", std::string{get_namespace()}, "global_costmap"); @@ -79,12 +86,6 @@ PlannerServer::on_configure(const rclcpp_lifecycle::State & state) tf_ = costmap_ros_->getTfBuffer(); - get_parameter("planner_plugins", planner_ids_); - if (planner_ids_ == default_ids_) { - for (size_t i = 0; i < default_ids_.size(); ++i) { - declare_parameter(default_ids_[i] + ".plugin", default_types_[i]); - } - } planner_types_.resize(planner_ids_.size()); auto node = shared_from_this(); @@ -151,6 +152,9 @@ PlannerServer::on_activate(const rclcpp_lifecycle::State & state) it->second->activate(); } + // create bond connection + createBond(); + return nav2_util::CallbackReturn::SUCCESS; } @@ -168,6 +172,9 @@ PlannerServer::on_deactivate(const rclcpp_lifecycle::State & state) it->second->deactivate(); } + // destroy bond connection + destroyBond(); + return nav2_util::CallbackReturn::SUCCESS; } diff --git a/nav2_recoveries/include/nav2_recoveries/recovery.hpp b/nav2_recoveries/include/nav2_recoveries/recovery.hpp index 04aed1b02a10f5823b6336692ffaa8991f4fd2f3..174382b4ddfc297aa4429b606fafe2faf50ac354 100644 --- a/nav2_recoveries/include/nav2_recoveries/recovery.hpp +++ b/nav2_recoveries/include/nav2_recoveries/recovery.hpp @@ -124,12 +124,14 @@ public: RCLCPP_INFO(node_->get_logger(), "Activating %s", recovery_name_.c_str()); vel_pub_->on_activate(); + action_server_->activate(); enabled_ = true; } void deactivate() override { vel_pub_->on_deactivate(); + action_server_->deactivate(); enabled_ = false; } diff --git a/nav2_recoveries/src/recovery_server.cpp b/nav2_recoveries/src/recovery_server.cpp index 49b7428d1f3c744fd27933a630d332bda4663f16..8fab3b6e18ef64244baf61c8729050c74d69d81e 100644 --- a/nav2_recoveries/src/recovery_server.cpp +++ b/nav2_recoveries/src/recovery_server.cpp @@ -37,6 +37,13 @@ RecoveryServer::RecoveryServer() declare_parameter("cycle_frequency", rclcpp::ParameterValue(10.0)); declare_parameter("recovery_plugins", default_ids_); + get_parameter("recovery_plugins", recovery_ids_); + if (recovery_ids_ == default_ids_) { + for (size_t i = 0; i < default_ids_.size(); ++i) { + declare_parameter(default_ids_[i] + ".plugin", default_types_[i]); + } + } + declare_parameter( "global_frame", rclcpp::ParameterValue(std::string("odom"))); @@ -81,12 +88,6 @@ RecoveryServer::on_configure(const rclcpp_lifecycle::State & /*state*/) *costmap_sub_, *footprint_sub_, *tf_, this->get_name(), global_frame, robot_base_frame, transform_tolerance_); - get_parameter("recovery_plugins", recovery_ids_); - if (recovery_ids_ == default_ids_) { - for (size_t i = 0; i < default_ids_.size(); ++i) { - declare_parameter(default_ids_[i] + ".plugin", default_types_[i]); - } - } recovery_types_.resize(recovery_ids_.size()); loadRecoveryPlugins(); @@ -126,6 +127,9 @@ RecoveryServer::on_activate(const rclcpp_lifecycle::State & /*state*/) (*iter)->activate(); } + // create bond connection + createBond(); + return nav2_util::CallbackReturn::SUCCESS; } @@ -139,6 +143,9 @@ RecoveryServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) (*iter)->deactivate(); } + // destroy bond connection + destroyBond(); + return nav2_util::CallbackReturn::SUCCESS; } diff --git a/nav2_util/CMakeLists.txt b/nav2_util/CMakeLists.txt index 6221118d156a7839fb5c07174c7843131de6820a..21be6cdfa9596f528b1becaae50efc9672acb3a2 100644 --- a/nav2_util/CMakeLists.txt +++ b/nav2_util/CMakeLists.txt @@ -15,6 +15,8 @@ find_package(rclcpp_action REQUIRED) find_package(test_msgs REQUIRED) find_package(rclcpp_lifecycle REQUIRED) find_package(tf2_geometry_msgs REQUIRED) +find_package(bondcpp REQUIRED) +find_package(bond REQUIRED) set(dependencies nav2_msgs @@ -28,6 +30,8 @@ set(dependencies rclcpp_action test_msgs rclcpp_lifecycle + bondcpp + bond ) nav2_package() diff --git a/nav2_util/include/nav2_util/lifecycle_node.hpp b/nav2_util/include/nav2_util/lifecycle_node.hpp index e97dc6a86a2778a47578d4ed123fb88e146eccf7..cb48feeab6c21c7108168f21078b3f83cfbc6c97 100644 --- a/nav2_util/include/nav2_util/lifecycle_node.hpp +++ b/nav2_util/include/nav2_util/lifecycle_node.hpp @@ -22,6 +22,8 @@ #include "nav2_util/node_thread.hpp" #include "rclcpp_lifecycle/lifecycle_node.hpp" #include "rclcpp/rclcpp.hpp" +#include "bondcpp/bond.hpp" +#include "bond/msg/constants.hpp" namespace nav2_util { @@ -121,6 +123,10 @@ public: rclcpp_lifecycle::LifecycleNode::shared_from_this()); } + // bond connection to lifecycle manager + void createBond(); + void destroyBond(); + protected: void print_lifecycle_node_notification(); @@ -133,6 +139,9 @@ protected: // When creating a local node, this class will launch a separate thread created to spin the node std::unique_ptr<NodeThread> rclcpp_thread_; + + // Connection to tell that server is still up + std::unique_ptr<bond::Bond> bond_{nullptr}; }; } // namespace nav2_util diff --git a/nav2_util/include/nav2_util/simple_action_server.hpp b/nav2_util/include/nav2_util/simple_action_server.hpp index e4767abf5f858c12e8a60822f15023b0d983d085..f0c01b71acbfbbcd24605f5160408ad84d39bb52 100644 --- a/nav2_util/include/nav2_util/simple_action_server.hpp +++ b/nav2_util/include/nav2_util/simple_action_server.hpp @@ -38,14 +38,13 @@ public: typename nodeT::SharedPtr node, const std::string & action_name, ExecuteCallback execute_callback, - bool autostart = true, std::chrono::milliseconds server_timeout = std::chrono::milliseconds(500)) : SimpleActionServer( node->get_node_base_interface(), node->get_node_clock_interface(), node->get_node_logging_interface(), node->get_node_waitables_interface(), - action_name, execute_callback, autostart, server_timeout) + action_name, execute_callback, server_timeout) {} explicit SimpleActionServer( @@ -55,7 +54,6 @@ public: rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface, const std::string & action_name, ExecuteCallback execute_callback, - bool autostart = true, std::chrono::milliseconds server_timeout = std::chrono::milliseconds(500)) : node_base_interface_(node_base_interface), node_clock_interface_(node_clock_interface), @@ -65,12 +63,7 @@ public: execute_callback_(execute_callback), server_timeout_(server_timeout) { - if (autostart) { - server_active_ = true; - } - using namespace std::placeholders; // NOLINT - action_server_ = rclcpp_action::create_server<ActionT>( node_base_interface_, node_clock_interface_, diff --git a/nav2_util/package.xml b/nav2_util/package.xml index 57cbbd9f7e92b38f92861410f7211fc46142b625..87f9086b9c2f1435165615ffe5dbce61593f1c3b 100644 --- a/nav2_util/package.xml +++ b/nav2_util/package.xml @@ -21,6 +21,8 @@ <depend>tf2_ros</depend> <depend>tf2_geometry_msgs</depend> <depend>lifecycle_msgs</depend> + <depend>bondcpp</depend> + <depend>bond</depend> <depend>rclcpp_action</depend> <depend>test_msgs</depend> <depend>rclcpp_lifecycle</depend> diff --git a/nav2_util/src/CMakeLists.txt b/nav2_util/src/CMakeLists.txt index bcaf94b5bacfafac3c35660bddf67e4b43735b5d..ee9f69ee55c66af5467fe28b660045152af5f5f4 100644 --- a/nav2_util/src/CMakeLists.txt +++ b/nav2_util/src/CMakeLists.txt @@ -20,6 +20,7 @@ ament_target_dependencies(${library_name} lifecycle_msgs rclcpp_lifecycle tf2_geometry_msgs + bondcpp ) add_executable(lifecycle_bringup diff --git a/nav2_util/src/lifecycle_node.cpp b/nav2_util/src/lifecycle_node.cpp index e3b9bd6279b52d20d887cb5ffb6ccbd7d12eca21..c031e41dbb82966c7a12b516446e349dd12db377 100644 --- a/nav2_util/src/lifecycle_node.cpp +++ b/nav2_util/src/lifecycle_node.cpp @@ -47,6 +47,12 @@ LifecycleNode::LifecycleNode( : rclcpp_lifecycle::LifecycleNode(node_name, namespace_, options), use_rclcpp_node_(use_rclcpp_node) { + // server side never times out from lifecycle manager + this->declare_parameter(bond::msg::Constants::DISABLE_HEARTBEAT_TIMEOUT_PARAM, true); + this->set_parameter( + rclcpp::Parameter( + bond::msg::Constants::DISABLE_HEARTBEAT_TIMEOUT_PARAM, true)); + if (use_rclcpp_node_) { std::vector<std::string> new_args = options.arguments(); new_args.push_back("--ros-args"); @@ -57,6 +63,7 @@ LifecycleNode::LifecycleNode( "_", namespace_, rclcpp::NodeOptions(options).arguments(new_args)); rclcpp_thread_ = std::make_unique<NodeThread>(rclcpp_node_); } + print_lifecycle_node_notification(); } @@ -71,6 +78,29 @@ LifecycleNode::~LifecycleNode() } } +void LifecycleNode::createBond() +{ + RCLCPP_INFO(get_logger(), "Creating bond (%s) to lifecycle manager.", this->get_name()); + + bond_ = std::make_unique<bond::Bond>( + std::string("bond"), + this->get_name(), + shared_from_this()); + + bond_->setHeartbeatPeriod(0.10); + bond_->setHeartbeatTimeout(4.0); + bond_->start(); +} + +void LifecycleNode::destroyBond() +{ + RCLCPP_INFO(get_logger(), "Destroying bond (%s) to lifecycle manager.", this->get_name()); + + if (bond_) { + bond_.reset(); + } +} + void LifecycleNode::print_lifecycle_node_notification() { RCLCPP_INFO( diff --git a/nav2_util/test/test_actions.cpp b/nav2_util/test/test_actions.cpp index 5619d115ebdfbe76be35d6dc8341858e958bf2a9..b999a28b7c97c2d089884b0ebd75912b21df956b 100644 --- a/nav2_util/test/test_actions.cpp +++ b/nav2_util/test/test_actions.cpp @@ -236,6 +236,8 @@ protected: TEST_F(ActionTest, test_simple_action) { + node_->activate_server(); + // The goal for this invocation auto goal = Fibonacci::Goal(); goal.order = 12; diff --git a/nav2_waypoint_follower/src/waypoint_follower.cpp b/nav2_waypoint_follower/src/waypoint_follower.cpp index 3a0edabce6ebd6bf7fed045d850b8781c306f23c..6940758925377287f43b4a31fb5b67ee8c209548 100644 --- a/nav2_waypoint_follower/src/waypoint_follower.cpp +++ b/nav2_waypoint_follower/src/waypoint_follower.cpp @@ -59,7 +59,7 @@ WaypointFollower::on_configure(const rclcpp_lifecycle::State & /*state*/) get_node_clock_interface(), get_node_logging_interface(), get_node_waitables_interface(), - "FollowWaypoints", std::bind(&WaypointFollower::followWaypoints, this), false); + "FollowWaypoints", std::bind(&WaypointFollower::followWaypoints, this)); return nav2_util::CallbackReturn::SUCCESS; } @@ -71,6 +71,9 @@ WaypointFollower::on_activate(const rclcpp_lifecycle::State & /*state*/) action_server_->activate(); + // create bond connection + createBond(); + return nav2_util::CallbackReturn::SUCCESS; } @@ -81,6 +84,9 @@ WaypointFollower::on_deactivate(const rclcpp_lifecycle::State & /*state*/) action_server_->deactivate(); + // destroy bond connection + destroyBond(); + return nav2_util::CallbackReturn::SUCCESS; } diff --git a/tools/ros2_dependencies.repos b/tools/ros2_dependencies.repos index b6645197b0f5dc27aa9f88e51aa12dbaba0e4743..e2ca35962ba62f3a27d9dc0943c54a318804b25c 100644 --- a/tools/ros2_dependencies.repos +++ b/tools/ros2_dependencies.repos @@ -19,3 +19,7 @@ repositories: type: git url: https://github.com/ros-perception/vision_opencv.git version: ros2 + ros/bond_core: + type: git + url: https://github.com/SteveMacenski/bond_core.git + version: lifecycle_support_2