diff --git a/rclpy/rclpy/node.py b/rclpy/rclpy/node.py index a460833b3..bd43f75a4 100644 --- a/rclpy/rclpy/node.py +++ b/rclpy/rclpy/node.py @@ -21,7 +21,6 @@ from typing import List from typing import Optional from typing import overload -from typing import Sequence from typing import Tuple from typing import Type from typing import TypeVar @@ -164,7 +163,7 @@ def __init__( """ self.__handle = None self._context = get_default_context() if context is None else context - self._parameters: dict = {} + self._parameters: Dict[str, Parameter] = {} self._publishers: List[Publisher] = [] self._subscriptions: List[Subscription] = [] self._clients: List[Client] = [] @@ -179,8 +178,8 @@ def __init__( self._post_set_parameters_callbacks: List[Callable[[List[Parameter]], None]] = [] self._rate_group = ReentrantCallbackGroup() self._allow_undeclared_parameters = allow_undeclared_parameters - self._parameter_overrides: Dict[str, Parameter] = {} - self._descriptors = {} + self._parameter_overrides: Dict[str, Parameter[AllowableParameterValue]] = {} + self._descriptors: Dict[str, ParameterDescriptor] = {} namespace = namespace or '' if not self._context.ok(): @@ -357,12 +356,14 @@ def get_logger(self): return self._logger @overload - def declare_parameter(self, name: str, value: None = None, + def declare_parameter(self, name: str, + value: Union[None, Parameter.Type, ParameterValue] = None, descriptor: Optional[ParameterDescriptor] = None, ignore_override: bool = False) -> Parameter[None]: ... @overload - def declare_parameter(self, name: str, value: AllowableParameterValueT, + def declare_parameter(self, name: str, value: Union[AllowableParameterValueT, + Parameter.Type, ParameterValue], descriptor: Optional[ParameterDescriptor] = None, ignore_override: bool = False ) -> Parameter[AllowableParameterValueT]: ... @@ -370,7 +371,7 @@ def declare_parameter(self, name: str, value: AllowableParameterValueT, def declare_parameter( self, name: str, - value: AllowableParameterValue = None, + value: Union[AllowableParameterValue, Parameter.Type, ParameterValue] = None, descriptor: Optional[ParameterDescriptor] = None, ignore_override: bool = False ) -> Parameter: @@ -395,7 +396,8 @@ def declare_parameter( """ if value is None and descriptor is None: # Temporal patch so we get deprecation warning if only a name is provided. - args: Union[Tuple[str], Tuple[str, AllowableParameterValue, + args: Union[Tuple[str], Tuple[str, Union[AllowableParameterValue, + Parameter.Type, ParameterValue], ParameterDescriptor]] = (name, ) else: descriptor = ParameterDescriptor() if descriptor is None else descriptor @@ -408,7 +410,8 @@ def declare_parameters( parameters: List[Union[ Tuple[str], Tuple[str, Parameter.Type], - Tuple[str, AllowableParameterValue, ParameterDescriptor], + Tuple[str, Union[AllowableParameterValue, Parameter.Type, ParameterValue], + ParameterDescriptor], ]], ignore_override: bool = False ) -> List[Parameter]: @@ -483,9 +486,8 @@ def declare_parameters( # Note(jubeira): declare_parameters verifies the name, but set_parameters doesn't. validate_parameter_name(name) - second_arg = parameter_tuple[1] if 1 < len(parameter_tuple) else None - descriptor = parameter_tuple[2] if 2 < len(parameter_tuple) else ParameterDescriptor() - + second_arg = parameter_tuple[1] if len(parameter_tuple) > 1 else None + descriptor = parameter_tuple[2] if len(parameter_tuple) > 2 else ParameterDescriptor() if not isinstance(descriptor, ParameterDescriptor): raise TypeError( f'Third element {descriptor} at index {index} in parameters list ' @@ -529,6 +531,10 @@ def declare_parameters( if not ignore_override and name in self._parameter_overrides: value = self._parameter_overrides[name].value + if isinstance(value, ParameterValue): + raise ValueError('Cannot declare a Parameter from a ParameterValue without it' + 'being included _parameter_overrides, and ignore_override=False') + parameter_list.append(Parameter(name, value=value)) descriptors.update({name: descriptor}) @@ -729,10 +735,7 @@ def get_parameter_or( return self._parameters[name] - def get_parameters_by_prefix(self, prefix: str) -> Dict[str, Optional[Union[ - bool, int, float, str, bytes, - Sequence[bool], Sequence[int], Sequence[float], Sequence[str] - ]]]: + def get_parameters_by_prefix(self, prefix: str) -> Dict[str, Parameter]: """ Get parameters that have a given prefix in their names as a dictionary. @@ -1049,7 +1052,7 @@ def _check_undeclared_parameters(self, parameter_list: List[Parameter]): if not self._allow_undeclared_parameters and any(undeclared_parameters): raise ParameterNotDeclaredException(list(undeclared_parameters)) - def _call_pre_set_parameters_callback(self, parameter_list: [List[Parameter]]): + def _call_pre_set_parameters_callback(self, parameter_list: List[Parameter]): if self._pre_set_parameters_callbacks: modified_parameter_list = [] for callback in self._pre_set_parameters_callbacks: @@ -1059,7 +1062,7 @@ def _call_pre_set_parameters_callback(self, parameter_list: [List[Parameter]]): else: return None - def _call_post_set_parameters_callback(self, parameter_list: [List[Parameter]]): + def _call_post_set_parameters_callback(self, parameter_list: List[Parameter]): if self._post_set_parameters_callbacks: for callback in self._post_set_parameters_callbacks: callback(parameter_list) diff --git a/rclpy/rclpy/parameter.py b/rclpy/rclpy/parameter.py index ae4ca23c2..a741f2bb5 100644 --- a/rclpy/rclpy/parameter.py +++ b/rclpy/rclpy/parameter.py @@ -12,8 +12,8 @@ # See the License for the specific language governing permissions and # limitations under the License. -import sys import array +import sys from enum import IntEnum from typing import Dict from typing import Generic @@ -41,7 +41,8 @@ list[float], Tuple[float, ...], array.array[float], list[str], Tuple[str, ...], array.array[str]] AllowableParameterValueT = TypeVar('AllowableParameterValueT', None, bool, int, float, str, - list[bytes], Tuple[bytes, ...], List[bool], Tuple[bool, ...], + list[bytes], Tuple[bytes, ...], list[bool], + Tuple[bool, ...], list[int], Tuple[int, ...], array.array[int], list[float], Tuple[float, ...], array.array[float], list[str], Tuple[str, ...], array.array[str]) @@ -54,10 +55,11 @@ List[str], Tuple[str, ...], 'array.array[str]'] AllowableParameterValueT = TypeVar('AllowableParameterValueT', None, bool, int, float, str, - List[bytes], Tuple[bytes, ...], List[bool], Tuple[bool, ...], - List[int], Tuple[int, ...], 'array.array[int]', - List[float], Tuple[float, ...], 'array.array[float]', - List[str], Tuple[str, ...], 'array.array[str]') + List[bytes], Tuple[bytes, ...], List[bool], + Tuple[bool, ...], List[int], Tuple[int, ...], + 'array.array[int]', List[float], Tuple[float, ...], + 'array.array[float]', List[str], Tuple[str, ...], + 'array.array[str]') class Parameter(Generic[AllowableParameterValueT]):