From 898a4b7cc10623dabb5c79fd10d4af186289719a Mon Sep 17 00:00:00 2001 From: GoesM Date: Mon, 20 Nov 2023 15:53:46 +0800 Subject: [PATCH 01/47] bug fixed --- nav2_controller/src/controller_server.cpp | 2 ++ .../nav2_costmap_2d/costmap_2d_ros.hpp | 21 +++++++++++++++++++ nav2_planner/src/planner_server.cpp | 2 ++ 3 files changed, 25 insertions(+) diff --git a/nav2_controller/src/controller_server.cpp b/nav2_controller/src/controller_server.cpp index 0386c06fc7..9c289c53bc 100644 --- a/nav2_controller/src/controller_server.cpp +++ b/nav2_controller/src/controller_server.cpp @@ -284,6 +284,7 @@ ControllerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) */ if (costmap_ros_->get_current_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) + //this condition could be removed { costmap_ros_->deactivate(); } @@ -314,6 +315,7 @@ ControllerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/) progress_checkers_.clear(); if (costmap_ros_->get_current_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) + //this condition could be removed { costmap_ros_->cleanup(); } diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index f319e52f33..0a9910af93 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -134,6 +134,27 @@ class Costmap2DROS : public nav2_util::LifecycleNode */ nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; + /** + * @brief override on_rcl_preshutdown() as empty + * [reason] costmap only could be created by its parents like planner/controller_server + * [reason] costmap should react to ctrl+C later than its parents to avoid nullptr-accessed + * so the reaction must be later than its parent + * + * thus, it's a more perfect way to make on_rcl_preshutdown() as empty function + * only joint in planner/controller_server->on_deactivate() + * and planner/controller_server->on_cleanup() + * + * !!! a mention !!! + * if any other place use this class (Costmap2DROS) + * it's neccessary to let costmap->deactivate() joint in parent->deactivate() + * and let costmap->cleanup() joint in parent->cleanup() + */ + void on_rcl_preshutdown() override + { + //do nothing + return; + } + /** * @brief Subscribes to sensor topics if necessary and starts costmap * updates, can be called to restart the costmap after calls to either diff --git a/nav2_planner/src/planner_server.cpp b/nav2_planner/src/planner_server.cpp index 84edc6e4df..3aa47adf6c 100644 --- a/nav2_planner/src/planner_server.cpp +++ b/nav2_planner/src/planner_server.cpp @@ -220,6 +220,7 @@ PlannerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) */ if (costmap_ros_->get_current_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) + //this condition could be removed { costmap_ros_->deactivate(); } @@ -253,6 +254,7 @@ PlannerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/) */ if (costmap_ros_->get_current_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) + //this condition could be removed { costmap_ros_->cleanup(); } From e83da7c7d0d95bfbdd3b15c785d3fd19860b19a9 Mon Sep 17 00:00:00 2001 From: GoesM Date: Mon, 20 Nov 2023 17:20:20 +0800 Subject: [PATCH 02/47] add space --- nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index 0a9910af93..995e7877d2 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -151,7 +151,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode */ void on_rcl_preshutdown() override { - //do nothing + // do nothing return; } From bd5fbde21cf31c6744478add1786da2d0314225d Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Tue, 21 Nov 2023 15:47:47 +0800 Subject: [PATCH 03/47] Update planner_server.cpp --- nav2_planner/src/planner_server.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/nav2_planner/src/planner_server.cpp b/nav2_planner/src/planner_server.cpp index 3aa47adf6c..20683e600c 100644 --- a/nav2_planner/src/planner_server.cpp +++ b/nav2_planner/src/planner_server.cpp @@ -220,7 +220,7 @@ PlannerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) */ if (costmap_ros_->get_current_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) - //this condition could be removed + // this condition could be removed { costmap_ros_->deactivate(); } @@ -254,7 +254,7 @@ PlannerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/) */ if (costmap_ros_->get_current_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) - //this condition could be removed + // this condition could be removed { costmap_ros_->cleanup(); } From 510c70bf48ff2db88e76dd7a73cd87acee244c8b Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Tue, 21 Nov 2023 15:51:49 +0800 Subject: [PATCH 04/47] add space for code style --- nav2_controller/src/controller_server.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/nav2_controller/src/controller_server.cpp b/nav2_controller/src/controller_server.cpp index 9c289c53bc..645b2d4fec 100644 --- a/nav2_controller/src/controller_server.cpp +++ b/nav2_controller/src/controller_server.cpp @@ -284,7 +284,7 @@ ControllerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) */ if (costmap_ros_->get_current_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) - //this condition could be removed + // this condition could be removed { costmap_ros_->deactivate(); } @@ -315,7 +315,7 @@ ControllerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/) progress_checkers_.clear(); if (costmap_ros_->get_current_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) - //this condition could be removed + // this condition could be removed { costmap_ros_->cleanup(); } From 14325f6cc973a47b9388198fc6dbc0f3f6a094a9 Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Wed, 22 Nov 2023 15:45:44 +0800 Subject: [PATCH 05/47] add childLifecycleNode mode to costmap_2d_ros --- nav2_controller/src/controller_server.cpp | 26 +++++++++++++---------- 1 file changed, 15 insertions(+), 11 deletions(-) diff --git a/nav2_controller/src/controller_server.cpp b/nav2_controller/src/controller_server.cpp index 645b2d4fec..d2dcfb556b 100644 --- a/nav2_controller/src/controller_server.cpp +++ b/nav2_controller/src/controller_server.cpp @@ -130,7 +130,9 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & /*state*/) costmap_ros_->configure(); // Launch a thread to run the costmap node costmap_thread_ = std::make_unique(costmap_ros_); - + // work as a child-LifecycleNode of its parent controller_server + costmap_ros_->turnChildLifecycleNode(); + for (size_t i = 0; i != progress_checker_ids_.size(); i++) { try { progress_checker_types_[i] = nav2_util::get_plugin_type_param( @@ -282,12 +284,13 @@ ControllerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) * unordered_set iteration. Once this issue is resolved, we can maybe make a stronger * ordering assumption: https://github.com/ros2/rclcpp/issues/2096 */ - if (costmap_ros_->get_current_state().id() == - lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) - // this condition could be removed - { +// if (costmap_ros_->get_current_state().id() == +// lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) +// { +// RCLCPP_INFO(get_logger(), "costmap_ros_->cleanup()"); costmap_ros_->deactivate(); - } +// } + // after turnChildLifecycleNode(), this double check is not neccessary anymore publishZeroVelocity(); vel_publisher_->on_deactivate(); @@ -313,12 +316,13 @@ ControllerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/) goal_checkers_.clear(); progress_checkers_.clear(); - if (costmap_ros_->get_current_state().id() == - lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) - // this condition could be removed - { +// if (costmap_ros_->get_current_state().id() == +// lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) +// { +// RCLCPP_INFO(get_logger(), "costmap_ros_->cleanup()"); costmap_ros_->cleanup(); - } +// } + // after turnChildLifecycleNode(), this double check is not neccessary anymore // Release any allocated resources action_server_.reset(); From ec8e2d05b17b191bcabf3e3448f721a5041989df Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Wed, 22 Nov 2023 15:46:16 +0800 Subject: [PATCH 06/47] add childLifecycleNode mode to costmap_2d_ros --- nav2_planner/src/planner_server.cpp | 26 +++++++++++++++----------- 1 file changed, 15 insertions(+), 11 deletions(-) diff --git a/nav2_planner/src/planner_server.cpp b/nav2_planner/src/planner_server.cpp index 20683e600c..8d6691e941 100644 --- a/nav2_planner/src/planner_server.cpp +++ b/nav2_planner/src/planner_server.cpp @@ -88,7 +88,9 @@ PlannerServer::on_configure(const rclcpp_lifecycle::State & /*state*/) // Launch a thread to run the costmap node costmap_thread_ = std::make_unique(costmap_ros_); - + // work as a child-LifecycleNode of its parent planner_server + costmap_ros_->turnChildLifecycleNode(); + RCLCPP_DEBUG( get_logger(), "Costmap size: %d,%d", costmap_->getSizeInCellsX(), costmap_->getSizeInCellsY()); @@ -218,12 +220,13 @@ PlannerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) * unordered_set iteration. Once this issue is resolved, we can maybe make a stronger * ordering assumption: https://github.com/ros2/rclcpp/issues/2096 */ - if (costmap_ros_->get_current_state().id() == - lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) - // this condition could be removed - { +// if (costmap_ros_->get_current_state().id() == +// lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) +// { +// RCLCPP_INFO(get_logger(), "costmap_ros_->cleanup()"); costmap_ros_->deactivate(); - } +// } + // after turnChildLifecycleNode(), this double check is not neccessary anymore PlannerMap::iterator it; for (it = planners_.begin(); it != planners_.end(); ++it) { @@ -252,12 +255,13 @@ PlannerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/) * Double check whether something else transitioned it to INACTIVE * already, e.g. the rcl preshutdown callback. */ - if (costmap_ros_->get_current_state().id() == - lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) - // this condition could be removed - { +// if (costmap_ros_->get_current_state().id() == +// lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) +// { +// RCLCPP_INFO(get_logger(), "costmap_ros_->cleanup()"); costmap_ros_->cleanup(); - } +// } + // after turnChildLifecycleNode(), this double check is not neccessary anymore PlannerMap::iterator it; for (it = planners_.begin(); it != planners_.end(); ++it) { From c7a86da79e7e990fa7e996b3001e7effabff1f32 Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Wed, 22 Nov 2023 15:46:52 +0800 Subject: [PATCH 07/47] add childLifecycleNode mode to costmap_2d_ros --- .../nav2_costmap_2d/costmap_2d_ros.hpp | 45 ++++++++++++------- 1 file changed, 30 insertions(+), 15 deletions(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index 995e7877d2..13a6cb32bf 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -135,24 +135,39 @@ class Costmap2DROS : public nav2_util::LifecycleNode nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; /** - * @brief override on_rcl_preshutdown() as empty - * [reason] costmap only could be created by its parents like planner/controller_server - * [reason] costmap should react to ctrl+C later than its parents to avoid nullptr-accessed - * so the reaction must be later than its parent - * - * thus, it's a more perfect way to make on_rcl_preshutdown() as empty function - * only joint in planner/controller_server->on_deactivate() - * and planner/controller_server->on_cleanup() - * - * !!! a mention !!! - * if any other place use this class (Costmap2DROS) - * it's neccessary to let costmap->deactivate() joint in parent->deactivate() - * and let costmap->cleanup() joint in parent->cleanup() + * @brief child-LifecycleNode mode + * sometimes costmap may be launched by another LifecycleNode and work as a child-thread + * child-LifecycleNode should react to ctrl+C later than its parents to avoid unclean shutdown + * Thus, it's neccessary to turnChildLifecycleNode() to change its launch mode + * + * in ChildLifecycleNode mode, it would react to rcl_preshutdown anymore + * all its lifecycle state would be controlled by its parent-LifecycleNode */ + void turnChildLifecycleNode() + { + // as a child-LifecycleNode launched by its parent-LifecycleNode + // and work as a child-thread + is_thread_ = true; + } + bool isThread() + { + return is_thread_; + } void on_rcl_preshutdown() override { - // do nothing - return; + if( isThread() ){ + // all of its reaction is up to its parent + return; + } + + // else, same as ``on_rcl_preshutdown` in lifecycle_node.cpp` + RCLCPP_INFO( + get_logger(), "Running Nav2 LifecycleNode rcl preshutdown (%s)", + this->get_name()); + + runCleanups(); + + destroyBond(); } /** From 4a09cffeba61f2cc5debee5a3337b2553b025778 Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Wed, 22 Nov 2023 15:54:20 +0800 Subject: [PATCH 08/47] add childLifecycleNode mode in costmap_2d_ros --- .../include/nav2_costmap_2d/costmap_2d_ros.hpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index 13a6cb32bf..ecd5c65558 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -136,10 +136,10 @@ class Costmap2DROS : public nav2_util::LifecycleNode /** * @brief child-LifecycleNode mode - * sometimes costmap may be launched by another LifecycleNode and work as a child-thread + * sometimes costmap may be launched by another LifecycleNode and work as a child-thread * child-LifecycleNode should react to ctrl+C later than its parents to avoid unclean shutdown * Thus, it's neccessary to turnChildLifecycleNode() to change its launch mode - * + * * in ChildLifecycleNode mode, it would react to rcl_preshutdown anymore * all its lifecycle state would be controlled by its parent-LifecycleNode */ @@ -151,19 +151,19 @@ class Costmap2DROS : public nav2_util::LifecycleNode } bool isThread() { - return is_thread_; + return is_thread_; } void on_rcl_preshutdown() override { - if( isThread() ){ + if (isThread() ) { // all of its reaction is up to its parent return; } - // else, same as ``on_rcl_preshutdown` in lifecycle_node.cpp` + // else, same as ``on_rcl_preshutdown` in lifecycle_node.cpp` RCLCPP_INFO( - get_logger(), "Running Nav2 LifecycleNode rcl preshutdown (%s)", - this->get_name()); + get_logger(), "Running Nav2 LifecycleNode rcl preshutdown (%s)", + this->get_name()); runCleanups(); From 2637de11e1cb3c4d796476840faabf1e02fbd677 Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Wed, 22 Nov 2023 15:54:51 +0800 Subject: [PATCH 09/47] add childLifecycleNode mode in costmap_2d_ros --- nav2_controller/src/controller_server.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/nav2_controller/src/controller_server.cpp b/nav2_controller/src/controller_server.cpp index d2dcfb556b..fe1759cba3 100644 --- a/nav2_controller/src/controller_server.cpp +++ b/nav2_controller/src/controller_server.cpp @@ -132,7 +132,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & /*state*/) costmap_thread_ = std::make_unique(costmap_ros_); // work as a child-LifecycleNode of its parent controller_server costmap_ros_->turnChildLifecycleNode(); - + for (size_t i = 0; i != progress_checker_ids_.size(); i++) { try { progress_checker_types_[i] = nav2_util::get_plugin_type_param( @@ -288,9 +288,9 @@ ControllerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) // lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) // { // RCLCPP_INFO(get_logger(), "costmap_ros_->cleanup()"); - costmap_ros_->deactivate(); + costmap_ros_->deactivate(); // } - // after turnChildLifecycleNode(), this double check is not neccessary anymore +// after turnChildLifecycleNode(), this double check is not neccessary anymore publishZeroVelocity(); vel_publisher_->on_deactivate(); @@ -320,9 +320,9 @@ ControllerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/) // lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) // { // RCLCPP_INFO(get_logger(), "costmap_ros_->cleanup()"); - costmap_ros_->cleanup(); + costmap_ros_->cleanup(); // } - // after turnChildLifecycleNode(), this double check is not neccessary anymore +// after turnChildLifecycleNode(), this double check is not neccessary anymore // Release any allocated resources action_server_.reset(); From ff6ee9f2ca9eff3a4a51990c981831987d369a08 Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Wed, 22 Nov 2023 15:55:31 +0800 Subject: [PATCH 10/47] add childLifecycleNode mode in costmap_2d_ros --- nav2_planner/src/planner_server.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/nav2_planner/src/planner_server.cpp b/nav2_planner/src/planner_server.cpp index 8d6691e941..7558a0d4ce 100644 --- a/nav2_planner/src/planner_server.cpp +++ b/nav2_planner/src/planner_server.cpp @@ -90,7 +90,7 @@ PlannerServer::on_configure(const rclcpp_lifecycle::State & /*state*/) costmap_thread_ = std::make_unique(costmap_ros_); // work as a child-LifecycleNode of its parent planner_server costmap_ros_->turnChildLifecycleNode(); - + RCLCPP_DEBUG( get_logger(), "Costmap size: %d,%d", costmap_->getSizeInCellsX(), costmap_->getSizeInCellsY()); @@ -224,9 +224,9 @@ PlannerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) // lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) // { // RCLCPP_INFO(get_logger(), "costmap_ros_->cleanup()"); - costmap_ros_->deactivate(); + costmap_ros_->deactivate(); // } - // after turnChildLifecycleNode(), this double check is not neccessary anymore +// after turnChildLifecycleNode(), this double check is not neccessary anymore PlannerMap::iterator it; for (it = planners_.begin(); it != planners_.end(); ++it) { @@ -259,9 +259,9 @@ PlannerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/) // lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) // { // RCLCPP_INFO(get_logger(), "costmap_ros_->cleanup()"); - costmap_ros_->cleanup(); + costmap_ros_->cleanup(); // } - // after turnChildLifecycleNode(), this double check is not neccessary anymore +// after turnChildLifecycleNode(), this double check is not neccessary anymore PlannerMap::iterator it; for (it = planners_.begin(); it != planners_.end(); ++it) { From bfb97f99d36452e9bcbd8df6efed919302484995 Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Wed, 22 Nov 2023 15:59:41 +0800 Subject: [PATCH 11/47] add ChildLifecycleNode mode in costmap_2d_ros --- nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index ecd5c65558..e5fb36c7ac 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -353,6 +353,9 @@ class Costmap2DROS : public nav2_util::LifecycleNode double getRobotRadius() {return robot_radius_;} protected: + // launch mode: as a child-thread or an independent-process + bool is_thread_{false}; + // Publishers and subscribers rclcpp_lifecycle::LifecyclePublisher::SharedPtr footprint_pub_; From 9a0e9d0e0fc15a91a86a6691fd9dd4afa5b9df52 Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Thu, 23 Nov 2023 21:52:53 +0800 Subject: [PATCH 12/47] NodeOption: is_lifecycle_follower_ --- .../nav2_costmap_2d/costmap_2d_ros.hpp | 39 +++++++++++-------- 1 file changed, 22 insertions(+), 17 deletions(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index e5fb36c7ac..d28a106b26 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -99,6 +99,21 @@ class Costmap2DROS : public nav2_util::LifecycleNode const std::string & local_namespace, const bool & use_sim_time); + /** + * @brief Constructor for the wrapper + * @param name Name of the costmap ROS node + * @param parent_namespace Absolute namespace of the node hosting the costmap node + * @param local_namespace Namespace to append to the parent namespace + * @param use_sim_time Whether to use simulation or real time + * @param is_lifecycle_follower Whether launch as a child-LifecycleNode following others + */ + explicit Costmap2DROS( + const std::string & name, + const std::string & parent_namespace, + const std::string & local_namespace, + const bool & use_sim_time, + const bool & is_lifecycle_follower); + /** * @brief Common initialization for constructors */ @@ -135,28 +150,18 @@ class Costmap2DROS : public nav2_util::LifecycleNode nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; /** - * @brief child-LifecycleNode mode + * @brief as a child-LifecycleNode : * sometimes costmap may be launched by another LifecycleNode and work as a child-thread * child-LifecycleNode should react to ctrl+C later than its parents to avoid unclean shutdown - * Thus, it's neccessary to turnChildLifecycleNode() to change its launch mode + * Thus, it's neccessary to set NodeOption is_lifecycle_follower_ as false * - * in ChildLifecycleNode mode, it would react to rcl_preshutdown anymore + * in this NodeOption, it would not react to rcl_preshutdown anymore * all its lifecycle state would be controlled by its parent-LifecycleNode */ - void turnChildLifecycleNode() - { - // as a child-LifecycleNode launched by its parent-LifecycleNode - // and work as a child-thread - is_thread_ = true; - } - bool isThread() - { - return is_thread_; - } void on_rcl_preshutdown() override { - if (isThread() ) { - // all of its reaction is up to its parent + if (!is_lifecycle_follower_) { + // all of its reaction is up to its parent-LifecycleNode return; } @@ -353,8 +358,8 @@ class Costmap2DROS : public nav2_util::LifecycleNode double getRobotRadius() {return robot_radius_;} protected: - // launch mode: as a child-thread or an independent-process - bool is_thread_{false}; + // whether is a child-LifecycleNode following another parent-LifecycleNode + bool is_lifecycle_follower_{false}; // Publishers and subscribers rclcpp_lifecycle::LifecyclePublisher::SharedPtr From c6946fdbeef4bf592b3f3e416c5795e45f34b9f9 Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Thu, 23 Nov 2023 21:54:10 +0800 Subject: [PATCH 13/47] NodeOption: is_lifecycle_follower_ --- nav2_costmap_2d/src/costmap_2d_ros.cpp | 14 ++++++++++++-- 1 file changed, 12 insertions(+), 2 deletions(-) diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index c35933c908..abdcf93269 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -68,7 +68,8 @@ Costmap2DROS::Costmap2DROS() default_types_{ "nav2_costmap_2d::StaticLayer", "nav2_costmap_2d::ObstacleLayer", - "nav2_costmap_2d::InflationLayer"} + "nav2_costmap_2d::InflationLayer"}, + is_lifecycle_follower_(false) // default: work as an independent node { declare_parameter("map_topic", rclcpp::ParameterValue(std::string("map"))); init(); @@ -79,6 +80,14 @@ Costmap2DROS::Costmap2DROS( const std::string & parent_namespace, const std::string & local_namespace, const bool & use_sim_time) +: Costmap2DROS(name, parent_namespace, local_namespace, use_sim_time, false) {} + +Costmap2DROS::Costmap2DROS( + const std::string & name, + const std::string & parent_namespace, + const std::string & local_namespace, + const bool & use_sim_time, + const bool & is_lifecycle_follower) : nav2_util::LifecycleNode(name, "", // NodeOption arguments take precedence over the ones provided on the command line // use this to make sure the node is placed on the provided namespace @@ -96,7 +105,8 @@ Costmap2DROS::Costmap2DROS( default_types_{ "nav2_costmap_2d::StaticLayer", "nav2_costmap_2d::ObstacleLayer", - "nav2_costmap_2d::InflationLayer"} + "nav2_costmap_2d::InflationLayer"}, + is_lifecycle_follower_(is_lifecycle_follower) { declare_parameter( "map_topic", rclcpp::ParameterValue( From db96ddec709bd4ca24deff12a4117010236b415a Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Thu, 23 Nov 2023 21:54:43 +0800 Subject: [PATCH 14/47] fit to NodeOption: is_lifecycle_follower_ --- nav2_planner/src/planner_server.cpp | 27 ++++++++------------------- 1 file changed, 8 insertions(+), 19 deletions(-) diff --git a/nav2_planner/src/planner_server.cpp b/nav2_planner/src/planner_server.cpp index 7558a0d4ce..fa36587f06 100644 --- a/nav2_planner/src/planner_server.cpp +++ b/nav2_planner/src/planner_server.cpp @@ -65,7 +65,9 @@ PlannerServer::PlannerServer(const rclcpp::NodeOptions & options) // Setup the global costmap costmap_ros_ = std::make_shared( "global_costmap", std::string{get_namespace()}, "global_costmap", - get_parameter("use_sim_time").as_bool()); + get_parameter("use_sim_time").as_bool(), + true); // work as a child-LifecycleNode of planner_server + } PlannerServer::~PlannerServer() @@ -88,8 +90,6 @@ PlannerServer::on_configure(const rclcpp_lifecycle::State & /*state*/) // Launch a thread to run the costmap node costmap_thread_ = std::make_unique(costmap_ros_); - // work as a child-LifecycleNode of its parent planner_server - costmap_ros_->turnChildLifecycleNode(); RCLCPP_DEBUG( get_logger(), "Costmap size: %d,%d", @@ -220,13 +220,12 @@ PlannerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) * unordered_set iteration. Once this issue is resolved, we can maybe make a stronger * ordering assumption: https://github.com/ros2/rclcpp/issues/2096 */ -// if (costmap_ros_->get_current_state().id() == -// lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) -// { -// RCLCPP_INFO(get_logger(), "costmap_ros_->cleanup()"); + /* + * The costmap is changed into is_lifecycle_follower_{true} + * https://github.com/ros-planning/navigation2/pull/3972 + * within this NodeOption, no neccessary to set double check. + */ costmap_ros_->deactivate(); -// } -// after turnChildLifecycleNode(), this double check is not neccessary anymore PlannerMap::iterator it; for (it = planners_.begin(); it != planners_.end(); ++it) { @@ -251,17 +250,7 @@ PlannerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/) plan_publisher_.reset(); tf_.reset(); - /* - * Double check whether something else transitioned it to INACTIVE - * already, e.g. the rcl preshutdown callback. - */ -// if (costmap_ros_->get_current_state().id() == -// lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) -// { -// RCLCPP_INFO(get_logger(), "costmap_ros_->cleanup()"); costmap_ros_->cleanup(); -// } -// after turnChildLifecycleNode(), this double check is not neccessary anymore PlannerMap::iterator it; for (it = planners_.begin(); it != planners_.end(); ++it) { From cb8128e7b903c98d4d8d705d7cd573c980418393 Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Thu, 23 Nov 2023 21:55:14 +0800 Subject: [PATCH 15/47] NodeOption: is_lifecycle_follower_ --- nav2_controller/src/controller_server.cpp | 48 +++++++++-------------- 1 file changed, 18 insertions(+), 30 deletions(-) diff --git a/nav2_controller/src/controller_server.cpp b/nav2_controller/src/controller_server.cpp index 27c474f39f..fb629dcc4d 100644 --- a/nav2_controller/src/controller_server.cpp +++ b/nav2_controller/src/controller_server.cpp @@ -62,12 +62,12 @@ ControllerServer::ControllerServer(const rclcpp::NodeOptions & options) declare_parameter("speed_limit_topic", rclcpp::ParameterValue("speed_limit")); declare_parameter("failure_tolerance", rclcpp::ParameterValue(0.0)); - declare_parameter("use_realtime_priority", rclcpp::ParameterValue(false)); // The costmap node is used in the implementation of the controller costmap_ros_ = std::make_shared( "local_costmap", std::string{get_namespace()}, "local_costmap", - get_parameter("use_sim_time").as_bool()); + get_parameter("use_sim_time").as_bool(), + true); // work as a child-LifecycleNode following controller_server } ControllerServer::~ControllerServer() @@ -127,13 +127,10 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & /*state*/) std::string speed_limit_topic; get_parameter("speed_limit_topic", speed_limit_topic); get_parameter("failure_tolerance", failure_tolerance_); - get_parameter("use_realtime_priority", use_realtime_priority_); costmap_ros_->configure(); // Launch a thread to run the costmap node costmap_thread_ = std::make_unique(costmap_ros_); - // work as a child-LifecycleNode of its parent controller_server - costmap_ros_->turnChildLifecycleNode(); for (size_t i = 0; i != progress_checker_ids_.size(); i++) { try { @@ -225,19 +222,13 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & /*state*/) server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout); // Create the action server that we implement with our followPath method - // This may throw due to real-time prioritzation if user doesn't have real-time permissions - try { - action_server_ = std::make_unique( - shared_from_this(), - "follow_path", - std::bind(&ControllerServer::computeControl, this), - nullptr, - std::chrono::milliseconds(500), - true /*spin thread*/, server_options, use_realtime_priority_ /*soft realtime*/); - } catch (const std::runtime_error & e) { - RCLCPP_ERROR(get_logger(), "Error creating action server! %s", e.what()); - return nav2_util::CallbackReturn::FAILURE; - } + action_server_ = std::make_unique( + shared_from_this(), + "follow_path", + std::bind(&ControllerServer::computeControl, this), + nullptr, + std::chrono::milliseconds(500), + true, server_options); // Set subscribtion to the speed limiting topic speed_limit_sub_ = create_subscription( @@ -292,13 +283,13 @@ ControllerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) * unordered_set iteration. Once this issue is resolved, we can maybe make a stronger * ordering assumption: https://github.com/ros2/rclcpp/issues/2096 */ -// if (costmap_ros_->get_current_state().id() == -// lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) -// { -// RCLCPP_INFO(get_logger(), "costmap_ros_->cleanup()"); + /* + * The costmap is changed into is_lifecycle_follower_{true} + * https://github.com/ros-planning/navigation2/pull/3972 + * within this NodeOption, no neccessary to set double check. + */ costmap_ros_->deactivate(); -// } -// after turnChildLifecycleNode(), this double check is not neccessary anymore + publishZeroVelocity(); vel_publisher_->on_deactivate(); @@ -324,13 +315,10 @@ ControllerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/) goal_checkers_.clear(); progress_checkers_.clear(); -// if (costmap_ros_->get_current_state().id() == -// lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) -// { -// RCLCPP_INFO(get_logger(), "costmap_ros_->cleanup()"); + + costmap_ros_->cleanup(); -// } -// after turnChildLifecycleNode(), this double check is not neccessary anymore + // Release any allocated resources action_server_.reset(); From fde11557b4ca35cf6ab87ae436dc94d088fa0889 Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Thu, 23 Nov 2023 22:00:31 +0800 Subject: [PATCH 16/47] fit to NodeOption: is_lifecycle_follower --- nav2_controller/src/controller_server.cpp | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/nav2_controller/src/controller_server.cpp b/nav2_controller/src/controller_server.cpp index fb629dcc4d..bbc27f0b5c 100644 --- a/nav2_controller/src/controller_server.cpp +++ b/nav2_controller/src/controller_server.cpp @@ -127,6 +127,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & /*state*/) std::string speed_limit_topic; get_parameter("speed_limit_topic", speed_limit_topic); get_parameter("failure_tolerance", failure_tolerance_); + get_parameter("use_realtime_priority", use_realtime_priority_); costmap_ros_->configure(); // Launch a thread to run the costmap node @@ -222,13 +223,26 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & /*state*/) server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout); // Create the action server that we implement with our followPath method + // This may throw due to real-time prioritzation if user doesn't have real-time permissions action_server_ = std::make_unique( + try { shared_from_this(), + action_server_ = std::make_unique( "follow_path", + shared_from_this(), std::bind(&ControllerServer::computeControl, this), + "follow_path", nullptr, + std::bind(&ControllerServer::computeControl, this), std::chrono::milliseconds(500), + nullptr, true, server_options); + std::chrono::milliseconds(500), + true /*spin thread*/, server_options, use_realtime_priority_ /*soft realtime*/); + } catch (const std::runtime_error & e) { + RCLCPP_ERROR(get_logger(), "Error creating action server! %s", e.what()); + return nav2_util::CallbackReturn::FAILURE; + } // Set subscribtion to the speed limiting topic speed_limit_sub_ = create_subscription( From 852f5477cf0c86159b706d2b652915bf7f04d6fe Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Thu, 23 Nov 2023 22:08:51 +0800 Subject: [PATCH 17/47] fit to NodeOption: is_lifecycle_follower --- nav2_controller/src/controller_server.cpp | 12 ++---------- 1 file changed, 2 insertions(+), 10 deletions(-) diff --git a/nav2_controller/src/controller_server.cpp b/nav2_controller/src/controller_server.cpp index bbc27f0b5c..3f66c15604 100644 --- a/nav2_controller/src/controller_server.cpp +++ b/nav2_controller/src/controller_server.cpp @@ -62,12 +62,13 @@ ControllerServer::ControllerServer(const rclcpp::NodeOptions & options) declare_parameter("speed_limit_topic", rclcpp::ParameterValue("speed_limit")); declare_parameter("failure_tolerance", rclcpp::ParameterValue(0.0)); + declare_parameter("use_realtime_priority", rclcpp::ParameterValue(false)); // The costmap node is used in the implementation of the controller costmap_ros_ = std::make_shared( "local_costmap", std::string{get_namespace()}, "local_costmap", get_parameter("use_sim_time").as_bool(), - true); // work as a child-LifecycleNode following controller_server + true); // work as a child-LifecycleNode of planner_server } ControllerServer::~ControllerServer() @@ -224,19 +225,12 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & /*state*/) // Create the action server that we implement with our followPath method // This may throw due to real-time prioritzation if user doesn't have real-time permissions - action_server_ = std::make_unique( try { - shared_from_this(), action_server_ = std::make_unique( - "follow_path", shared_from_this(), - std::bind(&ControllerServer::computeControl, this), "follow_path", - nullptr, std::bind(&ControllerServer::computeControl, this), - std::chrono::milliseconds(500), nullptr, - true, server_options); std::chrono::milliseconds(500), true /*spin thread*/, server_options, use_realtime_priority_ /*soft realtime*/); } catch (const std::runtime_error & e) { @@ -304,7 +298,6 @@ ControllerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) */ costmap_ros_->deactivate(); - publishZeroVelocity(); vel_publisher_->on_deactivate(); dyn_params_handler_.reset(); @@ -330,7 +323,6 @@ ControllerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/) goal_checkers_.clear(); progress_checkers_.clear(); - costmap_ros_->cleanup(); From 6a6715c7cc7466be29b8f5a7631cf115f61517de Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Thu, 23 Nov 2023 22:40:22 +0800 Subject: [PATCH 18/47] fit reorder Werror --- nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index d28a106b26..6318a575f6 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -358,9 +358,6 @@ class Costmap2DROS : public nav2_util::LifecycleNode double getRobotRadius() {return robot_radius_;} protected: - // whether is a child-LifecycleNode following another parent-LifecycleNode - bool is_lifecycle_follower_{false}; - // Publishers and subscribers rclcpp_lifecycle::LifecyclePublisher::SharedPtr footprint_pub_; @@ -424,6 +421,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode bool track_unknown_space_{false}; double transform_tolerance_{0}; ///< The timeout before transform errors double initial_transform_timeout_{0}; ///< The timeout before activation of the node errors + bool is_lifecycle_follower_{false}; ///< whether is a child-LifecycleNode following another parent-LifecycleNode // Derived parameters bool use_radius_{false}; From 4fda15d8b83b644baec48e91340a43860f8164bf Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Fri, 24 Nov 2023 00:16:25 +0800 Subject: [PATCH 19/47] fix wrong use of is_lifecycle_follower --- nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index 6318a575f6..70c90e2d8c 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -160,7 +160,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode */ void on_rcl_preshutdown() override { - if (!is_lifecycle_follower_) { + if (is_lifecycle_follower_) { // all of its reaction is up to its parent-LifecycleNode return; } From 0d4e98916088864d0c96c9736e06cfc2b0b88dd4 Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Fri, 24 Nov 2023 01:41:54 +0800 Subject: [PATCH 20/47] remove blank line --- nav2_planner/src/planner_server.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/nav2_planner/src/planner_server.cpp b/nav2_planner/src/planner_server.cpp index fa36587f06..e1d3c39a79 100644 --- a/nav2_planner/src/planner_server.cpp +++ b/nav2_planner/src/planner_server.cpp @@ -67,7 +67,6 @@ PlannerServer::PlannerServer(const rclcpp::NodeOptions & options) "global_costmap", std::string{get_namespace()}, "global_costmap", get_parameter("use_sim_time").as_bool(), true); // work as a child-LifecycleNode of planner_server - } PlannerServer::~PlannerServer() From f81615ba90e9bdd00dbb0b2a25d9e74033cbb583 Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Fri, 24 Nov 2023 14:15:54 +0800 Subject: [PATCH 21/47] NodeOption: is_lifecycle_follower_ --- nav2_costmap_2d/src/costmap_2d_ros.cpp | 13 ++----------- 1 file changed, 2 insertions(+), 11 deletions(-) diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index abdcf93269..4093ecc80b 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -69,7 +69,7 @@ Costmap2DROS::Costmap2DROS() "nav2_costmap_2d::StaticLayer", "nav2_costmap_2d::ObstacleLayer", "nav2_costmap_2d::InflationLayer"}, - is_lifecycle_follower_(false) // default: work as an independent node + is_lifecycle_follower_(false) //default: is an independent node { declare_parameter("map_topic", rclcpp::ParameterValue(std::string("map"))); init(); @@ -80,14 +80,6 @@ Costmap2DROS::Costmap2DROS( const std::string & parent_namespace, const std::string & local_namespace, const bool & use_sim_time) -: Costmap2DROS(name, parent_namespace, local_namespace, use_sim_time, false) {} - -Costmap2DROS::Costmap2DROS( - const std::string & name, - const std::string & parent_namespace, - const std::string & local_namespace, - const bool & use_sim_time, - const bool & is_lifecycle_follower) : nav2_util::LifecycleNode(name, "", // NodeOption arguments take precedence over the ones provided on the command line // use this to make sure the node is placed on the provided namespace @@ -105,8 +97,7 @@ Costmap2DROS::Costmap2DROS( default_types_{ "nav2_costmap_2d::StaticLayer", "nav2_costmap_2d::ObstacleLayer", - "nav2_costmap_2d::InflationLayer"}, - is_lifecycle_follower_(is_lifecycle_follower) + "nav2_costmap_2d::InflationLayer"} { declare_parameter( "map_topic", rclcpp::ParameterValue( From 897b26328478047085deaf5702598a50b4abb24c Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Fri, 24 Nov 2023 14:16:32 +0800 Subject: [PATCH 22/47] NodeOption: is_lifecycle_follower_ --- .../nav2_costmap_2d/costmap_2d_ros.hpp | 21 +++---------------- 1 file changed, 3 insertions(+), 18 deletions(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index 6318a575f6..ecffd94565 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -99,21 +99,6 @@ class Costmap2DROS : public nav2_util::LifecycleNode const std::string & local_namespace, const bool & use_sim_time); - /** - * @brief Constructor for the wrapper - * @param name Name of the costmap ROS node - * @param parent_namespace Absolute namespace of the node hosting the costmap node - * @param local_namespace Namespace to append to the parent namespace - * @param use_sim_time Whether to use simulation or real time - * @param is_lifecycle_follower Whether launch as a child-LifecycleNode following others - */ - explicit Costmap2DROS( - const std::string & name, - const std::string & parent_namespace, - const std::string & local_namespace, - const bool & use_sim_time, - const bool & is_lifecycle_follower); - /** * @brief Common initialization for constructors */ @@ -153,14 +138,14 @@ class Costmap2DROS : public nav2_util::LifecycleNode * @brief as a child-LifecycleNode : * sometimes costmap may be launched by another LifecycleNode and work as a child-thread * child-LifecycleNode should react to ctrl+C later than its parents to avoid unclean shutdown - * Thus, it's neccessary to set NodeOption is_lifecycle_follower_ as false + * Thus, it's neccessary to set NodeOption is_lifecycle_follower_ as true * * in this NodeOption, it would not react to rcl_preshutdown anymore * all its lifecycle state would be controlled by its parent-LifecycleNode */ void on_rcl_preshutdown() override { - if (!is_lifecycle_follower_) { + if (is_lifecycle_follower_) { // all of its reaction is up to its parent-LifecycleNode return; } @@ -421,7 +406,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode bool track_unknown_space_{false}; double transform_tolerance_{0}; ///< The timeout before transform errors double initial_transform_timeout_{0}; ///< The timeout before activation of the node errors - bool is_lifecycle_follower_{false}; ///< whether is a child-LifecycleNode following another parent-LifecycleNode + bool is_lifecycle_follower_{true}; ///< whether is a child-LifecycleNode or an independent node // Derived parameters bool use_radius_{false}; From 0fa7cc00a6e8955b5306a374034726b5232699ce Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Fri, 24 Nov 2023 14:17:20 +0800 Subject: [PATCH 23/47] Add files via upload --- nav2_controller/src/controller_server.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/nav2_controller/src/controller_server.cpp b/nav2_controller/src/controller_server.cpp index 3f66c15604..05dc9a3898 100644 --- a/nav2_controller/src/controller_server.cpp +++ b/nav2_controller/src/controller_server.cpp @@ -67,8 +67,7 @@ ControllerServer::ControllerServer(const rclcpp::NodeOptions & options) // The costmap node is used in the implementation of the controller costmap_ros_ = std::make_shared( "local_costmap", std::string{get_namespace()}, "local_costmap", - get_parameter("use_sim_time").as_bool(), - true); // work as a child-LifecycleNode of planner_server + get_parameter("use_sim_time").as_bool()); // work as a child-LifecycleNode of planner_server } ControllerServer::~ControllerServer() From 1007d2b24438c7caa2391623e5467ce49eb1e78a Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Fri, 24 Nov 2023 14:17:55 +0800 Subject: [PATCH 24/47] NodeOption: is_lifecycle_follower_ --- nav2_planner/src/planner_server.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/nav2_planner/src/planner_server.cpp b/nav2_planner/src/planner_server.cpp index fa36587f06..d649a47651 100644 --- a/nav2_planner/src/planner_server.cpp +++ b/nav2_planner/src/planner_server.cpp @@ -65,9 +65,7 @@ PlannerServer::PlannerServer(const rclcpp::NodeOptions & options) // Setup the global costmap costmap_ros_ = std::make_shared( "global_costmap", std::string{get_namespace()}, "global_costmap", - get_parameter("use_sim_time").as_bool(), - true); // work as a child-LifecycleNode of planner_server - + get_parameter("use_sim_time").as_bool()); } PlannerServer::~PlannerServer() From 2348f1fd402afcd65f6e66c4bbe58b9ba2a302db Mon Sep 17 00:00:00 2001 From: GoesM Date: Fri, 24 Nov 2023 14:24:51 +0800 Subject: [PATCH 25/47] NodeOption:is_lifecycle_follower_ --- nav2_controller/src/controller_server.cpp | 2 +- nav2_costmap_2d/src/costmap_2d_ros.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/nav2_controller/src/controller_server.cpp b/nav2_controller/src/controller_server.cpp index 05dc9a3898..1a0d753dff 100644 --- a/nav2_controller/src/controller_server.cpp +++ b/nav2_controller/src/controller_server.cpp @@ -67,7 +67,7 @@ ControllerServer::ControllerServer(const rclcpp::NodeOptions & options) // The costmap node is used in the implementation of the controller costmap_ros_ = std::make_shared( "local_costmap", std::string{get_namespace()}, "local_costmap", - get_parameter("use_sim_time").as_bool()); // work as a child-LifecycleNode of planner_server + get_parameter("use_sim_time").as_bool()); } ControllerServer::~ControllerServer() diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index 4093ecc80b..0cd937c4d9 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -69,7 +69,7 @@ Costmap2DROS::Costmap2DROS() "nav2_costmap_2d::StaticLayer", "nav2_costmap_2d::ObstacleLayer", "nav2_costmap_2d::InflationLayer"}, - is_lifecycle_follower_(false) //default: is an independent node + is_lifecycle_follower_(false) // default: is an independent node { declare_parameter("map_topic", rclcpp::ParameterValue(std::string("map"))); init(); From 0e31e190a4a282fb4d6afe27b768c52a516dc77c Mon Sep 17 00:00:00 2001 From: GoesM Date: Fri, 24 Nov 2023 17:00:13 +0800 Subject: [PATCH 26/47] NodeOption:is_lifecycle_follower --- nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp | 2 +- nav2_costmap_2d/src/costmap_2d_ros.cpp | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index ecffd94565..1d3e54cf10 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -406,7 +406,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode bool track_unknown_space_{false}; double transform_tolerance_{0}; ///< The timeout before transform errors double initial_transform_timeout_{0}; ///< The timeout before activation of the node errors - bool is_lifecycle_follower_{true}; ///< whether is a child-LifecycleNode or an independent node + bool is_lifecycle_follower_{false}; ///< whether is a child-LifecycleNode or an independent node // Derived parameters bool use_radius_{false}; diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index 0cd937c4d9..376b9a3426 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -97,7 +97,8 @@ Costmap2DROS::Costmap2DROS( default_types_{ "nav2_costmap_2d::StaticLayer", "nav2_costmap_2d::ObstacleLayer", - "nav2_costmap_2d::InflationLayer"} + "nav2_costmap_2d::InflationLayer"}, + is_lifecycle_follower_(true) // default: is an independent node { declare_parameter( "map_topic", rclcpp::ParameterValue( From add3ecad253c6ed458b13f3271cf617f62b974ce Mon Sep 17 00:00:00 2001 From: GoesM Date: Fri, 24 Nov 2023 17:04:50 +0800 Subject: [PATCH 27/47] NodeOption:is_lifecycle_follower --- nav2_costmap_2d/src/costmap_2d_ros.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index 376b9a3426..a4a704e6cc 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -98,7 +98,7 @@ Costmap2DROS::Costmap2DROS( "nav2_costmap_2d::StaticLayer", "nav2_costmap_2d::ObstacleLayer", "nav2_costmap_2d::InflationLayer"}, - is_lifecycle_follower_(true) // default: is an independent node + is_lifecycle_follower_(true) // default: is not an independent node { declare_parameter( "map_topic", rclcpp::ParameterValue( From f91c1211bfae7dc28da3d0a14a2823aba6c514a8 Mon Sep 17 00:00:00 2001 From: GoesM Date: Fri, 24 Nov 2023 18:52:50 +0800 Subject: [PATCH 28/47] NodeOption:is_lifecycle_follower --- nav2_costmap_2d/src/costmap_2d_ros.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index a4a704e6cc..c35933c908 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -68,8 +68,7 @@ Costmap2DROS::Costmap2DROS() default_types_{ "nav2_costmap_2d::StaticLayer", "nav2_costmap_2d::ObstacleLayer", - "nav2_costmap_2d::InflationLayer"}, - is_lifecycle_follower_(false) // default: is an independent node + "nav2_costmap_2d::InflationLayer"} { declare_parameter("map_topic", rclcpp::ParameterValue(std::string("map"))); init(); @@ -97,8 +96,7 @@ Costmap2DROS::Costmap2DROS( default_types_{ "nav2_costmap_2d::StaticLayer", "nav2_costmap_2d::ObstacleLayer", - "nav2_costmap_2d::InflationLayer"}, - is_lifecycle_follower_(true) // default: is not an independent node + "nav2_costmap_2d::InflationLayer"} { declare_parameter( "map_topic", rclcpp::ParameterValue( From aff34e2c845818247507af3fa385db0182fc60d2 Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Fri, 24 Nov 2023 18:56:20 +0800 Subject: [PATCH 29/47] change default --- nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index 1d3e54cf10..ecffd94565 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -406,7 +406,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode bool track_unknown_space_{false}; double transform_tolerance_{0}; ///< The timeout before transform errors double initial_transform_timeout_{0}; ///< The timeout before activation of the node errors - bool is_lifecycle_follower_{false}; ///< whether is a child-LifecycleNode or an independent node + bool is_lifecycle_follower_{true}; ///< whether is a child-LifecycleNode or an independent node // Derived parameters bool use_radius_{false}; From 4c40d1f4d111e78c5467c6871f5ecec7b0cd432a Mon Sep 17 00:00:00 2001 From: GoesM Date: Tue, 28 Nov 2023 18:07:27 +0800 Subject: [PATCH 30/47] add NodeOption for costmap_2d_ros --- nav2_controller/src/controller_server.cpp | 5 ----- .../nav2_costmap_2d/costmap_2d_ros.hpp | 3 ++- nav2_costmap_2d/src/costmap_2d_ros.cpp | 20 ++++++++++++++----- nav2_planner/src/planner_server.cpp | 5 ----- 4 files changed, 17 insertions(+), 16 deletions(-) diff --git a/nav2_controller/src/controller_server.cpp b/nav2_controller/src/controller_server.cpp index 1a0d753dff..76754c5815 100644 --- a/nav2_controller/src/controller_server.cpp +++ b/nav2_controller/src/controller_server.cpp @@ -290,11 +290,6 @@ ControllerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) * unordered_set iteration. Once this issue is resolved, we can maybe make a stronger * ordering assumption: https://github.com/ros2/rclcpp/issues/2096 */ - /* - * The costmap is changed into is_lifecycle_follower_{true} - * https://github.com/ros-planning/navigation2/pull/3972 - * within this NodeOption, no neccessary to set double check. - */ costmap_ros_->deactivate(); publishZeroVelocity(); diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index ecffd94565..2c2c559187 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -75,8 +75,9 @@ class Costmap2DROS : public nav2_util::LifecycleNode public: /** * @brief Constructor for the wrapper + * @param options Additional options to control creation of the node. */ - Costmap2DROS(); + Costmap2DROS(const rclcpp::NodeOptions & options); /** * @brief Constructor for the wrapper, the node will diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index 0cd937c4d9..5afc76473b 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -61,17 +61,27 @@ namespace nav2_costmap_2d Costmap2DROS::Costmap2DROS(const std::string & name, const bool & use_sim_time) : Costmap2DROS(name, "/", name, use_sim_time) {} -Costmap2DROS::Costmap2DROS() -: nav2_util::LifecycleNode("costmap", ""), +Costmap2DROS::Costmap2DROS(const rclcpp::NodeOptions & options) +: nav2_util::LifecycleNode("costmap", "",options), name_("costmap"), default_plugins_{"static_layer", "obstacle_layer", "inflation_layer"}, default_types_{ "nav2_costmap_2d::StaticLayer", "nav2_costmap_2d::ObstacleLayer", - "nav2_costmap_2d::InflationLayer"}, - is_lifecycle_follower_(false) // default: is an independent node + "nav2_costmap_2d::InflationLayer"} { declare_parameter("map_topic", rclcpp::ParameterValue(std::string("map"))); + /** + * @brief as an independent node + * if launched as an independent node, + * set `is_lifecycle_follower_ = true`. + * thus, it would react to rcl_preshutdown + * + * else if launched in a thread created by another LifecycleNode (its parent), + * set `is_lifecycle_follower_ = false`. + * it would not react to rcl_preshutdown anymore and its lifecycle state is controlled by its parent + */ + is_lifecycle_follower_ = false; init(); } @@ -79,7 +89,7 @@ Costmap2DROS::Costmap2DROS( const std::string & name, const std::string & parent_namespace, const std::string & local_namespace, - const bool & use_sim_time) + const bool & use_sim_time) : nav2_util::LifecycleNode(name, "", // NodeOption arguments take precedence over the ones provided on the command line // use this to make sure the node is placed on the provided namespace diff --git a/nav2_planner/src/planner_server.cpp b/nav2_planner/src/planner_server.cpp index d649a47651..fea40ea405 100644 --- a/nav2_planner/src/planner_server.cpp +++ b/nav2_planner/src/planner_server.cpp @@ -218,11 +218,6 @@ PlannerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) * unordered_set iteration. Once this issue is resolved, we can maybe make a stronger * ordering assumption: https://github.com/ros2/rclcpp/issues/2096 */ - /* - * The costmap is changed into is_lifecycle_follower_{true} - * https://github.com/ros-planning/navigation2/pull/3972 - * within this NodeOption, no neccessary to set double check. - */ costmap_ros_->deactivate(); PlannerMap::iterator it; From 70104cea523b2895b33cc5bb217171a92f8feca6 Mon Sep 17 00:00:00 2001 From: GoesM Date: Tue, 28 Nov 2023 22:48:09 +0800 Subject: [PATCH 31/47] add node options for costmap2dros as an independent node --- .../include/nav2_costmap_2d/costmap_2d_ros.hpp | 3 ++- nav2_costmap_2d/src/costmap_2d_ros.cpp | 18 ++++++++---------- nav2_costmap_2d/test/unit/lifecycle_test.cpp | 4 +++- 3 files changed, 13 insertions(+), 12 deletions(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index 2c2c559187..f524399f39 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -77,7 +77,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode * @brief Constructor for the wrapper * @param options Additional options to control creation of the node. */ - Costmap2DROS(const rclcpp::NodeOptions & options); + Costmap2DROS(const rclcpp::NodeOptions & options=rclcpp::NodeOptions()); /** * @brief Constructor for the wrapper, the node will @@ -407,6 +407,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode bool track_unknown_space_{false}; double transform_tolerance_{0}; ///< The timeout before transform errors double initial_transform_timeout_{0}; ///< The timeout before activation of the node errors + bool is_lifecycle_follower_{true}; ///< whether is a child-LifecycleNode or an independent node // Derived parameters diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index 5afc76473b..012bc0d973 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -68,20 +68,18 @@ Costmap2DROS::Costmap2DROS(const rclcpp::NodeOptions & options) default_types_{ "nav2_costmap_2d::StaticLayer", "nav2_costmap_2d::ObstacleLayer", - "nav2_costmap_2d::InflationLayer"} + "nav2_costmap_2d::InflationLayer"}, { declare_parameter("map_topic", rclcpp::ParameterValue(std::string("map"))); /** - * @brief as an independent node - * if launched as an independent node, - * set `is_lifecycle_follower_ = true`. - * thus, it would react to rcl_preshutdown - * - * else if launched in a thread created by another LifecycleNode (its parent), - * set `is_lifecycle_follower_ = false`. - * it would not react to rcl_preshutdown anymore and its lifecycle state is controlled by its parent + * @brief + * If launched as an independent node, set `is_lifecycle_follower_ = true`. + * Thus, it would react to rcl_preshutdown. + * Else if launched in a thread created by another LifecycleNode(its parent), set + * `is_lifecycle_follower_ = false`. It would not react to rcl_preshutdown anymore + * and its lifecycle state is controlled by its parent. */ - is_lifecycle_follower_ = false; + get_parameter("is_lifecycle_follower", is_lifecycle_follower_); init(); } diff --git a/nav2_costmap_2d/test/unit/lifecycle_test.cpp b/nav2_costmap_2d/test/unit/lifecycle_test.cpp index 8a657d81ad..6822ba05c7 100644 --- a/nav2_costmap_2d/test/unit/lifecycle_test.cpp +++ b/nav2_costmap_2d/test/unit/lifecycle_test.cpp @@ -22,7 +22,9 @@ TEST(LifecylceTest, CheckInitialTfTimeout) { rclcpp::init(0, nullptr); - auto costmap = std::make_shared("test_costmap"); + // launch costmap as an independent node + auto costmap = std::make_shared( + rclcpp::NodeOptions.append_paramerter_override("is_lifecycle_follower", false)); costmap->set_parameter({"initial_transform_timeout", 0.0}); std::thread spin_thread{[costmap]() {rclcpp::spin(costmap->get_node_base_interface());}}; From 838393faa44be6e005ad40593cb9e3971d9a4086 Mon Sep 17 00:00:00 2001 From: GoesM Date: Tue, 28 Nov 2023 22:49:42 +0800 Subject: [PATCH 32/47] code style reformat --- nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp | 4 ++-- nav2_costmap_2d/src/costmap_2d_ros.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index f524399f39..0c2c0bdabe 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -77,7 +77,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode * @brief Constructor for the wrapper * @param options Additional options to control creation of the node. */ - Costmap2DROS(const rclcpp::NodeOptions & options=rclcpp::NodeOptions()); + Costmap2DROS(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); /** * @brief Constructor for the wrapper, the node will @@ -407,7 +407,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode bool track_unknown_space_{false}; double transform_tolerance_{0}; ///< The timeout before transform errors double initial_transform_timeout_{0}; ///< The timeout before activation of the node errors - + bool is_lifecycle_follower_{true}; ///< whether is a child-LifecycleNode or an independent node // Derived parameters diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index 012bc0d973..8fbe88c327 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -62,7 +62,7 @@ Costmap2DROS::Costmap2DROS(const std::string & name, const bool & use_sim_time) : Costmap2DROS(name, "/", name, use_sim_time) {} Costmap2DROS::Costmap2DROS(const rclcpp::NodeOptions & options) -: nav2_util::LifecycleNode("costmap", "",options), +: nav2_util::LifecycleNode("costmap", "", options), name_("costmap"), default_plugins_{"static_layer", "obstacle_layer", "inflation_layer"}, default_types_{ @@ -87,7 +87,7 @@ Costmap2DROS::Costmap2DROS( const std::string & name, const std::string & parent_namespace, const std::string & local_namespace, - const bool & use_sim_time) + const bool & use_sim_time) : nav2_util::LifecycleNode(name, "", // NodeOption arguments take precedence over the ones provided on the command line // use this to make sure the node is placed on the provided namespace From bb96f1201808abd06b23d7c605bcb3b6eaedaa44 Mon Sep 17 00:00:00 2001 From: GoesM Date: Tue, 28 Nov 2023 23:26:18 +0800 Subject: [PATCH 33/47] fit to NodeOption of Costmap2DROS --- nav2_costmap_2d/test/unit/lifecycle_test.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/nav2_costmap_2d/test/unit/lifecycle_test.cpp b/nav2_costmap_2d/test/unit/lifecycle_test.cpp index 6822ba05c7..3fde293104 100644 --- a/nav2_costmap_2d/test/unit/lifecycle_test.cpp +++ b/nav2_costmap_2d/test/unit/lifecycle_test.cpp @@ -22,9 +22,10 @@ TEST(LifecylceTest, CheckInitialTfTimeout) { rclcpp::init(0, nullptr); - // launch costmap as an independent node auto costmap = std::make_shared( - rclcpp::NodeOptions.append_paramerter_override("is_lifecycle_follower", false)); + rclcpp::NodeOptions().append_parameter_override("is_lifecycle_follower",false) + // launched as an independent node + ); costmap->set_parameter({"initial_transform_timeout", 0.0}); std::thread spin_thread{[costmap]() {rclcpp::spin(costmap->get_node_base_interface());}}; @@ -53,4 +54,4 @@ TEST(LifecylceTest, CheckInitialTfTimeout) { if (spin_thread.joinable()) { spin_thread.join(); } -} +} \ No newline at end of file From 6c291aed34dd9814c5c0495429c3b5ed640d99e2 Mon Sep 17 00:00:00 2001 From: GoesM Date: Tue, 28 Nov 2023 23:31:10 +0800 Subject: [PATCH 34/47] fit to NodeOption of Costmap2DROS --- nav2_costmap_2d/test/unit/lifecycle_test.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/nav2_costmap_2d/test/unit/lifecycle_test.cpp b/nav2_costmap_2d/test/unit/lifecycle_test.cpp index 3fde293104..5e892360de 100644 --- a/nav2_costmap_2d/test/unit/lifecycle_test.cpp +++ b/nav2_costmap_2d/test/unit/lifecycle_test.cpp @@ -22,9 +22,9 @@ TEST(LifecylceTest, CheckInitialTfTimeout) { rclcpp::init(0, nullptr); + // launch costmap as an independent node auto costmap = std::make_shared( - rclcpp::NodeOptions().append_parameter_override("is_lifecycle_follower",false) - // launched as an independent node + rclcpp::NodeOptions().append_parameter_override("is_lifecycle_follower", false) ); costmap->set_parameter({"initial_transform_timeout", 0.0}); @@ -54,4 +54,4 @@ TEST(LifecylceTest, CheckInitialTfTimeout) { if (spin_thread.joinable()) { spin_thread.join(); } -} \ No newline at end of file +} From 2e49282ee187a076d934d21be54245706a021ec9 Mon Sep 17 00:00:00 2001 From: GoesM Date: Tue, 28 Nov 2023 23:32:31 +0800 Subject: [PATCH 35/47] fit to NodeOption of Costmap2DROS --- nav2_costmap_2d/src/costmap_2d_ros.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index 8fbe88c327..050b41570e 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -68,7 +68,7 @@ Costmap2DROS::Costmap2DROS(const rclcpp::NodeOptions & options) default_types_{ "nav2_costmap_2d::StaticLayer", "nav2_costmap_2d::ObstacleLayer", - "nav2_costmap_2d::InflationLayer"}, + "nav2_costmap_2d::InflationLayer"} { declare_parameter("map_topic", rclcpp::ParameterValue(std::string("map"))); /** From 69277616b4edd0c179ad8a13113b53acbbcb175a Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Wed, 29 Nov 2023 01:38:37 +0800 Subject: [PATCH 36/47] Update nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp Co-authored-by: Steve Macenski --- nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index 0c2c0bdabe..d86fa8acf9 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -147,7 +147,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode void on_rcl_preshutdown() override { if (is_lifecycle_follower_) { - // all of its reaction is up to its parent-LifecycleNode + // Transitioning handled by parent node return; } From ad4bcea22bd831197fe1c56d0c8fdf982979bbe3 Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Wed, 29 Nov 2023 01:39:30 +0800 Subject: [PATCH 37/47] Update nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp Co-authored-by: Steve Macenski --- nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index d86fa8acf9..46a315945e 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -151,7 +151,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode return; } - // else, same as ``on_rcl_preshutdown` in lifecycle_node.cpp` + // Else, we need to cleanup ourselves RCLCPP_INFO( get_logger(), "Running Nav2 LifecycleNode rcl preshutdown (%s)", this->get_name()); From 1719e567712c045a5cb16cc77a3dd60dd72b6e93 Mon Sep 17 00:00:00 2001 From: GoesM <130988564+GoesM@users.noreply.github.com> Date: Wed, 29 Nov 2023 01:40:02 +0800 Subject: [PATCH 38/47] Update nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp Co-authored-by: Steve Macenski --- nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index 46a315945e..7470e726d5 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -138,7 +138,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode /** * @brief as a child-LifecycleNode : * sometimes costmap may be launched by another LifecycleNode and work as a child-thread - * child-LifecycleNode should react to ctrl+C later than its parents to avoid unclean shutdown + * child-LifecycleNodes should wait for their parents to handle the shutdown, which includes this module * Thus, it's neccessary to set NodeOption is_lifecycle_follower_ as true * * in this NodeOption, it would not react to rcl_preshutdown anymore From a52ef13d1510f330fea3c128867f629129287ff7 Mon Sep 17 00:00:00 2001 From: GoesM Date: Wed, 29 Nov 2023 01:43:57 +0800 Subject: [PATCH 39/47] changes --- .../include/nav2_costmap_2d/costmap_2d_ros.hpp | 9 --------- nav2_costmap_2d/test/unit/lifecycle_test.cpp | 7 ++----- 2 files changed, 2 insertions(+), 14 deletions(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index 7470e726d5..c81f14e2aa 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -135,15 +135,6 @@ class Costmap2DROS : public nav2_util::LifecycleNode */ nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; - /** - * @brief as a child-LifecycleNode : - * sometimes costmap may be launched by another LifecycleNode and work as a child-thread - * child-LifecycleNodes should wait for their parents to handle the shutdown, which includes this module - * Thus, it's neccessary to set NodeOption is_lifecycle_follower_ as true - * - * in this NodeOption, it would not react to rcl_preshutdown anymore - * all its lifecycle state would be controlled by its parent-LifecycleNode - */ void on_rcl_preshutdown() override { if (is_lifecycle_follower_) { diff --git a/nav2_costmap_2d/test/unit/lifecycle_test.cpp b/nav2_costmap_2d/test/unit/lifecycle_test.cpp index 5e892360de..9516dcbebf 100644 --- a/nav2_costmap_2d/test/unit/lifecycle_test.cpp +++ b/nav2_costmap_2d/test/unit/lifecycle_test.cpp @@ -22,10 +22,7 @@ TEST(LifecylceTest, CheckInitialTfTimeout) { rclcpp::init(0, nullptr); - // launch costmap as an independent node - auto costmap = std::make_shared( - rclcpp::NodeOptions().append_parameter_override("is_lifecycle_follower", false) - ); + auto costmap = std::make_shared("test_costmap"); costmap->set_parameter({"initial_transform_timeout", 0.0}); std::thread spin_thread{[costmap]() {rclcpp::spin(costmap->get_node_base_interface());}}; @@ -54,4 +51,4 @@ TEST(LifecylceTest, CheckInitialTfTimeout) { if (spin_thread.joinable()) { spin_thread.join(); } -} +} \ No newline at end of file From fe9f0be38564c175e390082446293147a961698a Mon Sep 17 00:00:00 2001 From: GoesM Date: Wed, 29 Nov 2023 01:47:06 +0800 Subject: [PATCH 40/47] comment changes --- nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index c81f14e2aa..674f04cd30 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -142,7 +142,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode return; } - // Else, we need to cleanup ourselves + // Else, if this is an independent node, this node needs to handle itself. RCLCPP_INFO( get_logger(), "Running Nav2 LifecycleNode rcl preshutdown (%s)", this->get_name()); From 297c1d60bed4908d4e116b0ae5756a899a3a99cf Mon Sep 17 00:00:00 2001 From: GoesM Date: Wed, 29 Nov 2023 01:50:01 +0800 Subject: [PATCH 41/47] change get_parameter into =false --- nav2_costmap_2d/src/costmap_2d_ros.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index 050b41570e..5baf92219d 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -79,7 +79,7 @@ Costmap2DROS::Costmap2DROS(const rclcpp::NodeOptions & options) * `is_lifecycle_follower_ = false`. It would not react to rcl_preshutdown anymore * and its lifecycle state is controlled by its parent. */ - get_parameter("is_lifecycle_follower", is_lifecycle_follower_); + is_lifecycle_follower_ = false; init(); } From 3f6748a1847e2e074e8fa22a75915a5215f47704 Mon Sep 17 00:00:00 2001 From: GoesM Date: Wed, 29 Nov 2023 01:56:39 +0800 Subject: [PATCH 42/47] comment modification --- .../include/nav2_costmap_2d/costmap_2d_ros.hpp | 7 +++++++ nav2_costmap_2d/src/costmap_2d_ros.cpp | 8 -------- 2 files changed, 7 insertions(+), 8 deletions(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index 674f04cd30..ed150dc0cb 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -135,6 +135,13 @@ class Costmap2DROS : public nav2_util::LifecycleNode */ nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; + /** + * @brief as a child-LifecycleNode : + * sometimes costmap may be launched by another LifecycleNode and work as a child-thread + * child-LifecycleNodes should wait for their parents to handle the shutdown, which includes this module + * Thus, it's neccessary to set NodeOption is_lifecycle_follower_ as true + * + */ void on_rcl_preshutdown() override { if (is_lifecycle_follower_) { diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index 5baf92219d..bc887eeeb3 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -71,14 +71,6 @@ Costmap2DROS::Costmap2DROS(const rclcpp::NodeOptions & options) "nav2_costmap_2d::InflationLayer"} { declare_parameter("map_topic", rclcpp::ParameterValue(std::string("map"))); - /** - * @brief - * If launched as an independent node, set `is_lifecycle_follower_ = true`. - * Thus, it would react to rcl_preshutdown. - * Else if launched in a thread created by another LifecycleNode(its parent), set - * `is_lifecycle_follower_ = false`. It would not react to rcl_preshutdown anymore - * and its lifecycle state is controlled by its parent. - */ is_lifecycle_follower_ = false; init(); } From caf44473060f2a0519366db1a89d4599ce0166c5 Mon Sep 17 00:00:00 2001 From: GoesM Date: Wed, 29 Nov 2023 02:05:39 +0800 Subject: [PATCH 43/47] missing line --- nav2_costmap_2d/test/unit/lifecycle_test.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nav2_costmap_2d/test/unit/lifecycle_test.cpp b/nav2_costmap_2d/test/unit/lifecycle_test.cpp index 9516dcbebf..8a657d81ad 100644 --- a/nav2_costmap_2d/test/unit/lifecycle_test.cpp +++ b/nav2_costmap_2d/test/unit/lifecycle_test.cpp @@ -51,4 +51,4 @@ TEST(LifecylceTest, CheckInitialTfTimeout) { if (spin_thread.joinable()) { spin_thread.join(); } -} \ No newline at end of file +} From 125dd8eeb858cf46f4e5882fade831b0fb15545c Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Tue, 28 Nov 2023 12:00:38 -0800 Subject: [PATCH 44/47] Update nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp --- nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index ed150dc0cb..140f6148d7 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -137,7 +137,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode /** * @brief as a child-LifecycleNode : - * sometimes costmap may be launched by another LifecycleNode and work as a child-thread + * Costmap2DROS may be launched by another Lifecycle Node as a composed module * child-LifecycleNodes should wait for their parents to handle the shutdown, which includes this module * Thus, it's neccessary to set NodeOption is_lifecycle_follower_ as true * From 57b2726763ec894ea336b863931462436ad0898a Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Tue, 28 Nov 2023 12:00:44 -0800 Subject: [PATCH 45/47] Update nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp --- nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index 140f6148d7..a894aded07 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -138,7 +138,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode /** * @brief as a child-LifecycleNode : * Costmap2DROS may be launched by another Lifecycle Node as a composed module - * child-LifecycleNodes should wait for their parents to handle the shutdown, which includes this module + * If composed, its parents will handle the shutdown, which includes this module * Thus, it's neccessary to set NodeOption is_lifecycle_follower_ as true * */ From 08fc25b97784ff1a0b57a870ada9ea4a00d17c27 Mon Sep 17 00:00:00 2001 From: GoesM Date: Wed, 29 Nov 2023 19:07:42 +0800 Subject: [PATCH 46/47] delete last line --- nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index a894aded07..b1ddedceeb 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -139,8 +139,6 @@ class Costmap2DROS : public nav2_util::LifecycleNode * @brief as a child-LifecycleNode : * Costmap2DROS may be launched by another Lifecycle Node as a composed module * If composed, its parents will handle the shutdown, which includes this module - * Thus, it's neccessary to set NodeOption is_lifecycle_follower_ as true - * */ void on_rcl_preshutdown() override { From 6dde48a983532bfeb27f01efa4f1cce21b2a4732 Mon Sep 17 00:00:00 2001 From: GoesM Date: Fri, 1 Dec 2023 11:57:39 +0800 Subject: [PATCH 47/47] change lifecycle_test fit to NodeOption --- nav2_costmap_2d/test/unit/lifecycle_test.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nav2_costmap_2d/test/unit/lifecycle_test.cpp b/nav2_costmap_2d/test/unit/lifecycle_test.cpp index 8a657d81ad..a8ab817df3 100644 --- a/nav2_costmap_2d/test/unit/lifecycle_test.cpp +++ b/nav2_costmap_2d/test/unit/lifecycle_test.cpp @@ -22,7 +22,7 @@ TEST(LifecylceTest, CheckInitialTfTimeout) { rclcpp::init(0, nullptr); - auto costmap = std::make_shared("test_costmap"); + auto costmap = std::make_shared(rclcpp::NodeOptions()); costmap->set_parameter({"initial_transform_timeout", 0.0}); std::thread spin_thread{[costmap]() {rclcpp::spin(costmap->get_node_base_interface());}};