From 05870d500a5366ade361e8bdb45592adc658cad4 Mon Sep 17 00:00:00 2001 From: Michael Carlstrom Date: Thu, 29 Aug 2024 13:50:55 -0400 Subject: [PATCH 1/3] use @deprecated Signed-off-by: Michael Carlstrom --- rclpy/package.xml | 1 + rclpy/rclpy/event_handler.py | 3 +++ rclpy/rclpy/impl/rcutils_logger.py | 10 ++-------- 3 files changed, 6 insertions(+), 8 deletions(-) diff --git a/rclpy/package.xml b/rclpy/package.xml index aad3a2431..437858c88 100644 --- a/rclpy/package.xml +++ b/rclpy/package.xml @@ -38,6 +38,7 @@ action_msgs ament_index_python builtin_interfaces + python3-typing-extensions python3-yaml rosgraph_msgs rpyutils diff --git a/rclpy/rclpy/event_handler.py b/rclpy/rclpy/event_handler.py index e846b9135..438de8de2 100644 --- a/rclpy/rclpy/event_handler.py +++ b/rclpy/rclpy/event_handler.py @@ -27,6 +27,7 @@ from rclpy.qos import qos_policy_name_from_kind from rclpy.waitable import NumberOfEntities from rclpy.waitable import Waitable +from typing_extensions import deprecated if TYPE_CHECKING: from typing import TypeAlias @@ -144,6 +145,8 @@ def destroy(self) -> None: self.__event.destroy_when_not_in_use() +@deprecated('QoSEventHandler foo is deprecated, use EventHandler instead.', + category=DeprecationWarning, stacklevel=2) class QoSEventHandler(EventHandler): def __init_subclass__(cls, **kwargs): diff --git a/rclpy/rclpy/impl/rcutils_logger.py b/rclpy/rclpy/impl/rcutils_logger.py index 041566397..56807e1a6 100644 --- a/rclpy/rclpy/impl/rcutils_logger.py +++ b/rclpy/rclpy/impl/rcutils_logger.py @@ -12,10 +12,8 @@ # See the License for the specific language governing permissions and # limitations under the License. -from contextlib import suppress import inspect import os -import sys from types import FrameType from typing import cast from typing import ClassVar @@ -33,12 +31,7 @@ from rclpy.clock import Clock from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy from rclpy.impl.logging_severity import LoggingSeverity - -if sys.version_info >= (3, 12): - from typing import Unpack -else: - with suppress(ModuleNotFoundError): - from typing_extensions import Unpack +from typing_extensions import deprecated, Unpack SupportedFiltersKeys = Literal['throttle', 'skip_first', 'once'] @@ -430,6 +423,7 @@ def warning(self, message: str, **kwargs: 'Unpack[LoggingArgs]') -> bool: """Log a message with `WARN` severity via :py:classmethod:RcutilsLogger.log:.""" return self.log(message, LoggingSeverity.WARN, **kwargs) + @deprecated('Deprecated in favor of :py:classmethod:RcutilsLogger.warning:.') def warn(self, message: str, **kwargs: 'Unpack[LoggingArgs]') -> bool: """ Log a message with `WARN` severity via :py:classmethod:RcutilsLogger.log:. From 368737181a4e4fb8aa1cc2aacbd31cdc64acdc4c Mon Sep 17 00:00:00 2001 From: Michael Carlstrom Date: Thu, 29 Aug 2024 14:07:47 -0400 Subject: [PATCH 2/3] move typing_extensions Signed-off-by: Michael Carlstrom --- rclpy/rclpy/clock.py | 7 ++----- rclpy/rclpy/event_handler.py | 7 ++----- rclpy/rclpy/parameter.py | 3 +-- rclpy/rclpy/qos.py | 8 +++----- rclpy/rclpy/qos_overriding_options.py | 4 ++-- rclpy/rclpy/waitable.py | 6 ++---- 6 files changed, 12 insertions(+), 23 deletions(-) diff --git a/rclpy/rclpy/clock.py b/rclpy/rclpy/clock.py index 3b9f363e8..c91caa056 100644 --- a/rclpy/rclpy/clock.py +++ b/rclpy/rclpy/clock.py @@ -17,6 +17,7 @@ from typing import Callable, Optional, Type, TYPE_CHECKING, TypedDict from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy +from typing_extensions import TypeAlias from .clock_type import ClockType from .context import Context @@ -26,10 +27,6 @@ from .utilities import get_default_context -if TYPE_CHECKING: - from typing import TypeAlias - - class ClockChange(IntEnum): ROS_TIME_NO_CHANGE = _rclpy.ClockChange.ROS_TIME_NO_CHANGE ROS_TIME_ACTIVATED = _rclpy.ClockChange.ROS_TIME_ACTIVATED @@ -90,7 +87,7 @@ class TimeJumpDictionary(TypedDict): delta: int -JumpHandlePreCallbackType: 'TypeAlias' = Callable[[], None] +JumpHandlePreCallbackType: TypeAlias = Callable[[], None] class JumpHandle: diff --git a/rclpy/rclpy/event_handler.py b/rclpy/rclpy/event_handler.py index 438de8de2..3700c438d 100644 --- a/rclpy/rclpy/event_handler.py +++ b/rclpy/rclpy/event_handler.py @@ -17,7 +17,6 @@ from typing import Callable from typing import List from typing import Optional -from typing import TYPE_CHECKING import warnings import rclpy @@ -28,9 +27,7 @@ from rclpy.waitable import NumberOfEntities from rclpy.waitable import Waitable from typing_extensions import deprecated - -if TYPE_CHECKING: - from typing import TypeAlias +from typing_extensions import TypeAlias QoSPublisherEventType = _rclpy.rcl_publisher_event_type_t @@ -76,7 +73,7 @@ UnsupportedEventTypeError = _rclpy.UnsupportedEventTypeError -EventHandlerData: 'TypeAlias' = Optional[Any] +EventHandlerData: TypeAlias = Optional[Any] class EventHandler(Waitable[EventHandlerData]): diff --git a/rclpy/rclpy/parameter.py b/rclpy/rclpy/parameter.py index 464ee7065..06aff89df 100644 --- a/rclpy/rclpy/parameter.py +++ b/rclpy/rclpy/parameter.py @@ -28,12 +28,12 @@ from rcl_interfaces.msg import Parameter as ParameterMsg from rcl_interfaces.msg import ParameterType from rcl_interfaces.msg import ParameterValue +from typing_extensions import TypeVar import yaml PARAMETER_SEPARATOR_STRING = '.' if TYPE_CHECKING: - from typing_extensions import TypeVar # Mypy does not handle string literals of array.array[int/str/float] very well # So if user has newer version of python can use proper array types. if sys.version_info > (3, 9): @@ -55,7 +55,6 @@ bound=AllowableParameterValue, default=AllowableParameterValue) else: - from typing import TypeVar # Done to prevent runtime errors of undefined values. # after python3.13 is minimum support this could be removed. AllowableParameterValue = Any diff --git a/rclpy/rclpy/qos.py b/rclpy/rclpy/qos.py index 6c8b18f92..4b7aaabf5 100644 --- a/rclpy/rclpy/qos.py +++ b/rclpy/rclpy/qos.py @@ -13,15 +13,13 @@ # limitations under the License. from enum import Enum, IntEnum -from typing import (Callable, Iterable, List, Optional, Tuple, Type, TYPE_CHECKING, +from typing import (Callable, Iterable, List, Optional, Tuple, Type, TypedDict, TypeVar, Union) import warnings from rclpy.duration import Duration from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy - -if TYPE_CHECKING: - from typing import TypeAlias +from typing_extensions import TypeAlias class QoSPolicyKind(IntEnum): @@ -528,7 +526,7 @@ def get_from_short_key(cls, name: str) -> QoSProfile: return cls[name.upper()].value -QoSCompatibility: 'TypeAlias' = _rclpy.QoSCompatibility +QoSCompatibility: TypeAlias = _rclpy.QoSCompatibility def qos_check_compatible(publisher_qos: QoSProfile, diff --git a/rclpy/rclpy/qos_overriding_options.py b/rclpy/rclpy/qos_overriding_options.py index f64b83d30..69af01f7d 100644 --- a/rclpy/rclpy/qos_overriding_options.py +++ b/rclpy/rclpy/qos_overriding_options.py @@ -36,9 +36,9 @@ from rclpy.qos import QoSProfile from rclpy.qos import QoSReliabilityPolicy from rclpy.subscription import Subscription +from typing_extensions import TypeAlias if TYPE_CHECKING: - from typing import TypeAlias from rclpy.node import Node @@ -47,7 +47,7 @@ class InvalidQosOverridesError(Exception): # Return type of qos validation callbacks -QosCallbackResult: 'TypeAlias' = SetParametersResult +QosCallbackResult: TypeAlias = SetParametersResult # Qos callback type annotation QosCallbackType = Callable[[QoSProfile], QosCallbackResult] diff --git a/rclpy/rclpy/waitable.py b/rclpy/rclpy/waitable.py index 56b363df5..129d460f9 100644 --- a/rclpy/rclpy/waitable.py +++ b/rclpy/rclpy/waitable.py @@ -17,13 +17,11 @@ from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy +from typing_extensions import Self T = TypeVar('T') - if TYPE_CHECKING: - from typing_extensions import Self - from rclpy.callback_groups import CallbackGroup from rclpy.task import Future @@ -91,7 +89,7 @@ def __init__(self, callback_group: 'CallbackGroup'): # List of Futures that have callbacks needing execution self._futures: List[Future[Any]] = [] - def __enter__(self) -> 'Self': + def __enter__(self) -> Self: """Implement to mark entities as in-use to prevent destruction while waiting on them.""" raise NotImplementedError('Must be implemented by subclass') From 88bc4567fb1b2081ef9f2f419fb7f2a1b6afb9d1 Mon Sep 17 00:00:00 2001 From: Michael Carlstrom Date: Fri, 30 Aug 2024 13:22:32 -0400 Subject: [PATCH 3/3] Add deprecated to declare_parameters Signed-off-by: Michael Carlstrom --- rclpy/rclpy/node.py | 54 ++++++++++++++++++++++++++++++++++++++++++--- 1 file changed, 51 insertions(+), 3 deletions(-) diff --git a/rclpy/rclpy/node.py b/rclpy/rclpy/node.py index cba822bbb..5ec69f667 100644 --- a/rclpy/rclpy/node.py +++ b/rclpy/rclpy/node.py @@ -98,6 +98,8 @@ from rclpy.validate_parameter_name import validate_parameter_name from rclpy.validate_topic_name import validate_topic_name from rclpy.waitable import Waitable +from typing_extensions import deprecated + HIDDEN_NODE_PREFIX = '_' @@ -371,11 +373,23 @@ def declare_parameter(self, name: str, value: Union[AllowableParameterValueT, ignore_override: bool = False ) -> Parameter[AllowableParameterValueT]: ... + @overload + @deprecated('when declaring a parameter only providing its name is deprecated. ' + 'You have to either:\n' + '\t- Pass a name and a default value different to "PARAMETER NOT SET"' + ' (and optionally a descriptor).\n' + '\t- Pass a name and a parameter type.\n' + '\t- Pass a name and a descriptor with `dynamic_typing=True') + def declare_parameter(self, name: str, + value: None = None, + descriptor: None = None, + ignore_override: bool = False) -> Parameter[Any]: ... + @overload def declare_parameter(self, name: str, value: Union[None, Parameter.Type, ParameterValue] = None, descriptor: Optional[ParameterDescriptor] = None, - ignore_override: bool = False) -> Parameter[None]: ... + ignore_override: bool = False) -> Parameter[Any]: ... def declare_parameter( self, @@ -383,7 +397,7 @@ def declare_parameter( value: Union[AllowableParameterValue, Parameter.Type, ParameterValue] = None, descriptor: Optional[ParameterDescriptor] = None, ignore_override: bool = False - ) -> Parameter: + ) -> Parameter[Any]: """ Declare and initialize a parameter. @@ -413,6 +427,13 @@ def declare_parameter( args = (name, value, descriptor) return self.declare_parameters('', [args], ignore_override)[0] + @overload + @deprecated('when declaring a parameter only providing its name is deprecated. ' + 'You have to either:\n' + '\t- Pass a name and a default value different to "PARAMETER NOT SET"' + ' (and optionally a descriptor).\n' + '\t- Pass a name and a parameter type.\n' + '\t- Pass a name and a descriptor with `dynamic_typing=True') def declare_parameters( self, namespace: str, @@ -423,7 +444,34 @@ def declare_parameters( ParameterDescriptor], ]], ignore_override: bool = False - ) -> List[Parameter]: + ) -> List[Parameter[Any]]: ... + + @overload + def declare_parameters( + self, + namespace: str, + parameters: List[Union[ + Tuple[str, Parameter.Type], + Tuple[str, Union[AllowableParameterValue, Parameter.Type, ParameterValue], + ParameterDescriptor], + ]], + ignore_override: bool = False + ) -> List[Parameter[Any]]: ... + + def declare_parameters( + self, + namespace: str, + parameters: Union[List[Union[ + Tuple[str], + Tuple[str, Parameter.Type], + Tuple[str, Union[AllowableParameterValue, Parameter.Type, ParameterValue], + ParameterDescriptor]]], + List[Union[ + Tuple[str, Parameter.Type], + Tuple[str, Union[AllowableParameterValue, Parameter.Type, ParameterValue], + ParameterDescriptor]]]], + ignore_override: bool = False + ) -> List[Parameter[Any]]: """ Declare a list of parameters.