Skip to content

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

Closed
@dawonn-haval

Description

@dawonn-haval

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'

Metadata

Metadata

Labels

bugSomething isn't working

Type

No type

Projects

No projects

Milestone

No milestone

Relationships

None yet

Development

No branches or pull requests

Issue actions