Commit 36ff7d37 authored by Guilhem Saurel's avatar Guilhem Saurel
Browse files

ur_description: fix inertia in ur3 & ur10

parent 2abddbc5
......@@ -223,6 +223,11 @@
<origin rpy="0.0 0.0 1.57079632679" xyz="0.0 0.0922 0.0"/>
</joint>
<link name="ee_link">
<inertial>
<mass value="0.0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<collision>
<geometry>
<box size="0.01 0.01 0.01"/>
......@@ -306,7 +311,13 @@
<selfCollide>true</selfCollide>
</gazebo>
<!-- ROS base_link to UR 'Base' Coordinates transform -->
<link name="base"/>
<link name="base">
<inertial>
<mass value="0.0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
</link>
<joint name="base_link-base_fixed_joint" type="fixed">
<!-- NOTE: this rotation is only needed as long as base_link itself is
not corrected wrt the real robot (ie: rotated over 180
......@@ -317,7 +328,13 @@
<child link="base"/>
</joint>
<!-- Frame coincident with all-zeros TCP on UR controller -->
<link name="tool0"/>
<link name="tool0">
<inertial>
<mass value="0.0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
</link>
<joint name="wrist_3_link-tool0_fixed_joint" type="fixed">
<origin rpy="-1.57079632679 0 0" xyz="0 0.0922 0"/>
<parent link="wrist_3_link"/>
......@@ -330,4 +347,3 @@
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
</joint>
</robot>
......@@ -236,6 +236,11 @@
<origin rpy="0.0 0.0 1.570796325" xyz="0.0 0.0819 0.0"/>
</joint>
<link name="ee_link">
<inertial>
<mass value="0.0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<collision>
<geometry>
<box size="0.01 0.01 0.01"/>
......@@ -299,7 +304,13 @@
</transmission>
<!-- nothing to do here at the moment -->
<!-- ROS base_link to UR 'Base' Coordinates transform -->
<link name="base"/>
<link name="base">
<inertial>
<mass value="0.0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
</link>
<joint name="base_link-base_fixed_joint" type="fixed">
<!-- NOTE: this rotation is only needed as long as base_link itself is
not corrected wrt the real robot (ie: rotated over 180
......@@ -311,6 +322,11 @@
</joint>
<!-- Frame coincident with all-zeros TCP on UR controller -->
<link name="tool0">
<inertial>
<mass value="0.0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<geometry>
<box size="0.005 0.02 0.05" />
......
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment