Closed katallen405 closed 1 month ago
Hi @katallen405, can you provide an example description?
We can reproduce this as well on Humble.
Adding ParameterValue(robot_description_content, value_type=str)
to all instances across the different packages/launchfiles seems to fix the issue.
I was not aware of this problem, thanks for pointing that out.
I think this is the xacro file that is catching the issue. Thanks!
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<!--
Based on the URDF file by Cristian C Beltran-Hernandez
-->
<!-- If visualizing just the gripper with no arm, set the true, otherwise, set to false -->
<xacro:property name="gripper_only" value="false"/>
<xacro:property name="parent"/>
<xacro:include filename="$(find robotiq_hande_description)/urdf/materials.xacro" />
<xacro:macro name="robotiq_hande_gripper" params="
name
prefix
parent
*origin
sim_isaac:=false
use_fake_hardware:=false
include_ros2_control:=true
com_port:=/dev/ttyUSB0">
<!-- ros2 control include -->
<xacro:include filename="$(find robotiq_description)/urdf/robotiq_gripper.ros2_control.xacro" />
<!-- if we are simulating or directly communicating with the gripper we need a ros2 control instance -->
<xacro:if value="${include_ros2_control}">
<xacro:robotiq_gripper_ros2_control
name="${name}" prefix="${prefix}"
sim_isaac="${sim_isaac}"
use_fake_hardware="${use_fake_hardware}"
com_port="${com_port}"/>
</xacro:if>
<!-- Robotiq Coupler -->
<!-- + Height added by the coupler: 13.9mm -->
<!-- + Reference frame: at the middle (6.95mm) -->
<joint name="robotiq_coupler_joint" type="fixed">
<origin xyz="0 0 0.00695" rpy="0 0 ${-pi/2.0}" />
<parent link="${parent}"/>
<child link="${prefix}_robotiq_coupler"/>
</joint>
<link name="${prefix}_robotiq_coupler">
<inertial>
<mass value="0.168" />
<inertia
ixx="6.17674E-05" ixy="0.0" ixz="0.0"
iyy="6.17674E-05" iyz="0.0"
izz="1.18125E-04"
/>
</inertial>
<collision>
<geometry>
<cylinder length="0.0139" radius="0.0375"/>
</geometry>
</collision>
<visual>
<geometry>
<mesh filename="package://robotiq_hande_description/meshes/coupler.dae" />
</geometry>
<material name="DarkGrey" />
</visual>
</link>
<!-- gripper body -->
<joint name="${prefix}_robotiq_hande_base_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.055"/>
<parent link="${prefix}_robotiq_coupler"/>
<child link="${prefix}_hande_link"/>
</joint>
<link name="${prefix}_hande_link">
<inertial>
<mass value="0.86387"/>
<inertia
ixx="0.001" ixy="0.0" ixz="0.0"
iyy="0.001" iyz="0.0"
izz="0.0006"
/>
</inertial>
<collision>
<geometry>
<cylinder length="0.0988" radius="0.0375"/>
</geometry>
</collision>
<visual>
<origin rpy="0 -1.570796 -1.570796" xyz="0 0 -0.0016"/>
<geometry>
<mesh filename="package://robotiq_hande_description/meshes/hande.dae" scale="1.0 1.0 1.0"/>
</geometry>
<material name="DarkGrey"/>
</visual>
</link>
<!-- gripper left finger -->
<joint name="${prefix}_hande_left_finger_joint" type="prismatic">
<origin rpy="0 0 0" xyz="0 -0.025 0.0345"/>
<parent link="${prefix}_hande_link"/>
<child link="${prefix}_hande_left_finger"/>
<axis xyz="0 1 0"/>
<limit effort="130" lower="0" upper="0.025" velocity="0.15"/>
</joint>
<link name="${prefix}_hande_left_finger">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.03804"/>
<inertia
ixx="1E-9" ixy="0.0" ixz="0.0"
iyy="1E-9" iyz="0.0"
izz="1E-9"
/>
</inertial>
<collision>
<origin rpy="0 0 3.1415926" xyz="0 0 0"/>
<geometry>
<mesh filename="package://robotiq_hande_description/meshes/finger_collision.dae" scale="1.0 1.0 1.0"/>
</geometry>
</collision>
<visual>
<origin rpy="1.570796 0 3.1415926" xyz="0 0 0"/>
<geometry>
<mesh filename="package://robotiq_hande_description/meshes/finger.dae" scale="1.0 1.0 1.0"/>
</geometry>
<material name="Grey"/>
</visual>
</link>
<!-- gripper right finger -->
<joint name="${prefix}_hande_right_finger_joint" type="prismatic">
<origin rpy="0 0 0" xyz="0 0.025 0.0345"/>
<parent link="${prefix}_hande_link"/>
<child link="${prefix}_hande_right_finger"/>
<axis xyz="0 -1 0"/>
<limit effort="130" lower="0" upper="0.025" velocity="0.15"/>
<mimic joint="${prefix}_hande_left_finger_joint" multiplier="1" offset="0"/>
</joint>
<link name="${prefix}_hande_right_finger">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.03804"/>
<inertia
ixx="1E-9" ixy="0.0" ixz="0.0"
iyy="1E-9" iyz="0.0"
izz="1E-9"
/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://robotiq_hande_description/meshes/finger_collision.dae" scale="1.0 1.0 1.0"/>
</geometry>
</collision>
<visual>
<origin rpy="1.570796 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://robotiq_hande_description/meshes/finger.dae" scale="1.0 1.0 1.0"/>
</geometry>
<material name="Grey" />
</visual>
</link>
<!--end of gripper frame -->
<joint name="${prefix}_robotiq_hande_end_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.095"/>
<parent link="${prefix}_hande_link"/>
<child link="${prefix}_hande_end"/>
</joint>
<link name="${prefix}_hande_end" />
</xacro:macro>
</robot>
Closed in #1115
Affected ROS2 Driver version(s)
2.4.10
Used ROS distribution.
Humble
Which combination of platform is the ROS driver running on.
Ubuntu Linux with realtime patch
How is the UR ROS2 Driver installed.
From binary packets
Which robot platform is the driver connected to.
UR E-series robot
Robot SW / URSim version(s)
all
How is the ROS driver used.
Through the robot teach pendant using External Control URCap
Issue details
Summary
xacro files can be interpret as xacro when using description_package
Issue details
When launching with a custom description package (to show gripper), it causes the following error: [ERROR] [launch]: Caught exception in launch (see debug for traceback): Unable to parse the value of parameter robot_description as yaml. If the parameter is meant to be a string, try wrapping it in launch_ros.parameter_descriptions.ParameterValue(value, value_type=str)
This ROS issue has a known bug and workaround, but it requires that you change something in the file: https://answers.ros.org/question/417369/caught-exception-in-launch-see-debug-for-traceback-unable-to-parse-the-value-of-parameter-robot_description-as-yaml/
/ur_control.launch.py https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver/blob/main/ur_robot_driver/launch/ur_control.launch.py
Steps to Reproduce
xacro files with commented xacro lines are particularly prone to this issue
Expected Behavior
valid xacro should launch correctly
Actual Behavior
[ERROR] [launch]: Caught exception in launch (see debug for traceback): Unable to parse the value of parameter robot_description as yaml. If the parameter is meant to be a string, try wrapping it in launch_ros.parameter_descriptions.ParameterValue(value, value_type=str)
What did you observe? If possible please attach relevant information.
Workaround Suggestion
no workaround
Relevant log output
Accept Public visibility