Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Reduce lifecycle manager nodes #2456

Merged
Merged
Show file tree
Hide file tree
Changes from 6 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -18,11 +18,11 @@
#include <map>
#include <memory>
#include <string>
#include <thread>
#include <unordered_map>
#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"
Expand Down Expand Up @@ -52,9 +52,10 @@ class LifecycleManager : public rclcpp::Node
~LifecycleManager();

protected:
// The ROS node to create bond
rclcpp::Node::SharedPtr bond_client_node_;
std::unique_ptr<nav2_util::NodeThread> bond_node_thread_;
// Callback group used by services and timers
rclcpp::CallbackGroup::SharedPtr callback_group_;
rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
std::thread callback_group_executor_thread_;

// The services provided by this node
rclcpp::Service<ManageLifecycleNodes>::SharedPtr manager_srv_;
Expand Down
29 changes: 19 additions & 10 deletions nav2_lifecycle_manager/src/lifecycle_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,18 +49,18 @@ LifecycleManager::LifecycleManager()
bond_timeout_ = std::chrono::duration_cast<std::chrono::milliseconds>(
std::chrono::duration<double>(bond_timeout_s));

callback_group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive, false);
manager_srv_ = create_service<ManageLifecycleNodes>(
get_name() + std::string("/manage_nodes"),
std::bind(&LifecycleManager::managerCallback, this, _1, _2, _3));
std::bind(&LifecycleManager::managerCallback, this, _1, _2, _3),
rmw_qos_profile_services_default,
callback_group_);

is_active_srv_ = create_service<std_srvs::srv::Trigger>(
get_name() + std::string("/is_active"),
std::bind(&LifecycleManager::isActiveCallback, this, _1, _2, _3));

auto bond_options = rclcpp::NodeOptions().arguments(
{"--ros-args", "-r", std::string("__node:=") + get_name() + "_bond_client", "--"});
bond_client_node_ = std::make_shared<rclcpp::Node>("_", bond_options);
bond_node_thread_ = std::make_unique<nav2_util::NodeThread>(bond_client_node_);
std::bind(&LifecycleManager::isActiveCallback, this, _1, _2, _3),
rmw_qos_profile_services_default,
callback_group_);

transition_state_map_[Transition::TRANSITION_CONFIGURE] = State::PRIMARY_STATE_INACTIVE;
transition_state_map_[Transition::TRANSITION_CLEANUP] = State::PRIMARY_STATE_UNCONFIGURED;
Expand All @@ -84,12 +84,20 @@ LifecycleManager::LifecycleManager()
if (autostart_) {
startup();
}
});
},
callback_group_);

callback_group_executor_thread_ = std::thread([this]() {
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
callback_group_executor_.add_callback_group(callback_group_, this->get_node_base_interface());
callback_group_executor_.spin();
});
}

LifecycleManager::~LifecycleManager()
{
RCLCPP_INFO(get_logger(), "Destroying %s", get_name());
callback_group_executor_.cancel();
callback_group_executor_thread_.join();
}

void
Expand Down Expand Up @@ -154,7 +162,7 @@ LifecycleManager::createBondConnection(const std::string & node_name)

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_);
std::make_shared<bond::Bond>("bond", node_name, shared_from_this());
bond_map_[node_name]->setHeartbeatTimeout(timeout_s);
bond_map_[node_name]->setHeartbeatPeriod(0.10);
bond_map_[node_name]->start();
Expand Down Expand Up @@ -317,7 +325,8 @@ LifecycleManager::createBondTimer()

bond_timer_ = this->create_wall_timer(
200ms,
std::bind(&LifecycleManager::checkBondConnections, this));
std::bind(&LifecycleManager::checkBondConnections, this),
callback_group_);
}

void
Expand Down
2 changes: 1 addition & 1 deletion nav2_lifecycle_manager/src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
auto node = std::make_shared<nav2_lifecycle_manager::LifecycleManager>();
rclcpp::spin(node->get_node_base_interface());
rclcpp::spin(node);
rclcpp::shutdown();

return 0;
Expand Down