Skip to content

async callbacks are not awaited #123

Open
@TSoli

Description

@TSoli

So I have a callback that I need to await a transform from tf2 in. Here is a MWE using a regular ros2 subscription that works

import rclpy
from rclpy.node import Node
from sensor_msgs.msg import Image as ImgMsg
from tf2_ros import TransformException
from tf2_ros.buffer import Buffer
from tf2_ros.transform_listener import TransformListener


class TestAsync(Node):
    def __init__(self) -> None:
        super().__init__("test_async")
        self.tf_buffer = Buffer()
        self.tf_listener = TransformListener(self.tf_buffer, self)
        self.create_subscription(
            ImgMsg, "zed2/zed_node/rgb/image_rect_color", self.async_callback, 10
        )

    async def async_callback(self, msg: ImgMsg) -> None:
        self.get_logger().info("Entered callback")
        now = rclpy.time.Time.from_msg(msg.header.stamp)
        try:
            tf = await self.tf_buffer.lookup_transform_async(
                msg.header.frame_id, "odom", now
            )
            self.get_logger().info(f"Got {repr(tf)}")
        except TransformException as ex:
            self.get_logger().info(f"Exception: {ex}")


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

When I switch this MWE to using message_filters like this

        img_sub = message_filters.Subscriber(
            self, ImgMsg, "zed2/zed_node/rgb/image_rect_color"
        )
        img_sync = message_filters.TimeSynchronizer([img_sub], 1)
        img_sync.registerCallback(self.async_callback)

instead of

        self.create_subscription(
            ImgMsg, "zed2/zed_node/rgb/image_rect_color", self.async_callback, 10
        )

I get the error

timeWarning: coroutine 'TestAsync.async_callback' was never awaited 
  cb(*(msg + args))  
RuntimeWarning: Enable tracemalloc to get the object allocation traceback

and the callback does not seem to be called correctly (I see no logs).

This is a toy example for demonstration but in my use case I am trying to use message_filters.TimeSynchronizer to synchronize messages from callbacks for multiple topics. Is there something I am doing wrong or is this a bug?

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions