ros2 / launch_ros

Tools for launching ROS nodes and for writing tests involving ROS nodes.

Geek Repo:Geek Repo

Github PK Tool:Github PK Tool

ComposableNode.parameters with a file path does not take effect.

dawonn-haval opened this issue · comments

Bug report

  1. I used ros2 param dump /exampleConfig to generate exampleConfig.yaml.
  2. I set parameters=['/module/exampleConfig.yaml'] in my ComposableNode within a launch.py file
  3. The parameters were not set, but I do get a warning from libyaml, so I think it's trying but not succeeding...

Required Info:

  • Operating System: Ubuntu 20.04
  • Installation type: Binary
  • Version or commit hash: Foxy
  • DDS implementation: Fast-RTPS
  • Client library (if applicable): rclpy

Steps to reproduce issue

launch.py

"""Launch in a component container."""

import launch
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode


def generate_launch_description():
    """Generate launch description with multiple components."""
    ld = launch.LaunchDescription()

    ld.add_action(ComposableNodeContainer(
        name='example_container',
        namespace=[],
        package='rclcpp_components',
        executable='component_container',

        composable_node_descriptions=[
            ComposableNode(
                package='example',
                plugin='ExampleConfig',
                name='exampleConfig',
                parameters=['/module/exampleConfig.yaml']),
        ],
        output='screen',
    ))
    return ld

example_config.cc

#include <cstdint>
#include <iostream>

#include "rclcpp/rclcpp.hpp"

/**
 * This Example Class is used to show how to read parameters stored in the
 * params.yaml.
 */
class ExampleConfig : public rclcpp::Node {
   public:
    explicit ExampleConfig(const rclcpp::NodeOptions &options)
        // The node name `config` is used in the params.yaml file.
        : Node("config", options) {
        RCLCPP_INFO(this->get_logger(), "Starting %s.", this->get_name());

        // Parameters

        // example int (meters)
        // This is a simple example of an integer parameter
        int example_int = declare_parameter("example_int", 42);

        // example float (hz)
        // This is a simple example of an float parameter
        double example_float = declare_parameter("example_float", 23.0);

        // example string
        // This is a simple example of an string parameter
        std::string example_string =
            declare_parameter("example_string", std::string("Default Value"));

        // Log the parameter values as an example
        RCLCPP_INFO(this->get_logger(), "example_int: %d", example_int);
        RCLCPP_INFO(this->get_logger(), "example_float: %f", example_float);
        RCLCPP_INFO(this->get_logger(), "example_string: %s", example_string.c_str());

        // flushes values from the buffer to the active log.
        std::flush(std::cout);
    }

   private:
    // Prevents this Node from being copied
    RCLCPP_DISABLE_COPY(ExampleConfig)
};

// Used to register this node as a ros 2 component
#include "rclcpp_components/register_node_macro.hpp"
RCLCPP_COMPONENTS_REGISTER_NODE(ExampleConfig)

exampleConfig.yaml

exampleConfig:
  ros__parameters:
    example_int: 98765
    example_float: 9.8765
    example_string: "example"
    use_sim_time: false

Expected behavior

parameters should be set in the node

Actual behavior

parameters are not set

Additional information

Here's the console output of the above:

[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [component_container-1]: process started with pid [12476]
/opt/ros/foxy/lib/python3.8/site-packages/launch_ros/utilities/to_parameters_list.py:49: YAMLLoadWarning: calling yaml.load() without Loader=... is deprecated, as the default Loader is unsafe. Please read https://msg.pyyaml.org/load for full details.
  context, normalize_parameter_dict(yaml.load(f))
[component_container-1] [INFO] [1592763714.853802170] [example_container]: Load Library: /module/install/example/lib/libexample_config.so
[component_container-1] [INFO] [1592763714.854225507] [example_container]: Found class: rclcpp_components::NodeFactoryTemplate<ExampleConfig>
[component_container-1] [INFO] [1592763714.854239504] [example_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ExampleConfig>
[component_container-1] [INFO] [1592763714.856834111] [exampleConfig]: Starting exampleConfig.
[component_container-1] [INFO] [1592763714.856919332] [exampleConfig]: example_int: 42
[component_container-1] [INFO] [1592763714.856931555] [exampleConfig]: example_float: 23.000000
[component_container-1] [INFO] [1592763714.856943773] [exampleConfig]: example_string: Default Value
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/exampleConfig' in container '/example_container'

Not sure if I should make another issue, but I also discovered that the launch will hang if the specified parameter file doesn't exist.

Appears to hang here @ yaml.load()
https://github.com/ros2/launch_ros/blob/master/launch_ros/launch_ros/utilities/to_parameters_list.py#L48

Progress Report;

The YAML file format is different when loading parameters with the ComposableNode Parameters option compared to the function that was in Dashing. This works:

exampleConfig.yaml

example_int: 98765
example_float: 9.8765
example_string: "example"

This is in contrast to the --ros-args --params-file format.

I think someone with broader ros2 architecture & design intent knowledge should review this issue briefly. Essentially, ROS2 currently has two different parameter file formats, which seems less than ideal. I think it makes sense to extend launch_ros to support the same file format as the --params-file flag in rcl.

It's not exactly an 'easy' task though; to_parameters_list() would need access the current node name to be able to extract the correct parameters. Could be done though... Thoughts?

I think someone with broader ros2 architecture & design intent knowledge should review this issue briefly. Essentially, ROS2 currently has two different parameter file formats, which seems less than ideal. I think it makes sense to extend launch_ros to support the same file format as the --params-file flag in rcl.

It's not exactly an 'easy' task though; to_parameters_list() would need access the current node name to be able to extract the correct parameters. Could be done though... Thoughts?

Yeah, it will need to access the current node name.
That's only possible if the user passed both the node name and namespace.
In that case, the parameters can be easily extracted from the file.

See this comment for more details.

Not sure if I should make another issue, but I also discovered that the launch will hang if the specified parameter file doesn't exist.

Can you share an example to reproduce that problem?
I find quite strange that it hangs

@ivanpauno here is an example producing the error. You can run it locally.

Right now the yaml reads:

L1: 2.0 # length of link 1 (m)
L2: 1.0 # length of link 2 (m)
T: 20.0 # duration of one trajectory cycle (s)

and the params are loaded correctly.

Modify it to (as shown in the ros2 tutorials):

simple_arm:
  ros__parameters:
    L1: 2.0 # length of link 1 (m)
    L2: 1.0 # length of link 2 (m)
    T: 20.0 # duration of one trajectory cycle (s)

and the params will not be visible for the simple_arm node when running ros2 param list.

and the params will not be visible for the simple_arm node when running ros2 param list.

It's known that the format is different, and it's probably something we should modify.
My question was particularly about the launch process "hanging" if it doesn't found a parameter, but I'm not sure how that could happen and it doesn't seem to happen in your example.

Duplicate of this well known issue:

ros2/rclcpp#715

I think that using a bit of logic to support both file formats, the one that starts with <node_name>: ros__parameters: and the one that's directly a parameters dict would be fine.

For supporting both, either deprecating the parameters argument in ComposableNode in favor of one supporting the new format or using the same argument and detecting at runtime what format is being used, would be fine. The second option would be a bit ambiguous, but I hope nobody wants to write ros__parameters in their parameter name.

What would need to be fixed is the line here:

context, normalize_parameter_dict(yaml.safe_load(f))

My two cents: I strongly prefer solution 2

Has this issue been solved?
I just faced it today working with a launch file to demonstrate how to use ComposableNode with the ZED ROS2 wrapper with ROS2 Foxy

This is still present in Rolling. What is the path forward?