Skip to content

Commit

Permalink
Using get_parameter_or in rclpy modules to prevent spurious exceptions.
Browse files Browse the repository at this point in the history
- Minor doc improvements.

Signed-off-by: Juan Ignacio Ubeira <jubeira@ekumenlabs.com>
  • Loading branch information
Juan Ignacio Ubeira committed Apr 30, 2019
1 parent 61845e3 commit 9147c83
Show file tree
Hide file tree
Showing 3 changed files with 15 additions and 10 deletions.
17 changes: 11 additions & 6 deletions rclpy/rclpy/node.py
Original file line number Diff line number Diff line change
Expand Up @@ -328,24 +328,29 @@ def get_parameter(self, name: str) -> Parameter:
else:
raise ParameterNotDeclaredException()

def get_parameter_or(self, name: str, alternative_value: Parameter) -> Parameter:
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, 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 function will raise a ParameterNotDeclaredException exception.
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
Expand Down Expand Up @@ -381,7 +386,7 @@ def _set_parameters(
"""
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.
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.
Expand Down Expand Up @@ -415,7 +420,7 @@ def set_parameters_atomically(self, parameter_list: List[Parameter]) -> SetParam
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.
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
Expand Down Expand Up @@ -484,7 +489,7 @@ def _set_parameters_atomically(self, parameter_list: List[Parameter]) -> SetPara
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())
Expand All @@ -493,7 +498,7 @@ def _set_parameters_atomically(self, parameter_list: List[Parameter]) -> SetPara
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:
Expand Down
6 changes: 3 additions & 3 deletions rclpy/rclpy/parameter_service.py
Original file line number Diff line number Diff line change
Expand Up @@ -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)
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).type_)
response.types.append(self._node.get_parameter_or(name).type_)
return response

def _list_parameters_callback(self, request, response):
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 @@ -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
Expand Down

0 comments on commit 9147c83

Please sign in to comment.