Skip to content

Commit

Permalink
Fixing existing test-cases.
Browse files Browse the repository at this point in the history
- Adjusting documentation.

Signed-off-by: Juan Ignacio Ubeira <jubeira@ekumenlabs.com>
  • Loading branch information
Juan Ignacio Ubeira committed Apr 30, 2019
1 parent 3f2803a commit 7fae791
Show file tree
Hide file tree
Showing 8 changed files with 64 additions and 36 deletions.
7 changes: 5 additions & 2 deletions rclpy/rclpy/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -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`.
Expand All @@ -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
Expand All @@ -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:
Expand Down
4 changes: 4 additions & 0 deletions rclpy/rclpy/exceptions.py
Original file line number Diff line number Diff line change
Expand Up @@ -74,24 +74,28 @@ class ParameterNotDeclaredException(Exception):
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."""

Expand Down
61 changes: 35 additions & 26 deletions rclpy/rclpy/node.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
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
Expand All @@ -30,7 +31,6 @@
from rclpy.clock import ROSClock
from rclpy.constants import S_TO_NS
from rclpy.context import Context
from rclpy.exceptions import InvalidParameterException
from rclpy.exceptions import InvalidParameterValueException
from rclpy.exceptions import NotInitializedException
from rclpy.exceptions import ParameterAlreadyDeclaredException
Expand Down Expand Up @@ -88,7 +88,7 @@ def __init__(
use_global_arguments: bool = True,
start_parameter_services: bool = True,
initial_parameters: List[Parameter] = None,
allow_undeclared_parameters = False
allow_undeclared_parameters: bool = False
) -> None:
"""
Constructor.
Expand Down Expand Up @@ -234,7 +234,7 @@ def declare_parameter(self, parameter: Parameter) -> Parameter:
Declare and initialize a parameter.
This method, if successful, will result in any callback registered with
set_parameters_callback to be called.
: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.
Expand All @@ -246,12 +246,12 @@ def declare_parameter(self, parameter: Parameter) -> Parameter:

def declare_parameters(self, namespace: str, parameters: List[Parameter]) -> List[Parameter]:
"""
Declares a list of parameters.
Declare a list of parameters.
This method, if successful, will result in any callback registered with
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 set. Parameters declared up to that point will not be undeclared.
: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.
Expand All @@ -265,7 +265,7 @@ def declare_parameters(self, namespace: str, parameters: List[Parameter]) -> Lis
# 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]):
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
Expand All @@ -275,19 +275,22 @@ def declare_parameters(self, namespace: str, parameters: List[Parameter]) -> Lis

def undeclare_parameter(self, name: str):
"""
Undeclares a parameter.
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
and undeclared parameters are not allowed.
"""
try:
del self._parameters[name]
except KeyError e:
except KeyError:
raise ParameterNotDeclaredException()

def has_parameter(self, name: str) -> bool:
"""Returns True if parameter is declared; False otherwise."""
"""Return True if parameter is declared; False otherwise."""
return name in self._parameters

def get_parameters(self, names: List[str]) -> List[Parameter]:
Expand Down Expand Up @@ -339,9 +342,15 @@ def set_parameters(self, parameter_list: List[Parameter]) -> List[SetParametersR
"""
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]:
def _set_parameters(
self,
parameter_list: List[Parameter],
setter_func=None,
raise_on_failure=False
) -> List[SetParametersResult]:
"""
Set parameters for the node, applying a setter function for each of the parameters in the list.
Set parameters for the node, applying 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.
Expand All @@ -351,11 +360,11 @@ def _set_parameters(self, parameter_list: List[Parameter], setter_func=None, rai
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,
: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 parameter value
and raise_on_failure flag is True.
: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
Expand All @@ -365,7 +374,7 @@ def _set_parameters(self, parameter_list: List[Parameter], setter_func=None, rai
result = setter_func([param])
if raise_on_failure and not result.successful:
raise InvalidParameterValueException()
results.append()
results.append(result)
return results

def set_parameters_atomically(self, parameter_list: List[Parameter]) -> SetParametersResult:
Expand All @@ -381,9 +390,12 @@ def set_parameters_atomically(self, parameter_list: List[Parameter]) -> SetParam
: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):
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)
Expand Down Expand Up @@ -418,9 +430,6 @@ def _set_parameters_atomically(self, parameter_list: List[Parameter]) -> SetPara
else:
parameter_event.node = self.get_namespace() + '/' + self.get_name()
for param in parameter_list:
if not isinstance(param, Parameter):
raise TypeError("parameter must be instance of type '{}'".format(repr(Parameter)))

if Parameter.Type.NOT_SET == param.type_:
if Parameter.Type.NOT_SET != self.get_parameter(param.name).type_:
# Parameter deleted. (Parameter had value and new value is not set)
Expand All @@ -446,7 +455,7 @@ def _set_parameters_atomically(self, parameter_list: List[Parameter]) -> SetPara

def describe_parameter(self, name: str) -> ParameterDescriptor:
"""
Gets the parameter descriptor of a given parameter.
Get the parameter descriptor of a given parameter.
:param name: Name of the parameter to describe.
:return: ParameterDescriptor corresponding to the parameter,
Expand All @@ -457,15 +466,15 @@ def describe_parameter(self, name: str) -> ParameterDescriptor:
"""
try:
return self._parameters[name].descriptor
except KeyError e:
except KeyError:
if self._allow_undeclared_parameters:
return ParameterDescriptor()
else:
raise ParameterNotDeclaredException()

def describe_parameters(self, names: List[str]) -> List[ParameterDescriptor]:
"""
Gets the parameter descriptors of a given list of parameters.
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.
Expand Down
9 changes: 8 additions & 1 deletion rclpy/rclpy/parameter.py
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,13 @@ def from_parameter_msg(cls, param_msg):
return cls(param_msg.name, type_, value)

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)))

Expand All @@ -97,7 +104,7 @@ def __init__(self, name, type_, value=None, descriptor=ParameterDescriptor()):
self._name = name
self._value = value
descriptor.name = name
descriptor.value = value
descriptor.type = type_.value
self._descriptor = descriptor

@property
Expand Down
7 changes: 3 additions & 4 deletions rclpy/rclpy/validate_parameter_name.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from rclpy.exceptions import InvalidParameterNameException
from rclpy.validate_topic_name import validate_topic_name
from rclpy.exceptions import InvalidParameterException
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy


def validate_parameter_name(name):
Expand All @@ -30,11 +30,10 @@ def validate_parameter_name(name):
: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 InvalidParameterNameException(name, error_msg, invalid_index)
raise InvalidParameterException(name, error_msg, invalid_index)
4 changes: 3 additions & 1 deletion rclpy/test/test_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -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):
Expand Down
4 changes: 3 additions & 1 deletion rclpy/test/test_parameters_callback.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,9 @@ 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()
Expand Down
4 changes: 3 additions & 1 deletion rclpy/test/test_time_source.py
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down

0 comments on commit 7fae791

Please sign in to comment.