diff --git a/ros2param/ros2param/api/__init__.py b/ros2param/ros2param/api/__init__.py index 3b91e03c0..9ae41f03e 100644 --- a/ros2param/ros2param/api/__init__.py +++ b/ros2param/ros2param/api/__init__.py @@ -62,9 +62,7 @@ def get_parameter_value(*, string_value): try: yaml_value = yaml.safe_load(string_value) except yaml.parser.ParserError: - value.type = ParameterType.PARAMETER_STRING - value.string_value = string_value - return value + yaml_value = string_value if isinstance(yaml_value, bool): value.type = ParameterType.PARAMETER_BOOL @@ -93,7 +91,7 @@ def get_parameter_value(*, string_value): value.string_value = string_value else: value.type = ParameterType.PARAMETER_STRING - value.string_value = string_value + value.string_value = yaml_value return value diff --git a/ros2param/test/test_api.py b/ros2param/test/test_api.py index 6da0ce882..8144539ca 100644 --- a/ros2param/test/test_api.py +++ b/ros2param/test/test_api.py @@ -66,6 +66,28 @@ 'string_value', '["foo", "bar", "buzz"', ), + ( + # With 'off', YAML interprets this as a bool + 'off', + ParameterType.PARAMETER_BOOL, + 'bool_value', + False + ), + ( + # With !!str, text that would otherwise be a bool is a string + '!!str off', + ParameterType.PARAMETER_STRING, + 'string_value', + 'off' + ), + ( + # While YAML supports a mixed-type list, ROS 2 parameters do not, + # so these end up being strings + '[true,0.1,1]', + ParameterType.PARAMETER_STRING, + 'string_value', + '[true,0.1,1]' + ), ], ) def test_get_parameter_value(