Skip to content

Commit

Permalink
Modifying behavior of get_parameters to comply with new API.
Browse files Browse the repository at this point in the history
Signed-off-by: Juan Ignacio Ubeira <jubeira@ekumenlabs.com>
  • Loading branch information
Juan Ignacio Ubeira committed Apr 30, 2019
1 parent 7fae791 commit d418adc
Show file tree
Hide file tree
Showing 15 changed files with 175 additions and 73 deletions.
127 changes: 90 additions & 37 deletions rclpy/rclpy/node.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
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
Expand Down Expand Up @@ -205,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

Expand Down Expand Up @@ -281,12 +282,15 @@ def undeclare_parameter(self, name: str):
:func:`set_parameters_callback` to be called.
:param name: name of the parameter.
:raises ParameterNotDeclaredException: if parameter had not been declared before
and undeclared parameters are not allowed.
:raises: ParameterNotDeclaredException if parameter had not been declared before.
:raises: ParameterImmutableException if the parameter was created as read-only.
"""
try:
del self._parameters[name]
except KeyError:
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:
Expand All @@ -298,7 +302,10 @@ 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')
Expand All @@ -309,36 +316,59 @@ 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.
"""
if name not in self._parameters:
: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 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) -> Parameter:
"""
Get a parameter or the alternative value if it had not been declared before.
Get a parameter or the alternative value.
This method does not declare parameters in any case.
:param name: Name of the parameter to get.
:alternative_value: Alternative parameter to get if it had not been declared before.
: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 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 a callback was registered previously with :func:`set_parameters_callback`, it will be
called prior to setting the parameters for the node.
For each successfully set parameter, a :class:`ParameterEvent` message is
published.
If any parameter in the list was not declared beforehand and undeclared parameters are not
allowed for the node, this function 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 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)

Expand All @@ -349,21 +379,24 @@ def _set_parameters(
raise_on_failure=False
) -> List[SetParametersResult]:
"""
Set parameters for the node, applying a setter function for each parameters in the list.
Set parameters for the node, and return the result for the set action.
Method for internal usage; applies a setter function 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. 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.
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.
:raises InvalidParameterValueException: if the user-defined callback rejects the
: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:
Expand All @@ -379,15 +412,31 @@ def _set_parameters(

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 function 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.
:raises ParameterNotDeclaredException: if undeclared paramers are not allowed, and at least
: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):
Expand All @@ -402,19 +451,23 @@ def set_parameters_atomically(self, parameter_list: List[Parameter]) -> SetParam

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.
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. If the callback doesn't succeed
for a given parameter, it won't be set and an unsuccessful result will be returned
for that parameter.
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.
This method does not check if the parameters were declared beforehand, and is intended
for internal use of this class.
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:
Expand Down Expand Up @@ -461,7 +514,7 @@ def describe_parameter(self, name: str) -> ParameterDescriptor:
: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
:raises: ParameterNotDeclaredException if parameter had not been declared before
and undeclared parameters are not allowed.
"""
try:
Expand All @@ -480,7 +533,7 @@ def describe_parameters(self, names: List[str]) -> List[ParameterDescriptor]:
: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
:raises: ParameterNotDeclaredException if at least one parameter
had not been declared before and undeclared parameters are not allowed.
"""
parameter_descriptors = []
Expand Down
3 changes: 2 additions & 1 deletion rclpy/test/action/test_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,8 @@ def setUpClass(cls):
cls.context = rclpy.context.Context()
rclpy.init(context=cls.context)
cls.executor = SingleThreadedExecutor(context=cls.context)
cls.node = rclpy.create_node('TestActionClient', context=cls.context)
cls.node = rclpy.create_node(
'TestActionClient', context=cls.context, allow_undeclared_parameters=True)
cls.mock_action_server = MockActionServer(cls.node)

@classmethod
Expand Down
12 changes: 9 additions & 3 deletions rclpy/test/action/test_graph.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,9 +40,15 @@ class TestActionGraph(unittest.TestCase):
def setUpClass(cls):
cls.context = rclpy.context.Context()
rclpy.init(context=cls.context)
cls.node0 = rclpy.create_node(TEST_NODE0, namespace=TEST_NAMESPACE0, context=cls.context)
cls.node1 = rclpy.create_node(TEST_NODE1, namespace=TEST_NAMESPACE1, context=cls.context)
cls.node2 = rclpy.create_node(TEST_NODE2, namespace=TEST_NAMESPACE2, context=cls.context)
cls.node0 = rclpy.create_node(
TEST_NODE0, namespace=TEST_NAMESPACE0, context=cls.context,
allow_undeclared_parameters=True)
cls.node1 = rclpy.create_node(
TEST_NODE1, namespace=TEST_NAMESPACE1, context=cls.context,
allow_undeclared_parameters=True)
cls.node2 = rclpy.create_node(
TEST_NODE2, namespace=TEST_NAMESPACE2, context=cls.context,
allow_undeclared_parameters=True)

cls.action_client10 = ActionClient(cls.node1, Fibonacci, TEST_ACTION0)
cls.action_server10 = ActionServer(cls.node1, Fibonacci, TEST_ACTION0, lambda: None)
Expand Down
3 changes: 2 additions & 1 deletion rclpy/test/action/test_server.py
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,8 @@ def setUp(self):
self.context = rclpy.context.Context()
rclpy.init(context=self.context)
self.executor = SingleThreadedExecutor(context=self.context)
self.node = rclpy.create_node('TestActionServer', context=self.context)
self.node = rclpy.create_node(
'TestActionServer', context=self.context, allow_undeclared_parameters=True)
self.mock_action_client = MockActionClient(self.node)

def tearDown(self):
Expand Down
4 changes: 3 additions & 1 deletion rclpy/test/test_callback_group.py
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,9 @@ class TestCallbackGroup(unittest.TestCase):
def setUpClass(cls):
cls.context = rclpy.context.Context()
rclpy.init(context=cls.context)
cls.node = rclpy.create_node('TestCallbackGroup', namespace='/rclpy', context=cls.context)
cls.node = rclpy.create_node(
'TestCallbackGroup', namespace='/rclpy', context=cls.context,
allow_undeclared_parameters=True)

@classmethod
def tearDownClass(cls):
Expand Down
3 changes: 2 additions & 1 deletion rclpy/test/test_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,8 @@ class TestClient(unittest.TestCase):
def setUpClass(cls):
cls.context = rclpy.context.Context()
rclpy.init(context=cls.context)
cls.node = rclpy.create_node('TestClient', context=cls.context)
cls.node = rclpy.create_node(
'TestClient', context=cls.context, allow_undeclared_parameters=True)

@classmethod
def tearDownClass(cls):
Expand Down
26 changes: 19 additions & 7 deletions rclpy/test/test_create_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,43 +33,55 @@ def tearDownClass(cls):

def test_create_node(self):
node_name = 'create_node_test'
rclpy.create_node(node_name, context=self.context).destroy_node()
rclpy.create_node(
node_name, context=self.context, allow_undeclared_parameters=True).destroy_node()

def test_create_node_with_namespace(self):
node_name = 'create_node_test'
namespace = '/ns'
rclpy.create_node(node_name, namespace=namespace, context=self.context).destroy_node()
rclpy.create_node(
node_name, namespace=namespace, context=self.context,
allow_undeclared_parameters=True).destroy_node()

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,
allow_undeclared_parameters=True)
self.assertEqual('/', node.get_namespace())
node.destroy_node()

def test_create_node_with_relative_namespace(self):
node_name = 'create_node_test'
namespace = 'ns'
node = rclpy.create_node(node_name, namespace=namespace, context=self.context)
node = rclpy.create_node(
node_name, namespace=namespace, context=self.context,
allow_undeclared_parameters=True)
self.assertEqual('/ns', node.get_namespace())
node.destroy_node()

def test_create_node_invalid_name(self):
node_name = 'create_node_test_invalid_name?'
with self.assertRaisesRegex(InvalidNodeNameException, 'must not contain characters'):
rclpy.create_node(node_name, context=self.context)
rclpy.create_node(
node_name, context=self.context, allow_undeclared_parameters=True)

def test_create_node_invalid_relative_namespace(self):
node_name = 'create_node_test_invalid_namespace'
namespace = 'invalid_namespace?'
with self.assertRaisesRegex(InvalidNamespaceException, 'must not contain characters'):
rclpy.create_node(node_name, namespace=namespace, context=self.context)
rclpy.create_node(
node_name, namespace=namespace, context=self.context,
allow_undeclared_parameters=True)

def test_create_node_invalid_namespace(self):
node_name = 'create_node_test_invalid_namespace'
namespace = '/invalid_namespace?'
with self.assertRaisesRegex(InvalidNamespaceException, 'must not contain characters'):
rclpy.create_node(node_name, namespace=namespace, context=self.context)
rclpy.create_node(
node_name, namespace=namespace, context=self.context,
allow_undeclared_parameters=True)


if __name__ == '__main__':
Expand Down
Loading

0 comments on commit d418adc

Please sign in to comment.