Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix: Ensure parameters are initialized with default values if undefined in params.yml #5

Merged

Conversation

nzantopp
Copy link

Description:
This merge request resolves the issue where parameters declared in a Python ROS2 node were not being initialized when missing from params.yml. This caused the parameters to be inaccessible in parameter management tools like rqt and unavailable via ros2 param get commands.


Issue Reference:
Closes #4.


Changes:

  • Modified the parameter declaration logic to ensure parameters are initialized with their default values even when not defined in params.yml.
  • Used set_parameters after declaring the parameters to register them correctly.

Steps to Reproduce:
The issue can be reproduced as follows:

  1. Create a ROS2 node with the following parameter declaration:
    self.param2 = 1
    self.param2 = self.declareAndLoadParameter(name="param2",
                                                param_type=rclpy.Parameter.Type.INTEGER,
                                                description="TODO",
                                                default=self.param2,
                                                from_value=0,
                                                to_value=9,
                                                step_value=1)
  2. Launch the node without defining param2 in params.yml.
  3. Before the fix, no parameters would appear in rqt or via ros2 param get. After the fix, the declared parameter should be initialized and visible.

Testing:

  • Tested locally on ROS2 Humble with Ubuntu 22.04.
  • Verified that:
    • Parameters not defined in params.yml are initialized with default values.
    • These parameters appear in rqt.
    • ros2 param commands (e.g., ros2 param get) correctly display the parameters.

Impact:
This fix does not break existing functionality. Instead, it ensures that declared parameters are initialized properly, even if not defined in external configuration files.


Screenshots/Logs:
(Optional: Include screenshots or logs demonstrating the fix in action. For example, a screenshot of rqt showing the previously missing parameter.)


Code Snippet of the Fix:

# Ensure the parameter is explicitly registered if not provided in params.yml
            else:
                self.get_logger().warn(f"Missing parameter '{name}', using default value: {default}")
                param = default
                self.set_parameters([rclpy.Parameter(name=name, value=param)])

…Solves the problem that the parameter is not set if it is not defined in the parameter file.
@lreiher
Copy link
Member

lreiher commented Nov 20, 2024

Thank you very much for the extensive issue description and the fix!

I have two small requests:

  1. Would you mind also checking if a similar change is required in the C++ template node?
  2. Could you please regenerate the samples by simply running generate_samples.sh and then committing the changes?

@nzantopp
Copy link
Author

Would you mind also checking if a similar change is required in the C++ template node?

  • Similar changes added

Could you please regenerate the samples by simply running generate_samples.sh and then committing the changes?

  • Generated and added

@lreiher lreiher merged commit c7b3afc into ika-rwth-aachen:main Nov 20, 2024
41 of 42 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

Parameters not initialized if undefined in params.yml (Python ROS2 package)
2 participants