diff --git a/bdai_ros2_wrappers/bdai_ros2_wrappers/node.py b/bdai_ros2_wrappers/bdai_ros2_wrappers/node.py index 0e5810b..6690cdb 100644 --- a/bdai_ros2_wrappers/bdai_ros2_wrappers/node.py +++ b/bdai_ros2_wrappers/bdai_ros2_wrappers/node.py @@ -5,9 +5,10 @@ from rclpy.callback_groups import CallbackGroup from rclpy.exceptions import InvalidHandle from rclpy.node import Node as BaseNode -from rclpy.wait_set import WaitSet from rclpy.waitables import Waitable +from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy + from bdai_ros2_wrappers.callback_groups import NonReentrantCallbackGroup from bdai_ros2_wrappers.logging import MemoizingRcutilsLogger, as_memoizing_logger @@ -21,7 +22,7 @@ def __init__(self, wrapped: Waitable) -> None: def __getattr__(self, name: str) -> Any: return getattr(self._wrapped, name) - def add_to_wait_set(self, wait_set: WaitSet) -> None: + def add_to_wait_set(self, wait_set: _rclpy.WaitSet) -> None: """Add waitable to `wait_set` safely.""" with contextlib.suppress(InvalidHandle): self._wrapped.add_to_wait_set(wait_set)