Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
20 changes: 20 additions & 0 deletions rclpy/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -149,6 +149,14 @@ if(BUILD_TESTING)
# Give cppcheck hints about macro definitions coming from outside this package
get_target_property(ament_cmake_cppcheck_ADDITIONAL_INCLUDE_DIRS rcutils::rcutils INTERFACE_INCLUDE_DIRECTORIES)
list(APPEND AMENT_LINT_AUTO_EXCLUDE "ament_cmake_cppcheck")

if(Python3_VERSION VERSION_LESS 3.12)
file(GLOB AMENT_LINT_AUTO_FILE_EXCLUDE
"${CMAKE_CURRENT_SOURCE_DIR}/rclpy/experimental/async_*.py"
"${CMAKE_CURRENT_SOURCE_DIR}/test/test_async_*.py"
)
endif()

ament_lint_auto_find_test_dependencies()

find_package(ament_cmake_cppcheck REQUIRED)
Expand Down Expand Up @@ -228,6 +236,18 @@ if(BUILD_TESTING)
test/test_wait_for_message.py
)

if(Python3_VERSION VERSION_GREATER_EQUAL 3.12)
list(APPEND _rclpy_pytest_tests
test/test_async_node.py
test/test_async_publisher.py
test/test_async_subscription.py
test/test_async_service.py
test/test_async_client.py
test/test_async_timer.py
test/test_async_clock.py
)
endif()

foreach(_test_path ${_rclpy_pytest_tests})
get_filename_component(_test_name ${_test_path} NAME_WE)
ament_add_pytest_test(${_test_name} ${_test_path}
Expand Down
5 changes: 5 additions & 0 deletions rclpy/docs/source/api/clock.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,3 +2,8 @@ Clock
=====

.. automodule:: rclpy.clock
:inherited-members:
:exclude-members: BaseClock

.. automodule:: rclpy.experimental.async_clock
:inherited-members:
5 changes: 5 additions & 0 deletions rclpy/docs/source/api/node.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,3 +2,8 @@ Node
====

.. automodule:: rclpy.node
:inherited-members:
:exclude-members: BaseNode

.. automodule:: rclpy.experimental.async_node
:inherited-members:
10 changes: 10 additions & 0 deletions rclpy/docs/source/api/services.rst
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,18 @@ Client
------

.. automodule:: rclpy.client
:inherited-members:
:exclude-members: BaseClient

.. automodule:: rclpy.experimental.async_client
:inherited-members:

Service
-------

.. automodule:: rclpy.service
:inherited-members:
:exclude-members: BaseService

.. automodule:: rclpy.experimental.async_service
:inherited-members:
5 changes: 5 additions & 0 deletions rclpy/docs/source/api/timers.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,3 +2,8 @@ Timer
=====

.. automodule:: rclpy.timer
:inherited-members:
:exclude-members: BaseTimer

.. automodule:: rclpy.experimental.async_timer
:inherited-members:
11 changes: 11 additions & 0 deletions rclpy/docs/source/api/topics.rst
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,19 @@ Publisher
---------

.. automodule:: rclpy.publisher
:inherited-members:
:exclude-members: BasePublisher

.. automodule:: rclpy.experimental.async_publisher
:inherited-members:

Subscription
------------

.. automodule:: rclpy.subscription
:inherited-members:
:exclude-members: BaseSubscription, CallbackType

.. automodule:: rclpy.experimental.async_subscription
:inherited-members:
:exclude-members: CallbackType
3 changes: 2 additions & 1 deletion rclpy/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,8 @@
<test_depend>python3-pytest</test_depend>
<test_depend>rosidl_generator_py</test_depend>
<test_depend>test_msgs</test_depend>

<test_depend>python3-pytest-asyncio</test_depend>

<doc_depend>python3-sphinx</doc_depend>
<doc_depend>python3-sphinx-rtd-theme</doc_depend>
<!-- We add these modules as doc_depends in order to include them into the
Expand Down
6 changes: 6 additions & 0 deletions rclpy/rclpy/client.py
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,12 @@ def __init__(
*,
on_destroy: Optional[Callable[['BaseClient[SrvRequestT, SrvResponseT]'], None]] = None,
) -> None:
"""
Create a container for a ROS service client.

.. warning:: Users should not create a service client with this constructor, instead they
should call :meth:`.Node.create_client` or :meth:`.AsyncNode.create_client`.
"""
self.context = context
self.__client = client_impl
self.srv_type = srv_type
Expand Down
6 changes: 6 additions & 0 deletions rclpy/rclpy/clock.py
Original file line number Diff line number Diff line change
Expand Up @@ -140,6 +140,12 @@ def __exit__(self, t: Optional[Type[BaseException]],
class BaseClock:

def __init__(self, *, clock_type: ClockType = ClockType.SYSTEM_TIME) -> None:
"""
Create a clock.

.. warning:: Users should not create a clock with this constructor, instead they
should obtain one via :meth:`.Node.get_clock` or :meth:`.AsyncNode.get_clock`.
"""
if not isinstance(clock_type, ClockType):
raise TypeError('Clock type must be a ClockType enum')
self.__clock = _rclpy.Clock(clock_type.value)
Expand Down
6 changes: 6 additions & 0 deletions rclpy/rclpy/exceptions.py
Original file line number Diff line number Diff line change
Expand Up @@ -156,3 +156,9 @@ class ROSInterruptException(Exception):

def __init__(self) -> None:
Exception.__init__(self, 'rclpy.shutdown() has been called')


class TimeSourceChangedError(Exception):
"""Raised when a sleep is interrupted by a time source change."""

pass
27 changes: 26 additions & 1 deletion rclpy/rclpy/experimental/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,4 +12,29 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from .events_executor import EventsExecutor as EventsExecutor # noqa: F401
import sys

from .events_executor import EventsExecutor

__all__ = [
'EventsExecutor'
]

if sys.version_info >= (3, 12):
from .async_client import AsyncClient
from .async_clock import AsyncClock
from .async_node import AsyncNode
from .async_publisher import AsyncPublisher
from .async_service import AsyncService
from .async_subscription import AsyncSubscription
from .async_timer import AsyncTimer

__all__ += [
'AsyncClient',
'AsyncClock',
'AsyncNode',
'AsyncPublisher',
'AsyncService',
'AsyncSubscription',
'AsyncTimer'
]
111 changes: 111 additions & 0 deletions rclpy/rclpy/experimental/async_client.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,111 @@
# Copyright 2026 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import asyncio
from typing import Callable, Dict, Optional, Type

from rclpy.client import BaseClient
from rclpy.context import Context
from rclpy.qos import QoSProfile
from rclpy.type_support import Srv, SrvRequestT, SrvResponseT


class AsyncClient(BaseClient[SrvRequestT, SrvResponseT]):
"""
A client of a ROS service.

.. admonition:: Experimental

This API is experimental.
"""

def __init__(
self,
context: Context,
client_impl: object,
srv_type: Type[Srv[SrvRequestT, SrvResponseT]],
srv_name: str,
qos_profile: QoSProfile,
on_destroy: Callable[['AsyncClient'], None],
tg: Optional[asyncio.TaskGroup] = None,
) -> None:
super().__init__(context, client_impl, srv_type, srv_name, qos_profile,
on_destroy=on_destroy)
self._pending_requests: Dict[int, asyncio.Future] = {}
self._task: Optional[asyncio.Task] = None
self._loop: Optional[asyncio.AbstractEventLoop] = None
self._read_event = asyncio.Event()
if tg is not None:
self._task = tg.create_task(self._run())

def _on_new_response(self, _num_waiting: int) -> None:
assert self._loop is not None
self._loop.call_soon_threadsafe(self._read_event.set)

async def wait_for_service(self, *, check_interval: float = 0.1) -> None:
"""
Wait for a service server to become ready.

To apply a timeout, wrap the call with ``async with asyncio.timeout()``.

:param check_interval: Seconds between checks. Defaults to 0.1.
"""
while not self.service_is_ready():
await asyncio.sleep(check_interval)

def _destroy(self) -> None:
if self._task is not None:
self._task.cancel()
self.handle.clear_on_new_response_callback()
for future in self._pending_requests.values():
future.cancel()
super()._destroy()

async def call(self, request: SrvRequestT) -> SrvResponseT:
"""Send a service request and await the response."""
if self._destroyed:
raise RuntimeError('Calling a destroyed client is forbidden')
loop = asyncio.get_running_loop()
future: asyncio.Future[SrvResponseT] = loop.create_future()
sequence_number = self.handle.send_request(request)
self._pending_requests[sequence_number] = future
try:
return await future
finally:
self._pending_requests.pop(sequence_number)

async def _responses(self):
"""Async generator yielding (header, response) from DDS."""
self.handle.set_on_new_response_callback(self._on_new_response)
while not self._destroyed:
header_and_response = self.handle.take_response(
self.srv_type.Response)
if header_and_response != (None, None):
yield header_and_response
else:
self._read_event.clear()
await self._read_event.wait()

async def _run(self) -> None:
"""DDS bridge response loop for clients."""
self._loop = asyncio.get_running_loop()
try:
async for header, response in self._responses():
future = self._pending_requests.get(
header.request_id.sequence_number)
if future is not None:
future.set_result(response)
finally:
self._task = None
self.destroy()
107 changes: 107 additions & 0 deletions rclpy/rclpy/experimental/async_clock.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,107 @@
# Copyright 2026 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import asyncio
from typing import Dict, Optional

from rclpy.clock import BaseClock, ClockChange, JumpHandle, JumpThreshold, TimeJump
from rclpy.clock_type import ClockType
from rclpy.duration import Duration
from rclpy.exceptions import TimeSourceChangedError
from rclpy.time import Time


class AsyncClock(BaseClock):
"""
A ROS clock with async ``sleep``.

.. admonition:: Experimental

This API is experimental.
"""

def __init__(self, *, clock_type: ClockType = ClockType.SYSTEM_TIME) -> None:
super().__init__(clock_type=clock_type)
self._pending_sleeps: Dict[asyncio.Future, Optional[Time]] = {}
self._destroyed = False

threshold = JumpThreshold(
min_forward=Duration(nanoseconds=1),
min_backward=None,
on_clock_change=True,
)
self._jump_handle: JumpHandle = self.create_jump_callback(
threshold, post_callback=self._on_jump)

@staticmethod
def _resolve_future(future: asyncio.Future) -> None:
if not future.done():
future.set_result(None)

def _on_jump(self, time_jump: TimeJump) -> None:
if time_jump.clock_change in (
ClockChange.ROS_TIME_ACTIVATED,
ClockChange.ROS_TIME_DEACTIVATED,
):
for future in self._pending_sleeps:
if not future.done():
future.set_exception(TimeSourceChangedError())
elif time_jump.clock_change == ClockChange.ROS_TIME_NO_CHANGE:
now = self.now()
for future, target in self._pending_sleeps.items():
if target is not None and now >= target:
self._resolve_future(future)

def _destroy(self) -> None:
"""Cancel all pending sleeps. Called by AsyncNode.destroy_node()."""
if self._destroyed:
return
self._destroyed = True
self._jump_handle.unregister()
for future in self._pending_sleeps:
future.cancel()
Comment thread
nadavelkabets marked this conversation as resolved.
self.handle.destroy_when_not_in_use()

async def sleep(self, duration_sec: float) -> None:
"""
Sleep for a duration respecting sim time.

Cancelled on clock destruction. Raises TimeSourceChangedError if ROS
time is activated or deactivated during the sleep.
"""
if self._destroyed:
raise RuntimeError('Cannot sleep on a destroyed clock')
duration = Duration(seconds=duration_sec)
if duration <= Duration(nanoseconds=0):
await asyncio.sleep(0)
return

loop = asyncio.get_running_loop()
future: asyncio.Future[None] = loop.create_future()
timer_handle: Optional[asyncio.TimerHandle] = None
target: Optional[Time] = None

if self.ros_time_is_active:
target = self.now() + duration
else:
timer_handle = loop.call_later(
duration_sec, AsyncClock._resolve_future, future)

self._pending_sleeps[future] = target
try:
await future
finally:
self._pending_sleeps.pop(future)
if timer_handle is not None:
timer_handle.cancel()
Loading