Skip to content

rclcpp_lifecycle does not handle service de-registration the same as rclcpp #2961

@JWhitleyWork

Description

@JWhitleyWork

Generated by Generative AI

No response

Operating System:

Linux pop-os 6.16.3-76061603-generic #202508231538175856113522.04~171c8de SMP PREEMPT_DYNAMIC Mon S x86_64 x86_64 x86_64 GNU/Linux

ROS version or commit hash:

humble

RMW implementation (if applicable):

rmw_cyclonedds_cpp

RMW Configuration (if applicable):

No response

Client library (if applicable):

rclcppp and rclcpp_lifecycle

'ros2 doctor --report' output

ros2 doctor --report
<COPY OUTPUT HERE>

Steps to reproduce issue

Test for the existence of a service (using a client) which was created by a node which inherits from rclcpp_lifecycle::LifeCycleNodeInterface after the last reference to an owned rclcpp::Client::SharedPtr has been removed and/or the node has been transitioned to UNCONFIGURED. Example below of a test which reproduces the issue (and also tests similar/expected behavior from an rclcpp::Node):

#include <gtest/gtest.h>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_lifecycle/lifecycle_node.hpp>
#include <std_srvs/srv/trigger.hpp>

#include <chrono>
#include <memory>
#include <thread>

using namespace std::chrono_literals;

class TestLifecycleNode : public rclcpp_lifecycle::LifecycleNode
{
public:
  TestLifecycleNode() : rclcpp_lifecycle::LifecycleNode("test_lifecycle") {}

  CallbackReturn on_configure(const rclcpp_lifecycle::State& /*previous_state*/) override
  {
    service_ = create_service<std_srvs::srv::Trigger>("test_lifecycle_service", std::bind(&TestLifecycleNode::service_callback, this, std::placeholders::_1, std::placeholders::_2));
    return CallbackReturn::SUCCESS;
  }

  CallbackReturn on_activate(const rclcpp_lifecycle::State& /*previous_state*/) override
  {
    return CallbackReturn::SUCCESS;
  }

  CallbackReturn on_deactivate(const rclcpp_lifecycle::State& /*previous_state*/) override
  {
    return CallbackReturn::SUCCESS;
  }

  CallbackReturn on_cleanup(const rclcpp_lifecycle::State& /*previous_state*/) override
  {
    service_.reset();
    return CallbackReturn::SUCCESS;
  }
private:
  void service_callback(const std::shared_ptr<std_srvs::srv::Trigger::Request> /*request*/, std::shared_ptr<std_srvs::srv::Trigger::Response> response)
  {
    response->success = true;
  }

  rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr service_;
};

class TestRegularNode : public rclcpp::Node
{
public:
  TestRegularNode() : rclcpp::Node("test_regular")
  {
    service_ = create_service<std_srvs::srv::Trigger>("test_regular_service", std::bind(&TestRegularNode::service_callback, this, std::placeholders::_1, std::placeholders::_2));
  }

  void cleanup()
  {
    service_.reset();
  }

private:
  void service_callback(const std::shared_ptr<std_srvs::srv::Trigger::Request> /*request*/, std::shared_ptr<std_srvs::srv::Trigger::Response> response)
  {
    response->success = true;
  }

  rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr service_;
};

class TestLifecycle : public ::testing::Test
{
public:
  static void SetUpTestSuite()
  {
    rclcpp::init(0, nullptr);
  }

  static void TearDownTestSuite()
  {
    rclcpp::shutdown();
  }

  void SetUp()
  {
    node_ = std::make_shared<TestLifecycleNode>();
  }

  void TearDown()
  {
    node_.reset();
  }

  std::shared_ptr<TestLifecycleNode> node_;
};

class TestRegular : public ::testing::Test
{
public:
  static void SetUpTestSuite()
  {
    rclcpp::init(0, nullptr);
  }

  static void TearDownTestSuite()
  {
    rclcpp::shutdown();
  }

  void SetUp()
  {
    node_ = std::make_shared<TestRegularNode>();
  }

  void TearDown()
  {
    node_.reset();
  }

  std::shared_ptr<TestRegularNode> node_;
};

TEST_F(TestRegular, test_regular)
{
  auto test_node = rclcpp::Node::make_shared("test_node");

  auto exec = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
  exec->add_node(node_->get_node_base_interface());
  exec->add_node(test_node->get_node_base_interface());

  std::thread ros_thread([exec]() { exec->spin(); });
  while (!exec->is_spinning()) {}

  node_->cleanup();

  std::this_thread::sleep_for(100ms);

  auto test_client = test_node->create_client<std_srvs::srv::Trigger>("test_regular_service");
  ASSERT_FALSE(test_client->service_is_ready()) << "Test client service should not be active after cleanup";

  exec->cancel();
  if (ros_thread.joinable()) {
    ros_thread.join();
  }
}

TEST_F(TestLifecycle, test_lifecycle)
{
  auto test_node = rclcpp::Node::make_shared("test_node");

  auto exec = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();

  exec->add_node(node_->get_node_base_interface());
  exec->add_node(test_node->get_node_base_interface());

  // Use shared_ptr capture to ensure executor lives as long as the thread
  std::thread ros_thread([exec]() { exec->spin(); });
  while (!exec->is_spinning()) {}

  node_->configure();
  node_->activate();
  node_->deactivate();
  node_->cleanup();

  std::this_thread::sleep_for(100ms);

  auto test_client = test_node->create_client<std_srvs::srv::Trigger>("test_lifecycle_service");
  ASSERT_FALSE(test_client->service_is_ready()) << "Test client service should not be active after cleanup";

  exec->cancel();
  if (ros_thread.joinable()) {
    ros_thread.join();
  }
}

Expected behavior

rclcpp::Service::SharedPtr instances which have their last std::shared_ptr reference removed should destruct, eventually calling rcl_service_fini/rmw_destroy_service, removing the service from DDS registration, making rclcpp::Client::service_is_ready() and rclcpp::Client::wait_for_service() return False immediately (or nearly immediately). I would expect this to happen no matter the LifeCycle state of the parent node but theoretically, based on the design doc, I would expect the service to be unavailable as soon as the node transitions out of CONFIGURED as well (when in CONFIGURED, I would expect the service to be discoverable but not respond to any requests).

Actual behavior

rclcpp::Client::service_is_ready() and rclcpp::Client::wait_for_service() sometimes return True (~10% of the time) after the rclcpp::Service::SharedPtr has been destructed and the owning class instance inheriting from rclcpp_lifecycle::LifeCycleNodeInterface has been transitioned to UNCONFIGURED. In my testing, this does not ever happen with the same conditions in an rclcpp::Node.

Additional information

No response

Metadata

Metadata

Assignees

Labels

bugSomething isn't working

Type

No type

Projects

No projects

Milestone

No milestone

Relationships

None yet

Development

No branches or pull requests

Issue actions