From 38a408867719cb76c4b4f0b1caaf9cc191336970 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Wed, 19 May 2021 12:29:18 -0700 Subject: [PATCH] Allow declaring uninitialized parameters (#798) * Allow declaring uninitialized parameters Parameters can now be declared without a default value and without an override. Attempting to access a statically typed parameter that does not have value will raise an exception. Getting dynamically typed parameters will return an unset parameter value. This change is equivalent to that made in rclcpp: https://github.com/ros2/rclcpp/pull/1673 Signed-off-by: Jacob Perron * Fix flake8 Signed-off-by: Jacob Perron * Minor refactor Signed-off-by: Jacob Perron * Don't allow static parameters to be undeclared Signed-off-by: Jacob Perron * Return alternative for uninitialized parameters in get_parameter_or Signed-off-by: Jacob Perron * Ditto for dynamic parameters This is the same behavior as rclcpp. Signed-off-by: Jacob Perron * Fix lint Signed-off-by: Jacob Perron --- rclpy/rclpy/exceptions.py | 6 +++--- rclpy/rclpy/node.py | 45 ++++++++++++++++++++++++++++++--------- rclpy/test/test_node.py | 44 +++++++++++++++++++++++++++++++++++--- 3 files changed, 79 insertions(+), 16 deletions(-) diff --git a/rclpy/rclpy/exceptions.py b/rclpy/rclpy/exceptions.py index b47af556e..4dc1e881f 100644 --- a/rclpy/rclpy/exceptions.py +++ b/rclpy/rclpy/exceptions.py @@ -132,13 +132,13 @@ def __init__(self, parameter, *args): Exception.__init__(self, 'Attempted to modify read-only parameter', parameter, *args) -class NoParameterOverrideProvidedException(ParameterException): - """Raised when no override is provided for a statically typed parameter with no default.""" +class ParameterUninitializedException(ParameterException): + """Raised when an uninitialized parameter is accessed.""" def __init__(self, parameter_name, *args): Exception.__init__( self, - f"No parameter override provided for '{parameter_name}' when one was expected", + f"The parameter '{parameter_name}' is not initialized", *args) diff --git a/rclpy/rclpy/node.py b/rclpy/rclpy/node.py index 908311aac..83de95950 100644 --- a/rclpy/rclpy/node.py +++ b/rclpy/rclpy/node.py @@ -49,11 +49,11 @@ from rclpy.exceptions import InvalidParameterTypeException from rclpy.exceptions import InvalidParameterValueException from rclpy.exceptions import InvalidTopicNameException -from rclpy.exceptions import NoParameterOverrideProvidedException from rclpy.exceptions import NotInitializedException from rclpy.exceptions import ParameterAlreadyDeclaredException from rclpy.exceptions import ParameterImmutableException from rclpy.exceptions import ParameterNotDeclaredException +from rclpy.exceptions import ParameterUninitializedException from rclpy.executors import Executor from rclpy.expand_topic_name import expand_topic_name from rclpy.guard_condition import GuardCondition @@ -364,7 +364,6 @@ def declare_parameters( parameters: List[Union[ Tuple[str], Tuple[str, Parameter.Type], - Tuple[str, Any], Tuple[str, Any, ParameterDescriptor], ]], ignore_override: bool = False @@ -467,9 +466,6 @@ def declare_parameters( if not ignore_override and name in self._parameter_overrides: value = self._parameter_overrides[name].value - if value is None and not descriptor.dynamic_typing: - raise NoParameterOverrideProvidedException(name) - if namespace: name = f'{namespace}.{name}' @@ -493,7 +489,8 @@ def declare_parameters( raise_on_failure=True, allow_undeclared_parameters=True ) - return self.get_parameters([parameter.name for parameter in parameter_list]) + # Don't call get_parameters() to bypass check for NOT_SET parameters + return [self._parameters[parameter.name] for parameter in parameter_list] def undeclare_parameter(self, name: str): """ @@ -562,6 +559,8 @@ def get_parameters(self, names: List[str]) -> List[Parameter]: undeclared parameters are allowed. :raises: ParameterNotDeclaredException if undeclared parameters are not allowed, and at least one parameter hadn't been declared beforehand. + :raises: ParameterUninitializedException if at least one parameter is statically typed and + uninitialized. """ if not all(isinstance(name, str) for name in names): raise TypeError('All names must be instances of type str') @@ -577,9 +576,18 @@ def get_parameter(self, name: str) -> Parameter: undeclared parameters are allowed. :raises: ParameterNotDeclaredException if undeclared parameters are not allowed, and the parameter hadn't been declared beforehand. + :raises: ParameterUninitializedException if the parameter is statically typed and + uninitialized. """ if self.has_parameter(name): - return self._parameters[name] + parameter = self._parameters[name] + if ( + parameter.type_ != Parameter.Type.NOT_SET or + self._descriptors[name].dynamic_typing + ): + return self._parameters[name] + # Statically typed, uninitialized parameter + raise ParameterUninitializedException(name) elif self._allow_undeclared_parameters: return Parameter(name, Parameter.Type.NOT_SET, None) else: @@ -595,12 +603,20 @@ def get_parameter_or( :param name: Fully-qualified name of the parameter, including its namespace. :param alternative_value: Alternative parameter to get if it had not been declared before. - :return: Requested parameter, or alternative value if it hadn't been declared before. + :return: Requested parameter, or alternative value if it hadn't been declared before or is + an uninitialized statically typed parameter. """ if alternative_value is None: alternative_value = Parameter(name, Parameter.Type.NOT_SET) - return self._parameters.get(name, alternative_value) + if not self.has_parameter(name): + return alternative_value + + # Return alternative for uninitialized parameters + if (self._parameters[name].type_ == Parameter.Type.NOT_SET): + return alternative_value + + return self._parameters[name] def get_parameters_by_prefix(self, prefix: str) -> Dict[str, Optional[Union[ bool, int, float, str, bytes, @@ -941,7 +957,16 @@ def _apply_descriptor( if descriptor.dynamic_typing: descriptor.type = parameter.type_.value - elif descriptor.type != parameter.type_.value: + # If this parameter has already been declared, do not allow undeclaring it + elif self.has_parameter(parameter.name) and parameter.type_ == Parameter.Type.NOT_SET: + return SetParametersResult( + successful=False, + reason='Static parameter cannot be undeclared' + ) + elif ( + parameter.type_ != Parameter.Type.NOT_SET and + parameter.type_.value != descriptor.type + ): return SetParametersResult( successful=False, reason=( diff --git a/rclpy/test/test_node.py b/rclpy/test/test_node.py index 5ba2abfe1..81db2432f 100644 --- a/rclpy/test/test_node.py +++ b/rclpy/test/test_node.py @@ -36,10 +36,10 @@ from rclpy.exceptions import InvalidParameterValueException from rclpy.exceptions import InvalidServiceNameException from rclpy.exceptions import InvalidTopicNameException -from rclpy.exceptions import NoParameterOverrideProvidedException from rclpy.exceptions import ParameterAlreadyDeclaredException from rclpy.exceptions import ParameterImmutableException from rclpy.exceptions import ParameterNotDeclaredException +from rclpy.exceptions import ParameterUninitializedException from rclpy.executors import SingleThreadedExecutor from rclpy.parameter import Parameter from rclpy.qos import qos_profile_sensor_data @@ -631,8 +631,9 @@ def test_declare_parameters(self): ('value_not_set',) ] - with pytest.raises(NoParameterOverrideProvidedException): - self.node.declare_parameter('no_override', Parameter.Type.INTEGER) + # Declare uninitialized parameter + parameter_type = self.node.declare_parameter('no_override', Parameter.Type.INTEGER).type_ + assert parameter_type == Parameter.Type.NOT_SET with pytest.raises(InvalidParameterTypeException): self.node.declare_parameter('initial_decl_wrong_type', Parameter.Type.INTEGER) @@ -857,6 +858,22 @@ def test_node_get_undeclared_parameter_or(self): self.assertEqual(result.name, 'foo') self.assertEqual(result.value, 152) + def test_node_get_uninitialized_parameter_or(self): + # Statically typed parameter + self.node.declare_parameter('uninitialized_foo', Parameter.Type.INTEGER) + result = self.node.get_parameter_or( + 'uninitialized_foo', Parameter('foo', Parameter.Type.INTEGER, 152)) + self.assertEqual(result.name, 'foo') + self.assertEqual(result.value, 152) + + # Dynamically typed parameter + self.node.declare_parameter( + 'uninitialized_bar', None, ParameterDescriptor(dynamic_typing=True)) + result = self.node.get_parameter_or( + 'uninitialized_bar', Parameter('foo', Parameter.Type.INTEGER, 153)) + self.assertEqual(result.name, 'foo') + self.assertEqual(result.value, 153) + def test_node_get_parameters_by_prefix(self): parameters = [ ('foo_prefix.foo', 43), @@ -1833,16 +1850,37 @@ def test_integer_range_descriptor(self): def test_static_dynamic_typing(self): parameters = [ ('int_param', 0), + ('int_param_no_default', Parameter.Type.INTEGER), ('dynamic_param', None, ParameterDescriptor(dynamic_typing=True)), ] result = self.node.declare_parameters('', parameters) + # Try getting parameters before setting values + int_param = self.node.get_parameter('int_param') + self.assertEqual(int_param.type_, Parameter.Type.INTEGER) + self.assertEqual(int_param.value, 0) + with pytest.raises(ParameterUninitializedException): + self.node.get_parameter('int_param_no_default') + self.assertEqual(self.node.get_parameter('dynamic_param').type_, Parameter.Type.NOT_SET) + result = self.node.set_parameters([Parameter('int_param', value='asd')])[0] self.assertFalse(result.successful) self.assertTrue(result.reason.startswith('Wrong parameter type')) self.assertTrue(self.node.set_parameters([Parameter('int_param', value=3)])[0].successful) + result = self.node.set_parameters([Parameter('int_param_no_default', value='asd')])[0] + self.assertFalse(result.successful) + self.assertTrue(result.reason.startswith('Wrong parameter type')) + + self.assertTrue( + self.node.set_parameters([Parameter('int_param_no_default', value=3)])[0].successful) + self.assertEqual(self.node.get_parameter('int_param_no_default').value, 3) + + result = self.node.set_parameters([Parameter('int_param_no_default', value=None)])[0] + self.assertFalse(result.successful) + self.assertTrue(result.reason.startswith('Static parameter cannot be undeclared')) + self.assertTrue( self.node.set_parameters([Parameter('dynamic_param', value='asd')])[0].successful) self.assertTrue(