Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Deprecate set_parameters_callback API #504

Merged
merged 2 commits into from
Mar 10, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
30 changes: 19 additions & 11 deletions rclpy/rclpy/node.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
from typing import TypeVar
from typing import Union

import warnings
import weakref

from rcl_interfaces.msg import FloatingPointRange
Expand Down Expand Up @@ -326,7 +327,7 @@ def declare_parameter(
Declare and initialize a parameter.

This method, if successful, will result in any callback registered with
:func:`set_parameters_callback` to be called.
:func:`add_on_set_parameters_callback` to be called.

:param name: Fully-qualified name of the parameter, including its namespace.
:param value: Value of the parameter to declare.
Expand Down Expand Up @@ -368,7 +369,7 @@ def declare_parameters(
This allows you to declare several parameters at once without a namespace.

This method, if successful, will result in any callback registered with
:func:`set_parameters_callback` to be called once for each parameter.
:func:`add_on_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.
Expand Down Expand Up @@ -456,7 +457,7 @@ 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.
:func:`add_on_set_parameters_callback` to be called.

:param name: Fully-qualified name of the parameter, including its namespace.
:raises: ParameterNotDeclaredException if parameter had not been declared before.
Expand Down Expand Up @@ -569,8 +570,8 @@ def set_parameters(self, parameter_list: List[Parameter]) -> List[SetParametersR
declared before being set even if they were not declared beforehand.
Parameter overrides are ignored by this method.

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 a callback was registered previously with :func:`add_on_set_parameters_callback`, it
will be 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
Expand Down Expand Up @@ -600,8 +601,8 @@ def _set_parameters(
By default it checks if the parameters were declared, raising an exception if at least
one of them was not.

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 a callback was registered previously with :func:`add_on_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.
Expand Down Expand Up @@ -651,8 +652,8 @@ def set_parameters_atomically(self, parameter_list: List[Parameter]) -> SetParam
If undeclared parameters are allowed for the node, 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 only once for all parameters.
If a callback was registered previously with :func:`add_on_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.
Expand Down Expand Up @@ -696,8 +697,8 @@ def _set_parameters_atomically(
This internal method does not reject undeclared parameters.
If :param:`allow_not_set_type` is False, a parameter with type NOT_SET will be undeclared.

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 a callback was registered previously with :func:`add_on_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
Expand Down Expand Up @@ -1055,10 +1056,17 @@ def set_parameters_callback(
"""
Register a set parameters callback.

.. deprecated:: Foxy
Use :func:`add_on_set_parameters_callback()` instead.

Calling this function will add a callback to the self._parameter_callbacks list.

:param callback: The function that is called whenever parameters are set for the node.
"""
warnings.warn(
'set_parameters_callback() is deprecated. '
'Use add_on_set_parameters_callback() instead'
)
self._parameters_callbacks = [callback]

def _validate_topic_or_service_name(self, topic_or_service_name, *, is_service=False):
Expand Down
2 changes: 1 addition & 1 deletion rclpy/rclpy/time_source.py
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@ def attach_node(self, node):
"'{}' parameter not set, using wall time by default"
.format(USE_SIM_TIME_NAME))

node.set_parameters_callback(self._on_parameter_event)
node.add_on_set_parameters_callback(self._on_parameter_event)

def detach_node(self):
# Remove the subscription to the clock topic.
Expand Down
8 changes: 4 additions & 4 deletions rclpy/test/test_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -431,7 +431,7 @@ def test_declare_parameter(self):
self.node.declare_parameter(
'', 'raise', ParameterDescriptor())

self.node.set_parameters_callback(self.reject_parameter_callback)
self.node.add_on_set_parameters_callback(self.reject_parameter_callback)
with self.assertRaises(InvalidParameterValueException):
self.node.declare_parameter(
'reject_me', 'raise', ParameterDescriptor())
Expand Down Expand Up @@ -549,7 +549,7 @@ def test_declare_parameters(self):
('im_also_ok', 'world', ParameterDescriptor()),
('reject_me', 2.41, ParameterDescriptor()),
]
self.node.set_parameters_callback(self.reject_parameter_callback)
self.node.add_on_set_parameters_callback(self.reject_parameter_callback)
with self.assertRaises(InvalidParameterValueException):
self.node.declare_parameters('', parameters)

Expand Down Expand Up @@ -829,7 +829,7 @@ def test_node_set_parameters_rejection(self):
ParameterDescriptor()
)
self.node.declare_parameter(*reject_parameter_tuple)
self.node.set_parameters_callback(self.reject_parameter_callback)
self.node.add_on_set_parameters_callback(self.reject_parameter_callback)
result = self.node.set_parameters(
[
Parameter(
Expand Down Expand Up @@ -1177,7 +1177,7 @@ def test_node_set_parameters_atomically_rejection(self):
)

self.node.declare_parameter(*reject_parameter_tuple)
self.node.set_parameters_callback(self.reject_parameter_callback)
self.node.add_on_set_parameters_callback(self.reject_parameter_callback)
result = self.node.set_parameters_atomically(
[
Parameter(
Expand Down
18 changes: 15 additions & 3 deletions rclpy/test/test_parameters_callback.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
# limitations under the License.

import unittest
import warnings

from rcl_interfaces.msg import SetParametersResult
import rclpy
Expand Down Expand Up @@ -44,7 +45,11 @@ def callback(parameter_list):
nonlocal callback_called
callback_called = True
return SetParametersResult(successful=True)
self.node.set_parameters_callback(callback)

with warnings.catch_warnings(record=True) as w:
warnings.simplefilter('always')
self.node.set_parameters_callback(callback)
assert issubclass(w[0].category, UserWarning)
result = self.node.set_parameters_atomically(
[Parameter('foo', Parameter.Type.STRING, 'Hello')]
)
Expand All @@ -59,7 +64,11 @@ def callback(parameter_list):
nonlocal callback_called
callback_called = True
return SetParametersResult(successful=False)
self.node.set_parameters_callback(callback)

with warnings.catch_warnings(record=True) as w:
warnings.simplefilter('always')
self.node.set_parameters_callback(callback)
assert issubclass(w[0].category, UserWarning)
result = self.node.set_parameters_atomically(
[Parameter('foo', Parameter.Type.STRING, 'Hello')]
)
Expand All @@ -84,7 +93,10 @@ def callback(parameter_list):
r.reason = 'Integer must be even'
return r
return r
self.node.set_parameters_callback(callback)
with warnings.catch_warnings(record=True) as w:
warnings.simplefilter('always')
self.node.set_parameters_callback(callback)
assert issubclass(w[0].category, UserWarning)
result = self.node.set_parameters_atomically(
[Parameter('foo', Parameter.Type.STRING, 'Hello')]
)
Expand Down