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

How to receive subscription callbacks while a loop is running?

asked 2022-05-20 08:32:12 -0500

printf42 gravatar image

Software: python, ros2 (foxy)

I have a main loop in my node, and I would also still like to receive updates from a subscription - however, I can't quite figure out how to make it work. I tried to play around with the executor but that didn't go quite right... Any help or pointers in the right direction would be greatly appreciated.

Simple example, starting with the simple subscriber:

  # subscriber
  import rclpy
  from rclpy.node import Node
  from std_msgs.msg import String

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

      self.run_loop()

    def run_loop(self):
      while True:
        pass


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


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

    minimal_subscriber = MinimalSubscriber()

    rclpy.spin(minimal_subscriber)

    minimal_subscriber.destroy_node()
    rclpy.shutdown()


  if __name__ == '__main__':
    main()

The publisher:

  # publisher
  import rclpy
  from rclpy.node import Node
  from std_msgs.msg import String


  class MinimalPublisher(Node):
    def __init__(self):
      super().__init__('minimal_publisher')
      self.publisher_ = self.create_publisher(String, 'topic', 10) 
      timer_period = 0.5  # seconds
      self.timer = self.create_timer(timer_period, self.timer_callback)
      self.i = 0 

    def timer_callback(self):
      msg = String()
      msg.data = 'Hello World: %d' % self.i
      self.publisher_.publish(msg)
      self.get_logger().info('Publishing: "%s"' % msg.data)
      self.i += 1

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

    minimal_publisher = MinimalPublisher()

    rclpy.spin(minimal_publisher)

    minimal_publisher.destroy_node()
    rclpy.shutdown()


  if __name__ == '__main__':
    main()
edit retag flag offensive close merge delete

Comments

What exactly is happening in your main loop? Maybe this can be solved with async callbacks?

ljaniec gravatar image ljaniec  ( 2022-05-20 09:22:17 -0500 )edit

Hi thanks for your comment, I know only of async callbacks in javascript -- would like to know more about what you mean.

The loop is running a webcam class which is classifying data...

printf42 gravatar image printf42  ( 2022-05-20 09:53:58 -0500 )edit
1

This topic and the tutorial there: https://discourse.ros.org/t/how-to-us... is really helpful for understanding SingleThreadedExecutors (default) and MultiThreadedExecutors in ROS2

ljaniec gravatar image ljaniec  ( 2022-05-23 09:03:59 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2022-05-20 08:44:11 -0500

updated 2022-05-23 02:48:13 -0500

Edit; in the original answer I did no understand the question. The run() function includes a in definetly runnjng while loop, so the object creation never completes since the function is executed in constructor. Instead of blocking while loop you may want to use timer callback for periodic loops. Below is an example;

import rclpy
import rclpy.node
import rclpy.qos

from geometry_msgs.msg import Point


class ROS2Pub(rclpy.node.Node):

    def __init__(self, *args):
        super(ROS2Pub, self).__init__("topic_pub")
        self.my_pub = self.create_publisher(
            Point, "points", rclpy.qos.qos_profile_sensor_data)
        self.timer = self.create_timer(0.1, self.timer_callback)
        self.get_logger().info("Started the node")

    def timer_callback(self):
        msg = Point()
        msg.x = 10.0
        self.my_pub.publish(msg)
        self.get_logger().info("Published a point with x of %s" % msg.x)


def main():
    rclpy.init()
    node = ROS2Pub()
    rclpy.spin(node)
    rclpy.shutdown()


if __name__ == '__main__':
    main()
edit flag offensive delete link more

Comments

Thanks for your comment -- unfortunately this doesn't work as listener_callback is still not being called while the loop is active...

printf42 gravatar image printf42  ( 2022-05-20 08:51:46 -0500 )edit

I did not understand your question. You are calling self.run_loop() in constructor, your code stucks there, so the node never gets spinned hence no callback is executed.

Fetullah Atas gravatar image Fetullah Atas  ( 2022-05-20 10:07:47 -0500 )edit

Any ideas how I can make it work? I can call rclpy.spin_once(self) inside the loop - however that will only block until a callback comes in... It seems it can be solved with the help of the executor however, I haven't quite figured out how to do that yet...

Edit: so I can do rclpy.spin_once(self, timeout_sec=0.001) for example - but this really seems like a duct tape solution... There must be a more elegant way of doing this...

printf42 gravatar image printf42  ( 2022-05-20 10:30:20 -0500 )edit
1

Instead of doing a while loop you can use a timer callback, see an example here

Fetullah Atas gravatar image Fetullah Atas  ( 2022-05-22 06:15:06 -0500 )edit

Please introduce this as an answer and I will accep it. Thank you.

printf42 gravatar image printf42  ( 2022-05-23 01:24:06 -0500 )edit

I edited the answer

Fetullah Atas gravatar image Fetullah Atas  ( 2022-05-23 02:48:30 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2022-05-20 08:32:12 -0500

Seen: 919 times

Last updated: May 23 '22