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

ROS2 how to do multi-threading, subscription callbacks, spinning , executors

asked 2022-05-21 04:31:28 -0500

printf42 gravatar image

updated 2022-05-21 04:34:07 -0500

What is the correct way of multi threading in ROS2? As I understand it, ROS1 multi-threading was implicit.

I've been trying to find the convention for ROS2 of solving the following, relatively simple problem:

  1. Run a node which is running a practically _forever_ loop.
  2. Have the node receive subscription callbacks succesfully.

An attempt was made by me here and I "solved" that (read: made it work - doesn't seem like the correct way) by forcing a call to rclpy.spin_once() inside the loop in (1). So, it clear to me that I need a better understanding of what is happening under the hood with ROS2. Can I put the main loop on a rate or something so that the spin procedure can run as intended? Where can I read more about this?

Another attempt was made as follows (see below), here am using threading in a raw manner, which also seems to "work" but also seems very rough around the edges. I also attempted to use MultiThreadedExector, however I fail to see how it is meant to help.

import rclpy
from rclpy.node import Node
from std_msgs.msg import String
from rclpy.executors import MultiThreadedExecutor
import threading
import time

class LoopRunner(Node):
  def __init__(self):
    super().__init__('loop_runnner')
    threading.Thread(target=self.run_loop).start()

  def run_loop(self):
    while True:
      #self.get_logger().info("I work")
      time.sleep(0.001)
      pass

class MinimalSubscriber(Node):
  def __init__(self):
    super().__init__('minimal_subscriber')
    self.subscription = self.create_subscription(
        String,
        'topic',
        self.listener_callback,
        10)

  def listener_callback(self, msg):
    self.get_logger().info('I heard: "%s"' % msg.data)


def main(args=None):
  rclpy.init(args=args)

  try:
    minimal_subscriber = MinimalSubscriber()
    loop_runner = LoopRunner()

    executor = MultiThreadedExecutor()
    executor.add_node(loop_runner)
    executor.add_node(minimal_subscriber)

    try:
      executor.spin()
    finally:
      executor.shutdown()
      minimal_subscriber.destroy_node()
      loop_runner.destroy_node()
  finally:
    rclpy.shutdown()


if __name__ == '__main__':
  main()

I guess this all comes down to better understanding the spinning process / callback queues and multi-threading of ROS2. I'll take any resources that can help out here as I've been looking around and while there is bits and pieces, I cannot find a comprehensive piece of code or documentation that paints the full picture.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2022-05-23 05:21:54 -0500

ljaniec gravatar image

This post on the ROS Discourse

https://discourse.ros.org/t/how-to-us...

has a nice explanation for the SingleThreadedExecutor (default) and MultiThreadedExecutor next to the use of callback groups in ROS2. I hope it will help you.

edit flag offensive delete link more

Comments

That is a very informative resource, thank you very much.

printf42 gravatar image printf42  ( 2022-05-23 06:11:06 -0500 )edit
2

That's now being turned into a guide: ros2/ros2_documentation#2652.

@printf42: perhaps you have some comments you could share on the PR as a review?

gvdhoorn gravatar image gvdhoorn  ( 2022-05-24 04:05:53 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2022-05-21 04:31:28 -0500

Seen: 8,325 times

Last updated: May 23 '22