Skip to content

Commit

Permalink
Add types to wait_for_message.py and moves Handles into type stubs (#…
Browse files Browse the repository at this point in the history
…1325)

* Add types to wait_for_message.py

Signed-off-by: Michael Carlstrom <rmc@carlstrom.com>

* Add copyright

Signed-off-by: Michael Carlstrom <rmc@carlstrom.com>

* re-run CI

Signed-off-by: Michael Carlstrom <rmc@carlstrom.com>

* re-run CI

Signed-off-by: Michael Carlstrom <rmc@carlstrom.com>

* move Handles into _rclpy_pybind11

Signed-off-by: Michael Carlstrom <rmc@carlstrom.com>

* Move Handles into type stubs:

Signed-off-by: Michael Carlstrom <rmc@carlstrom.com>

* Move Handles into type stubs

Signed-off-by: Michael Carlstrom <rmc@carlstrom.com>

* move [] into string

Signed-off-by: Michael Carlstrom <rmc@carlstrom.com>

* fix imports

Signed-off-by: Michael Carlstrom <rmc@carlstrom.com>

* remove extra line

Signed-off-by: Michael Carlstrom <rmc@carlstrom.com>

* puy _rclpy.Publisher in quotes

Signed-off-by: Michael Carlstrom <rmc@carlstrom.com>

* fix capitalization

Signed-off-by: Michael Carlstrom <rmc@carlstrom.com>

* Add EventHandle Constructor

Signed-off-by: Michael Carlstrom <rmc@carlstrom.com>

* Use RuntimeError for context

Signed-off-by: Michael Carlstrom <rmc@carlstrom.com>

* Add TYPE_CHECKING import

Signed-off-by: Michael Carlstrom <rmc@carlstrom.com>

---------

Signed-off-by: Michael Carlstrom <rmc@carlstrom.com>
Co-authored-by: mergify[bot] <37929162+mergify[bot]@users.noreply.github.com>
  • Loading branch information
InvincibleRMC and mergify[bot] authored Aug 23, 2024
1 parent 7e3005a commit f338416
Show file tree
Hide file tree
Showing 15 changed files with 366 additions and 250 deletions.
38 changes: 4 additions & 34 deletions rclpy/rclpy/clock.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,16 +14,15 @@

from enum import IntEnum
from types import TracebackType
from typing import Callable, Optional, Protocol, Type, TYPE_CHECKING, TypedDict
from typing import Callable, Optional, Type, TYPE_CHECKING, TypedDict

from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy

from .clock_type import ClockType
from .context import Context
from .destroyable import DestroyableType
from .duration import Duration
from .exceptions import NotInitializedException
from .time import Time, TimeHandle
from .time import Time
from .utilities import get_default_context


Expand Down Expand Up @@ -146,39 +145,10 @@ def __exit__(self, t: Optional[Type[BaseException]],
self.unregister()


class ClockHandle(DestroyableType, Protocol):
"""Generic alias of _rclpy.Clock."""

def get_now(self) -> TimeHandle:
"""Value of the clock."""
...

def get_ros_time_override_is_enabled(self) -> bool:
"""Return if a clock using ROS time has the ROS time override enabled."""
...

def set_ros_time_override_is_enabled(self, enabled: bool) -> None:
"""Set if a clock using ROS time has the ROS time override enabled."""
...

def set_ros_time_override(self, time_point: TimeHandle) -> None:
"""Set the ROS time override for a clock using ROS time."""
...

def add_clock_callback(self, pyjump_handle: JumpHandle,
on_clock_change: bool, min_forward: int, min_backward: int) -> None:
"""Add a time jump callback to a clock."""
...

def remove_clock_callback(self, pyjump_handle: JumpHandle) -> None:
"""Remove a time jump callback from a clock."""
...


class Clock:

if TYPE_CHECKING:
__clock: ClockHandle
__clock: _rclpy.Clock
_clock_type: ClockType

def __new__(cls, *,
Expand All @@ -198,7 +168,7 @@ def clock_type(self) -> ClockType:
return self._clock_type

@property
def handle(self) -> ClockHandle:
def handle(self) -> _rclpy.Clock:
"""
Return the internal instance of ``rclpy::Clock``.
Expand Down
20 changes: 3 additions & 17 deletions rclpy/rclpy/context.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,31 +20,17 @@
from typing import ContextManager
from typing import List
from typing import Optional
from typing import Protocol
from typing import Type
from typing import TYPE_CHECKING
from typing import Union
import warnings
import weakref

from rclpy.destroyable import DestroyableType
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy

if TYPE_CHECKING:
from rclpy.node import Node


class ContextHandle(DestroyableType, Protocol):

def ok(self) -> bool:
...

def get_domain_id(self) -> int:
...

def shutdown(self) -> None:
...


g_logging_configure_lock = threading.Lock()
g_logging_ref_count: int = 0

Expand All @@ -68,11 +54,11 @@ def __init__(self) -> None:
self._lock = threading.RLock()
self._callbacks: List[Union['weakref.WeakMethod[MethodType]', Callable[[], None]]] = []
self._logging_initialized = False
self.__context: Optional[ContextHandle] = None
self.__context: Optional[_rclpy.Context] = None
self.__node_weak_ref_list: List[weakref.ReferenceType['Node']] = []

@property
def handle(self) -> Optional[ContextHandle]:
def handle(self) -> Optional[_rclpy.Context]:
return self.__context

def destroy(self) -> None:
Expand Down
29 changes: 0 additions & 29 deletions rclpy/rclpy/destroyable.py

This file was deleted.

12 changes: 3 additions & 9 deletions rclpy/rclpy/duration.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,19 +12,13 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from typing import Protocol, Union
from typing import Union

import builtin_interfaces.msg
from rclpy.constants import S_TO_NS
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy


class DurationHandle(Protocol):
"""Type alias of _rclpy.rcl_duration_t."""

nanoseconds: int


class Duration:
"""A period between two time points, with nanosecond precision."""

Expand All @@ -41,7 +35,7 @@ def __init__(self, *, seconds: Union[int, float] = 0, nanoseconds: int = 0):
# pybind11 would raise TypeError, but we want OverflowError
raise OverflowError(
'Total nanoseconds value is too large to store in C duration.')
self._duration_handle: DurationHandle = _rclpy.rcl_duration_t(total_nanoseconds)
self._duration_handle = _rclpy.rcl_duration_t(total_nanoseconds)

@property
def nanoseconds(self) -> int:
Expand Down Expand Up @@ -106,7 +100,7 @@ def from_msg(cls, msg: builtin_interfaces.msg.Duration) -> 'Duration':
raise TypeError('Must pass a builtin_interfaces.msg.Duration object')
return cls(seconds=msg.sec, nanoseconds=msg.nanosec)

def get_c_duration(self) -> DurationHandle:
def get_c_duration(self) -> _rclpy.rcl_duration_t:
return self._duration_handle


Expand Down
6 changes: 1 addition & 5 deletions rclpy/rclpy/event_handler.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,10 +32,6 @@
from typing import TypeAlias


if TYPE_CHECKING:
from rclpy.subscription import SubscriptionHandle


QoSPublisherEventType = _rclpy.rcl_publisher_event_type_t
QoSSubscriptionEventType = _rclpy.rcl_subscription_event_type_t

Expand Down Expand Up @@ -201,7 +197,7 @@ def __init__(
self.use_default_callbacks = use_default_callbacks

def create_event_handlers(
self, callback_group: CallbackGroup, subscription: 'SubscriptionHandle',
self, callback_group: CallbackGroup, subscription: '_rclpy.Subscription',
topic_name: str) -> List[EventHandler]:
with subscription:
logger = get_logger(subscription.get_logger_name())
Expand Down
13 changes: 3 additions & 10 deletions rclpy/rclpy/guard_condition.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,21 +12,14 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from typing import Callable, Optional, Protocol
from typing import Callable, Optional

from rclpy.callback_groups import CallbackGroup
from rclpy.context import Context
from rclpy.destroyable import DestroyableType
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
from rclpy.utilities import get_default_context


class GuardConditionHandle(DestroyableType, Protocol):

def trigger_guard_condition(self) -> None:
...


class GuardCondition:

def __init__(self, callback: Optional[Callable],
Expand All @@ -44,7 +37,7 @@ def __init__(self, callback: Optional[Callable],
raise RuntimeError('Context must be initialized a GuardCondition can be created')

with self._context.handle:
self.__gc: GuardConditionHandle = _rclpy.GuardCondition(self._context.handle)
self.__gc = _rclpy.GuardCondition(self._context.handle)
self.callback = callback
self.callback_group = callback_group
# True when the callback is ready to fire but has not been "taken" by an executor
Expand All @@ -57,7 +50,7 @@ def trigger(self) -> None:
self.__gc.trigger_guard_condition()

@property
def handle(self) -> GuardConditionHandle:
def handle(self) -> _rclpy.GuardCondition:
return self.__gc

def destroy(self) -> None:
Expand Down
Loading

0 comments on commit f338416

Please sign in to comment.