Skip to content
Merged
Show file tree
Hide file tree
Changes from 4 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
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@ install
__pycache__/
*.py[cod]
.ipynb_checkpoints
.pytest_cache/

sphinx_doc/_build

Expand Down
4 changes: 4 additions & 0 deletions nav2_bringup/launch/bringup_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,10 @@ def generate_launch_description() -> LaunchDescription:
source_file=params_file,
root_key=namespace,
param_rewrites={},
value_rewrites={
'KEEPOUT_ZONE_ENABLED': use_keepout_zones,
'SPEED_ZONE_ENABLED': use_speed_zones,
},
convert_types=True,
),
allow_substs=True,
Expand Down
1 change: 1 addition & 0 deletions nav2_bringup/launch/keepout_zone_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ def generate_launch_description() -> LaunchDescription:
source_file=params_file,
root_key=namespace,
param_rewrites={},
value_rewrites={'KEEPOUT_ZONE_ENABLED': use_keepout_zones},
convert_types=True,
),
allow_substs=True,
Expand Down
1 change: 1 addition & 0 deletions nav2_bringup/launch/speed_zone_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ def generate_launch_description() -> LaunchDescription:
source_file=params_file,
root_key=namespace,
param_rewrites={},
value_rewrites={'SPEED_ZONE_ENABLED': use_speed_zones},
convert_types=True,
),
allow_substs=True,
Expand Down
6 changes: 3 additions & 3 deletions nav2_bringup/params/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -227,7 +227,7 @@ local_costmap:
filters: ["keepout_filter"]
keepout_filter:
plugin: "nav2_costmap_2d::KeepoutFilter"
enabled: True
enabled: KEEPOUT_ZONE_ENABLED
filter_info_topic: "keepout_costmap_filter_info"
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
Expand Down Expand Up @@ -279,11 +279,11 @@ global_costmap:
filters: ["keepout_filter", "speed_filter"]
keepout_filter:
plugin: "nav2_costmap_2d::KeepoutFilter"
enabled: True
enabled: KEEPOUT_ZONE_ENABLED
filter_info_topic: "keepout_costmap_filter_info"
speed_filter:
plugin: "nav2_costmap_2d::SpeedFilter"
enabled: True
enabled: SPEED_ZONE_ENABLED
filter_info_topic: "speed_costmap_filter_info"
speed_limit_topic: "speed_limit"
obstacle_layer:
Expand Down
13 changes: 13 additions & 0 deletions nav2_common/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,3 +15,16 @@ install(
DIRECTORY cmake
DESTINATION share/${PROJECT_NAME}
)

install(
DIRECTORY test
DESTINATION share/${PROJECT_NAME}
)

if(BUILD_TESTING)
find_package(ament_cmake_test REQUIRED)
find_package(ament_cmake_pytest REQUIRED)

ament_add_pytest_test(test_rewritten_yaml test/test_rewritten_yaml.py
)
endif()
43 changes: 39 additions & 4 deletions nav2_common/nav2_common/launch/rewritten_yaml.py
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@ def __init__(
param_rewrites: dict[str, launch.SomeSubstitutionsType],
root_key: Optional[launch.SomeSubstitutionsType] = None,
key_rewrites: Optional[dict[str, launch.SomeSubstitutionsType]] = None,
value_rewrites: Optional[dict[str, launch.SomeSubstitutionsType]] = None,
convert_types: bool = False,
) -> None:
super().__init__()
Expand All @@ -58,6 +59,7 @@ def __init__(
:param: param_rewrites mappings to replace
:param: root_key if provided, the contents are placed under this key
:param: key_rewrites keys of mappings to replace
:param: value_rewrites values to replace
:param: convert_types whether to attempt converting the string to a number or boolean
"""

Expand All @@ -68,6 +70,7 @@ def __init__(
normalize_to_list_of_substitutions(source_file)
self.__param_rewrites = {}
self.__key_rewrites = {}
self.__value_rewrites = {}
self.__convert_types = convert_types
self.__root_key = None
for key in param_rewrites:
Expand All @@ -79,6 +82,11 @@ def __init__(
self.__key_rewrites[key] = normalize_to_list_of_substitutions(
key_rewrites[key]
)
if value_rewrites is not None:
for value in value_rewrites:
self.__value_rewrites[value] = normalize_to_list_of_substitutions(
value_rewrites[value]
)
if root_key is not None:
self.__root_key = normalize_to_list_of_substitutions(root_key)

Expand All @@ -94,11 +102,15 @@ def describe(self) -> str:
def perform(self, context: launch.LaunchContext) -> str:
yaml_filename = launch.utilities.perform_substitutions(context, self.name)
rewritten_yaml = tempfile.NamedTemporaryFile(mode='w', delete=False)
param_rewrites, keys_rewrites = self.resolve_rewrites(context)
data = yaml.safe_load(open(yaml_filename))
param_rewrites, keys_rewrites, value_rewrites = self.resolve_rewrites(context)

with open(yaml_filename, 'r') as yaml_file:
data = yaml.safe_load(yaml_file)

self.substitute_params(data, param_rewrites)
self.add_params(data, param_rewrites)
self.substitute_keys(data, keys_rewrites)
self.substitute_values(data, value_rewrites)
if self.__root_key is not None:
root_key = launch.utilities.perform_substitutions(context, self.__root_key)
if root_key:
Expand All @@ -108,7 +120,7 @@ def perform(self, context: launch.LaunchContext) -> str:
return rewritten_yaml.name

def resolve_rewrites(self, context: launch.LaunchContext) -> \
tuple[dict[str, str], dict[str, str]]:
tuple[dict[str, str], dict[str, str], dict[str, str]]:
resolved_params = {}
for key in self.__param_rewrites:
resolved_params[key] = launch.utilities.perform_substitutions(
Expand All @@ -119,7 +131,12 @@ def resolve_rewrites(self, context: launch.LaunchContext) -> \
resolved_keys[key] = launch.utilities.perform_substitutions(
context, self.__key_rewrites[key]
)
return resolved_params, resolved_keys
resolved_values = {}
for value in self.__value_rewrites:
resolved_values[value] = launch.utilities.perform_substitutions(
context, self.__value_rewrites[value]
)
return resolved_params, resolved_keys, resolved_values

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

def substitute_values(
self, yaml: dict[str, YamlValue],
value_rewrites: dict[str, str]) -> None:

def process_value(value: YamlValue) -> YamlValue:
if isinstance(value, dict):
for k, v in list(value.items()):
value[k] = process_value(v)
return value
elif isinstance(value, list):
return [process_value(v) for v in value]
elif str(value) in value_rewrites:
return self.convert(value_rewrites[str(value)])
return value

for key in list(yaml.keys()):
yaml[key] = process_value(yaml[key])

def updateYamlPathVals(
self, yaml: dict[str, YamlValue],
yaml_key_list: list[str], rewrite_val: YamlValue) -> dict[str, YamlValue]:
Expand Down
4 changes: 4 additions & 0 deletions nav2_common/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,10 @@

<buildtool_export_depend>ament_cmake_core</buildtool_export_depend>

<test_depend>ament_cmake_test</test_depend>
<test_depend>ament_cmake_pytest</test_depend>
<test_depend>python3-pytest</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
Expand Down
133 changes: 133 additions & 0 deletions nav2_common/test/test_rewritten_yaml.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,133 @@
# Copyright (c) 2025 Leander Stephen Desouza
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import os
import tempfile
from typing import Generator

import launch
from launch.substitutions import LaunchConfiguration
from nav2_common.launch import RewrittenYaml
import pytest
import yaml


class TestRewrittenYamlValueRewrites:
"""Test that value rewrites work correctly in RewrittenYaml."""

@pytest.fixture(autouse=True)
def setup_teardown(self) -> Generator[None, None, None]:
# Create a temporary YAML file for testing
self.test_yaml = tempfile.NamedTemporaryFile(mode='w', delete=False)
self.test_yaml.write("""\
param0: placeholder_bool
param1: placeholder_string
param2: placeholder_float
param3: placeholder_int
param4: placeholder_list
param5: placeholder_dict
nested:
param6: placeholder_bool
param7: placeholder_string
param8: placeholder_float
param9: placeholder_int
param10: placeholder_list
param11: placeholder_dict
other_value: 42
list_values:
- placeholder_bool
- placeholder_string
- placeholder_float
- placeholder_int
- placeholder_list
- placeholder_dict
- normal_value
""")
self.test_yaml.close()
yield
os.unlink(self.test_yaml.name)

def test_value_rewrites(self) -> None:
"""Test that value rewrites work for various types."""
# Set up launch configurations for our test values
launch_configurations = {
'test_bool': 'true',
'test_string': 'replaced_string',
'test_float': '3.14',
'test_int': '100',
'test_list': '["string", 42, 2.718, ["sublist_item1", "sublist_item2"]]',
'test_dict': ('{"key1": "value1", "key2": 2, "key3": 3.14, '
'"key4": ["list_item1", "list_item2"]}')
}
context = launch.LaunchContext()
for key, value in launch_configurations.items():
context.launch_configurations[key] = value

value_rewrites = {
'placeholder_bool': LaunchConfiguration('test_bool'),
'placeholder_string': LaunchConfiguration('test_string'),
'placeholder_float': LaunchConfiguration('test_float'),
'placeholder_int': LaunchConfiguration('test_int'),
'placeholder_list': LaunchConfiguration('test_list'),
'placeholder_dict': LaunchConfiguration('test_dict'),
}

rewriter = RewrittenYaml(
source_file=self.test_yaml.name,
param_rewrites={},
value_rewrites=value_rewrites,
convert_types=True,
)
output_file = rewriter.perform(context)

try:
with open(output_file) as f:
result = yaml.safe_load(f)

assert result['param0'] is True
assert result['param1'] == 'replaced_string'
assert result['param2'] == 3.14
assert result['param3'] == 100
assert result['param4'] == \
'["string", 42, 2.718, ["sublist_item1", "sublist_item2"]]'
assert result['param5'] == \
'{"key1": "value1", "key2": 2, "key3": 3.14, "key4": ["list_item1", "list_item2"]}'

# Check nested values
assert result['nested']['param6'] is True
assert result['nested']['param7'] == 'replaced_string'
assert result['nested']['param8'] == 3.14
assert result['nested']['param9'] == 100
assert result['nested']['param10'] == \
'["string", 42, 2.718, ["sublist_item1", "sublist_item2"]]'
assert result['nested']['param11'] == \
'{"key1": "value1", "key2": 2, "key3": 3.14, "key4": ["list_item1", "list_item2"]}'

# Check list values
assert result['list_values'][0] is True
assert result['list_values'][1] == 'replaced_string'
assert result['list_values'][2] == 3.14
assert result['list_values'][3] == 100
assert result['list_values'][4] == \
'["string", 42, 2.718, ["sublist_item1", "sublist_item2"]]'
assert result['list_values'][5] == \
'{"key1": "value1", "key2": 2, "key3": 3.14, "key4": ["list_item1", "list_item2"]}'

# Check other values remain unchanged
assert result['nested']['other_value'] == 42
assert result['list_values'][6] == 'normal_value'

finally:
if os.path.exists(output_file):
os.unlink(output_file)
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,12 @@ def generate_launch_description() -> LaunchDescription:

# Replace the `use_astar` setting on the params file
configured_params = RewrittenYaml(
source_file=params_file, root_key='', param_rewrites={}, convert_types=True
source_file=params_file, root_key='', param_rewrites={},
value_rewrites={
'KEEPOUT_ZONE_ENABLED': 'False',
'SPEED_ZONE_ENABLED': 'False',
},
convert_types=True
)

return LaunchDescription(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,10 @@ def generate_launch_description() -> LaunchDescription:
source_file=params_file,
root_key='',
param_rewrites=param_substitutions,
value_rewrites={
'KEEPOUT_ZONE_ENABLED': 'False',
'SPEED_ZONE_ENABLED': 'False',
},
convert_types=True,
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,10 @@ def generate_launch_description() -> LaunchDescription:
source_file=params_file,
root_key='',
param_rewrites=param_substitutions,
value_rewrites={
'KEEPOUT_ZONE_ENABLED': 'False',
'SPEED_ZONE_ENABLED': 'False',
},
convert_types=True,
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,10 @@ def generate_launch_description() -> LaunchDescription:
source_file=params_file,
root_key='',
param_rewrites=param_substitutions,
value_rewrites={
'KEEPOUT_ZONE_ENABLED': 'False',
'SPEED_ZONE_ENABLED': 'False',
},
convert_types=True,
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,12 @@ def generate_launch_description() -> LaunchDescription:

# Replace the `use_astar` setting on the params file
configured_params = RewrittenYaml(
source_file=params_file, root_key='', param_rewrites={}, convert_types=True
source_file=params_file, root_key='', param_rewrites={},
value_rewrites={
'KEEPOUT_ZONE_ENABLED': 'False',
'SPEED_ZONE_ENABLED': 'False',
},
convert_types=True
)

return LaunchDescription(
Expand Down
4 changes: 4 additions & 0 deletions nav2_system_tests/src/route/test_route_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,10 @@ def generate_launch_description() -> LaunchDescription:
source_file=params_file,
root_key='',
param_rewrites=param_substitutions,
value_rewrites={
'KEEPOUT_ZONE_ENABLED': 'False',
'SPEED_ZONE_ENABLED': 'False',
},
convert_types=True,
)

Expand Down
Loading
Loading