rclcpp icon indicating copy to clipboard operation
rclcpp copied to clipboard

spin_until_future_complete may block forever if nothing wakes the executor after the future completes

Open sloretz opened this issue 2 years ago • 7 comments

Bug report

Required Info:

  • Operating System:
    • jammy
  • Installation type:
    • source
  • Version or commit hash:
    • 85a7046ac39bfc0d787ed2bbe62574424e31b871
  • DDS implementation:
    • Fast-DDS
  • Client library (if applicable):
    • rclcpp

Steps to reproduce issue

C++:

#include <iostream>
#include <thread>
#include <chrono>
#include "rclcpp/rclcpp.hpp"


void sleep_a_bit()
{
  std::cerr << "Sleeping for 5 seconds\n";
  std::this_thread::sleep_for(std::chrono::seconds(5));
  std::cerr << "Waking up and exiting function\n";
}

void rescue_callback()
{
  std::cerr << "rescue timer ran\n";
}

int main(int argc, char ** argv)
{
  rclcpp::init(argc, argv);

  auto node = std::make_shared<rclcpp::Node>("rclcpp_spin_until_future_complete_blocked");

  // Rescue timer will wake the executor, causing it to look at the future again
  auto rescue_timer = rclcpp::create_timer(
      node,
      node->get_clock(),
      rclcpp::Duration(10, 0),
      std::bind(rescue_callback));

  rclcpp::executors::SingleThreadedExecutor exe;
  exe.add_node(node);

  std::shared_future<void> script = std::async(std::launch::async, sleep_a_bit);
  std::cerr << "About to sleep until future complete\n";
  exe.spin_until_future_complete(script);
  std::cerr << "Executor realized future is complete\n";

  rclcpp::shutdown();

  return 0;
}

CMake:

add_executable(rclcpp_spin_until_future_complete_blocked
  src/rclcpp_spin_until_future_complete_blocked.cpp)
target_link_libraries(rclcpp_spin_until_future_complete_blocked
  rclcpp::rclcpp)

Expected behavior

I would expect the future being completed would cause spin_until_future_complete() to return, and the program would shutdown without the timer callback running.

$ ./rclcpp_spin_until_future_complete_blocked 
About to sleep until future complete
Sleeping for 5 seconds
Waking up and exiting function
Executor realized future is complete

Actual behavior

After the future completes, spin_until_future_complete() blocks for another 5 seconds until the timer callback is run.

$ ./rclcpp_spin_until_future_complete_blocked 
About to sleep until future complete
Sleeping for 5 seconds
Waking up and exiting function
rescue timer ran
Executor realized future is complete

Additional information

A similar limitation exists in rclpy. I thinkspin_until_future_complete() only returns immediately after completion if the future is completed in the callback of the same executor. We should probably document it here. This limitation is why the demo for lifecycle_service_client doesn't exit (related issue ros2/demos#504)

sloretz avatar Apr 07 '22 21:04 sloretz