ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
2

[ROS2] What's the best way to wait for a new message?

asked 2018-10-31 18:39:58 -0600

talos gravatar image

I'm trying to sync up some behaviors and some data while avoiding callback hell. What's a good way to effectively wait for a new data on a subscription in a synchronous manner?

Here's the high level of what I'd like to do:

start_process_callback() {
    trigger_led();
    wait_seconds();
    leftimage = get_left_image();
    trigger_different_led();
    rightimage = get_right_image();
    result = do_things_to_images(leftimage, rightimage);
    send_result(result);
}

Where the LED functions are publishers and the get_image functions block until a new image is received on a topic then return that image. I hope this helps clarify things. ROS1 had a wait_for_message, but ROS2 doesn't seem to have anything like that. The only other alternative I can think of is to have a convoluted state machine in a bunch of nested callbacks, but I'd really rather not do that if possible.

Thoughts?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2018-10-31 20:09:51 -0600

William gravatar image

There's no way to do it right now, but we want to change that, see: https://github.com/ros2/rclcpp/issues... You can use the C API directly, however. It has a wait set which can wait on one or more subscriptions to be ready and then you can take from them in any order.

edit flag offensive delete link more

Comments

Thanks for the link! I notice that this says how to wait without an executor, are there any examples about how to wait with an executor?

talos gravatar image talos  ( 2018-11-01 11:57:01 -0600 )edit

No, but the solution to that issue I linked to might be that the executor can either spin or wait. Not sure yet.

I know some people are doing it but they've created their own Subscription class in C++ to accomplish it, which isn't ideal.

William gravatar image William  ( 2018-11-01 12:26:23 -0600 )edit

If you really want to do it now, perhaps this function from the rcl tests will be helpful: https://github.com/ros2/rcl/blob/77ef...

William gravatar image William  ( 2018-11-01 12:26:43 -0600 )edit

We've temporarily set it up to spin in an executor with multiple threads and manual flags. Not an elegant solution, but it works fine for now.

talos gravatar image talos  ( 2018-11-04 21:05:45 -0600 )edit
2

What is the status of this now in 2021? I have so far not been able to finding anything on it, so i guess it is still not implemented?

bvaningen gravatar image bvaningen  ( 2021-05-12 10:22:35 -0600 )edit

that worked for me in Foxy. Not vouching for any correctness here and this should most likely be added to subscription class itself upstream:

rclcpp::WaitSet wait_set;
wait_set.add_subscription(subscription);
auto ret = wait_set.wait(std::chrono::seconds(10));
if (ret.kind() == rclcpp::WaitResultKind::Ready) {
  std_msgs::msg::String msg;
  rclcpp::MessageInfo info;
  auto ret_take = subscription->take(msg, info);
  if (ret_take) {
    RCLCPP_INFO(this->get_logger(), "got message: %s", msg.data.c_str());
  } else {
    RCLCPP_ERROR(this->get_logger(), "no message received");
  }
} else {
  RCLCPP_ERROR(this->get_logger(), "couldn't wait for message");
}
Karsten gravatar image Karsten  ( 2021-06-30 16:26:08 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2018-10-31 18:39:58 -0600

Seen: 6,443 times

Last updated: Oct 31 '18