Skip to content

Commit 8fa97fc

Browse files
Add value rewrites to RewrittenYaml (#5191)
* Added context manager for safe file closing and prevent warnings. Signed-off-by: Leander Stephen D'Souza <[email protected]> * Implement value_rewrites to ReWrittenYaml. Signed-off-by: Leander Stephen D'Souza <[email protected]> * Use placeholders for costmap filters using the new value rewrite feature. Signed-off-by: Leander Stephen D'Souza <[email protected]> * Enable system tests to use value rewrites. Signed-off-by: Leander Stephen D'Souza <[email protected]> * Define remappings for costmap filters instead of inline substitution. Signed-off-by: Leander Stephen D'Souza <[email protected]> --------- Signed-off-by: Leander Stephen D'Souza <[email protected]>
1 parent 7c5d0de commit 8fa97fc

File tree

17 files changed

+245
-9
lines changed

17 files changed

+245
-9
lines changed

.gitignore

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,7 @@ install
4545
__pycache__/
4646
*.py[cod]
4747
.ipynb_checkpoints
48+
.pytest_cache/
4849

4950
sphinx_doc/_build
5051

nav2_bringup/launch/bringup_launch.py

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -51,11 +51,17 @@ def generate_launch_description() -> LaunchDescription:
5151
# Map fully qualified names to relative ones so the node's namespace can be prepended.
5252
remappings = [('/tf', 'tf'), ('/tf_static', 'tf_static')]
5353

54+
yaml_substitutions = {
55+
'KEEPOUT_ZONE_ENABLED': use_keepout_zones,
56+
'SPEED_ZONE_ENABLED': use_speed_zones,
57+
}
58+
5459
configured_params = ParameterFile(
5560
RewrittenYaml(
5661
source_file=params_file,
5762
root_key=namespace,
5863
param_rewrites={},
64+
value_rewrites=yaml_substitutions,
5965
convert_types=True,
6066
),
6167
allow_substs=True,

nav2_bringup/launch/keepout_zone_launch.py

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -45,11 +45,16 @@ def generate_launch_description() -> LaunchDescription:
4545
# Map fully qualified names to relative ones so the node's namespace can be prepended.
4646
remappings = [('/tf', 'tf'), ('/tf_static', 'tf_static')]
4747

48+
yaml_substitutions = {
49+
'KEEPOUT_ZONE_ENABLED': use_keepout_zones,
50+
}
51+
4852
configured_params = ParameterFile(
4953
RewrittenYaml(
5054
source_file=params_file,
5155
root_key=namespace,
5256
param_rewrites={},
57+
value_rewrites=yaml_substitutions,
5358
convert_types=True,
5459
),
5560
allow_substs=True,

nav2_bringup/launch/speed_zone_launch.py

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -45,11 +45,16 @@ def generate_launch_description() -> LaunchDescription:
4545
# Map fully qualified names to relative ones so the node's namespace can be prepended.
4646
remappings = [('/tf', 'tf'), ('/tf_static', 'tf_static')]
4747

48+
yaml_substitutions = {
49+
'SPEED_ZONE_ENABLED': use_speed_zones,
50+
}
51+
4852
configured_params = ParameterFile(
4953
RewrittenYaml(
5054
source_file=params_file,
5155
root_key=namespace,
5256
param_rewrites={},
57+
value_rewrites=yaml_substitutions,
5358
convert_types=True,
5459
),
5560
allow_substs=True,

nav2_bringup/params/nav2_params.yaml

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -227,7 +227,7 @@ local_costmap:
227227
filters: ["keepout_filter"]
228228
keepout_filter:
229229
plugin: "nav2_costmap_2d::KeepoutFilter"
230-
enabled: True
230+
enabled: KEEPOUT_ZONE_ENABLED
231231
filter_info_topic: "keepout_costmap_filter_info"
232232
inflation_layer:
233233
plugin: "nav2_costmap_2d::InflationLayer"
@@ -279,11 +279,11 @@ global_costmap:
279279
filters: ["keepout_filter", "speed_filter"]
280280
keepout_filter:
281281
plugin: "nav2_costmap_2d::KeepoutFilter"
282-
enabled: True
282+
enabled: KEEPOUT_ZONE_ENABLED
283283
filter_info_topic: "keepout_costmap_filter_info"
284284
speed_filter:
285285
plugin: "nav2_costmap_2d::SpeedFilter"
286-
enabled: True
286+
enabled: SPEED_ZONE_ENABLED
287287
filter_info_topic: "speed_costmap_filter_info"
288288
speed_limit_topic: "speed_limit"
289289
obstacle_layer:

nav2_common/CMakeLists.txt

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,3 +15,16 @@ install(
1515
DIRECTORY cmake
1616
DESTINATION share/${PROJECT_NAME}
1717
)
18+
19+
install(
20+
DIRECTORY test
21+
DESTINATION share/${PROJECT_NAME}
22+
)
23+
24+
if(BUILD_TESTING)
25+
find_package(ament_cmake_test REQUIRED)
26+
find_package(ament_cmake_pytest REQUIRED)
27+
28+
ament_add_pytest_test(test_rewritten_yaml test/test_rewritten_yaml.py
29+
)
30+
endif()

nav2_common/nav2_common/launch/rewritten_yaml.py

Lines changed: 39 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,7 @@ def __init__(
4848
param_rewrites: dict[str, launch.SomeSubstitutionsType],
4949
root_key: Optional[launch.SomeSubstitutionsType] = None,
5050
key_rewrites: Optional[dict[str, launch.SomeSubstitutionsType]] = None,
51+
value_rewrites: Optional[dict[str, launch.SomeSubstitutionsType]] = None,
5152
convert_types: bool = False,
5253
) -> None:
5354
super().__init__()
@@ -58,6 +59,7 @@ def __init__(
5859
:param: param_rewrites mappings to replace
5960
:param: root_key if provided, the contents are placed under this key
6061
:param: key_rewrites keys of mappings to replace
62+
:param: value_rewrites values to replace
6163
:param: convert_types whether to attempt converting the string to a number or boolean
6264
"""
6365

@@ -68,6 +70,7 @@ def __init__(
6870
normalize_to_list_of_substitutions(source_file)
6971
self.__param_rewrites = {}
7072
self.__key_rewrites = {}
73+
self.__value_rewrites = {}
7174
self.__convert_types = convert_types
7275
self.__root_key = None
7376
for key in param_rewrites:
@@ -79,6 +82,11 @@ def __init__(
7982
self.__key_rewrites[key] = normalize_to_list_of_substitutions(
8083
key_rewrites[key]
8184
)
85+
if value_rewrites is not None:
86+
for value in value_rewrites:
87+
self.__value_rewrites[value] = normalize_to_list_of_substitutions(
88+
value_rewrites[value]
89+
)
8290
if root_key is not None:
8391
self.__root_key = normalize_to_list_of_substitutions(root_key)
8492

@@ -94,11 +102,15 @@ def describe(self) -> str:
94102
def perform(self, context: launch.LaunchContext) -> str:
95103
yaml_filename = launch.utilities.perform_substitutions(context, self.name)
96104
rewritten_yaml = tempfile.NamedTemporaryFile(mode='w', delete=False)
97-
param_rewrites, keys_rewrites = self.resolve_rewrites(context)
98-
data = yaml.safe_load(open(yaml_filename))
105+
param_rewrites, keys_rewrites, value_rewrites = self.resolve_rewrites(context)
106+
107+
with open(yaml_filename, 'r') as yaml_file:
108+
data = yaml.safe_load(yaml_file)
109+
99110
self.substitute_params(data, param_rewrites)
100111
self.add_params(data, param_rewrites)
101112
self.substitute_keys(data, keys_rewrites)
113+
self.substitute_values(data, value_rewrites)
102114
if self.__root_key is not None:
103115
root_key = launch.utilities.perform_substitutions(context, self.__root_key)
104116
if root_key:
@@ -108,7 +120,7 @@ def perform(self, context: launch.LaunchContext) -> str:
108120
return rewritten_yaml.name
109121

110122
def resolve_rewrites(self, context: launch.LaunchContext) -> \
111-
tuple[dict[str, str], dict[str, str]]:
123+
tuple[dict[str, str], dict[str, str], dict[str, str]]:
112124
resolved_params = {}
113125
for key in self.__param_rewrites:
114126
resolved_params[key] = launch.utilities.perform_substitutions(
@@ -119,7 +131,12 @@ def resolve_rewrites(self, context: launch.LaunchContext) -> \
119131
resolved_keys[key] = launch.utilities.perform_substitutions(
120132
context, self.__key_rewrites[key]
121133
)
122-
return resolved_params, resolved_keys
134+
resolved_values = {}
135+
for value in self.__value_rewrites:
136+
resolved_values[value] = launch.utilities.perform_substitutions(
137+
context, self.__value_rewrites[value]
138+
)
139+
return resolved_params, resolved_keys, resolved_values
123140

124141
def substitute_params(self, yaml: dict[str, YamlValue],
125142
param_rewrites: dict[str, str]) -> None:
@@ -149,6 +166,24 @@ def add_params(self, yaml: dict[str, YamlValue],
149166
if 'ros__parameters' in yaml_keys:
150167
yaml = self.updateYamlPathVals(yaml, yaml_keys, new_val)
151168

169+
def substitute_values(
170+
self, yaml: dict[str, YamlValue],
171+
value_rewrites: dict[str, str]) -> None:
172+
173+
def process_value(value: YamlValue) -> YamlValue:
174+
if isinstance(value, dict):
175+
for k, v in list(value.items()):
176+
value[k] = process_value(v)
177+
return value
178+
elif isinstance(value, list):
179+
return [process_value(v) for v in value]
180+
elif str(value) in value_rewrites:
181+
return self.convert(value_rewrites[str(value)])
182+
return value
183+
184+
for key in list(yaml.keys()):
185+
yaml[key] = process_value(yaml[key])
186+
152187
def updateYamlPathVals(
153188
self, yaml: dict[str, YamlValue],
154189
yaml_key_list: list[str], rewrite_val: YamlValue) -> dict[str, YamlValue]:

nav2_common/package.xml

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,10 @@
2020

2121
<buildtool_export_depend>ament_cmake_core</buildtool_export_depend>
2222

23+
<test_depend>ament_cmake_test</test_depend>
24+
<test_depend>ament_cmake_pytest</test_depend>
25+
<test_depend>python3-pytest</test_depend>
26+
2327
<export>
2428
<build_type>ament_cmake</build_type>
2529
</export>
Lines changed: 133 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,133 @@
1+
# Copyright (c) 2025 Leander Stephen Desouza
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
import os
16+
import tempfile
17+
from typing import Generator
18+
19+
import launch
20+
from launch.substitutions import LaunchConfiguration
21+
from nav2_common.launch import RewrittenYaml
22+
import pytest
23+
import yaml
24+
25+
26+
class TestRewrittenYamlValueRewrites:
27+
"""Test that value rewrites work correctly in RewrittenYaml."""
28+
29+
@pytest.fixture(autouse=True)
30+
def setup_teardown(self) -> Generator[None, None, None]:
31+
# Create a temporary YAML file for testing
32+
self.test_yaml = tempfile.NamedTemporaryFile(mode='w', delete=False)
33+
self.test_yaml.write("""\
34+
param0: placeholder_bool
35+
param1: placeholder_string
36+
param2: placeholder_float
37+
param3: placeholder_int
38+
param4: placeholder_list
39+
param5: placeholder_dict
40+
nested:
41+
param6: placeholder_bool
42+
param7: placeholder_string
43+
param8: placeholder_float
44+
param9: placeholder_int
45+
param10: placeholder_list
46+
param11: placeholder_dict
47+
other_value: 42
48+
list_values:
49+
- placeholder_bool
50+
- placeholder_string
51+
- placeholder_float
52+
- placeholder_int
53+
- placeholder_list
54+
- placeholder_dict
55+
- normal_value
56+
""")
57+
self.test_yaml.close()
58+
yield
59+
os.unlink(self.test_yaml.name)
60+
61+
def test_value_rewrites(self) -> None:
62+
"""Test that value rewrites work for various types."""
63+
# Set up launch configurations for our test values
64+
launch_configurations = {
65+
'test_bool': 'true',
66+
'test_string': 'replaced_string',
67+
'test_float': '3.14',
68+
'test_int': '100',
69+
'test_list': '["string", 42, 2.718, ["sublist_item1", "sublist_item2"]]',
70+
'test_dict': ('{"key1": "value1", "key2": 2, "key3": 3.14, '
71+
'"key4": ["list_item1", "list_item2"]}')
72+
}
73+
context = launch.LaunchContext()
74+
for key, value in launch_configurations.items():
75+
context.launch_configurations[key] = value
76+
77+
value_rewrites = {
78+
'placeholder_bool': LaunchConfiguration('test_bool'),
79+
'placeholder_string': LaunchConfiguration('test_string'),
80+
'placeholder_float': LaunchConfiguration('test_float'),
81+
'placeholder_int': LaunchConfiguration('test_int'),
82+
'placeholder_list': LaunchConfiguration('test_list'),
83+
'placeholder_dict': LaunchConfiguration('test_dict'),
84+
}
85+
86+
rewriter = RewrittenYaml(
87+
source_file=self.test_yaml.name,
88+
param_rewrites={},
89+
value_rewrites=value_rewrites,
90+
convert_types=True,
91+
)
92+
output_file = rewriter.perform(context)
93+
94+
try:
95+
with open(output_file) as f:
96+
result = yaml.safe_load(f)
97+
98+
assert result['param0'] is True
99+
assert result['param1'] == 'replaced_string'
100+
assert result['param2'] == 3.14
101+
assert result['param3'] == 100
102+
assert result['param4'] == \
103+
'["string", 42, 2.718, ["sublist_item1", "sublist_item2"]]'
104+
assert result['param5'] == \
105+
'{"key1": "value1", "key2": 2, "key3": 3.14, "key4": ["list_item1", "list_item2"]}'
106+
107+
# Check nested values
108+
assert result['nested']['param6'] is True
109+
assert result['nested']['param7'] == 'replaced_string'
110+
assert result['nested']['param8'] == 3.14
111+
assert result['nested']['param9'] == 100
112+
assert result['nested']['param10'] == \
113+
'["string", 42, 2.718, ["sublist_item1", "sublist_item2"]]'
114+
assert result['nested']['param11'] == \
115+
'{"key1": "value1", "key2": 2, "key3": 3.14, "key4": ["list_item1", "list_item2"]}'
116+
117+
# Check list values
118+
assert result['list_values'][0] is True
119+
assert result['list_values'][1] == 'replaced_string'
120+
assert result['list_values'][2] == 3.14
121+
assert result['list_values'][3] == 100
122+
assert result['list_values'][4] == \
123+
'["string", 42, 2.718, ["sublist_item1", "sublist_item2"]]'
124+
assert result['list_values'][5] == \
125+
'{"key1": "value1", "key2": 2, "key3": 3.14, "key4": ["list_item1", "list_item2"]}'
126+
127+
# Check other values remain unchanged
128+
assert result['nested']['other_value'] == 42
129+
assert result['list_values'][6] == 'normal_value'
130+
131+
finally:
132+
if os.path.exists(output_file):
133+
os.unlink(output_file)

nav2_system_tests/src/behaviors/assisted_teleop/test_assisted_teleop_behavior_launch.py

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,12 @@ def generate_launch_description() -> LaunchDescription:
5050

5151
# Replace the `use_astar` setting on the params file
5252
configured_params = RewrittenYaml(
53-
source_file=params_file, root_key='', param_rewrites={}, convert_types=True
53+
source_file=params_file, root_key='', param_rewrites={},
54+
value_rewrites={
55+
'KEEPOUT_ZONE_ENABLED': 'False',
56+
'SPEED_ZONE_ENABLED': 'False',
57+
},
58+
convert_types=True
5459
)
5560

5661
return LaunchDescription(

nav2_system_tests/src/behaviors/backup/test_backup_behavior.launch.py

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,10 @@ def generate_launch_description() -> LaunchDescription:
4444
source_file=params_file,
4545
root_key='',
4646
param_rewrites=param_substitutions,
47+
value_rewrites={
48+
'KEEPOUT_ZONE_ENABLED': 'False',
49+
'SPEED_ZONE_ENABLED': 'False',
50+
},
4751
convert_types=True,
4852
)
4953

nav2_system_tests/src/behaviors/drive_on_heading/test_drive_on_heading_behavior.launch.py

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,10 @@ def generate_launch_description() -> LaunchDescription:
4444
source_file=params_file,
4545
root_key='',
4646
param_rewrites=param_substitutions,
47+
value_rewrites={
48+
'KEEPOUT_ZONE_ENABLED': 'False',
49+
'SPEED_ZONE_ENABLED': 'False',
50+
},
4751
convert_types=True,
4852
)
4953

nav2_system_tests/src/behaviors/spin/test_spin_behavior.launch.py

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,10 @@ def generate_launch_description() -> LaunchDescription:
4444
source_file=params_file,
4545
root_key='',
4646
param_rewrites=param_substitutions,
47+
value_rewrites={
48+
'KEEPOUT_ZONE_ENABLED': 'False',
49+
'SPEED_ZONE_ENABLED': 'False',
50+
},
4751
convert_types=True,
4852
)
4953

0 commit comments

Comments
 (0)