-
Notifications
You must be signed in to change notification settings - Fork 130
Parser Error Couldn't parse parameter override rule - loading tricycle_controller from ros2_control #295
Description
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>
...