Skip to content

Commit

Permalink
Add types to Action Server and Action Client (#1349)
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carlstrom <[email protected]>
  • Loading branch information
InvincibleRMC authored Sep 7, 2024
1 parent d410670 commit d1d7d05
Show file tree
Hide file tree
Showing 10 changed files with 589 additions and 189 deletions.
222 changes: 145 additions & 77 deletions rclpy/rclpy/action/client.py

Large diffs are not rendered by default.

221 changes: 148 additions & 73 deletions rclpy/rclpy/action/server.py

Large diffs are not rendered by default.

8 changes: 4 additions & 4 deletions rclpy/rclpy/client.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,20 +28,20 @@
from rclpy.qos import QoSProfile
from rclpy.service_introspection import ServiceIntrospectionState
from rclpy.task import Future
from rclpy.type_support import Srv, SrvEventT, SrvRequestT, SrvResponseT
from rclpy.type_support import Srv, SrvRequestT, SrvResponseT

# Left To Support Legacy TypeVars
SrvType = TypeVar('SrvType')
SrvTypeRequest = TypeVar('SrvTypeRequest')
SrvTypeResponse = TypeVar('SrvTypeResponse')


class Client(Generic[SrvRequestT, SrvResponseT, SrvEventT]):
class Client(Generic[SrvRequestT, SrvResponseT]):
def __init__(
self,
context: Context,
client_impl: _rclpy.Client,
srv_type: Type[Srv[SrvRequestT, SrvResponseT, SrvEventT]],
srv_type: Type[Srv[SrvRequestT, SrvResponseT]],
srv_name: str,
qos_profile: QoSProfile,
callback_group: CallbackGroup
Expand Down Expand Up @@ -231,7 +231,7 @@ def destroy(self) -> None:
"""
self.__client.destroy_when_not_in_use()

def __enter__(self) -> 'Client[SrvRequestT, SrvResponseT, SrvEventT]':
def __enter__(self) -> 'Client[SrvRequestT, SrvResponseT]':
return self

def __exit__(
Expand Down
194 changes: 192 additions & 2 deletions rclpy/rclpy/impl/_rclpy_pybind11.pyi
Original file line number Diff line number Diff line change
Expand Up @@ -18,12 +18,17 @@ from enum import Enum, IntEnum
from types import TracebackType
from typing import Any, Generic, Literal, overload, Sequence, TypedDict


from action_msgs.msg import GoalInfo
from action_msgs.msg._goal_status_array import GoalStatusArray
from action_msgs.srv._cancel_goal import CancelGoal
from rclpy.clock import JumpHandle
from rclpy.clock_type import ClockType
from rclpy.duration import Duration
from rclpy.parameter import Parameter
from rclpy.subscription import MessageInfo
from rclpy.type_support import MsgT
from type_support import (MsgT, Action, GoalT, ResultT, FeedbackT, SendGoalServiceResponse,
GetResultServiceResponse, FeedbackMessage, SendGoalServiceRequest, GetResultServiceRequest)


def rclpy_remove_ros_args(pycli_args: Sequence[str]) -> list[str]:
Expand Down Expand Up @@ -443,6 +448,191 @@ class WaitSet(Destroyable):
"""Wait until timeout is reached or event happened."""


class ActionClient(Generic[GoalT, ResultT, FeedbackT], Destroyable):

def __init__(
self,
node: Node,
pyaction_type: type[Action[GoalT, ResultT, FeedbackT]],
goal_service_qos: rmw_qos_profile_t,
result_service_qos: rmw_qos_profile_t,
cancel_service_qos: rmw_qos_profile_t,
feedback_service_qos: rmw_qos_profile_t,
status_topci_qos: rmw_qos_profile_t
) -> None: ...

@property
def pointer(self) -> int:
"""Get the address of the entity as an integer."""

def take_goal_response(self, pymsg_type: type[SendGoalServiceResponse]
) -> tuple[int, SendGoalServiceResponse] | tuple[None, None]:
"""Take an action goal response."""

def send_result_request(self, pyrequest: GetResultServiceRequest) -> int:
"""Send an action result requst."""

def take_cancel_response(self, pymsg_type: type[CancelGoal.Response]
) -> tuple[int, CancelGoal.Response] | tuple[None, None]:
"""Take an action cancel response."""

def take_feedback(self, pymsg_type: type[FeedbackMessage[FeedbackT]]
) -> FeedbackMessage[FeedbackT] | None:
"""Take a feedback message from a given action client."""

def send_cancel_request(self: CancelGoal.Request) -> int:
"""Send an action cancel request."""

def send_goal_request(self: SendGoalServiceRequest[GoalT]) -> int:
"""Send an action goal request."""

def take_result_response(self, pymsg_type: type[GetResultServiceResponse[ResultT]]
) -> tuple[int, GetResultServiceResponse[ResultT]] | tuple[None, None]:
"""Take an action result response."""

def get_num_entities(self) -> tuple[int, int, int, int, int]:
"""Get the number of wait set entities that make up an action entity."""

def is_action_server_available(self) -> bool:
"""Check if an action server is available for the given action client."""

def add_to_waitset(self, waitset: WaitSet) -> None:
"""Add an action entity to a wait set."""

def is_ready(self) -> bool:
"""Check if an action entity has any ready wait set entities."""

def take_status(self, pymsg_type: type[GoalStatusArray]) -> GoalStatusArray | None:
"""Take an action status response."""


class GoalEvent(Enum):
_value_: int
EXECUTE = ...
CANCEL_GOAL = ...
SUCCEED = ...
ABORT = ...
CANCELED = ...


class rmw_request_id_t:
writer_guid: list[int]
sequence_number: int


class ActionServer(Generic[GoalT, ResultT, FeedbackT], Destroyable):

def __init__(
self,
node: Node,
rclpy_clock: Clock,
pyaction_type: type[Action[GoalT, ResultT, FeedbackT]],
action_name: str,
goal_service_qos: rmw_qos_profile_t,
result_service_qos: rmw_qos_profile_t,
cancel_service_qos: rmw_qos_profile_t,
feedback_topic_qos: rmw_qos_profile_t,
status_topic_qos: rmw_qos_profile_t,
result_timeout: float
) -> None: ...

@property
def pointer(self) -> int:
"""Get the address of the entity as an integer."""

def take_goal_request(
self,
pymsg_type: type[SendGoalServiceRequest[GoalT]]
) -> tuple[rmw_request_id_t, SendGoalServiceRequest[GoalT]] | tuple[None, None]:
"""Take an action goal request."""

def send_goal_response(
self,
header: rmw_request_id_t,
pyresponse: SendGoalServiceResponse
) -> None:
"""Send an action goal response."""

def send_result_response(
self,
header: rmw_request_id_t,
pyresponse: GetResultServiceResponse[ResultT]
) -> None:
"""Send an action result response."""

def take_cancel_request(
self,
pymsg_type: type[CancelGoal.Request]
) -> tuple[rmw_request_id_t, CancelGoal.Request] | tuple[None, None]:
"""Take an action cancel request."""

def take_result_request(
self,
pymsg_type: type[GetResultServiceRequest]
) -> tuple[rmw_request_id_t, GetResultServiceRequest] | tuple[None, None]:
"""Take an action result request."""

def send_cancel_response(
self,
header: rmw_request_id_t,
pyresponse: int
) -> None:
"""Send an action cancel response."""

def publish_feedback(
self,
pymsg: FeedbackMessage[FeedbackT]
) -> None:
"""Publish a feedback message from a given action server."""

def publish_status(self) -> None:
"""Publish a status message from a given action server."""

def notify_goal_done(self) -> None:
"""Notify goal is done."""

def goal_exists(self, pygoal_info: GoalInfo) -> bool:
"""Check is a goal exists in the server."""

def process_cancel_request(
self,
pycancel_request: CancelGoal.Request,
pycancel_response_tpye: type[CancelGoal.Response]
) -> CancelGoal.Response:
"""Process a cancel request"""

def expire_goals(self, max_num_goals: int) -> tuple[GoalInfo, ...]:
"""Expired goals."""

def get_num_entities(self) -> tuple[int, int, int, int, int]:
"""Get the number of wait set entities that make up an action entity."""

def is_ready(self, wait_set: WaitSet) -> tuple[bool, bool, bool, bool]:
"""Check if an action entity has any ready wait set entities."""

def add_to_waitset(self, wait_set: WaitSet) -> None:
"""Add an action entity to a wait set."""


class ActionGoalHandle:

def __init__(self, action_server: ActionServer, pygoal_info_msg: GoalInfo) -> None:
...

@property
def pointer(self) -> int:
"""Get the address of the entity as an integer."""

def get_status(self) -> GoalEvent:
"""Get the status of a goal."""

def update_goal_state(self, event: GoalEvent) -> None:
"""Update a goal state."""

def is_active(self) -> bool:
"""Check if a goal is active."""


class RCLError(RuntimeError):
pass

Expand All @@ -454,7 +644,7 @@ class NodeNameNonExistentError(RCLError):
class InvalidHandle(RuntimeError):
pass


class SignalHandlerOptions(Enum):
_value_: int
NO = ...
Expand Down
2 changes: 1 addition & 1 deletion rclpy/rclpy/impl/implementation_singleton.pyi
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,6 @@
# limitations under the License.


from rclpy.impl import _rclpy_pybind11
from impl import _rclpy_pybind11

rclpy_implementation = _rclpy_pybind11
21 changes: 10 additions & 11 deletions rclpy/rclpy/node.py
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,6 @@
from rclpy.type_support import check_is_valid_srv_type
from rclpy.type_support import MsgT
from rclpy.type_support import Srv
from rclpy.type_support import SrvEventT
from rclpy.type_support import SrvRequestT
from rclpy.type_support import SrvResponseT
from rclpy.utilities import get_default_context
Expand Down Expand Up @@ -173,8 +172,8 @@ def __init__(
self._parameters: Dict[str, Parameter[Any]] = {}
self._publishers: List[Publisher[Any]] = []
self._subscriptions: List[Subscription[Any]] = []
self._clients: List[Client[Any, Any, Any]] = []
self._services: List[Service[Any, Any, Any]] = []
self._clients: List[Client[Any, Any]] = []
self._services: List[Service[Any, Any]] = []
self._timers: List[Timer] = []
self._guards: List[GuardCondition] = []
self.__waitables: List[Waitable[Any]] = []
Expand Down Expand Up @@ -270,12 +269,12 @@ def subscriptions(self) -> Iterator[Subscription[Any]]:
yield from self._subscriptions

@property
def clients(self) -> Iterator[Client[Any, Any, Any]]:
def clients(self) -> Iterator[Client[Any, Any]]:
"""Get clients that have been created on this node."""
yield from self._clients

@property
def services(self) -> Iterator[Service[Any, Any, Any]]:
def services(self) -> Iterator[Service[Any, Any]]:
"""Get services that have been created on this node."""
yield from self._services

Expand Down Expand Up @@ -1690,12 +1689,12 @@ def create_subscription(

def create_client(
self,
srv_type: Type[Srv[SrvRequestT, SrvResponseT, SrvEventT]],
srv_type: Type[Srv[SrvRequestT, SrvResponseT]],
srv_name: str,
*,
qos_profile: QoSProfile = qos_profile_services_default,
callback_group: Optional[CallbackGroup] = None
) -> Client[SrvRequestT, SrvResponseT, SrvEventT]:
) -> Client[SrvRequestT, SrvResponseT]:
"""
Create a new service client.
Expand Down Expand Up @@ -1732,13 +1731,13 @@ def create_client(

def create_service(
self,
srv_type: Type[Srv[SrvRequestT, SrvResponseT, SrvEventT]],
srv_type: Type[Srv[SrvRequestT, SrvResponseT]],
srv_name: str,
callback: Callable[[SrvRequestT, SrvResponseT], SrvResponseT],
*,
qos_profile: QoSProfile = qos_profile_services_default,
callback_group: Optional[CallbackGroup] = None
) -> Service[SrvRequestT, SrvResponseT, SrvEventT]:
) -> Service[SrvRequestT, SrvResponseT]:
"""
Create a new service server.
Expand Down Expand Up @@ -1892,7 +1891,7 @@ def destroy_subscription(self, subscription: Subscription[Any]) -> bool:
return True
return False

def destroy_client(self, client: Client[Any, Any, Any]) -> bool:
def destroy_client(self, client: Client[Any, Any]) -> bool:
"""
Destroy a service client created by the node.
Expand All @@ -1908,7 +1907,7 @@ def destroy_client(self, client: Client[Any, Any, Any]) -> bool:
return True
return False

def destroy_service(self, service: Service[Any, Any, Any]) -> bool:
def destroy_service(self, service: Service[Any, Any]) -> bool:
"""
Destroy a service server created by the node.
Expand Down
8 changes: 4 additions & 4 deletions rclpy/rclpy/service.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,19 +24,19 @@
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
from rclpy.qos import QoSProfile
from rclpy.service_introspection import ServiceIntrospectionState
from rclpy.type_support import Srv, SrvEventT, SrvRequestT, SrvResponseT
from rclpy.type_support import Srv, SrvRequestT, SrvResponseT

# Used for documentation purposes only
SrvType = TypeVar('SrvType')
SrvTypeRequest = TypeVar('SrvTypeRequest')
SrvTypeResponse = TypeVar('SrvTypeResponse')


class Service(Generic[SrvRequestT, SrvResponseT, SrvEventT]):
class Service(Generic[SrvRequestT, SrvResponseT]):
def __init__(
self,
service_impl: _rclpy.Service,
srv_type: Type[Srv[SrvRequestT, SrvResponseT, SrvEventT]],
srv_type: Type[Srv[SrvRequestT, SrvResponseT]],
srv_name: str,
callback: Callable[[SrvRequestT, SrvResponseT], SrvResponseT],
callback_group: CallbackGroup,
Expand Down Expand Up @@ -121,7 +121,7 @@ def destroy(self) -> None:
"""
self.__service.destroy_when_not_in_use()

def __enter__(self) -> 'Service[SrvRequestT, SrvResponseT, SrvEventT]':
def __enter__(self) -> 'Service[SrvRequestT, SrvResponseT]':
return self

def __exit__(
Expand Down
Loading

0 comments on commit d1d7d05

Please sign in to comment.