Skip to content

Commit

Permalink
SingleThreadedExecutor with awaited service call doesn't process othe…
Browse files Browse the repository at this point in the history
…r callbacks when rclpy.spin is passed a timeout

  ros2/rclpy#1159

Signed-off-by: Tomoya Fujita <[email protected]>
  • Loading branch information
fujitatomoya committed Sep 6, 2023
1 parent 544e615 commit 196683d
Show file tree
Hide file tree
Showing 2 changed files with 52 additions and 0 deletions.
1 change: 1 addition & 0 deletions prover_rclpy/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,7 @@
'rclpy_1098 = src.rclpy_1098:main',
'rclpy_1132 = src.rclpy_1132:main',
'rclpy_1149 = src.rclpy_1149:main',
'rclpy_1159 = src.rclpy_1159:main',
'ros2cli_818 = src.ros2cli_818:main',
],
},
Expand Down
51 changes: 51 additions & 0 deletions prover_rclpy/src/rclpy_1159.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
import rclpy
from rclpy.node import Node
from rclpy.callback_groups import ReentrantCallbackGroup
from rclpy.task import Future

# Random service example.
from rcl_interfaces.srv import GetParameters


class AsyncClient(Node):
def __init__(self):
super().__init__("async_client_node")
callback_group = ReentrantCallbackGroup()

self.cli = self.create_client(
GetParameters, "test_service", callback_group=callback_group
)
self.service_call_timer = self.create_timer(
1.0, self.call_service_cb, callback_group=callback_group
)
self.log_timer = self.create_timer(
2.0,
self.log_cb,
callback_group=callback_group,
)

def log_cb(self):
self.get_logger().info("Logging timer fired.")

async def call_service_cb(self):
self.service_call_timer.cancel()

self.get_logger().info("Calling service")
# I know there's no service, this is intentional and I expect this task to not complete,
# but other tasks should still be able to complete!
response = await self.cli.call_async(GetParameters.Request())
self.get_logger().info(f"Service call response: {response.message}")


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

# If I run this, my log_cb is called.
#rclpy.spin_until_future_complete(node, Future())
# If I run this, my log_cb isn't called!
rclpy.spin_until_future_complete(node, Future(), timeout_sec=5.0)


if __name__ == '__main__':
main()

0 comments on commit 196683d

Please sign in to comment.