Skip to content

Commit 6062617

Browse files
gezpwjwwood
andauthored
Reduce lifecycle manager nodes (#2456)
* remove bond_client_node_ in class LifecycleManager Signed-off-by: zhenpeng ge <zhenpeng.ge@qq.com> * clear unused variables Signed-off-by: zhenpeng ge <zhenpeng.ge@qq.com> * fix lint Signed-off-by: zhenpeng ge <zhenpeng.ge@qq.com> * use dedicated executor thread Signed-off-by: William Woodall <william@osrfoundation.org> * fix building error Signed-off-by: zhenpeng ge <zhenpeng.ge@qq.com> * support to process executor for NodeThread Signed-off-by: zhenpeng ge <zhenpeng.ge@qq.com> * use NodeThread for LifecycleManager Signed-off-by: zhenpeng ge <zhenpeng.ge@qq.com> Co-authored-by: William Woodall <william@osrfoundation.org>
1 parent c417e2f commit 6062617

File tree

5 files changed

+39
-20
lines changed

5 files changed

+39
-20
lines changed

‎nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager.hpp‎

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
#include <map>
1919
#include <memory>
2020
#include <string>
21+
#include <thread>
2122
#include <unordered_map>
2223
#include <vector>
2324

@@ -52,9 +53,9 @@ class LifecycleManager : public rclcpp::Node
5253
~LifecycleManager();
5354

5455
protected:
55-
// The ROS node to create bond
56-
rclcpp::Node::SharedPtr bond_client_node_;
57-
std::unique_ptr<nav2_util::NodeThread> bond_node_thread_;
56+
// Callback group used by services and timers
57+
rclcpp::CallbackGroup::SharedPtr callback_group_;
58+
std::unique_ptr<nav2_util::NodeThread> service_thread_;
5859

5960
// The services provided by this node
6061
rclcpp::Service<ManageLifecycleNodes>::SharedPtr manager_srv_;

‎nav2_lifecycle_manager/src/lifecycle_manager.cpp‎

Lines changed: 16 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -49,18 +49,18 @@ LifecycleManager::LifecycleManager()
4949
bond_timeout_ = std::chrono::duration_cast<std::chrono::milliseconds>(
5050
std::chrono::duration<double>(bond_timeout_s));
5151

52+
callback_group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive, false);
5253
manager_srv_ = create_service<ManageLifecycleNodes>(
5354
get_name() + std::string("/manage_nodes"),
54-
std::bind(&LifecycleManager::managerCallback, this, _1, _2, _3));
55+
std::bind(&LifecycleManager::managerCallback, this, _1, _2, _3),
56+
rmw_qos_profile_services_default,
57+
callback_group_);
5558

5659
is_active_srv_ = create_service<std_srvs::srv::Trigger>(
5760
get_name() + std::string("/is_active"),
58-
std::bind(&LifecycleManager::isActiveCallback, this, _1, _2, _3));
59-
60-
auto bond_options = rclcpp::NodeOptions().arguments(
61-
{"--ros-args", "-r", std::string("__node:=") + get_name() + "_bond_client", "--"});
62-
bond_client_node_ = std::make_shared<rclcpp::Node>("_", bond_options);
63-
bond_node_thread_ = std::make_unique<nav2_util::NodeThread>(bond_client_node_);
61+
std::bind(&LifecycleManager::isActiveCallback, this, _1, _2, _3),
62+
rmw_qos_profile_services_default,
63+
callback_group_);
6464

6565
transition_state_map_[Transition::TRANSITION_CONFIGURE] = State::PRIMARY_STATE_INACTIVE;
6666
transition_state_map_[Transition::TRANSITION_CLEANUP] = State::PRIMARY_STATE_UNCONFIGURED;
@@ -84,12 +84,17 @@ LifecycleManager::LifecycleManager()
8484
if (autostart_) {
8585
startup();
8686
}
87-
});
87+
},
88+
callback_group_);
89+
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
90+
executor->add_callback_group(callback_group_, get_node_base_interface());
91+
service_thread_ = std::make_unique<nav2_util::NodeThread>(executor);
8892
}
8993

9094
LifecycleManager::~LifecycleManager()
9195
{
9296
RCLCPP_INFO(get_logger(), "Destroying %s", get_name());
97+
service_thread_.reset();
9398
}
9499

95100
void
@@ -154,7 +159,7 @@ LifecycleManager::createBondConnection(const std::string & node_name)
154159

155160
if (bond_map_.find(node_name) == bond_map_.end() && bond_timeout_.count() > 0.0) {
156161
bond_map_[node_name] =
157-
std::make_shared<bond::Bond>("bond", node_name, bond_client_node_);
162+
std::make_shared<bond::Bond>("bond", node_name, shared_from_this());
158163
bond_map_[node_name]->setHeartbeatTimeout(timeout_s);
159164
bond_map_[node_name]->setHeartbeatPeriod(0.10);
160165
bond_map_[node_name]->start();
@@ -317,7 +322,8 @@ LifecycleManager::createBondTimer()
317322

318323
bond_timer_ = this->create_wall_timer(
319324
200ms,
320-
std::bind(&LifecycleManager::checkBondConnections, this));
325+
std::bind(&LifecycleManager::checkBondConnections, this),
326+
callback_group_);
321327
}
322328

323329
void

‎nav2_lifecycle_manager/src/main.cpp‎

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@ int main(int argc, char ** argv)
2121
{
2222
rclcpp::init(argc, argv);
2323
auto node = std::make_shared<nav2_lifecycle_manager::LifecycleManager>();
24-
rclcpp::spin(node->get_node_base_interface());
24+
rclcpp::spin(node);
2525
rclcpp::shutdown();
2626

2727
return 0;

‎nav2_util/include/nav2_util/node_thread.hpp‎

Lines changed: 8 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@ namespace nav2_util
2323
{
2424
/**
2525
* @class nav2_util::NodeThread
26-
* @brief A background thread to process node callbacks
26+
* @brief A background thread to process node/executor callbacks
2727
*/
2828
class NodeThread
2929
{
@@ -34,6 +34,12 @@ class NodeThread
3434
*/
3535
explicit NodeThread(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base);
3636

37+
/**
38+
* @brief A background thread to process executor's callbacks constructor
39+
* @param executor Interface to executor to spin in thread
40+
*/
41+
explicit NodeThread(rclcpp::executors::SingleThreadedExecutor::SharedPtr executor);
42+
3743
/**
3844
* @brief A background thread to process node callbacks constructor
3945
* @param node Node pointer to spin in thread
@@ -51,7 +57,7 @@ class NodeThread
5157
protected:
5258
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_;
5359
std::unique_ptr<std::thread> thread_;
54-
rclcpp::executors::SingleThreadedExecutor executor_;
60+
rclcpp::Executor::SharedPtr executor_;
5561
};
5662

5763
} // namespace nav2_util

‎nav2_util/src/node_thread.cpp‎

Lines changed: 10 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -22,19 +22,25 @@ namespace nav2_util
2222
NodeThread::NodeThread(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base)
2323
: node_(node_base)
2424
{
25+
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
2526
thread_ = std::make_unique<std::thread>(
2627
[&]()
2728
{
28-
executor_.add_node(node_);
29-
executor_.spin();
30-
executor_.remove_node(node_);
29+
executor_->add_node(node_);
30+
executor_->spin();
31+
executor_->remove_node(node_);
3132
});
3233
}
3334

35+
NodeThread::NodeThread(rclcpp::executors::SingleThreadedExecutor::SharedPtr executor)
36+
: executor_(executor)
37+
{
38+
thread_ = std::make_unique<std::thread>([&]() {executor_->spin();});
39+
}
3440

3541
NodeThread::~NodeThread()
3642
{
37-
executor_.cancel();
43+
executor_->cancel();
3844
thread_->join();
3945
}
4046

0 commit comments

Comments
 (0)