diff --git a/rclpy/rclpy/__init__.py b/rclpy/rclpy/__init__.py index 18e67a46f..95511cf3f 100644 --- a/rclpy/rclpy/__init__.py +++ b/rclpy/rclpy/__init__.py @@ -111,7 +111,8 @@ def create_node( namespace: str = None, use_global_arguments: bool = True, start_parameter_services: bool = True, - initial_parameters: List[Parameter] = None + initial_parameters: List[Parameter] = None, + allow_undeclared_parameters: bool = False ) -> 'Node': """ Create an instance of :class:`.Node`. @@ -126,6 +127,7 @@ def create_node( arguments. :param start_parameter_services: ``False`` if the node should not create parameter services. :param initial_parameters: A list of :class:`.Parameter` to be set during node creation. + :param allow_undeclared_parameters: True if undeclared parameters are allowed, False otherwise. :return: An instance of the newly created node. """ # imported locally to avoid loading extensions on module import @@ -134,7 +136,8 @@ def create_node( node_name, context=context, cli_args=cli_args, namespace=namespace, use_global_arguments=use_global_arguments, start_parameter_services=start_parameter_services, - initial_parameters=initial_parameters) + initial_parameters=initial_parameters, + allow_undeclared_parameters=allow_undeclared_parameters) def spin_once(node: 'Node', *, executor: 'Executor' = None, timeout_sec: float = None) -> None: diff --git a/rclpy/rclpy/exceptions.py b/rclpy/rclpy/exceptions.py index 807f47247..70d89c3ac 100644 --- a/rclpy/rclpy/exceptions.py +++ b/rclpy/rclpy/exceptions.py @@ -65,3 +65,39 @@ class InvalidServiceNameException(NameValidationException): def __init__(self, name, error_msg, invalid_index, *args): NameValidationException.__init__(self, 'service name', name, error_msg, invalid_index) + + +# TODO(jubeira): Polish parameter-related exceptions; improve error messages. +class ParameterNotDeclaredException(Exception): + """Raised when handling an undeclared parameter when it is not allowed.""" + + def __init__(self, *args): + Exception.__init__(self, 'Invalid access to undeclared parameter', *args) + + +class ParameterAlreadyDeclaredException(Exception): + """Raised when declaring a parameter that had been declared before.""" + + def __init__(self, *args): + Exception.__init__(self, 'Parameter already declared.', *args) + + +class InvalidParameterException(Exception): + """Raised when a parameter to be declared has an invalid name.""" + + def __init__(self, *args): + Exception.__init__(self, 'Invalid parameter name.', *args) + + +class InvalidParameterValueException(Exception): + """Raised when a parameter to be declared is rejected by a callback.""" + + def __init__(self, *args): + Exception.__init__(self, 'Invalid parameter value.', *args) + + +class ParameterImmutableException(Exception): + """Raised when a read-only parameter is modified.""" + + def __init__(self, *args): + Exception.__init__(self, 'Attempted to modify an read-only parameter.', *args) diff --git a/rclpy/rclpy/node.py b/rclpy/rclpy/node.py index 3212accb5..128842814 100644 --- a/rclpy/rclpy/node.py +++ b/rclpy/rclpy/node.py @@ -20,6 +20,8 @@ import weakref +# TODO(jubeira): check for missing imports. +from rcl_interfaces.msg import ParameterDescriptor from rcl_interfaces.msg import ParameterEvent from rcl_interfaces.msg import SetParametersResult from rclpy.callback_groups import CallbackGroup @@ -29,7 +31,11 @@ from rclpy.clock import ROSClock from rclpy.constants import S_TO_NS from rclpy.context import Context +from rclpy.exceptions import InvalidParameterValueException from rclpy.exceptions import NotInitializedException +from rclpy.exceptions import ParameterAlreadyDeclaredException +from rclpy.exceptions import ParameterImmutableException +from rclpy.exceptions import ParameterNotDeclaredException from rclpy.executors import Executor from rclpy.expand_topic_name import expand_topic_name from rclpy.guard_condition import GuardCondition @@ -52,6 +58,7 @@ from rclpy.validate_full_topic_name import validate_full_topic_name from rclpy.validate_namespace import validate_namespace from rclpy.validate_node_name import validate_node_name +from rclpy.validate_parameter_name import validate_parameter_name from rclpy.validate_topic_name import validate_topic_name from rclpy.waitable import Waitable @@ -81,7 +88,8 @@ def __init__( namespace: str = None, use_global_arguments: bool = True, start_parameter_services: bool = True, - initial_parameters: List[Parameter] = None + initial_parameters: List[Parameter] = None, + allow_undeclared_parameters: bool = False ) -> None: """ Constructor. @@ -97,6 +105,8 @@ def __init__( :param start_parameter_services: ``False`` if the node should not create parameter services. :param initial_parameters: A list of parameters to be set during node creation. + :param allow_undeclared_parameters: True if undeclared parameters are allowed. + This flag affects the behavior of parameter-related operations. """ self._handle = None self._context = get_default_context() if context is None else context @@ -110,6 +120,7 @@ def __init__( self.waitables: List[Waitable] = [] self._default_callback_group = MutuallyExclusiveCallbackGroup() self._parameters_callback = None + self._allow_undeclared_parameters = allow_undeclared_parameters namespace = namespace or '' if not self._context.ok(): @@ -145,6 +156,8 @@ def __init__( # use the set_parameters_atomically API so a parameter event is published. if initial_parameters is not None: node_parameters.update({p.name: p for p in initial_parameters}) + + self.declare_parameters('/', node_parameters.values()) self.set_parameters_atomically(node_parameters.values()) if start_parameter_services: @@ -193,7 +206,7 @@ def handle(self): Cannot be modified after node creation. - :raises AttributeError: if modified after creation. + :raises: AttributeError if modified after creation. """ return self._handle @@ -217,12 +230,82 @@ def get_logger(self): """Get the nodes logger.""" return self._logger + def declare_parameter(self, parameter: Parameter) -> Parameter: + """ + Declare and initialize a parameter. + + This method, if successful, will result in any callback registered with + :func:`set_parameters_callback` to be called. + + :param parameter: The parameter to declare, with a name, value and descriptor. + :return: Parameter with the effectively assigned value. + :raises: ParameterAlreadyDeclaredException if the parameter had already been declared. + :raises: InvalidParameterException if the parameter name is invalid. + :raises: InvalidParameterValueException if the registered callback rejects the parameter. + """ + return self.declare_parameters('/', [parameter]) + + def declare_parameters(self, namespace: str, parameters: List[Parameter]) -> List[Parameter]: + """ + Declare a list of parameters. + + This method, if successful, will result in any callback registered with + :func:`set_parameters_callback` to be called once for each parameter. + If one of those calls fail, an exception will be raised and the remaining parameters will + not be declared. Parameters declared up to that point will not be undeclared. + + :param namespace: Namespace for parameters. + :param parameters: The parameters to declare, with a name, value and descriptor. + :return: Parameter list with the effectively assigned values for each of them. + :raises: ParameterAlreadyDeclaredException if the parameter had already been declared. + :raises: InvalidParameterException if the parameter name is invalid. + :raises: InvalidParameterValueException if the registered callback rejects the parameter. + """ + for parameter in parameters: + parameter.name = namespace + parameter.name + # Note(jubeira): declare_parameters verifies the name, but set_parameters doesn't. + validate_parameter_name(parameter.name) + + if any(parameter.name in self._parameters for parameter in parameters): + raise ParameterAlreadyDeclaredException() + + # Call the callback once for each of the parameters, using method that doesn't + # check whether the parameter was declared beforehand or not. + self._set_parameters(parameters, raise_on_failure=True) + return self.get_parameters([parameter.name for parameter in parameters]) + + def undeclare_parameter(self, name: str): + """ + Undeclare a previously declared parameter. + + This method will not cause a callback registered with + :func:`set_parameters_callback` to be called. + + :param name: name of the parameter. + :raises: ParameterNotDeclaredException if parameter had not been declared before. + :raises: ParameterImmutableException if the parameter was created as read-only. + """ + if self.has_parameter(name): + if self._parameters[name].descriptor.read_only: + raise ParameterImmutableException() + else: + del self._parameters[name] + else: + raise ParameterNotDeclaredException() + + def has_parameter(self, name: str) -> bool: + """Return True if parameter is declared; False otherwise.""" + return name in self._parameters + def get_parameters(self, names: List[str]) -> List[Parameter]: """ Get a list of parameters. :param names: The names of the parameters to get. - :return: The values for the given parameter names. + :return: The values for the given parameter names. A default Parameter will be returned + for undeclared parameters if undeclared parameters are allowed. + :raises: ParameterNotDeclaredException if undeclared paramers are not allowed, and at least + one parameter hadn't been declared beforehand. """ if not all(isinstance(name, str) for name in names): raise TypeError('All names must be instances of type str') @@ -233,41 +316,163 @@ def get_parameter(self, name: str) -> Parameter: Get a parameter by name. :param name: The name of the parameter. - :return: The value of the parameter. + :return: The values for the given parameter names. A default Parameter will be returned + for an undeclared parameter if undeclared parameters are allowed. + :raises: ParameterNotDeclaredException if undeclared paramers are not allowed, and the + parameter hadn't been declared beforehand. """ - if name not in self._parameters: + if self.has_parameter(name): + return self._parameters[name] + elif self._allow_undeclared_parameters: return Parameter(name, Parameter.Type.NOT_SET, None) - return self._parameters[name] + else: + raise ParameterNotDeclaredException() + + def get_parameter_or(self, name: str, alternative_value: Parameter = None) -> Parameter: + """ + Get a parameter or the alternative value. + + If the alternative value is None, a default Parameter with the given name and NOT_SET + type will be returned. + This method does not declare parameters in any case. + + :param name: Name of the parameter to get. + :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. + """ + if alternative_value is None: + alternative_value = Parameter(name, Parameter.Type.NOT_SET) + + return self._parameters.get(name, alternative_value) def set_parameters(self, parameter_list: List[Parameter]) -> List[SetParametersResult]: """ - Set parameters for the node. + Set parameters for the node, and return the result for the set action. + + If any parameter in the list was not declared beforehand and undeclared parameters are not + allowed for the node, this method will raise a ParameterNotDeclaredException exception. + + Parameters are set in the order they are declared in the list. + If setting a parameter fails due to not being declared, then the + parameters which have already been set will stay set, and no attempt will + be made to set the parameters which come after. + + If undeclared parameters are allowed, then all the parameters will be implicitly + declared before being set even if they were not declared beforehand. If a callback was registered previously with :func:`set_parameters_callback`, it will be - called prior to setting the parameters for the node. + called prior to setting the parameters for the node once for each parameter. + If the callback prevents a parameter from being set, then it will be reflected in the + returned result; no exceptions will be raised in this case. For each successfully set parameter, a :class:`ParameterEvent` message is published. + If the value type of the parameter is NOT_SET, and the existing parameter type is + something else, then the parameter will be implicitly undeclared. + :param parameter_list: The list of parameters to set. - :return: A list of SetParametersResult messages. + :return: The result for each set action as a list. + :raises: ParameterNotDeclaredException if undeclared paramers are not allowed, and at least + one parameter in the list hadn't been declared beforehand. """ + return self._set_parameters(parameter_list, self.set_parameters_atomically) + + def _set_parameters( + self, + parameter_list: List[Parameter], + setter_func=None, + raise_on_failure=False + ) -> List[SetParametersResult]: + """ + Set parameters for the node, and return the result for the set action. + + Method for internal usage; applies a setter method for each parameters in the list. + By default it doesn't check if the parameters were declared, and both declares and sets + the given list. + + If a callback was registered previously with :func:`set_parameters_callback`, it will be + called prior to setting the parameters for the node once for each parameter. + If the callback doesn't succeed for a given parameter, it won't be set and either an + unsuccessful result will be returned for that parameter, or an exception will be raised + according to `raise_on_failure` flag. + + :param parameter_list: List of parameters to set. + :param setter_func: Method to set the parameters. Use :func:`_set_parameters_atomically` + to declare and set the parameters without checking if they had been declared, + or :func:`set_parameters_atomically` to check if they had been declared beforehand. + :return: The result for each set action as a list. + :raises: InvalidParameterValueException if the user-defined callback rejects the + parameter value and raise_on_failure flag is True. + """ + if setter_func is None: + setter_func = self._set_parameters_atomically + results = [] for param in parameter_list: - if not isinstance(param, Parameter): - raise TypeError("parameter must be instance of type '{}'".format(repr(Parameter))) - results.append(self.set_parameters_atomically([param])) + result = setter_func([param]) + if raise_on_failure and not result.successful: + raise InvalidParameterValueException() + results.append(result) return results def set_parameters_atomically(self, parameter_list: List[Parameter]) -> SetParametersResult: """ - Atomically set parameters for the node. + Set the given parameters, all at one time, and then aggregate result. + + If any parameter in the list was not declared beforehand and undeclared parameters are not + allowed for the node, this method will raise a ParameterNotDeclaredException exception. + + Parameters are set all at once. If setting a parameter fails due to not being declared, + then no parameter will be set set. Either all of the parameters are set or none of them + are set. + + If undeclared parameters are allowed, then all the parameters will be implicitly + declared before being set even if they were not declared beforehand. If a callback was registered previously with :func:`set_parameters_callback`, it will be - called prior to setting the parameters for the node. - If the parameters are set successfully, a :class:`ParameterEvent` message is + called prior to setting the parameters for the node only once for all parameters. + If the callback prevents the parameters from being set, then it will be reflected in the + returned result; no exceptions will be raised in this case. + For each successfully set parameter, a :class:`ParameterEvent` message is published. + If the value type of the parameter is NOT_SET, and the existing parameter type is + something else, then the parameter will be implicitly undeclared. + :param parameter_list: The list of parameters to set. + :return: Aggregate result of setting all the parameters atomically. + :raises: ParameterNotDeclaredException if undeclared paramers are not allowed, and at least + one parameter in the list hadn't been declared beforehand. + """ + if not all(isinstance(parameter, Parameter) for parameter in parameter_list): + raise TypeError("parameter must be instance of type '{}'".format(repr(Parameter))) + + # TODO(jubeira): add meaningful message to exception. + if (not self._allow_undeclared_parameters and + not all(parameter.name in self._parameters for parameter in parameter_list)): + raise ParameterNotDeclaredException() + + return self._set_parameters_atomically(parameter_list) + + def _set_parameters_atomically(self, parameter_list: List[Parameter]) -> SetParametersResult: + """ + Set the given parameters, all at one time, and then aggregate result. + + This method does not check if the parameters were declared beforehand, and is intended + for internal use of this class. + + If a callback was registered previously with :func:`set_parameters_callback`, it will be + called prior to setting the parameters for the node only once for all parameters. + If the callback prevents the parameters from being set, then it will be reflected in the + returned result; no exceptions will be raised in this case. + For each successfully set parameter, a :class:`ParameterEvent` message is + published. + + If the value type of the parameter is NOT_SET, and the existing parameter type is + something else, then the parameter will be implicitly undeclared. + + :param parameter_list: The list of parameters to set. + :return: Aggregate result of setting all the parameters atomically. """ result = None if self._parameters_callback: @@ -284,7 +489,7 @@ def set_parameters_atomically(self, parameter_list: List[Parameter]) -> SetParam parameter_event.node = self.get_namespace() + '/' + self.get_name() for param in parameter_list: if Parameter.Type.NOT_SET == param.type_: - if Parameter.Type.NOT_SET != self.get_parameter(param.name).type_: + if Parameter.Type.NOT_SET != self.get_parameter_or(param.name).type_: # Parameter deleted. (Parameter had value and new value is not set) parameter_event.deleted_parameters.append( param.to_parameter_msg()) @@ -293,7 +498,7 @@ def set_parameters_atomically(self, parameter_list: List[Parameter]) -> SetParam if param.name in self._parameters: del self._parameters[param.name] else: - if Parameter.Type.NOT_SET == self.get_parameter(param.name).type_: + if Parameter.Type.NOT_SET == self.get_parameter_or(param.name).type_: # Parameter is new. (Parameter had no value and new value is set) parameter_event.new_parameters.append(param.to_parameter_msg()) else: @@ -306,6 +511,42 @@ def set_parameters_atomically(self, parameter_list: List[Parameter]) -> SetParam return result + def describe_parameter(self, name: str) -> ParameterDescriptor: + """ + Get the parameter descriptor of a given parameter. + + :param name: Name of the parameter to describe. + :return: ParameterDescriptor corresponding to the parameter, + or default ParameterDescriptor if parameter had not been declared before + and undeclared parameters are allowed. + :raises: ParameterNotDeclaredException if parameter had not been declared before + and undeclared parameters are not allowed. + """ + try: + return self._parameters[name].descriptor + except KeyError: + if self._allow_undeclared_parameters: + return ParameterDescriptor() + else: + raise ParameterNotDeclaredException() + + def describe_parameters(self, names: List[str]) -> List[ParameterDescriptor]: + """ + Get the parameter descriptors of a given list of parameters. + + :param name: List of names of the parameters to describe. + :return: List of ParameterDescriptors corresponding to the given parameters. + Default ParameterDescriptors shall be returned for parameters that + had not been declared before if undeclared parameters are allowed. + :raises: ParameterNotDeclaredException if at least one parameter + had not been declared before and undeclared parameters are not allowed. + """ + parameter_descriptors = [] + for name in names: + parameter_descriptors.append(self.describe_parameter(name)) + + return parameter_descriptors + def set_parameters_callback( self, callback: Callable[[List[Parameter]], SetParametersResult] diff --git a/rclpy/rclpy/parameter.py b/rclpy/rclpy/parameter.py index 9cab972f7..35c4a1709 100644 --- a/rclpy/rclpy/parameter.py +++ b/rclpy/rclpy/parameter.py @@ -86,7 +86,14 @@ def from_parameter_msg(cls, param_msg): value = param_msg.value.string_array_value return cls(param_msg.name, type_, value) - def __init__(self, name, type_, value=None): + def __init__(self, name, type_, value=None, descriptor=ParameterDescriptor()): + """ + Constructor. + + The name and type in the given rcl_interfaces.msg.ParameterDescriptor + are ignored, and should be specified using the named arguments to this + function. + """ if not isinstance(type_, Parameter.Type): raise TypeError("type must be an instance of '{}'".format(repr(Parameter.Type))) @@ -96,6 +103,9 @@ def __init__(self, name, type_, value=None): self._type_ = type_ self._name = name self._value = value + descriptor.name = name + descriptor.type = type_.value + self._descriptor = descriptor @property def name(self): @@ -109,8 +119,9 @@ def type_(self): def value(self): return self._value - def get_descriptor(self): - return ParameterDescriptor(name=self.name, type=self.type_.value) + @property + def descriptor(self): + return self._descriptor def get_parameter_value(self): parameter_value = ParameterValue(type=self.type_.value) diff --git a/rclpy/rclpy/parameter_service.py b/rclpy/rclpy/parameter_service.py index 4a3b03a00..40ea69630 100644 --- a/rclpy/rclpy/parameter_service.py +++ b/rclpy/rclpy/parameter_service.py @@ -62,19 +62,19 @@ def __init__(self, node): def _describe_parameters_callback(self, request, response): for name in request.names: - p = self._node.get_parameter(name) - response.descriptors.append(p.get_descriptor()) + p = self._node.get_parameter_or(name) + response.descriptors.append(p.descriptor) return response def _get_parameters_callback(self, request, response): for name in request.names: - p = self._node.get_parameter(name) + p = self._node.get_parameter_or(name) response.values.append(p.get_parameter_value()) return response def _get_parameter_types_callback(self, request, response): for name in request.names: - response.types.append(self._node.get_parameter(name).get_parameter_type()) + response.types.append(self._node.get_parameter_or(name).type_) return response def _list_parameters_callback(self, request, response): diff --git a/rclpy/rclpy/time_source.py b/rclpy/rclpy/time_source.py index dccec253d..f3b6a499a 100644 --- a/rclpy/rclpy/time_source.py +++ b/rclpy/rclpy/time_source.py @@ -69,7 +69,7 @@ def attach_node(self, node): self.detach_node() self._node = node - use_sim_time_param = node.get_parameter('use_sim_time') + use_sim_time_param = node.get_parameter_or('use_sim_time') if use_sim_time_param.type_ != Parameter.Type.NOT_SET: if use_sim_time_param.type_ == Parameter.Type.BOOL: self.ros_time_is_active = use_sim_time_param.value diff --git a/rclpy/rclpy/validate_parameter_name.py b/rclpy/rclpy/validate_parameter_name.py new file mode 100644 index 000000000..5637accf1 --- /dev/null +++ b/rclpy/rclpy/validate_parameter_name.py @@ -0,0 +1,39 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from rclpy.exceptions import InvalidParameterException +from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy + + +def validate_parameter_name(name): + """ + Validate a given parameter name, and raise an exception if invalid. + + The name does not have to be fully-qualified and is not expanded. + + If the name is invalid then rclpy.exceptions.InvalidParameterNameException + will be raised. + + :param name str: topic or service name to be validated + :param is_service bool: if true, InvalidServiceNameException is raised + :returns: True when it is valid + :raises: InvalidParameterNameException: when the name is invalid + """ + # TODO(jubeira): define whether this is an appropriate method to validate + # parameter names. + result = _rclpy.rclpy_get_validation_error_for_topic_name(name) + if result is None: + return True + error_msg, invalid_index = result + raise InvalidParameterException(name, error_msg, invalid_index) diff --git a/rclpy/test/test_create_node.py b/rclpy/test/test_create_node.py index 3ec3c555e..e5076ec43 100644 --- a/rclpy/test/test_create_node.py +++ b/rclpy/test/test_create_node.py @@ -43,7 +43,8 @@ def test_create_node_with_namespace(self): def test_create_node_with_empty_namespace(self): node_name = 'create_node_test' namespace = '' - node = rclpy.create_node(node_name, namespace=namespace, context=self.context) + node = rclpy.create_node( + node_name, namespace=namespace, context=self.context) self.assertEqual('/', node.get_namespace()) node.destroy_node() diff --git a/rclpy/test/test_node.py b/rclpy/test/test_node.py index 4b62aa763..082cf484e 100644 --- a/rclpy/test/test_node.py +++ b/rclpy/test/test_node.py @@ -35,7 +35,9 @@ class TestNode(unittest.TestCase): def setUpClass(cls): cls.context = rclpy.context.Context() rclpy.init(context=cls.context) - cls.node = rclpy.create_node(TEST_NODE, namespace=TEST_NAMESPACE, context=cls.context) + cls.node = rclpy.create_node( + TEST_NODE, namespace=TEST_NAMESPACE, context=cls.context, + allow_undeclared_parameters=True) @classmethod def tearDownClass(cls): diff --git a/rclpy/test/test_parameters_callback.py b/rclpy/test/test_parameters_callback.py index e0a7dbefe..ceab86bd2 100644 --- a/rclpy/test/test_parameters_callback.py +++ b/rclpy/test/test_parameters_callback.py @@ -31,7 +31,8 @@ def tearDownClass(cls): rclpy.shutdown(context=cls.context) def setUp(self): - self.node = rclpy.create_node('parameters_callback_node', context=self.context) + self.node = rclpy.create_node( + 'parameters_callback_node', context=self.context, allow_undeclared_parameters=True) def tearDown(self): self.node.destroy_node() diff --git a/rclpy/test/test_time_source.py b/rclpy/test/test_time_source.py index e935be1c4..489160247 100644 --- a/rclpy/test/test_time_source.py +++ b/rclpy/test/test_time_source.py @@ -37,7 +37,9 @@ class TestTimeSource(unittest.TestCase): def setUp(self): self.context = rclpy.context.Context() rclpy.init(context=self.context) - self.node = rclpy.create_node('TestTimeSource', namespace='/rclpy', context=self.context) + self.node = rclpy.create_node( + 'TestTimeSource', namespace='/rclpy', context=self.context, + allow_undeclared_parameters=True) def tearDown(self): self.node.destroy_node() diff --git a/rclpy/test/test_waitable.py b/rclpy/test/test_waitable.py index 7d29f70bd..c78bb9bf0 100644 --- a/rclpy/test/test_waitable.py +++ b/rclpy/test/test_waitable.py @@ -282,7 +282,9 @@ class TestWaitable(unittest.TestCase): def setUpClass(cls): cls.context = rclpy.context.Context() rclpy.init(context=cls.context) - cls.node = rclpy.create_node('TestWaitable', namespace='/rclpy/test', context=cls.context) + cls.node = rclpy.create_node( + 'TestWaitable', namespace='/rclpy/test', context=cls.context, + allow_undeclared_parameters=True) cls.executor = SingleThreadedExecutor(context=cls.context) cls.executor.add_node(cls.node)