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

Open option to use parent node in lifecycle Manger Client #2328

Merged
Show file tree
Hide file tree
Changes from 1 commit
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 @@ -26,6 +26,7 @@
#include "std_srvs/srv/empty.hpp"
#include "nav2_msgs/srv/manage_lifecycle_nodes.hpp"
#include "std_srvs/srv/trigger.hpp"
#include "nav2_util/service_client.hpp"

namespace nav2_lifecycle_manager
{
Expand All @@ -45,7 +46,10 @@ class LifecycleManagerClient
/**
* @brief A constructor for LifeCycleMangerClient
*/
explicit LifecycleManagerClient(const std::string & name, const std::string & ns = "");
explicit LifecycleManagerClient(
const std::string & name,
const std::string & ns = "",
std::shared_ptr<rclcpp::Node> parent_node = nullptr);

// Client-side interface to the Nav2 lifecycle manager
/**
Expand Down Expand Up @@ -110,8 +114,8 @@ class LifecycleManagerClient
// The node to use for the service call
rclcpp::Node::SharedPtr node_;

rclcpp::Client<ManageLifecycleNodes>::SharedPtr manager_client_;
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr is_active_client_;
std::shared_ptr<nav2_util::ServiceClient<ManageLifecycleNodes>> manager_client_;
std::shared_ptr<nav2_util::ServiceClient<std_srvs::srv::Trigger>> is_active_client_;
std::string manage_service_name_;
std::string active_service_name_;
};
Expand Down
37 changes: 20 additions & 17 deletions nav2_lifecycle_manager/src/lifecycle_manager_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,17 +28,23 @@ using nav2_util::geometry_utils::orientationAroundZAxis;

LifecycleManagerClient::LifecycleManagerClient(
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
const std::string & name,
const std::string & ns)
const std::string & ns, std::shared_ptr<rclcpp::Node> parent_node)
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
{
manage_service_name_ = name + std::string("/manage_nodes");
active_service_name_ = name + std::string("/is_active");

// Create the node to use for all of the service clients
node_ = std::make_shared<rclcpp::Node>(name + "_service_client", ns);
if (parent_node == nullptr) {
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
node_ = std::make_shared<rclcpp::Node>(name + "_service_client", ns);
} else {
node_ = parent_node;
}

// Create the service clients
manager_client_ = node_->create_client<ManageLifecycleNodes>(manage_service_name_);
is_active_client_ = node_->create_client<std_srvs::srv::Trigger>(active_service_name_);
manager_client_ = std::make_shared<nav2_util::ServiceClient<ManageLifecycleNodes>>(
manage_service_name_, node_);
is_active_client_ = std::make_shared<nav2_util::ServiceClient<std_srvs::srv::Trigger>>(
active_service_name_, node_);
}

bool
Expand Down Expand Up @@ -75,6 +81,7 @@ SystemStatus
LifecycleManagerClient::is_active(const std::chrono::nanoseconds timeout)
{
auto request = std::make_shared<std_srvs::srv::Trigger::Request>();
auto response = std::make_shared<std_srvs::srv::Trigger::Response>();

RCLCPP_DEBUG(
node_->get_logger(), "Waiting for the %s service...",
Expand All @@ -87,15 +94,14 @@ LifecycleManagerClient::is_active(const std::chrono::nanoseconds timeout)
RCLCPP_DEBUG(
node_->get_logger(), "Sending %s request",
active_service_name_.c_str());
auto future_result = is_active_client_->async_send_request(request);

if (rclcpp::spin_until_future_complete(node_, future_result, timeout) !=
rclcpp::FutureReturnCode::SUCCESS)
{
try {
response = is_active_client_->invoke(request, timeout);
} catch (std::runtime_error &) {
return SystemStatus::TIMEOUT;
}

if (future_result.get()->success) {
if (response.get()->success) {
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
return SystemStatus::ACTIVE;
} else {
return SystemStatus::INACTIVE;
Expand All @@ -112,7 +118,7 @@ LifecycleManagerClient::callService(uint8_t command, const std::chrono::nanoseco
node_->get_logger(), "Waiting for the %s service...",
manage_service_name_.c_str());

while (!manager_client_->wait_for_service(std::chrono::seconds(1))) {
while (!manager_client_->wait_for_service(timeout)) {
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
if (!rclcpp::ok()) {
RCLCPP_ERROR(node_->get_logger(), "Client interrupted while waiting for service to appear");
return false;
Expand All @@ -123,15 +129,12 @@ LifecycleManagerClient::callService(uint8_t command, const std::chrono::nanoseco
RCLCPP_DEBUG(
node_->get_logger(), "Sending %s request",
manage_service_name_.c_str());
auto future_result = manager_client_->async_send_request(request);

if (rclcpp::spin_until_future_complete(node_, future_result, timeout) !=
rclcpp::FutureReturnCode::SUCCESS)
{
try {
auto future_result = manager_client_->invoke(request, timeout);
return future_result.get()->success;
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
} catch (std::runtime_error &) {
return false;
}

return future_result.get()->success;
}

} // namespace nav2_lifecycle_manager