ros2 / launch_ros

Tools for launching ROS nodes and for writing tests involving ROS nodes.
Apache License 2.0
59 stars 74 forks source link

Have SetParametersFromFile override node parameters #422

Open robin-zealrobotics opened 1 month ago

robin-zealrobotics commented 1 month ago

Feature request

Feature description

Have SetParametersFromFile (and probably similar functionalities) add the parameters after the ones defined on the nodes themselves. This allows SetParametersFromFile to actually override parameters defined on nodes themselves, which is not possible right now afaik.

Imagine a top-level launch file that launches another launch file with IncludeLaunchDescription, a common practice. The lower-level launch file typically defines default arguments either directly or through some parameter file specific for that launch file or a node in it. On the top-level launch file you can already have multiple SetParametersFromFile after each other, where the latest one overrides the former ones. Allowing to e.g. define robot-model default parameters, overridden by a specific project's parameters, overridden again by specific robot parameters. However, it's not possible to override parameters defined on nodes themselves or lower-level launch files in this same clean way. Also, I don't really see the use case where you would want SetParametersFromFile to NOT override those parameters, or at least I would think this case to be less common than the one I described here.

Implementation considerations

The current idea of parameters is that ones that are defined later/after take priority. This proposed change technically could be confusing as SetParametersFromFile has to be added to the LaunchDescription before the launch-file/node that it is applied to. So maybe another approach could be to be able to have SetParametersFromFile defined after that, but that probably opens a whole other can of worms. So maybe a flag argument 'override'/'add_after'/... on SetParametersFromFile makes more sense and also prevents making breaking changes.

cottsay commented 1 month ago

Hi there, this seems like a fairly complex issue.

Can you provide some example code demonstrating the limitations you're trying to overcome and maybe an example of how you'd like this feature to be used? It might help illustrate the value of the feature and help us understand how to move forward.

robin-zealrobotics commented 4 weeks ago

Imagine a main.launch.py file like this


from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import PathJoinSubstitution
from launch_ros.actions import SetParametersFromFile
from launch_ros.substitutions import FindPackageShare

def generate_launch_description():
    # paths to parameter files
    robot_specific_params
    fleet_specific_params
    robot_default_params

    # launch files of sub-systems
    sub_system_1 = IncludeLaunchDescription(
        PythonLaunchDescriptionSource(
            PathJoinSubstitution(
                [FindPackageShare("robot_launch"), "launch", "controller.launch.py"]
            )
        ),
    )
    sub_system_2 = IncludeLaunchDescription(
        PythonLaunchDescriptionSource(
            PathJoinSubstitution(
                [FindPackageShare("robot_launch"), "launch", "localisation.launch.py"]
            )
        ),
    )
    sub_system_3 = IncludeLaunchDescription(
        PythonLaunchDescriptionSource(
            PathJoinSubstitution(
                [FindPackageShare("robot_launch"), "launch", "hardware.launch.py"]
            )
        ),
    )

    return LaunchDescription(
        [
            SetParametersFromFile(robot_default_params),  # default parameters
            SetParametersFromFile(fleet_specific_params),  # takes precedence over default
            SetParametersFromFile(robot_specific_params),  # takes precedence over fleet
            sub_system_1,
            sub_system_2,
            sub_system_3,
        ]
    )

and the sub-system launch files something like this


from launch import LaunchDescription
from launch_ros.actions import Node

def generate_launch_description():
    # paths to parameter files
    sub_system_default_params

    # nodes
    node_1 = Node(
        package="hardware",
        executable="node_1",
        parameters=[sub_system_default_params, {"node_default_param": "value"}],
    )
    node_2 = Node(
        package="hardware",
        executable="node_2",
        parameters=[sub_system_default_params, {"node_default_param": "value"}],
    )
    node_3 = Node(
        package="hardware",
        executable="node_3",
        parameters=[sub_system_default_params, {"node_default_param": "value"}],
    )

    return LaunchDescription(
        [
            node_1,
            node_2,
            node_3,
        ]
    )

You have parameters at 5 different levels in this example (of course this could be extended), with a certain priority to them in terms of which one overrides the other. With the current codebase the priority in this example will be this (higher in the list overrides lower in the list)

Now actually, it's easy to change a few priorities here, with one meaningful exception. Any parameters defined in the sub-system launch file always take precedence over the ones defined using SetParametersFromFile. This to me feels like the complete opposite of what common use cases would want. Anyone using SetParametersFromFile or SetParameter in a main launch file probably wants parameters set to that value regardless of what sub-launch files have defined. The 'last' parameter you apply should get precedence, and while technically this is the ones defined on the node if you read the code here, from a launch-file structure perspective, parameters you would define in the main launch file feel more like the 'last' defined parameters.

But as we can't just put SetParametersFromFile after the inclusion of a launch file we don't have that option and I don't see a clean way of getting this functionality without having to pass all parameters individually or having to pass any 'robot-specific' or 'fleet-specific' parameter files (or other ones you would want) down to the launch files and adding it to the parameters-list of all nodes. That's just basically doing SetParametersFromFile manually, just to get those parameters to be declared last, making them take precedence. So why not have a flag on SetParametersFromFile instead to toggle this behavior?

So with the example code given above, currently a node would be launched like this


some_node \
    --ros-args \
    --params-file robot_default.yaml \
    --params-file fleet_specific.yaml \
    --params-file robot_specific.yaml \
    --params-file sub_system_default.yaml \
    --params-file /tmp/launch_params_l52gf7ks  # consisting of whatever is defined on the node itself

While it would be nice to have the option to have it launch like this instead


some_node \
    --ros-args \
    --params-file sub_system_default.yaml \
    --params-file /tmp/launch_params_l52gf7ks \  # consisting of whatever is defined on the node itself
    --params-file robot_default.yaml \
    --params-file fleet_specific.yaml \
    --params-file robot_specific.yaml

And because everything else already works nicely to override parameters, this new option would make it very easy to define parameters starting from defaults on a node-level, going to a sub-system level, going to a main launch file, going to specifics for a fleet of robots, going to specifics of a single robot, .... Basically going more and more specific, overriding defaults in previous levels.

And of course a similar argument can be made for SetParameter.