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

fix loading parameter behavior from yaml file. #1193

Open
wants to merge 3 commits into
base: rolling
Choose a base branch
from
Open
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
70 changes: 48 additions & 22 deletions rclpy/rclpy/parameter.py
Original file line number Diff line number Diff line change
Expand Up @@ -284,36 +284,62 @@ def parameter_dict_from_yaml_file(
"""
with open(parameter_file, 'r') as f:
param_file = yaml.safe_load(f)
param_keys = []
fujitatomoya marked this conversation as resolved.
Show resolved Hide resolved
param_dict = {}

if use_wildcard and '/**' in param_file:
param_keys.append('/**')
# check and add if wildcard is available in 1st keys
# wildcard key must go to the front of param_keys so that
# node-namespaced parameters will override the wildcard parameters
if use_wildcard and '/**' in param_file.keys():
value = param_file['/**']
if type(value) != dict and 'ros__parameters' not in value:
raise RuntimeError(
'YAML file is not a valid ROS parameter file for wildcard(/**)')
param_dict.update(value['ros__parameters'])

# parse parameter yaml file based on target node namespace and name
if target_nodes:
for n in target_nodes:
if n not in param_file.keys():
raise RuntimeError(f'Param file does not contain parameters for {n},'
f'only for nodes: {list(param_file.keys())} ')
param_keys.append(n)
else:
# wildcard key must go to the front of param_keys so that
# node-namespaced parameters will override the wildcard parameters
keys = set(param_file.keys())
keys.discard('/**')
param_keys.extend(keys)

if len(param_keys) == 0:
raise RuntimeError('Param file does not contain selected parameters')

for n in param_keys:
value = param_file[n]
if type(value) != dict or 'ros__parameters' not in value:
raise RuntimeError(f'YAML file is not a valid ROS parameter file for node {n}')
param_dict.update(value['ros__parameters'])
abs_name = _get_absolute_node_name(n)
fujitatomoya marked this conversation as resolved.
Show resolved Hide resolved
if abs_name is None:
continue
if abs_name in param_file.keys():
# found absolute node name w or w/o namespace
value = param_file[abs_name]
if type(value) != dict and 'ros__parameters' not in value:
raise RuntimeError(
f'YAML file is not a valid ROS parameter file for node {abs_name}')
param_dict.update(value['ros__parameters'])
fujitatomoya marked this conversation as resolved.
Show resolved Hide resolved
ns, node_basename = abs_name.rsplit('/', 1)
if not ns and node_basename in param_file.keys():
# found non-absolute node name without namespace
value = param_file[node_basename]
if type(value) != dict and 'ros__parameters' not in value:
raise RuntimeError('YAML file is not a valid ROS parameter '
f'file for node {node_basename}')
param_dict.update(value['ros__parameters'])
elif ns in param_file.keys():
# found namespace
if node_basename in param_file[ns].keys():
value = param_file[ns][node_basename]
if type(value) != dict and 'ros__parameters' not in value:
raise RuntimeError('YAML file is not a valid ROS parameter '
f'file for namespace {ns} node {node_basename}')
param_dict.update(value['ros__parameters'])

if not param_dict:
raise RuntimeError('Param file does not contain any valid parameters')

return _unpack_parameter_dict(namespace, param_dict)


def _get_absolute_node_name(node_name: str) -> Optional[str]:
if not node_name:
return None
if node_name[0] != '/':
node_name = '/' + node_name
return node_name


def _unpack_parameter_dict(namespace, parameter_dict):
"""
Flatten a parameter dictionary recursively.
Expand Down
6 changes: 4 additions & 2 deletions rclpy/rclpy/parameter_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -309,7 +309,8 @@ def load_parameter_file(
:param use_wildcard: Whether to use wildcard expansion.
:return: Future with the result from the set_parameters call.
"""
param_dict = parameter_dict_from_yaml_file(parameter_file, use_wildcard)
param_dict = parameter_dict_from_yaml_file(
parameter_file, use_wildcard, target_nodes=[self.remote_node_name])
fujitatomoya marked this conversation as resolved.
Show resolved Hide resolved
future = self.set_parameters(list(param_dict.values()), callback=callback)
return future

Expand All @@ -331,7 +332,8 @@ def load_parameter_file_atomically(
:param use_wildcard: Whether to use wildcard expansion.
:return: Future with the result from the set_parameters_atomically call.
"""
param_dict = parameter_dict_from_yaml_file(parameter_file, use_wildcard)
param_dict = parameter_dict_from_yaml_file(
parameter_file, use_wildcard, target_nodes=[self.remote_node_name])
future = self.set_parameters_atomically(list(param_dict.values()), callback=callback)
return future

Expand Down
75 changes: 66 additions & 9 deletions rclpy/test/test_parameter.py
Original file line number Diff line number Diff line change
Expand Up @@ -259,23 +259,80 @@ def test_parameter_value_to_python(self):
parameter_value_to_python(parameter_value)

def test_parameter_dict_from_yaml_file(self):
yaml_string = """/param_test_target:
ros__parameters:
param_1: 1
param_str: string
yaml_string = """
/param_test_target:
ros__parameters:
abs-nodename: true
param_test_target:
ros__parameters:
base-nodename: true
/foo/param_test_target:
ros__parameters:
abs-ns-nodename: true
/foo:
param_test_target:
ros__parameters:
abs-ns-base-nodename: true
/bar/param_test_target:
ros__parameters:
abs-ns-nodename: false
/bar:
param_test_target:
ros__parameters:
abs-ns-base-nodename: false
/**:
ros__parameters:
wildcard: true
"""
expected = {
'param_1': Parameter('param_1', Parameter.Type.INTEGER, 1).to_parameter_msg(),
'param_str': Parameter('param_str', Parameter.Type.STRING, 'string').to_parameter_msg()

# target nodes is specified, so it should only parse wildcard
expected_no_target_node = {
'wildcard': Parameter('wildcard', Parameter.Type.BOOL, True).to_parameter_msg(),
}
# target nodes is specified with wildcard enabled
expected_target_node_wildcard = {
'wildcard': Parameter(
'wildcard', Parameter.Type.BOOL, True).to_parameter_msg(),
'abs-nodename': Parameter(
'abs-nodename', Parameter.Type.BOOL, True).to_parameter_msg(),
'base-nodename': Parameter(
'base-nodename', Parameter.Type.BOOL, True).to_parameter_msg(),
}
# target nodes is specified with wildcard disabled
expected_target_node = {
'abs-nodename': Parameter(
'abs-nodename', Parameter.Type.BOOL, True).to_parameter_msg(),
'base-nodename': Parameter(
'base-nodename', Parameter.Type.BOOL, True).to_parameter_msg(),
}
# target nodes is specified with wildcard and namespace
expected_target_node_ns = {
'wildcard': Parameter('wildcard', Parameter.Type.BOOL, True).to_parameter_msg(),
'abs-ns-nodename': Parameter(
'abs-ns-nodename', Parameter.Type.BOOL, True).to_parameter_msg(),
'abs-ns-base-nodename': Parameter(
'abs-ns-base-nodename', Parameter.Type.BOOL, True).to_parameter_msg(),
}

try:
with NamedTemporaryFile(mode='w', delete=False) as f:
f.write(yaml_string)
f.flush()
f.close()
parameter_dict = parameter_dict_from_yaml_file(f.name)
fujitatomoya marked this conversation as resolved.
Show resolved Hide resolved
assert parameter_dict == expected
parameter_dict = parameter_dict_from_yaml_file(f.name, True)
assert parameter_dict == expected_no_target_node
parameter_dict = parameter_dict_from_yaml_file(
f.name, True, target_nodes=[''])
assert parameter_dict == expected_no_target_node
parameter_dict = parameter_dict_from_yaml_file(
f.name, True, target_nodes=['param_test_target'])
assert parameter_dict == expected_target_node_wildcard
parameter_dict = parameter_dict_from_yaml_file(
f.name, False, target_nodes=['/param_test_target'])
assert parameter_dict == expected_target_node
parameter_dict = parameter_dict_from_yaml_file(
f.name, True, target_nodes=['/foo/param_test_target'])
assert parameter_dict == expected_target_node_ns
finally:
if os.path.exists(f.name):
os.unlink(f.name)
Expand Down
4 changes: 2 additions & 2 deletions rclpy/test/test_parameter_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -139,7 +139,7 @@ def test_delete_parameters(self):
assert result.results[0].successful

def test_load_parameter_file(self):
yaml_string = """/param_test_target:
yaml_string = """/test_parameter_client_target:
fujitatomoya marked this conversation as resolved.
Show resolved Hide resolved
ros__parameters:
param_1: 1
param_str: "string"
Expand All @@ -160,7 +160,7 @@ def test_load_parameter_file(self):
os.unlink(f.name)

def test_load_parameter_file_atomically(self):
yaml_string = """/param_test_target:
yaml_string = """/test_parameter_client_target:
ros__parameters:
param_1: 1
param_str: "string"
Expand Down