Skip to content

Commit

Permalink
Use @deprecated to mark deprecated APIs for type checkers. (#1350)
Browse files Browse the repository at this point in the history
* use @deprecated

Signed-off-by: Michael Carlstrom <[email protected]>

* move typing_extensions

Signed-off-by: Michael Carlstrom <[email protected]>

* Add deprecated to declare_parameters

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>
  • Loading branch information
InvincibleRMC and mergify[bot] authored Nov 1, 2024
1 parent 5ab016b commit 53d7760
Show file tree
Hide file tree
Showing 8 changed files with 64 additions and 27 deletions.
1 change: 1 addition & 0 deletions rclpy/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@
<exec_depend>action_msgs</exec_depend>
<exec_depend>ament_index_python</exec_depend>
<exec_depend>builtin_interfaces</exec_depend>
<exec_depend>python3-typing-extensions</exec_depend>
<exec_depend>python3-yaml</exec_depend>
<exec_depend>rosgraph_msgs</exec_depend>
<exec_depend>rpyutils</exec_depend>
Expand Down
7 changes: 2 additions & 5 deletions rclpy/rclpy/clock.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand Down Expand Up @@ -90,7 +87,7 @@ class TimeJumpDictionary(TypedDict):
delta: int


JumpHandlePreCallbackType: 'TypeAlias' = Callable[[], None]
JumpHandlePreCallbackType: TypeAlias = Callable[[], None]


class JumpHandle:
Expand Down
10 changes: 5 additions & 5 deletions rclpy/rclpy/event_handler.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand Down Expand Up @@ -75,7 +73,7 @@
UnsupportedEventTypeError = _rclpy.UnsupportedEventTypeError


EventHandlerData: 'TypeAlias' = Optional[Any]
EventHandlerData: TypeAlias = Optional[Any]


class EventHandler(Waitable[EventHandlerData]):
Expand Down Expand Up @@ -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):
Expand Down
10 changes: 2 additions & 8 deletions rclpy/rclpy/impl/rcutils_logger.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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']
Expand Down Expand Up @@ -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:.
Expand Down
50 changes: 49 additions & 1 deletion rclpy/rclpy/node.py
Original file line number Diff line number Diff line change
Expand Up @@ -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 = '_'

Expand Down Expand Up @@ -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,
Expand Down Expand Up @@ -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,
Expand All @@ -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.
Expand Down
8 changes: 3 additions & 5 deletions rclpy/rclpy/qos.py
Original file line number Diff line number Diff line change
Expand Up @@ -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):
Expand Down Expand Up @@ -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,
Expand Down
4 changes: 2 additions & 2 deletions rclpy/rclpy/qos_overriding_options.py
Original file line number Diff line number Diff line change
Expand Up @@ -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


Expand All @@ -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]

Expand Down
1 change: 0 additions & 1 deletion rclpy/rclpy/waitable.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@

T = TypeVar('T')


if TYPE_CHECKING:
from typing_extensions import Self

Expand Down

0 comments on commit 53d7760

Please sign in to comment.