launch_ros icon indicating copy to clipboard operation
launch_ros copied to clipboard

Error when setting parameter with list of strings via substitution

Open paulerikf opened this issue 1 year ago • 3 comments

Bug report

Required Info:

  • Operating System:
    • Ubuntu 20.04
  • Installation type:
    • Source
  • Version or commit hash:
    • a9a9bc4
  • DDS implementation:
    • cyclonedds
  • Client library (if applicable):
    • N/A

Steps to reproduce issue

Hopefully I'm not misunderstanding something major about substitutions here, please let me know if I am.

I'm attempting to set a parameter value with a substitution that returns a list of strings. Everything is fine if I set the parameter value with a normal list i.e: 'ingredients': ['apples', 'oranges', 'berries']. However, when I use a Substitution that returns the same list I get an error.

Simple test node that gets a string list parameter:

import rclpy
from rclpy.node import Node

class Dummy(Node):
    def __init__(self):
        super().__init__('dummy_node')
        self.declare_parameter('ingredients', rclpy.Parameter.Type.STRING_ARRAY)
        
        ingredients = self.get_parameter('ingredients').value
        self.get_logger().info(f"Got ingredients: {ingredients}")

def main(args=None):
    rclpy.init(args=args)
    dummy_node = Dummy()
    rclpy.spin(dummy_node)
    dummy_node.destroy_node()
    rclpy.shutdown()

if __name__ == '__main__':
    main()

Launch file example:

from launch import LaunchDescription, Substitution
from launch.actions import DeclareLaunchArgument, Shutdown
from launch.substitutions import LaunchConfiguration

from launch_ros.actions import Node


class IngredientsSubstitution(Substitution):
    def __init__(self, use_grapes, use_apples, use_oranges):
        self.use_grapes = use_grapes
        self.use_apples = use_apples
        self.use_oranges = use_oranges

    def perform(self, context):
        # base ingredients
        ingredients = ['berries', 'chocolate']

        if self.use_grapes.perform(context).lower() == 'true':
            ingredients.append('grapes')
        if self.use_apples.perform(context).lower() == 'true':
            ingredients.append('apples')
        if self.use_oranges.perform(context).lower() == 'true':
            ingredients.append('oranges')

        return ingredients

def generate_launch_description():
    use_apples = LaunchConfiguration('use_apples', default='true')
    declare_use_apples = DeclareLaunchArgument('use_apples', default_value='true')

    use_grapes = LaunchConfiguration('use_grapes', default='true')
    declare_use_grapes = DeclareLaunchArgument('use_grapes', default_value='true')

    use_oranges = LaunchConfiguration('use_oranges', default='true')
    declare_use_oranges = DeclareLaunchArgument('use_oranges', default_value='true')

    recipe_node = Node(
            name='dummy_node',
            namespace='',
            package='kef_py_utils',
            executable='dummy',
            parameters = [{
                    'ingredients': IngredientsSubstitution(use_grapes, use_apples, use_oranges),
                    }],
            output='screen',
            on_exit=Shutdown(),
            )

    return LaunchDescription([
        declare_use_oranges,
        declare_use_grapes,
        declare_use_apples,
        recipe_node,
        ])

Expected behavior

I expect the parameter to be set to the result of the substitution. In this case, a list of strings (in the example: ['berries', 'chocolate', 'grapes', 'apples', 'oranges']).

This feels like it should be in line with the description of possible parameter values in normalize_parameters.py

Actual behavior

It seems like it's being treated as a list of substitutions: https://github.com/ros2/launch_ros/blob/bc609787102ae1c0b8ad2ee9dbecf0165a9108a2/launch_ros/launch_ros/utilities/evaluate_parameters.py#L69-L72

And therefore an attempt is made to convert it into a string: https://github.com/ros2/launch/blob/dd6ab0edf19c2f35b8e71aa8151df50b8a2feff9/launch/launch/utilities/perform_substitutions_impl.py#L24-L26

def perform_substitutions(context: LaunchContext, subs: List[Substitution]) -> Text:
    """Resolve a list of Substitutions with a context into a single string."""
    return ''.join([context.perform_substitution(sub) for sub in subs])

Which results in: TypeError: sequence item 0: expected str instance, list found

However this is just a single substitution. It would be great if it wasn't treated as a list of them.

Full stacktrace:

[DEBUG] [launch]: An exception was raised in an async action/event
[DEBUG] [launch]: Traceback (most recent call last):
  File "/home/frivold/kef_env/warm_dep_ws/build/launch/launch/launch_service.py", line 336, in run_async
    raise completed_tasks_exceptions[0]
  File "/home/frivold/kef_env/warm_dep_ws/build/launch/launch/launch_service.py", line 230, in _process_one_event
    await self.__process_event(next_event)
  File "/home/frivold/kef_env/warm_dep_ws/build/launch/launch/launch_service.py", line 250, in __process_event
    visit_all_entities_and_collect_futures(entity, self.__context))
  File "/home/frivold/kef_env/warm_dep_ws/build/launch/launch/utilities/visit_all_entities_and_collect_futures_impl.py", line 45, in visit_all_entities_and_collect_futures
    futures_to_return += visit_all_entities_and_collect_futures(sub_entity, context)
  File "/home/frivold/kef_env/warm_dep_ws/build/launch/launch/utilities/visit_all_entities_and_collect_futures_impl.py", line 45, in visit_all_entities_and_collect_futures
    futures_to_return += visit_all_entities_and_collect_futures(sub_entity, context)
  File "/home/frivold/kef_env/warm_dep_ws/build/launch/launch/utilities/visit_all_entities_and_collect_futures_impl.py", line 45, in visit_all_entities_and_collect_futures
    futures_to_return += visit_all_entities_and_collect_futures(sub_entity, context)
  [Previous line repeated 1 more time]
  File "/home/frivold/kef_env/warm_dep_ws/build/launch/launch/utilities/visit_all_entities_and_collect_futures_impl.py", line 38, in visit_all_entities_and_collect_futures
    sub_entities = entity.visit(context)
  File "/home/frivold/kef_env/warm_dep_ws/build/launch/launch/action.py", line 108, in visit
    return self.execute(context)
  File "/home/frivold/kef_env/warm_dep_ws/build/launch_ros/launch_ros/actions/node.py", line 490, in execute
    self._perform_substitutions(context)
  File "/home/frivold/kef_env/warm_dep_ws/build/launch_ros/launch_ros/actions/node.py", line 445, in _perform_substitutions
    evaluated_parameters = evaluate_parameters(context, self.__parameters)
  File "/home/frivold/kef_env/warm_dep_ws/build/launch_ros/launch_ros/utilities/evaluate_parameters.py", line 178, in evaluate_parameters
    output_params.append(evaluate_parameter_dict(context, param))
  File "/home/frivold/kef_env/warm_dep_ws/build/launch_ros/launch_ros/utilities/evaluate_parameters.py", line 72, in evaluate_parameter_dict
    evaluated_value = perform_substitutions(context, list(value))
  File "/home/frivold/kef_env/warm_dep_ws/build/launch/launch/utilities/perform_substitutions_impl.py", line 26, in perform_substitutions
    return ''.join([context.perform_substitution(sub) for sub in subs])
TypeError: sequence item 0: expected str instance, list found

[ERROR] [launch]: Caught exception in launch (see debug for traceback): sequence item 0: expected str instance, list found

Additional information

I was able to hack my way around this by adding a ListSubstitution type to launch/substitutions, and modifying evaluate_parameters.py to check for a ListSubstitution.

if isinstance(value, tuple) and len(value):
    if len(value) == 1 and isinstance(value[0], ListSubstitution):
        evaluated_value = value[0].perform(context)
    elif isinstance(value[0], Substitution):
        # Value is a list of substitutions, so perform them to make a string
        evaluated_value = perform_substitutions(context, list(value))

But I don't really know my way around the launch / launch_ros codebase, so I'm not sure that's a very clean solution.

paulerikf avatar Oct 22 '23 18:10 paulerikf

I now realize that I can work around this issue by having the substitution return a string with the list specified in yaml format. Would still be nice to be able to use a singular substitution that returns a non-string.

paulerikf avatar Oct 22 '23 19:10 paulerikf

@adityapande-1995 @methylDragon would one of you be willing to try reproducing this on rolling? 🧇

sloretz avatar Nov 02 '23 20:11 sloretz

I'm also having the same traceback on Humble and workedaround it for the moment. I haven't yet pinpointed where the issue comes from to create a minimal reproducible example, I'll try to find some time for it

tonynajjar avatar Feb 07 '24 09:02 tonynajjar