diff --git a/rclpy/package.xml b/rclpy/package.xml
index fecb1e1f1..1263309d9 100644
--- a/rclpy/package.xml
+++ b/rclpy/package.xml
@@ -37,6 +37,7 @@
action_msgs
ament_index_python
builtin_interfaces
+ python3-typing-extensions
python3-yaml
rosgraph_msgs
rpyutils
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 e846b9135..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
@@ -27,9 +26,8 @@
from rclpy.qos import qos_policy_name_from_kind
from rclpy.waitable import NumberOfEntities
from rclpy.waitable import Waitable
-
-if TYPE_CHECKING:
- from typing import TypeAlias
+from typing_extensions import deprecated
+from typing_extensions import TypeAlias
QoSPublisherEventType = _rclpy.rcl_publisher_event_type_t
@@ -75,7 +73,7 @@
UnsupportedEventTypeError = _rclpy.UnsupportedEventTypeError
-EventHandlerData: 'TypeAlias' = Optional[Any]
+EventHandlerData: TypeAlias = Optional[Any]
class EventHandler(Waitable[EventHandlerData]):
@@ -144,6 +142,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:.
diff --git a/rclpy/rclpy/node.py b/rclpy/rclpy/node.py
index 8da2faafc..87128694b 100644
--- a/rclpy/rclpy/node.py
+++ b/rclpy/rclpy/node.py
@@ -99,6 +99,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 = '_'
@@ -375,11 +377,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,
@@ -417,6 +431,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,
@@ -427,6 +448,33 @@ def declare_parameters(
ParameterDescriptor],
]],
ignore_override: bool = False
+ ) -> 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.
diff --git a/rclpy/rclpy/qos.py b/rclpy/rclpy/qos.py
index ceb6d2314..4c9dc0745 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,
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):
@@ -516,7 +514,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..6e622bccb 100644
--- a/rclpy/rclpy/waitable.py
+++ b/rclpy/rclpy/waitable.py
@@ -20,7 +20,6 @@
T = TypeVar('T')
-
if TYPE_CHECKING:
from typing_extensions import Self