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

ros2 param dump: null breaks round-trip numerical parameters #965

Open
b-adkins opened this issue Jan 28, 2025 · 3 comments
Open

ros2 param dump: null breaks round-trip numerical parameters #965

b-adkins opened this issue Jan 28, 2025 · 3 comments
Labels
more-information-needed Further information is required

Comments

@b-adkins
Copy link

Summary

ros2 param dump sometimes produces invalid YAML for a ros2 run. I would think that round-trip ROS params are a desirable feature. (Named after round-trip YAML.)

User Story

My user story is that I wish to use my IDE to debug a ROS node with insanely complex params - a full MoveIt config (462 lines long).

This is not specific to MoveIt, but is instead an example of ros2 param at scale. It is not feasible to manually convert every key to a command line arg or to ros2 param set them individually.

What I've been doing is:

  1. ros2 launch the node (using the moveit config builder)
  2. Get all its params:
    ros2 param dump /my_moveit_node > params.yaml
    
  3. In the IDE, load the params from the YAML file:
    ros2 run my_pkg my_moveit_node --ros-args --params-file params.yaml
    

Expected behavior

It loads as is and I only have to regenerate the YAML file when the ros2 launch config changes.

Actual behavior

Sometimes, the node halts.

terminate called after throwing an instance of 'rclcpp::exceptions::InvalidParameterTypeException'
  what():  parameter 'robot_description_planning.joint_limits.joint_1.max_position' has invalid type: expected [double] got [string]

The YAML file contains

/my_moveit_node:
  ros__parameters:
    robot_description_planning:
      joint_limits:
        joint_1:
          has_acceleration_limits: false
          has_jerk_limits: null
          has_velocity_limits: true
          max_acceleration: 0
          max_position: null
          max_velocity: 1.5
          min_position: null

I didn't set the null values. I have never even seen these keys. I am guessing they were filled in automatically by some declaration magic.

Requested behavior

Support round-trip params.

  1. During ros2 param dump, do not fill in unset param values with null.
  2. If there is a good reason to dump null, make it toggleable with a command-line flag.

Suggested Workaround

Use bash-fu on your params file to delete any line containing the text null

sed -i '/null/d' params.yaml

(You could also use grep -v, but I find this shorter)

Environment

Ubuntu 22.04
ROS2 humble

@fujitatomoya
Copy link
Collaborator

@b-adkins thanks for creating issue. there are a few things i want to confirm.

I didn't set the null values.

then what value did you set?

  • can you ros2 param describe /my_moveit_node robot_description_planning.joint_limits.joint_1.max_position? it seems that is statically typed with double from the exception message.
  • Do you use rclcpp for /my_moveit_node that parameters are dumped into the yaml file? i am asking this because of forbid parameter to be declared statically without initialization. rclpy#1216. static typed parameter declaration behavior is different from rclcpp and rclpy, rclpy did not get forbid parameter to be declared statically without initialization. rclpy#1216 that means we can declare the static type parameter without default value but rclcpp.
  • Do you use dynamic_typing == true (default false) to declare robot_description_planning.joint_limits.joint_1.max_position? i am assuming this is No, if you are using dynamic_typing parameter, this parameter typed exception should not be thrown.

for rolling, we have related issue like this.

if we have dynamic typing parameter without default value, that is going to be dumped as null in yaml format. this is the same for rclcpp and rclpy nodes.

/param_demo_cpp:
  ros__parameters:
    param_2_cpp: null
    qos_overrides:
      /parameter_events:
        publisher:
          depth: 1000
          durability: volatile
          history: keep_last
          reliability: reliable
    start_type_description_service: true
    use_sim_time: false
/param_demo_py:
  ros__parameters:
    param_2_py: null
    start_type_description_service: true
    use_sim_time: false

this seems to be okay as yaml, yaml converts the None value into null during dump process.
but the problem comes up when we are loading those null values to the nodes, as reported in this issue, those null values will be converted into string types. this is bad deduction, i think.

### ros2 run prover_rclpy ros2cli_965 --ros-args --params-file ./test_param_py.yaml
root@tomoyafujita:~/ros2_ws/colcon_ws# ros2 param dump /param_demo_py
/param_demo_py:
  ros__parameters:
    param_2_py: 'null'
    start_type_description_service: true
    use_sim_time: false

root@tomoyafujita:~/ros2_ws/colcon_ws# ros2 param describe /param_demo_py param_2_py
Parameter name: param_2_py
  Type: string
  Constraints:

### ros2 run prover_rclcpp ros2cli_965 --ros-args --params-file ./test_param_cpp.yaml
root@tomoyafujita:~/ros2_ws/colcon_ws# ros2 param dump /param_demo_cpp
/param_demo_cpp:
  ros__parameters:
    param_2_cpp: 'null'
    qos_overrides:
      /parameter_events:
        publisher:
          depth: 1000
          durability: volatile
          history: keep_last
          reliability: reliable
    start_type_description_service: true
    use_sim_time: false

root@tomoyafujita:~/ros2_ws/colcon_ws# ros2 param describe /param_demo_cpp param_2_cpp
Parameter name: param_2_cpp
  Type: string
  Constraints:

i think dump should save the all declared parameters even those have null values with dynamic typing (this is still useful for the user to see the all parameters without reloading), that said dump process works okay.
but the problem is loading process via rcl_yaml_param_parser. i believe that it should skip setting values if null, technically skipping is the only way to go because it cannot deduce the type if that value is actually null.

fujitatomoya added a commit to fujitatomoya/ros2_test_prover that referenced this issue Jan 29, 2025
@Yadunund
Copy link
Member

Yadunund commented Feb 6, 2025

@b-adkins could you please follow up on @fujitatomoya's feedback?

@Yadunund Yadunund added the more-information-needed Further information is required label Feb 6, 2025
@b-adkins
Copy link
Author

b-adkins commented Mar 7, 2025

Do you use rclcpp for /my_moveit_node that parameters are dumped into the yaml file? i am asking this because of forbid parameter to be declared statically without initialization. rclpy#1216. static typed parameter declaration behavior is different from rclcpp and rclpy, rclpy did not get forbid parameter to be declared statically without initialization. rclpy#1216 that means we can declare the static type parameter without default value but rclcpp.

Yes, it's a rclcpp node.

Do you use dynamic_typing == true (default false) to declare robot_description_planning.joint_limits.joint_1.max_position? i am assuming this is No, if you are using dynamic_typing parameter, this parameter typed exception should not be thrown.

I use:

    rclcpp::NodeOptions().
      allow_undeclared_parameters(true).
      automatically_declare_parameters_from_overrides(true)

In my experience, this is required for MoveIt to load all of the config yaml files in your _moveit_config package. If these aren't both set, then the values will silently not be loaded, and the params will be set to default values. (Which is a problem if you want to configure things like the kinematics or ompl.)

then what value did you set?

I modified the file my_robot_moveit_config/config/joint_limits.yaml, generated by moveit's setup assistant, to contain

joint_limits:
    joint_1:
          has_velocity_limits: true
          max_velocity: 1.5
          has_acceleration_limits: false
          max_acceleration: 0
    joint_2:
          has_velocity_limits: true
          max_velocity: 1.0
          has_acceleration_limits: true
          max_acceleration: 9.81

MoveIt's config builder loads that into name spaces for the move_group node, my_moveit_node (which contains a MoveGroupInterface), the robot state publisher, rviz, etc. It does the same for other config files, such as

initial_positions.yaml  joint_limits.yaml  kinematics.yaml  moveit_controllers.yaml  pilz_cartesian_limits.yaml  ros2_controllers.yaml

To readers not familiar with MoveIt:

These configs can contain literally hundreds of keys and values. To get an idea of the scope, look at https://github.com/moveit/panda_moveit_config/blob/rolling-devel/config/ompl_planning.yaml . MoveIt is an old ROS 1 library, from before there were static types and when the param server was global. Due to it having a plugin architecture, I don't know if they can ever do static types.

I believe this is the part of the code that, thanks to those node options, by asking for the values, causes them to be declared.
https://github.com/moveit/moveit2/blob/humble/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.hpp

can you ros2 param describe /my_moveit_node robot_description_planning.joint_limits.joint_1.max_position? it seems that is statically typed with double from the exception message.

$ ros2 param describe /my_moveit_node robot_description_planning.joint_limits.joint_1.max_position
Parameter name: robot_description_planning.joint_limits.p1_left/j1_motion_table_x.max_position
  Type: double
  Constraints:
$ ros2 param describe /my_moveit_node robot_description_planning.joint_limits.joint_1.has_jerk_limits
Parameter name: robot_description_planning.joint_limits.p1_left/j1_motion_table_x.has_jerk_limits
  Type: boolean
  Constraints:

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
more-information-needed Further information is required
Projects
None yet
Development

No branches or pull requests

3 participants