Skip to content

Calling a dead service causes a memory leak on the client side #1697

@umateusz

Description

@umateusz

Bug report

If the service is stopped (due to an error or user intervention) and the client keeps trying to call it, it will leak memory. Unprocessed requests will be accumulated in pending_requests_ (

std::map<int64_t, std::tuple<SharedPromise, CallbackType, SharedFuture>> pending_requests_;
). Is there a way to prevent this e.g. request timeout?

It should not be possible to leak memory on the client side. User cannot delete old requests, so they will hang until the end of the client's operation. Moreover, the problem will occur if the service does not keep up with the processing of client requests.

IMHO: Using spin_until_future_complete is not a solution as it cannot be called from a composable node and it cannot erase outdated entry from pending_request_ collection.

  • Operating System: Ubuntu 20.04
  • Installation type: binaries
  • Version or commit hash: foxy
  • DDS implementation: rmw_cyclonedds_cpp (should also be present for other implementations)
  • Client library (if applicable): rclcpp

Steps to reproduce issue

I prepared the problem example by modifying the standard (minimal_client, minimal_service) examples and placed it on the branch: https://github.com/umateusz/examples/tree/memory-leak-in-service-client

Client:

#include <chrono>
#include <cinttypes>
#include <memory>
#include "example_interfaces/srv/add_two_ints.hpp"
#include "rclcpp/rclcpp.hpp"

using AddTwoInts = example_interfaces::srv::AddTwoInts;
using namespace std::chrono_literals;

class ClientWithTimer : public rclcpp::Node
{
public:
  ClientWithTimer() : Node("client_with_timer")
  {
    client_ = create_client<AddTwoInts>("add_two_ints");
    while (!client_->wait_for_service(std::chrono::seconds(1))) {
      if (!rclcpp::ok()) {
        RCLCPP_ERROR(get_logger(), "client interrupted while waiting for service to appear.");
        rclcpp::shutdown();
        return;
      }
      RCLCPP_INFO(get_logger(), "waiting for service to appear...");
    }
    timer_ = create_wall_timer(500ms, std::bind(&ClientWithTimer::timer_callback, this));
  }

private:
  void timer_callback()
  {
    RCLCPP_INFO(this->get_logger(), "Hello, world!");
    auto request = std::make_shared<AddTwoInts::Request>();
    request->a = 41;
    request->b = 1;
    auto result_future = client_->async_send_request(
      request, [this, request](rclcpp::Client<AddTwoInts>::SharedFuture response) {
        RCLCPP_INFO(this->get_logger(), "Hello from response handler!");
        auto result = response.get();
        RCLCPP_INFO(
          get_logger(), "result of %" PRId64 " + %" PRId64 " = %" PRId64, request->a, request->b,
          result->sum);
      });
  }
  rclcpp::TimerBase::SharedPtr timer_;
  rclcpp::Client<AddTwoInts>::SharedPtr client_;
};

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<ClientWithTimer>());
  rclcpp::shutdown();
  return 0;
}

Service:

#include <inttypes.h>
#include <memory>
#include "example_interfaces/srv/add_two_ints.hpp"
#include "rclcpp/rclcpp.hpp"

using AddTwoInts = example_interfaces::srv::AddTwoInts;
rclcpp::Node::SharedPtr g_node = nullptr;

void handle_service(
  const std::shared_ptr<rmw_request_id_t> request_header,
  const std::shared_ptr<AddTwoInts::Request> request,
  const std::shared_ptr<AddTwoInts::Response> response)
{
  throw std::runtime_error("Some error in service");
  (void)request_header;
  RCLCPP_INFO(
    g_node->get_logger(),
    "request: %" PRId64 " + %" PRId64, request->a, request->b);
  response->sum = request->a + request->b;
}

int main(int argc, char ** argv)
{
  rclcpp::init(argc, argv);
  g_node = rclcpp::Node::make_shared("minimal_service");
  auto server = g_node->create_service<AddTwoInts>("add_two_ints", handle_service);
  rclcpp::spin(g_node);
  rclcpp::shutdown();
  g_node = nullptr;
  return 0;
}

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