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

Parser Error Couldn't parse parameter override rule - loading tricycle_controller from ros2_control #295

Open
ipa-ych opened this issue Mar 26, 2024 · 20 comments

Comments

@ipa-ych
Copy link

ipa-ych commented Mar 26, 2024

Hi,

I have been trying to apply ros2_control tricycle_controller to cutomized robot model with three-wheel-layout. I am using gazebo 11 classic and ROS2 humble (with all required packages installed)
I was following the tricycle_controller_tutorial (https://github.com/ros-controls/gazebo_ros2_control/blob/master/gazebo_ros2_control_demos/config/tricycle_drive_controller.yaml) to create tricycle_drive_controller.yaml and adding ros2_control & gazebo plugins to robot urdf file. In tricycle_drive_controller.yaml file, the traction_joint_name and steering_joint_name have been changed to match joints in the urdf model. The urdf can be correctly launched in rviz and geometry relationships are also correct.

However, when trying to run the launch file, the process always get stucked with parsing .yaml file and tricycle_controller cannot be launched. The Errorlog is as follow:

[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [gzserver-1]: process started with pid [88170]
[INFO] [gzclient-2]: process started with pid [88172]
[INFO] [robot_state_publisher-3]: process started with pid [88174]
[INFO] [spawn_entity.py-4]: process started with pid [88176]
[robot_state_publisher-3] [INFO] [1711449464.561027939] [robot_state_publisher]: got segment b_caster_r_wheel_link
[robot_state_publisher-3] [INFO] [1711449464.561137198] [robot_state_publisher]: got segment b_caster_rotation_link
[robot_state_publisher-3] [INFO] [1711449464.561151908] [robot_state_publisher]: got segment base_charger_link
[robot_state_publisher-3] [INFO] [1711449464.561160904] [robot_state_publisher]: got segment base_chassis_link
[robot_state_publisher-3] [INFO] [1711449464.561167991] [robot_state_publisher]: got segment base_footprint
[robot_state_publisher-3] [INFO] [1711449464.561174532] [robot_state_publisher]: got segment base_laser_front_link
[robot_state_publisher-3] [INFO] [1711449464.561181322] [robot_state_publisher]: got segment base_laser_left_link
[robot_state_publisher-3] [INFO] [1711449464.561189203] [robot_state_publisher]: got segment base_laser_right_link
[robot_state_publisher-3] [INFO] [1711449464.561196624] [robot_state_publisher]: got segment base_link
[robot_state_publisher-3] [INFO] [1711449464.561204047] [robot_state_publisher]: got segment fl_caster_r_wheel_link
[robot_state_publisher-3] [INFO] [1711449464.561211269] [robot_state_publisher]: got segment fl_caster_rotation_link
[robot_state_publisher-3] [INFO] [1711449464.561218172] [robot_state_publisher]: got segment fr_caster_r_wheel_link
[robot_state_publisher-3] [INFO] [1711449464.561225172] [robot_state_publisher]: got segment fr_caster_rotation_link
[spawn_entity.py-4] [INFO] [1711449464.905791202] [spawn_entity]: Spawn Entity started
[spawn_entity.py-4] [INFO] [1711449464.906083173] [spawn_entity]: Loading entity published on topic robot_description
[spawn_entity.py-4] /opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/qos.py:307: UserWarning: DurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL is deprecated. Use DurabilityPolicy.TRANSIENT_LOCAL instead.
[spawn_entity.py-4]   warnings.warn(
[spawn_entity.py-4] [INFO] [1711449464.908141048] [spawn_entity]: Waiting for entity xml on robot_description
[spawn_entity.py-4] [INFO] [1711449464.919340387] [spawn_entity]: Waiting for service /spawn_entity, timeout = 30
[spawn_entity.py-4] [INFO] [1711449464.919750535] [spawn_entity]: Waiting for service /spawn_entity
[spawn_entity.py-4] [INFO] [1711449465.424156357] [spawn_entity]: Calling service /spawn_entity
[gzserver-1] [INFO] [1711449465.626481917] [base_gazebo_ros_bumper_controller]: Publishing contact states to [/bumper_states]
[spawn_entity.py-4] [INFO] [1711449465.957910654] [spawn_entity]: Spawn status: SpawnEntity: Successfully spawned entity [cob4-25]
[gzserver-1] [INFO] [1711449466.010219988] [gazebo_ros2_control]: Loading gazebo_ros2_control plugin
[gzserver-1] [INFO] [1711449466.013500873] [gazebo_ros2_control]: Starting gazebo_ros2_control plugin in namespace: /
[gzserver-1] [INFO] [1711449466.013541761] [gazebo_ros2_control]: Starting gazebo_ros2_control plugin in ros 2 node: gazebo_ros2_control
[gzserver-1] [INFO] [1711449466.017293996] [gazebo_ros2_control]: connected to service!! robot_state_publisher
[gzserver-1] [INFO] [1711449466.019974784] [gazebo_ros2_control]: Received urdf from param server, parsing...
[gzserver-1] [INFO] [1711449466.020466875] [gazebo_ros2_control]: Loading parameter files /home/nhg-yc/ros2_ws/cob_ws/install/cob_hardware_config/share/cob_hardware_config/robots/cob4-25/config/tricycle_drive_controller.yaml
[gzserver-1] [rcutils|error_handling.c:65] an error string (message, file name, or formatted message) will be truncated
[gzserver-1] [ERROR] [1711449466.021404819] [gazebo_ros2_control]: parser error Couldn't parse parameter override rule: '--param robot_description:=<?xml version="1.0" ?><!-- =================================================================================== --><!-- |    This document was autogenerated by xacro from cob4-25.urdf-base.xacro        | --><!-- |    EDITING THIS FILE BY HAND IS NOT RECOMMENDED                                 | --><!-- =================================================================================== --><robot name="cob4-25"><material name="IPA/LightGrey"><color rgba="0.7 0.7 0.7 1.0"/></material><material name="IPA/DarkGrey"><color rgba="0.4 0.4 0.4 1.0"/></material><material name="IPA/Black"><color rgba="0.0 0.0 0.0 1.0"/></material><material name="IPA/Metall"><color rgba="0.7 0.7 0.7 1.0"/></material><ma, at ./src/rcl/arguments.c:343
[gzserver-1] 
[INFO] [spawn_entity.py-4]: process has finished cleanly [pid 88176]
[INFO] [ros2-5]: process started with pid [88303]
[ros2-5] Could not contact service /controller_manager/load_controller
[ERROR] [ros2-5]: process has died [pid 88303, exit code 1, cmd 'ros2 control load_controller --set-state active joint_state_broadcaster'].
[INFO] [ros2-6]: process started with pid [88410]
[ros2-6] Could not contact service /controller_manager/load_controller
[ERROR] [ros2-6]: process has died [pid 88410, exit code 1, cmd 'ros2 control load_controller --set-state active tricycle_controller'].

and my .yaml file is

controller_manager:
  ros__parameters:
    update_rate: 50 # Hz
    use_sim_time: true

    tricycle_controller:
      type: tricycle_controller/TricycleController

    joint_state_broadcaster:
      type: joint_state_broadcaster/JointStateBroadcaster

joint_state_broadcaster:
  ros__parameters:
    extra_joints: ["fl_caster_r_wheel_joint", "fr_caster_r_wheel_joint"]

tricycle_controller:
  ros__parameters:
    # Model
    traction_joint_name: b_caster_r_wheel_joint # Name of traction joint in URDF
    steering_joint_name: b_caster_rotation_joint # Name of steering joint in URDF
    wheel_radius: 0.0782 # Radius of front wheel
    wheelbase: 0.37266 # Distance between center of back wheels and front wheel

    # Odometry
    odom_frame_id: base_footprint
    base_frame_id: base_link
    publish_rate: 50.0 # publish rate of odom and tf
    open_loop: false # if True, uses cmd_vel instead of hardware interface feedback to compute odometry
    enable_odom_tf: true # If True, publishes odom<-base_link TF
    odom_only_twist: false # If True, publishes on /odom only linear.x and angular.z; Useful for computing odometry in another node, e.g robot_localization's ekf
    pose_covariance_diagonal: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0] # Need to be set if fusing odom with other localization source
    twist_covariance_diagonal: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0] # Need to be set if fusing odom with other localization source
    velocity_rolling_window_size: 10 # Rolling window size of rcppmath::RollingMeanAccumulator applied on linear and angular speeds published on odom

    # Rate Limiting
    traction: # All values should be positive
      # min_velocity: 0.0
      # max_velocity: 1000.0
      # min_acceleration: 0.0
      max_acceleration: 5.0
      # min_deceleration: 0.0
      max_deceleration: 8.0
      # min_jerk: 0.0
      # max_jerk: 1000.0
    steering:
      min_position: -1.57
      max_position: 1.57
      # min_velocity: 0.0
      max_velocity: 1.0
      # min_acceleration: 0.0
      # max_acceleration: 1000.0

    # cmd_vel input
    cmd_vel_timeout: 500 # In milliseconds. Timeout to stop if no cmd_vel is received
    use_stamped_vel: false # Set to True if using TwistStamped.

    # Debug
    publish_ackermann_command: true # Publishes AckermannDrive. The speed does not comply to the msg definition, it the wheel angular speed in rad/s.

The plgins in urdf model (before ):

  <!-- ros_control plugin -->
  <ros2_control name="GazeboSystem" type="system">
    <hardware>
      <plugin>gazebo_ros2_control/GazeboSystem</plugin>
    </hardware>
    <joint name="b_caster_rotation_joint">
      <command_interface name="position" />
      <state_interface name="position" />
    </joint>
    <joint name="b_caster_r_wheel_joint">
      <command_interface name="velocity" />
      <state_interface name="velocity" />
      <state_interface name="position" />
    </joint>
  </ros2_control>

  <gazebo>
    <plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
      <parameters>$(find cob_hardware_config)/robots/cob4-25/config/tricycle_drive_controller.yaml</parameters>
    </plugin>
  </gazebo>  

The problem seems to be pasring .yaml file and parameter overriding with the urdf, but no collisions are found in the urdf.
Section of urdf:

  <joint name="b_caster_rotation_joint" type="continuous">
    <origin rpy="0 0 0" xyz="-0.24844 0.0 0.0782"/>
    <parent link="base_chassis_link"/>
    <child link="b_caster_rotation_link"/>
    <axis xyz="0 0 1"/>
    <safety_controller k_velocity="10"/>
    <limit effort="100" velocity="12.0"/>
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
...
  <joint name="b_caster_r_wheel_joint" type="continuous">
    <origin rpy="0 0 0" xyz="0 -0.0 0"/>
    <parent link="b_caster_rotation_link"/>
    <child link="b_caster_r_wheel_link"/>
    <axis xyz="0 1 0"/>
    <safety_controller k_velocity="10"/>
    <limit effort="100" velocity="19.95"/>
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
...
@christophfroehlich
Copy link
Contributor

  • Have you installed all packages as binaries or installed them from source?
  • Does the original tricycle demo work?
  • Do you load the robot_description in your launch file? This is normally done via the robot_state_publisher
  • Check your URDF with xacro & check_urdf like here.

@ipa-ych
Copy link
Author

ipa-ych commented Mar 27, 2024

Hi,

problem resolved. The conflict aws located in the previous part of urdf with robot calibration. The controller and demo are working fine.

@mbed92
Copy link

mbed92 commented Mar 27, 2024

Hi,

problem resolved. The conflict aws located in the previous part of urdf with robot calibration. The controller and demo are working fine.

Can you elaborate more on your solution? In our project, it started to appear recently (like 2-3 days ago), and I thought it might be connected with the latest update and that issue (#277). Below is my error. YAML configuration of TricycleController is very similar and was working fine till this week:

[gzserver-1] [ERROR 1711549496.914657547] [gazebo_ros2_control]: parser error Couldn't parse parameter override rule: '--param robot_description:=<?xml version="1.0" ?>
[gzserver-1] <!-- =================================================================================== -->
[gzserver-1] <!-- |    This document was autogenerated by xacro from /ros2_ws/install/jablka_description/share/jablka_description/urdf/robot.urdf.xacro | -->
[gzserver-1] <!-- |    EDITING THIS FILE BY HAND IS NOT RECOMMENDED                                 | -->
[gzserver-1] <!-- =================================================================================== -->
[gzserver-1] <robot name="robot">
[gzserver-1]   <!-- ### ROBOT BASE ### -->
[gzserver-1]   <!-- Assume the base_link is right in the center of the rear axle. Mesh will be positioned as is in the STL file. -->
[gzserver-1]   <link name="base_link">
[gzserver-1]     <visual>
[gzserver-1]       <origin rpy="0 0 0" xyz="0 0 0"/>
[gzserver-1]   , at ./src/rcl/arguments.c:343
[gzserver-1]  (Load() at ./src/gazebo_ros2_control_plugin.cpp:260)

@smkyle90
Copy link

smkyle90 commented Mar 27, 2024

Hi,
problem resolved. The conflict aws located in the previous part of urdf with robot calibration. The controller and demo are working fine.

Can you elaborate more on your solution? In our project, it started to appear recently (like 2-3 days ago), and I thought it might be connected with the latest update and that issue (#277). Below is my error. YAML configuration of TricycleController is very similar and was working fine till this week:

[gzserver-1] [ERROR 1711549496.914657547] [gazebo_ros2_control]: parser error Couldn't parse parameter override rule: '--param robot_description:=<?xml version="1.0" ?>
[gzserver-1] <!-- =================================================================================== -->
[gzserver-1] <!-- |    This document was autogenerated by xacro from /ros2_ws/install/jablka_description/share/jablka_description/urdf/robot.urdf.xacro | -->
[gzserver-1] <!-- |    EDITING THIS FILE BY HAND IS NOT RECOMMENDED                                 | -->
[gzserver-1] <!-- =================================================================================== -->
[gzserver-1] <robot name="robot">
[gzserver-1]   <!-- ### ROBOT BASE ### -->
[gzserver-1]   <!-- Assume the base_link is right in the center of the rear axle. Mesh will be positioned as is in the STL file. -->
[gzserver-1]   <link name="base_link">
[gzserver-1]     <visual>
[gzserver-1]       <origin rpy="0 0 0" xyz="0 0 0"/>
[gzserver-1]   , at ./src/rcl/arguments.c:343
[gzserver-1]  (Load() at ./src/gazebo_ros2_control_plugin.cpp:260)

As of about 36 minutes ago, we are experiencing the same issue with 0.4.7.

I can confirm our simulation and control infrastructure will launch with ros-humble-gazebo-ros2-control/now 0.4.3-1jammy.20230523.211003 amd64 [installed,local].

Similar to @mbed92, the source of our issue comes from:

  <gazebo>
    <plugin name="gazebo_ros2_control" filename="libgazebo_ros2_control.so">
      <parameters>$(find at_gazebo)/config/bh3.yaml</parameters>
    </plugin>
  </gazebo>

If this is removed, there is no robot_description parameter error at launch, however, obviously, we cannot do anything useful with our system.

@mbed92
Copy link

mbed92 commented Mar 27, 2024

@christophfroehlich I can also confirm that the same URDF works fine using 0.4.6, but the error above arises when on 0.4.7. Has anything changed regarding loading the plugin? My current configuration was as follows:

    <gazebo>
        <plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
            <robot_param>robot_description</robot_param>
            <robot_param_node>robot_state_publisher</robot_param_node>
            <parameters>$(arg ros2_controllers_config)</parameters> <!-- I guess the error occurs here --->
            <ros>
                <remapping>/tricycle_controller/cmd_vel:=/cmd_vel</remapping>
                <remapping>/tricycle_controller/odom:=${common_params['wheel_odom_topic']}</remapping>
            </ros>
        </plugin>
    </gazebo>

@christophfroehlich
Copy link
Contributor

It seems that this came with #277, but I'm using gazebo_ros2_control 0.4.7 built from source and it works for my robot.

  • @mbed92 @smkyle90 can you confirm that the examples run with your setup? ros2 launch gazebo_ros2_control_demos tricycle_drive.launch.py
  • Have you checked your URDF with xacro & check_urdf like here?

If this is all fine I guess that some special character from your URDF can't be processed here

rcl_ret_t rcl_ret = rcl_parse_arguments(
static_cast<int>(argv.size()),
argv.data(), rcl_get_default_allocator(), &rcl_args);

@ahcorde If we can't fix this maybe we should think of reverting #277, because the robot_description parameter is deprecated anyways back to humble since ros-controls/ros2_control#940.
But I see that there is no possibility to pass the URDF to the controllers on humble and iron since ros-controls/ros2_control#1088 won't get backported.
Same feature request like in ros-controls/gz_ros2_control#168

@ipa-ych
Copy link
Author

ipa-ych commented Mar 27, 2024

My problem was that the parser could not process several lines of xacro-urdf code, which were even commented out after the auto generation. After removing these lines by deleting them, the parser was able to process the rest. Problem could be somewhere in the parser...try to modify your urdf and use it instead of xacro file

@mbed92
Copy link

mbed92 commented Mar 28, 2024

@christophfroehlich Thanks for reopening the issue.

@mbed92 @smkyle90 can you confirm that the examples run with your setup? ros2 launch gazebo_ros2_control_demos tricycle_drive.launch.py

I can confirm that the tricycle demo works fine on 0.4.7 using the command ros2 launch gazebo_ros2_control_demos tricycle_drive.launch.py gui:=false. By the way. When I start with gui:=true, I get the following error (but it's probably irrelevant to this issue):

[spawn_entity.py-5] [ERROR 1711610650.110016674] [spawn_entity]: Service %s/spawn_entity unavailable. Was Gazebo started with GazeboRosFactory? (_spawn_entity() at /opt/ros/humble/lib/gazebo_ros/spawn_entity.py:291)
[spawn_entity.py-5] [ERROR 1711610650.110274197] [spawn_entity]: Spawn service failed. Exiting. (run() at /opt/ros/humble/lib/gazebo_ros/spawn_entity.py:230)

Have you checked your URDF with xacro & check_urdf like here?

I can confirm that check_urdf returns Successfully Parsed XML. I ran the following command: xacro robot.urdf.xacro > tmp.urdf && check_urdf tmp.urdf.

@ipa-ych can you point out what lines were causing troubles? The issue seems to be some parser error, but I'm running out of ideas which characters/phrases might be wrong.

@mbed92
Copy link

mbed92 commented Mar 28, 2024

I figured out what comments were the problem in my setup. Let's start from the beginning for all the people who spend two days on that 🥲

I was loading the robot_description in the launchfile in the following way (similar to the Husky repo):

    robot_description_content = Command(
        [
            PathJoinSubstitution([FindExecutable(name="xacro")]),
            " ",
            urdf_path,
            ...
        ]
    )
    robot_description = ParameterValue(robot_description_content, value_type=str)
    
    return LaunchDescription([
                Node(
            package='robot_state_publisher',
            executable='robot_state_publisher',
            name='robot_state_publisher',
            output='screen',
            parameters=[{
                'use_sim_time': use_sim_time,
                'robot_description': robot_description
            }]
        ),
        ...
    ])

As you can see, ParameterValue parses the robot description content as a string (which is perfectly fine for the robot_state_publisher). However, it seems that further passing string instead of YAML to other ROS nodes due to recent changes causes troubles to parsing certain characters. To figure out what lines were problematic I changed the line:

robot_description = ParameterValue(robot_description_content, value_type=str)

to

robot_description = ParameterValue(robot_description_content, value_type=None) # which parses the param as YAML instead of string

That change caused a list of parsing errors. In my case it were comments like:

  • comments with a colon
<!-- TODO(mbed): if needed we can put the STL mesh here -->

or

<!-- More reading: https://github.com/ethz-asl/kalibr/wiki/IMU-Noise-Model -->
  • comments with "###" like:
<!-- ### ROBOT BASE ### -->

Generally, I think this kind of error is super difficult to find because all signs show that URDF is OK, so you look everywhere but not there (at least initially). The decision is up to @christophfroehlich and contributors on handling that, but I think it should be pointed out somewhere in docs not to use specific characters due to parsing errors.

@saikishor
Copy link
Member

saikishor commented Mar 28, 2024

@mbed92 yes, this is an issue from the launch_ros side ros2/launch_ros#214
Right now, there is no proper solution for it, so probably we have to be careful for now. May be we can do something at ros2_control side to make the URDF available to the controllers

@christophfroehlich
Copy link
Contributor

Thanks for the analysis. We'll discuss how we can fix this, but we have limited possibilities without breaking API for humble and iron.

@smkyle90
Copy link

smkyle90 commented Mar 28, 2024

I have run similar tests to @mbed92.

In summary:

  • The tricycle example launches successfully.
  • Original xacro check_urdf returns Expect URDF xml file to parse
  • My stack still fails to launch (parsing error, as above).
  • Per @mbed92's investigation, I removed comments with special characters from my xacro file. check_urdf returns Expect URDF xml file to parse.
  • The system launches successfully, i.e., urdf is parsed and gazebo_ros2_control initializes.

@christophfroehlich
Copy link
Contributor

* Original XML `check_urdf` returns `Expect URDF xml file to parse`

have you run xacro and passed the resulting urdf to check_urdf?

@smkyle90
Copy link

smkyle90 commented Mar 28, 2024

* Original XML `check_urdf` returns `Expect URDF xml file to parse`

have you run xacro and passed the resulting urdf to check_urdf?

Meant xacro, not XML, my mistake. Complete output for xacro file that results in a parsing error:

# .xacro
auto@simulation-XPS-8960:~/auto_simulation/at_gazebo/urdf$ check_urdf < bh3.xacro 
Expect URDF xml file to parse

# .urdf
auto@simulation-XPS-8960:~/auto_simulation/at_gazebo/urdf$ check_urdf < bh3.urdf 
Expect URDF xml file to parse

When I remove all comments with special characters, i.e., #, !, :, etc., check_urdf output is the same but I do not get the parsing error on launch.

@christophfroehlich
Copy link
Contributor

# .xacro
auto@simulation-XPS-8960:~/auto_simulation/at_gazebo/urdf$ check_urdf < bh3.xacro 
Expect URDF xml file to parse

# .urdf
auto@simulation-XPS-8960:~/auto_simulation/at_gazebo/urdf$ check_urdf < bh3.urdf 
Expect URDF xml file to parse

As commented above: use xacro to generate a valid URDF and then pass it to check_urdf. If this is already the step from bh3.xacro to bh3.urdf, then is there already some other issue.

@smkyle90
Copy link

Yes, this is with newly generated urdf using xacro.

@MansiP441
Copy link

I was getting the same error for the past 2-3 days. Removing the comments as suggested by @mbed92 worked for me.

@ebadi
Copy link

ebadi commented Apr 2, 2024

Thanks, removing comments worked for me as well. This simple function can be used in MOST cases:

import re
def remove_comments(text):
    pattern = r'<!--(.*?)-->'
    return re.sub(pattern, '', text, flags=re.DOTALL)

@Charifou
Copy link

Thanks. I confirm that the temp solution is to generate the urdf file with xacro and remove by hand the comments before using it in the launch file.

@mirnas1
Copy link

mirnas1 commented May 9, 2024

Had the same issue and can confirm, removing comments from my xacro files worked to solve the error

gtoff added a commit to icclab/summit_xl_sim that referenced this issue May 13, 2024
joefscholtz added a commit to joefscholtz/forg_bot that referenced this issue May 18, 2024
it was necessary to erase all semicolons in comments because of a [weird
bug in gazebo_ros2_control
0.4.7](ros-controls/gazebo_ros2_control#295),
I hope it will get fixed soon because I like my "TODO:"s using
folke/todo-comments.nvim
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

No branches or pull requests

9 participants