Skip to content
Closed
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
35 changes: 25 additions & 10 deletions rclpy/rclpy/client.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,15 +19,20 @@
from typing import Generic
from typing import Optional
from typing import Type
from typing import TYPE_CHECKING
from typing import TypeVar
import weakref

from rclpy.callback_groups import CallbackGroup

if TYPE_CHECKING:
from rclpy.node import Node
from rclpy.clock import Clock
from rclpy.context import Context
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
from rclpy.qos import QoSProfile
from rclpy.service_introspection import ServiceIntrospectionState
from rclpy.task import Future
from rclpy.task import Future, FutureLike
from rclpy.type_support import Srv, SrvRequestT, SrvResponseT

# Left To Support Legacy TypeVars
Expand All @@ -44,7 +49,8 @@ def __init__(
srv_type: Type[Srv],
srv_name: str,
qos_profile: QoSProfile,
callback_group: CallbackGroup
callback_group: CallbackGroup,
node: 'Node'
) -> None:
"""
Create a container for a ROS service client.
Expand All @@ -59,17 +65,19 @@ def __init__(
:param qos_profile: The quality of service profile to apply the service client.
:param callback_group: The callback group for the service client. If ``None``, then the
nodes default callback group is used.
:param node: The node that owns this client.
"""
self.context = context
self.__client = client_impl
self.srv_type = srv_type
self.srv_name = srv_name
self.qos_profile = qos_profile
# Key is a sequence number, value is an instance of a Future
self._pending_requests: Dict[int, Future[SrvResponseT]] = {}
# Key is a sequence number, value is a future (rclpy.Future or asyncio.Future)
self._pending_requests: Dict[int, FutureLike[SrvResponseT]] = {}
self.callback_group = callback_group
# True when the callback is ready to fire but has not been "taken" by an executor
self._executor_event = False
self._node: weakref.ReferenceType['Node'] = weakref.ref(node)

self._lock = threading.Lock()

Expand Down Expand Up @@ -117,12 +125,14 @@ def unblock(future: Future[SrvResponseT]) -> None:
raise exception
return future.result()

def call_async(self, request: SrvRequestT) -> Future[SrvResponseT]:
def call_async(self, request: SrvRequestT) -> FutureLike[SrvResponseT]:
"""
Make a service request and asynchronously get the result.

:param request: The service request.
:return: A future that completes when the request does.
:return: A future that completes when the request does. The concrete type
depends on the executor: asyncio.Future when using AsyncioExecutor,
or rclpy.task.Future otherwise.
:raises: TypeError if the type of the passed request isn't an instance
of the Request type of the provided service when the client was
constructed.
Expand All @@ -136,14 +146,19 @@ def call_async(self, request: SrvRequestT) -> Future[SrvResponseT]:
if sequence_number in self._pending_requests:
raise RuntimeError(f'Sequence ({sequence_number}) conflicts with pending request')

future = Future[SrvResponseT]()
self._pending_requests[sequence_number] = future
# Use executor's future factory if available
node = self._node()
if node is not None and node.executor is not None:
future: FutureLike[SrvResponseT] = node.executor.create_future()
else:
future = Future[SrvResponseT]()

self._pending_requests[sequence_number] = future
future.add_done_callback(self.remove_pending_request)

return future

def get_pending_request(self, sequence_number: int) -> Future[SrvResponseT]:
def get_pending_request(self, sequence_number: int) -> FutureLike[SrvResponseT]:
"""
Get a future from the list of pending requests.

Expand All @@ -154,7 +169,7 @@ def get_pending_request(self, sequence_number: int) -> Future[SrvResponseT]:
with self._lock:
return self._pending_requests[sequence_number]

def remove_pending_request(self, future: Future[SrvResponseT]) -> None:
def remove_pending_request(self, future: FutureLike[SrvResponseT]) -> None:
"""
Remove a future from the list of pending requests.

Expand Down
255 changes: 128 additions & 127 deletions rclpy/rclpy/executors.py
Original file line number Diff line number Diff line change
Expand Up @@ -185,7 +185,134 @@ class TaskData:
source_entity: 'Optional[Entity]' = None


class Executor(ContextManager['Executor']):
class BaseExecutor:
"""The base class for an executor."""

def create_future(self) -> Future:
"""Create a future attached to this executor."""
return Future(executor=self)

def _take_client(self, client: Client[Any, Any]
) -> Optional[Callable[[], Coroutine[None, None, None]]]:
try:
with client.handle:
header_and_response = client.handle.take_response(client.srv_type.Response)

async def _execute() -> None:
header, response = header_and_response
if header is None:
return
try:
sequence = header.request_id.sequence_number
future = client.get_pending_request(sequence)
except KeyError:
# The request was cancelled
pass
else:
# Only set executor for rclpy futures that don't have one yet
if isinstance(future, Future) and future._executor() is None:
future._set_executor(self)
future.set_result(response)
return _execute

except InvalidHandle:
# Client is a Destroyable, which means that on __enter__ it can throw an
# InvalidHandle exception if the entity has already been destroyed. Handle that here
# by just returning an empty argument, which means we will skip doing any real work
# in _execute_client below
pass

return None

def _take_subscription(self, sub: Subscription[Any]
) -> Optional[Callable[[], Coroutine[None, None, None]]]:
try:
with sub.handle:
msg_info = sub.handle.take_message(sub.msg_type, sub.raw)
if msg_info is None:
return None

if sub._callback_type is Subscription.CallbackType.MessageOnly:
msg_tuple: Union[Tuple[Msg], Tuple[Msg, MessageInfo]] = (msg_info[0], )
else:
msg_tuple = msg_info

async def _execute() -> None:
await await_or_execute(sub.callback, *msg_tuple)

return _execute
except InvalidHandle:
# Subscription is a Destroyable, which means that on __enter__ it can throw an
# InvalidHandle exception if the entity has already been destroyed. Handle that here
# by just returning an empty argument, which means we will skip doing any real work
# in _execute_subscription below
pass

return None

def _take_service(self, srv: Service[Any, Any]
) -> Optional[Callable[[], Coroutine[None, None, None]]]:
try:
with srv.handle:
request_and_header = srv.handle.service_take_request(srv.srv_type.Request)

async def _execute() -> None:
(request, header) = request_and_header
if header is None:
return

response = await await_or_execute(srv.callback, request, srv.srv_type.Response())
srv.send_response(response, header)
return _execute
except InvalidHandle:
# Service is a Destroyable, which means that on __enter__ it can throw an
# InvalidHandle exception if the entity has already been destroyed. Handle that here
# by just returning an empty argument, which means we will skip doing any real work
# in _execute_service below
pass

return None

def _take_timer(self, tmr: Timer) -> Optional[Callable[[], Coroutine[None, None, None]]]:
try:
with tmr.handle:
info = tmr.handle.call_timer_with_info()
timer_info = TimerInfo(
expected_call_time=info['expected_call_time'],
actual_call_time=info['actual_call_time'],
clock_type=tmr.clock.clock_type)

def check_argument_type(callback_func: TimerCallbackType,
target_type: Type[TimerInfo]) -> Optional[str]:
sig = inspect.signature(callback_func)
for param in sig.parameters.values():
if param.annotation == target_type:
return param.name
return None

if tmr.callback:
arg_name = check_argument_type(tmr.callback, target_type=TimerInfo)
if arg_name is not None:
prefilled_arg = {arg_name: timer_info}

async def _execute() -> None:
if tmr.callback:
await await_or_execute(partial(tmr.callback, **prefilled_arg))
return _execute
else:
async def _execute() -> None:
if tmr.callback:
await await_or_execute(tmr.callback)
return _execute
except InvalidHandle:
pass
except TimerCancelledError:
pass

return None


class Executor(ContextManager['Executor'], BaseExecutor):
"""
The base class for an executor.

Expand Down Expand Up @@ -487,132 +614,6 @@ def _spin_once_until_future_complete(
) -> None:
raise NotImplementedError()

def _take_timer(self, tmr: Timer) -> Optional[Callable[[], Coroutine[None, None, None]]]:
try:
with tmr.handle:
info = tmr.handle.call_timer_with_info()
timer_info = TimerInfo(
expected_call_time=info['expected_call_time'],
actual_call_time=info['actual_call_time'],
clock_type=tmr.clock.clock_type)

def check_argument_type(callback_func: TimerCallbackType,
target_type: Type[TimerInfo]) -> Optional[str]:
sig = inspect.signature(callback_func)
for param in sig.parameters.values():
if param.annotation == target_type:
# return 1st one immediately
return param.name
# We could not find the target type in the signature
return None

# User might change the Timer.callback function signature at runtime,
# so it needs to check the signature every time.
if tmr.callback:
arg_name = check_argument_type(tmr.callback, target_type=TimerInfo)
if arg_name is not None:
prefilled_arg = {arg_name: timer_info}

async def _execute() -> None:
if tmr.callback:
await await_or_execute(partial(tmr.callback, **prefilled_arg))
return _execute
else:
async def _execute() -> None:
if tmr.callback:
await await_or_execute(tmr.callback)
return _execute
except InvalidHandle:
# Timer is a Destroyable, which means that on __enter__ it can throw an
# InvalidHandle exception if the entity has already been destroyed. Handle that here
# by just returning an empty argument, which means we will skip doing any real work.
pass
except TimerCancelledError:
# If TimerCancelledError exception occurs when calling call_timer_with_info(), we will
# skip doing any real work.
pass

return None

def _take_subscription(self, sub: Subscription[Any]
) -> Optional[Callable[[], Coroutine[None, None, None]]]:
try:
with sub.handle:
msg_info = sub.handle.take_message(sub.msg_type, sub.raw)
if msg_info is None:
return None

if sub._callback_type is Subscription.CallbackType.MessageOnly:
msg_tuple: Union[Tuple[Msg], Tuple[Msg, MessageInfo]] = (msg_info[0], )
else:
msg_tuple = msg_info

async def _execute() -> None:
await await_or_execute(sub.callback, *msg_tuple)

return _execute
except InvalidHandle:
# Subscription is a Destroyable, which means that on __enter__ it can throw an
# InvalidHandle exception if the entity has already been destroyed. Handle that here
# by just returning an empty argument, which means we will skip doing any real work
# in _execute_subscription below
pass

return None

def _take_client(self, client: Client[Any, Any]
) -> Optional[Callable[[], Coroutine[None, None, None]]]:
try:
with client.handle:
header_and_response = client.handle.take_response(client.srv_type.Response)

async def _execute() -> None:
header, response = header_and_response
if header is None:
return
try:
sequence = header.request_id.sequence_number
future = client.get_pending_request(sequence)
except KeyError:
# The request was cancelled
pass
else:
future._set_executor(self)
future.set_result(response)
return _execute

except InvalidHandle:
# Client is a Destroyable, which means that on __enter__ it can throw an
# InvalidHandle exception if the entity has already been destroyed. Handle that here
# by just returning an empty argument, which means we will skip doing any real work
# in _execute_client below
pass

return None

def _take_service(self, srv: Service[Any, Any]
) -> Optional[Callable[[], Coroutine[None, None, None]]]:
try:
with srv.handle:
request_and_header = srv.handle.service_take_request(srv.srv_type.Request)

async def _execute() -> None:
(request, header) = request_and_header
if header is None:
return

response = await await_or_execute(srv.callback, request, srv.srv_type.Response())
srv.send_response(response, header)
return _execute
except InvalidHandle:
# Service is a Destroyable, which means that on __enter__ it can throw an
# InvalidHandle exception if the entity has already been destroyed. Handle that here
# by just returning an empty argument, which means we will skip doing any real work
# in _execute_service below
pass

return None

def _take_guard_condition(self, gc: GuardCondition
) -> Callable[[], Coroutine[None, None, None]]:
gc._executor_triggered = False
Expand Down
Loading