ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
2

Load yaml parameters conditionally in python launch file

asked 2022-06-22 09:45:30 -0500

vrichard gravatar image

I would like to use a launch parameter to decide whether to load a yaml file, or chose which yaml to load if I have many configuration

For example in ROS1 it would be possible to write something like this:

<arg name="load_config_X" default="true"/>
<arg name="config_type" default="config_A"/>    

<node ...>
    <rosparam if="$(eval arg('load_config_X') == True)" command="load" file="..." />
    <rosparam if="$(eval arg('config_type') == 'config_A') " command="load" file="..." />
    <rosparam if="$(eval arg('config_type') == 'config_B') " command="load" file="..." />
</node>

Is there any equivalent to this in ROS2 python files?

load_config_X = DeclareLaunchArgument("load_config_X", default_value=False)
config_type = DeclareLaunchArgument("config_type", default_value='config_A')

my_node = Node(
    package='my_pkg',
    name='my_node',
    executable='my_node',
    parameters=[
         # ???
         # os.path.join('path', 'to', 'config_X.yaml'),
         # os.path.join('path', 'to', 'config_A.yaml'),
    ]
)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2022-06-22 20:26:40 -0500

vrichard gravatar image

Found my way in the launch/launch_ros source code:

For example it is possible to switch between 2 configs A/B with SetLaunchConfiguration like this:

launch_configuration.append(SetLaunchConfiguration("yaml_config", "config_A.yaml", condition=UnlessCondition(LaunchConfiguration("some_option"))))
launch_configuration.append(SetLaunchConfiguration("yaml_config", "config_B.yaml", condition=IfCondition(LaunchConfiguration("some_option"))))

my_node = Node(
    package='my_pkg',
    name='my_node',
    executable='my_node',
    parameters=[
        PathJoinSubstitution([FindPackageShare('my_pkg'), 'config', LaunchConfiguration('yaml_config')])
    ]
)

There is also LaunchConfigurationEquals for non boolean tests:

condition=IfCondition(LaunchConfigurationEquals("config_type", "config_A"))

And to trigger loading with a bool, the full path could be set into a SetLaunchConfiguration like this:

launch_configuration.append(SetLaunchConfiguration("yaml_config",  PathJoinSubstitution([FindPackageShare('my_pkg'), 'config', 'config_X.yaml'), condition=IfCondition(LaunchConfiguration("load_config_X"))))
# ...
my_node = Node(
    # ...
    parameters=[
        LaunchConfiguration('yaml_config'),
    ]
)

At the end of the day, it was not complicated, unfortunately the launch api is not documented yet :(

edit flag offensive delete link more

Comments

Although it works, the solution is quickly cumbersome. A better approach is to use OpaqueFunction like here and .perform(context) to evaluate parameters value directly in the script

vrichard gravatar image vrichard  ( 2022-06-23 03:52:35 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2022-06-22 09:45:30 -0500

Seen: 452 times

Last updated: Jun 22 '22