Skip to content

Commit f338416

Browse files
Add types to wait_for_message.py and moves Handles into type stubs (#1325)
* Add types to wait_for_message.py Signed-off-by: Michael Carlstrom <[email protected]> * Add copyright Signed-off-by: Michael Carlstrom <[email protected]> * re-run CI Signed-off-by: Michael Carlstrom <[email protected]> * re-run CI Signed-off-by: Michael Carlstrom <[email protected]> * move Handles into _rclpy_pybind11 Signed-off-by: Michael Carlstrom <[email protected]> * Move Handles into type stubs: Signed-off-by: Michael Carlstrom <[email protected]> * Move Handles into type stubs Signed-off-by: Michael Carlstrom <[email protected]> * move [] into string Signed-off-by: Michael Carlstrom <[email protected]> * fix imports Signed-off-by: Michael Carlstrom <[email protected]> * remove extra line Signed-off-by: Michael Carlstrom <[email protected]> * puy _rclpy.Publisher in quotes Signed-off-by: Michael Carlstrom <[email protected]> * fix capitalization Signed-off-by: Michael Carlstrom <[email protected]> * Add EventHandle Constructor Signed-off-by: Michael Carlstrom <[email protected]> * Use RuntimeError for context Signed-off-by: Michael Carlstrom <[email protected]> * Add TYPE_CHECKING import Signed-off-by: Michael Carlstrom <[email protected]> --------- Signed-off-by: Michael Carlstrom <[email protected]> Co-authored-by: mergify[bot] <37929162+mergify[bot]@users.noreply.github.com>
1 parent 7e3005a commit f338416

15 files changed

+366
-250
lines changed

rclpy/rclpy/clock.py

+4-34
Original file line numberDiff line numberDiff line change
@@ -14,16 +14,15 @@
1414

1515
from enum import IntEnum
1616
from types import TracebackType
17-
from typing import Callable, Optional, Protocol, Type, TYPE_CHECKING, TypedDict
17+
from typing import Callable, Optional, Type, TYPE_CHECKING, TypedDict
1818

1919
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
2020

2121
from .clock_type import ClockType
2222
from .context import Context
23-
from .destroyable import DestroyableType
2423
from .duration import Duration
2524
from .exceptions import NotInitializedException
26-
from .time import Time, TimeHandle
25+
from .time import Time
2726
from .utilities import get_default_context
2827

2928

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

148147

149-
class ClockHandle(DestroyableType, Protocol):
150-
"""Generic alias of _rclpy.Clock."""
151-
152-
def get_now(self) -> TimeHandle:
153-
"""Value of the clock."""
154-
...
155-
156-
def get_ros_time_override_is_enabled(self) -> bool:
157-
"""Return if a clock using ROS time has the ROS time override enabled."""
158-
...
159-
160-
def set_ros_time_override_is_enabled(self, enabled: bool) -> None:
161-
"""Set if a clock using ROS time has the ROS time override enabled."""
162-
...
163-
164-
def set_ros_time_override(self, time_point: TimeHandle) -> None:
165-
"""Set the ROS time override for a clock using ROS time."""
166-
...
167-
168-
def add_clock_callback(self, pyjump_handle: JumpHandle,
169-
on_clock_change: bool, min_forward: int, min_backward: int) -> None:
170-
"""Add a time jump callback to a clock."""
171-
...
172-
173-
def remove_clock_callback(self, pyjump_handle: JumpHandle) -> None:
174-
"""Remove a time jump callback from a clock."""
175-
...
176-
177-
178148
class Clock:
179149

180150
if TYPE_CHECKING:
181-
__clock: ClockHandle
151+
__clock: _rclpy.Clock
182152
_clock_type: ClockType
183153

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

200170
@property
201-
def handle(self) -> ClockHandle:
171+
def handle(self) -> _rclpy.Clock:
202172
"""
203173
Return the internal instance of ``rclpy::Clock``.
204174

rclpy/rclpy/context.py

+3-17
Original file line numberDiff line numberDiff line change
@@ -20,31 +20,17 @@
2020
from typing import ContextManager
2121
from typing import List
2222
from typing import Optional
23-
from typing import Protocol
2423
from typing import Type
2524
from typing import TYPE_CHECKING
2625
from typing import Union
2726
import warnings
2827
import weakref
2928

30-
from rclpy.destroyable import DestroyableType
29+
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
3130

3231
if TYPE_CHECKING:
3332
from rclpy.node import Node
3433

35-
36-
class ContextHandle(DestroyableType, Protocol):
37-
38-
def ok(self) -> bool:
39-
...
40-
41-
def get_domain_id(self) -> int:
42-
...
43-
44-
def shutdown(self) -> None:
45-
...
46-
47-
4834
g_logging_configure_lock = threading.Lock()
4935
g_logging_ref_count: int = 0
5036

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

7460
@property
75-
def handle(self) -> Optional[ContextHandle]:
61+
def handle(self) -> Optional[_rclpy.Context]:
7662
return self.__context
7763

7864
def destroy(self) -> None:

rclpy/rclpy/destroyable.py

-29
This file was deleted.

rclpy/rclpy/duration.py

+3-9
Original file line numberDiff line numberDiff line change
@@ -12,19 +12,13 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15-
from typing import Protocol, Union
15+
from typing import Union
1616

1717
import builtin_interfaces.msg
1818
from rclpy.constants import S_TO_NS
1919
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
2020

2121

22-
class DurationHandle(Protocol):
23-
"""Type alias of _rclpy.rcl_duration_t."""
24-
25-
nanoseconds: int
26-
27-
2822
class Duration:
2923
"""A period between two time points, with nanosecond precision."""
3024

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

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

109-
def get_c_duration(self) -> DurationHandle:
103+
def get_c_duration(self) -> _rclpy.rcl_duration_t:
110104
return self._duration_handle
111105

112106

rclpy/rclpy/event_handler.py

+1-5
Original file line numberDiff line numberDiff line change
@@ -32,10 +32,6 @@
3232
from typing import TypeAlias
3333

3434

35-
if TYPE_CHECKING:
36-
from rclpy.subscription import SubscriptionHandle
37-
38-
3935
QoSPublisherEventType = _rclpy.rcl_publisher_event_type_t
4036
QoSSubscriptionEventType = _rclpy.rcl_subscription_event_type_t
4137

@@ -201,7 +197,7 @@ def __init__(
201197
self.use_default_callbacks = use_default_callbacks
202198

203199
def create_event_handlers(
204-
self, callback_group: CallbackGroup, subscription: 'SubscriptionHandle',
200+
self, callback_group: CallbackGroup, subscription: '_rclpy.Subscription',
205201
topic_name: str) -> List[EventHandler]:
206202
with subscription:
207203
logger = get_logger(subscription.get_logger_name())

rclpy/rclpy/guard_condition.py

+3-10
Original file line numberDiff line numberDiff line change
@@ -12,21 +12,14 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15-
from typing import Callable, Optional, Protocol
15+
from typing import Callable, Optional
1616

1717
from rclpy.callback_groups import CallbackGroup
1818
from rclpy.context import Context
19-
from rclpy.destroyable import DestroyableType
2019
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
2120
from rclpy.utilities import get_default_context
2221

2322

24-
class GuardConditionHandle(DestroyableType, Protocol):
25-
26-
def trigger_guard_condition(self) -> None:
27-
...
28-
29-
3023
class GuardCondition:
3124

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

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

5952
@property
60-
def handle(self) -> GuardConditionHandle:
53+
def handle(self) -> _rclpy.GuardCondition:
6154
return self.__gc
6255

6356
def destroy(self) -> None:

0 commit comments

Comments
 (0)