Skip to content
Snippets Groups Projects
Commit ff58d33e authored by Felix von Drigalski's avatar Felix von Drigalski Committed by G.A. vd. Hoorn
Browse files

Fix overlapping variable names between robot definition files (#356)

Squashed commits:

* Fix overlapping properties between robot definitions

   Uploading a different UR definition used to break the previous definition files by overwriting their link lengths. This commit makes the property names for each robot unique so they are independent of the other robot models.

* Move robot-specific parameters inside macro

   This is the cleaner solution for what the previous commit was meant to solve
parent f15aa40e
Branches
No related merge requests found
......@@ -9,47 +9,6 @@
<xacro:include filename="$(find ur_description)/urdf/ur.transmission.xacro" />
<xacro:include filename="$(find ur_description)/urdf/ur.gazebo.xacro" />
<!-- Inertia parameters -->
<xacro:property name="base_mass" value="4.0" /> <!-- This mass might be incorrect -->
<xacro:property name="shoulder_mass" value="7.778" />
<xacro:property name="upper_arm_mass" value="12.93" />
<xacro:property name="forearm_mass" value="3.87" />
<xacro:property name="wrist_1_mass" value="1.96" />
<xacro:property name="wrist_2_mass" value="1.96" />
<xacro:property name="wrist_3_mass" value="0.202" />
<!-- These parameters are borrowed from the urcontrol.conf file
but are not verified for the correct permutation.
The permutation was guessed by looking at the UR5 parameters.
Serious use of these parameters needs further inspection. -->
<xacro:property name="shoulder_cog" value="0.00008 0.00244 -0.037" />
<xacro:property name="upper_arm_cog" value="0.00001 0.15061 0.38757" />
<xacro:property name="forearm_cog" value="-0.00012 0.06112 0.1984" />
<xacro:property name="wrist_1_cog" value="-0.00021 -0.00112 0.02269" />
<xacro:property name="wrist_2_cog" value="-0.00021 0.00112 0.002269" />
<xacro:property name="wrist_3_cog" value="0 -0.001156 -0.00149" />
<!-- Kinematic model -->
<!-- Properties from urcontrol.conf -->
<xacro:property name="ur10_d1" value="0.1273" />
<xacro:property name="ur10_a2" value="-0.612" />
<xacro:property name="ur10_a3" value="-0.5723" />
<xacro:property name="ur10_d4" value="0.163941" />
<xacro:property name="ur10_d5" value="0.1157" />
<xacro:property name="ur10_d6" value="0.0922" />
<!-- Arbitrary offsets for shoulder/elbow joints -->
<xacro:property name="shoulder_offset" value="0.220941" /> <!-- measured from model -->
<xacro:property name="elbow_offset" value="-0.1719" /> <!-- measured from model -->
<!-- link lengths used in model -->
<xacro:property name="shoulder_height" value="${ur10_d1}" />
<xacro:property name="upper_arm_length" value="${-ur10_a2}" />
<xacro:property name="forearm_length" value="${-ur10_a3}" />
<xacro:property name="wrist_1_length" value="${ur10_d4 - elbow_offset - shoulder_offset}" />
<xacro:property name="wrist_2_length" value="${ur10_d5}" />
<xacro:property name="wrist_3_length" value="${ur10_d6}" />
<xacro:macro name="cylinder_inertial" params="radius length mass *origin">
<inertial>
<mass value="${mass}" />
......@@ -60,7 +19,6 @@
</inertial>
</xacro:macro>
<xacro:macro name="ur10_robot" params="prefix joint_limited
shoulder_pan_lower_limit:=${-pi} shoulder_pan_upper_limit:=${pi}
shoulder_lift_lower_limit:=${-pi} shoulder_lift_upper_limit:=${pi}
......@@ -69,6 +27,47 @@
wrist_2_lower_limit:=${-pi} wrist_2_upper_limit:=${pi}
wrist_3_lower_limit:=${-pi} wrist_3_upper_limit:=${pi}">
<!-- Inertia parameters -->
<xacro:property name="base_mass" value="4.0" /> <!-- This mass might be incorrect -->
<xacro:property name="shoulder_mass" value="7.778" />
<xacro:property name="upper_arm_mass" value="12.93" />
<xacro:property name="forearm_mass" value="3.87" />
<xacro:property name="wrist_1_mass" value="1.96" />
<xacro:property name="wrist_2_mass" value="1.96" />
<xacro:property name="wrist_3_mass" value="0.202" />
<!-- These parameters are borrowed from the urcontrol.conf file
but are not verified for the correct permutation.
The permutation was guessed by looking at the UR5 parameters.
Serious use of these parameters needs further inspection. -->
<xacro:property name="shoulder_cog" value="0.00008 0.00244 -0.037" />
<xacro:property name="upper_arm_cog" value="0.00001 0.15061 0.38757" />
<xacro:property name="forearm_cog" value="-0.00012 0.06112 0.1984" />
<xacro:property name="wrist_1_cog" value="-0.00021 -0.00112 0.02269" />
<xacro:property name="wrist_2_cog" value="-0.00021 0.00112 0.002269" />
<xacro:property name="wrist_3_cog" value="0 -0.001156 -0.00149" />
<!-- Kinematic model -->
<!-- Properties from urcontrol.conf -->
<xacro:property name="d1" value="0.1273" />
<xacro:property name="a2" value="-0.612" />
<xacro:property name="a3" value="-0.5723" />
<xacro:property name="d4" value="0.163941" />
<xacro:property name="d5" value="0.1157" />
<xacro:property name="d6" value="0.0922" />
<!-- Arbitrary offsets for shoulder/elbow joints -->
<xacro:property name="shoulder_offset" value="0.220941" /> <!-- measured from model -->
<xacro:property name="elbow_offset" value="-0.1719" /> <!-- measured from model -->
<!-- link lengths used in model -->
<xacro:property name="shoulder_height" value="${d1}" />
<xacro:property name="upper_arm_length" value="${-a2}" />
<xacro:property name="forearm_length" value="${-a3}" />
<xacro:property name="wrist_1_length" value="${d4 - elbow_offset - shoulder_offset}" />
<xacro:property name="wrist_2_length" value="${d5}" />
<xacro:property name="wrist_3_length" value="${d6}" />
<link name="${prefix}base_link" >
<visual>
<geometry>
......@@ -149,8 +148,8 @@
<mesh filename="package://ur_description/meshes/ur10/collision/upperarm.stl"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="0.075" length="${-ur10_a2}" mass="${upper_arm_mass}">
<origin xyz="0.0 0.0 ${-ur10_a2/2.0}" rpy="0 0 0" />
<xacro:cylinder_inertial radius="0.075" length="${-a2}" mass="${upper_arm_mass}">
<origin xyz="0.0 0.0 ${-a2/2.0}" rpy="0 0 0" />
</xacro:cylinder_inertial>
</link>
......@@ -182,8 +181,8 @@
<mesh filename="package://ur_description/meshes/ur10/collision/forearm.stl"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="0.075" length="${-ur10_a3}" mass="${forearm_mass}">
<origin xyz="0.0 0.0 ${-ur10_a3/2.0}" rpy="0 0 0" />
<xacro:cylinder_inertial radius="0.075" length="${-a3}" mass="${forearm_mass}">
<origin xyz="0.0 0.0 ${-a3/2.0}" rpy="0 0 0" />
</xacro:cylinder_inertial>
</link>
......
......@@ -8,48 +8,7 @@
<xacro:include filename="$(find ur_description)/urdf/ur.transmission.xacro" />
<xacro:include filename="$(find ur_description)/urdf/ur.gazebo.xacro" />
<!-- Inertia parameters -->
<xacro:property name="base_mass" value="2.0" /> <!-- This mass might be incorrect -->
<xacro:property name="shoulder_mass" value="2.0" />
<xacro:property name="upper_arm_mass" value="3.42" />
<xacro:property name="forearm_mass" value="1.26" />
<xacro:property name="wrist_1_mass" value="0.8" />
<xacro:property name="wrist_2_mass" value="0.8" />
<xacro:property name="wrist_3_mass" value="0.35" />
<!-- These parameters are borrowed from the urcontrol.conf file
but are not verified for the correct permutation.
The permutation was guessed by looking at the UR5 parameters.
Serious use of these parameters needs further inspection. -->
<xacro:property name="shoulder_cog" value="0.0 -0.02 0.0" />
<xacro:property name="upper_arm_cog" value="0.13 0.0 0.1157" />
<xacro:property name="forearm_cog" value="0.05 0.0 0.0238" />
<xacro:property name="wrist_1_cog" value="0.0 0.0 0.01" />
<xacro:property name="wrist_2_cog" value="0.0 0.0 0.01" />
<xacro:property name="wrist_3_cog" value="0.0 0.0 -0.02" />
<!-- Kinematic model -->
<!-- Properties from urcontrol.conf -->
<xacro:property name="ur3_d1" value="0.1519" />
<xacro:property name="ur3_a2" value="-0.24365" />
<xacro:property name="ur3_a3" value="-0.21325" />
<xacro:property name="ur3_d4" value="0.11235" />
<xacro:property name="ur3_d5" value="0.08535" />
<xacro:property name="ur3_d6" value="0.0819" />
<!-- Arbitrary offsets for shoulder/elbow joints -->
<xacro:property name="shoulder_offset" value="0.1198" /> <!-- measured from model -->
<xacro:property name="elbow_offset" value="-0.0925" /> <!-- measured from model -->
<!-- link lengths used in model -->
<xacro:property name="shoulder_height" value="${ur3_d1}" />
<xacro:property name="upper_arm_length" value="${-ur3_a2}" />
<xacro:property name="forearm_length" value="${-ur3_a3}" />
<xacro:property name="wrist_1_length" value="${ur3_d4 - elbow_offset - shoulder_offset}" />
<xacro:property name="wrist_2_length" value="${ur3_d5}" />
<xacro:property name="wrist_3_length" value="${ur3_d6}" />
<xacro:macro name="cylinder_inertial" params="radius length mass *origin">
<xacro:macro name="cylinder_inertial" params="radius length mass *origin">
<inertial>
<mass value="${mass}" />
<xacro:insert_block name="origin" />
......@@ -59,7 +18,6 @@
</inertial>
</xacro:macro>
<xacro:macro name="ur3_robot" params="prefix joint_limited
shoulder_pan_lower_limit:=${-pi} shoulder_pan_upper_limit:=${pi}
shoulder_lift_lower_limit:=${-pi} shoulder_lift_upper_limit:=${pi}
......@@ -68,6 +26,47 @@
wrist_2_lower_limit:=${-pi} wrist_2_upper_limit:=${pi}
wrist_3_lower_limit:=${-pi} wrist_3_upper_limit:=${pi}">
<!-- Inertia parameters -->
<xacro:property name="base_mass" value="2.0" /> <!-- This mass might be incorrect -->
<xacro:property name="shoulder_mass" value="2.0" />
<xacro:property name="upper_arm_mass" value="3.42" />
<xacro:property name="forearm_mass" value="1.26" />
<xacro:property name="wrist_1_mass" value="0.8" />
<xacro:property name="wrist_2_mass" value="0.8" />
<xacro:property name="wrist_3_mass" value="0.35" />
<!-- These parameters are borrowed from the urcontrol.conf file
but are not verified for the correct permutation.
The permutation was guessed by looking at the UR5 parameters.
Serious use of these parameters needs further inspection. -->
<xacro:property name="shoulder_cog" value="0.0 -0.02 0.0" />
<xacro:property name="upper_arm_cog" value="0.13 0.0 0.1157" />
<xacro:property name="forearm_cog" value="0.05 0.0 0.0238" />
<xacro:property name="wrist_1_cog" value="0.0 0.0 0.01" />
<xacro:property name="wrist_2_cog" value="0.0 0.0 0.01" />
<xacro:property name="wrist_3_cog" value="0.0 0.0 -0.02" />
<!-- Kinematic model -->
<!-- Properties from urcontrol.conf -->
<xacro:property name="d1" value="0.1519" />
<xacro:property name="a2" value="-0.24365" />
<xacro:property name="a3" value="-0.21325" />
<xacro:property name="d4" value="0.11235" />
<xacro:property name="d5" value="0.08535" />
<xacro:property name="d6" value="0.0819" />
<!-- Arbitrary offsets for shoulder/elbow joints -->
<xacro:property name="shoulder_offset" value="0.1198" /> <!-- measured from model -->
<xacro:property name="elbow_offset" value="-0.0925" /> <!-- measured from model -->
<!-- link lengths used in model -->
<xacro:property name="shoulder_height" value="${d1}" />
<xacro:property name="upper_arm_length" value="${-a2}" />
<xacro:property name="forearm_length" value="${-a3}" />
<xacro:property name="wrist_1_length" value="${d4 - elbow_offset - shoulder_offset}" />
<xacro:property name="wrist_2_length" value="${d5}" />
<xacro:property name="wrist_3_length" value="${d6}" />
<link name="${prefix}base_link" >
<visual>
<geometry>
......@@ -148,8 +147,8 @@
<mesh filename="package://ur_description/meshes/ur3/collision/upperarm.stl"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="0.075" length="${-ur3_a2}" mass="${upper_arm_mass}">
<origin xyz="0.0 0.0 ${-ur3_a2/2.0}" rpy="0 0 0" />
<xacro:cylinder_inertial radius="0.075" length="${-a2}" mass="${upper_arm_mass}">
<origin xyz="0.0 0.0 ${-a2/2.0}" rpy="0 0 0" />
</xacro:cylinder_inertial>
</link>
......@@ -181,8 +180,8 @@
<mesh filename="package://ur_description/meshes/ur3/collision/forearm.stl"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="0.075" length="${-ur3_a3}" mass="${forearm_mass}">
<origin xyz="0.0 0.0 ${-ur3_a3/2.0}" rpy="0 0 0" />
<xacro:cylinder_inertial radius="0.075" length="${-a3}" mass="${forearm_mass}">
<origin xyz="0.0 0.0 ${-a3/2.0}" rpy="0 0 0" />
</xacro:cylinder_inertial>
</link>
......
......@@ -4,67 +4,6 @@
<xacro:include filename="$(find ur_description)/urdf/ur.transmission.xacro" />
<xacro:include filename="$(find ur_description)/urdf/ur.gazebo.xacro" />
<!-- Inertia parameters -->
<xacro:property name="base_mass" value="4.0" /> <!-- This mass might be incorrect -->
<xacro:property name="shoulder_mass" value="3.7000" />
<xacro:property name="upper_arm_mass" value="8.3930" />
<xacro:property name="forearm_mass" value="2.2750" />
<xacro:property name="wrist_1_mass" value="1.2190" />
<xacro:property name="wrist_2_mass" value="1.2190" />
<xacro:property name="wrist_3_mass" value="0.1879" />
<xacro:property name="shoulder_cog" value="0.0 0.00193 -0.02561" />
<xacro:property name="upper_arm_cog" value="0.0 -0.024201 0.2125" />
<xacro:property name="forearm_cog" value="0.0 0.0265 0.11993" />
<xacro:property name="wrist_1_cog" value="0.0 0.110949 0.01634" />
<xacro:property name="wrist_2_cog" value="0.0 0.0018 0.11099" />
<xacro:property name="wrist_3_cog" value="0.0 0.001159 0.0" />
<!-- Kinematic model -->
<!-- Properties from urcontrol.conf -->
<!--
DH for UR5:
a = [0.00000, -0.42500, -0.39225, 0.00000, 0.00000, 0.0000]
d = [0.089159, 0.00000, 0.00000, 0.10915, 0.09465, 0.0823]
alpha = [ 1.570796327, 0, 0, 1.570796327, -1.570796327, 0 ]
q_home_offset = [0, -1.570796327, 0, -1.570796327, 0, 0]
joint_direction = [-1, -1, 1, 1, 1, 1]
mass = [3.7000, 8.3930, 2.2750, 1.2190, 1.2190, 0.1879]
center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, 0.0265], [0, -0.0018, 0.01634], [0, 0.0018,0.01634], [0, 0, -0.001159] ]
-->
<xacro:property name="ur5_d1" value="0.089159" />
<xacro:property name="ur5_a2" value="-0.42500" />
<xacro:property name="ur5_a3" value="-0.39225" />
<xacro:property name="ur5_d4" value="0.10915" />
<xacro:property name="ur5_d5" value="0.09465" />
<xacro:property name="ur5_d6" value="0.0823" />
<!-- Arbitrary offsets for shoulder/elbow joints -->
<xacro:property name="shoulder_offset" value="0.13585" /> <!-- measured from model -->
<xacro:property name="elbow_offset" value="-0.1197" /> <!-- measured from model -->
<!-- link lengths used in model -->
<xacro:property name="shoulder_height" value="${ur5_d1}" />
<xacro:property name="upper_arm_length" value="${-ur5_a2}" />
<xacro:property name="forearm_length" value="${-ur5_a3}" />
<xacro:property name="wrist_1_length" value="${ur5_d4 - elbow_offset - shoulder_offset}" />
<xacro:property name="wrist_2_length" value="${ur5_d5}" />
<xacro:property name="wrist_3_length" value="${ur5_d6}" />
<!--property name="shoulder_height" value="0.089159" /-->
<!--property name="shoulder_offset" value="0.13585" /--> <!-- shoulder_offset - elbow_offset + wrist_1_length = 0.10915 -->
<!--property name="upper_arm_length" value="0.42500" /-->
<!--property name="elbow_offset" value="0.1197" /--> <!-- CAD measured -->
<!--property name="forearm_length" value="0.39225" /-->
<!--property name="wrist_1_length" value="0.093" /--> <!-- CAD measured -->
<!--property name="wrist_2_length" value="0.09465" /--> <!-- In CAD this distance is 0.930, but in the spec it is 0.09465 -->
<!--property name="wrist_3_length" value="0.0823" /-->
<xacro:property name="shoulder_radius" value="0.060" /> <!-- manually measured -->
<xacro:property name="upper_arm_radius" value="0.054" /> <!-- manually measured -->
<xacro:property name="elbow_radius" value="0.060" /> <!-- manually measured -->
<xacro:property name="forearm_radius" value="0.040" /> <!-- manually measured -->
<xacro:property name="wrist_radius" value="0.045" /> <!-- manually measured -->
<xacro:macro name="cylinder_inertial" params="radius length mass *origin">
<inertial>
<mass value="${mass}" />
......@@ -75,7 +14,6 @@
</inertial>
</xacro:macro>
<xacro:macro name="ur5_robot" params="prefix joint_limited
shoulder_pan_lower_limit:=${-pi} shoulder_pan_upper_limit:=${pi}
shoulder_lift_lower_limit:=${-pi} shoulder_lift_upper_limit:=${pi}
......@@ -84,6 +22,68 @@
wrist_2_lower_limit:=${-pi} wrist_2_upper_limit:=${pi}
wrist_3_lower_limit:=${-pi} wrist_3_upper_limit:=${pi}">
<!-- Inertia parameters -->
<xacro:property name="base_mass" value="4.0" /> <!-- This mass might be incorrect -->
<xacro:property name="shoulder_mass" value="3.7000" />
<xacro:property name="upper_arm_mass" value="8.3930" />
<xacro:property name="forearm_mass" value="2.2750" />
<xacro:property name="wrist_1_mass" value="1.2190" />
<xacro:property name="wrist_2_mass" value="1.2190" />
<xacro:property name="wrist_3_mass" value="0.1879" />
<xacro:property name="shoulder_cog" value="0.0 0.00193 -0.02561" />
<xacro:property name="upper_arm_cog" value="0.0 -0.024201 0.2125" />
<xacro:property name="forearm_cog" value="0.0 0.0265 0.11993" />
<xacro:property name="wrist_1_cog" value="0.0 0.110949 0.01634" />
<xacro:property name="wrist_2_cog" value="0.0 0.0018 0.11099" />
<xacro:property name="wrist_3_cog" value="0.0 0.001159 0.0" />
<!-- Kinematic model -->
<!-- Properties from urcontrol.conf -->
<!--
DH for UR5:
a = [0.00000, -0.42500, -0.39225, 0.00000, 0.00000, 0.0000]
d = [0.089159, 0.00000, 0.00000, 0.10915, 0.09465, 0.0823]
alpha = [ 1.570796327, 0, 0, 1.570796327, -1.570796327, 0 ]
q_home_offset = [0, -1.570796327, 0, -1.570796327, 0, 0]
joint_direction = [-1, -1, 1, 1, 1, 1]
mass = [3.7000, 8.3930, 2.2750, 1.2190, 1.2190, 0.1879]
center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, 0.0265], [0, -0.0018, 0.01634], [0, 0.0018,0.01634], [0, 0, -0.001159] ]
-->
<xacro:property name="d1" value="0.089159" />
<xacro:property name="a2" value="-0.42500" />
<xacro:property name="a3" value="-0.39225" />
<xacro:property name="d4" value="0.10915" />
<xacro:property name="d5" value="0.09465" />
<xacro:property name="d6" value="0.0823" />
<!-- Arbitrary offsets for shoulder/elbow joints -->
<xacro:property name="shoulder_offset" value="0.13585" /> <!-- measured from model -->
<xacro:property name="elbow_offset" value="-0.1197" /> <!-- measured from model -->
<!-- link lengths used in model -->
<xacro:property name="shoulder_height" value="${d1}" />
<xacro:property name="upper_arm_length" value="${-a2}" />
<xacro:property name="forearm_length" value="${-a3}" />
<xacro:property name="wrist_1_length" value="${d4 - elbow_offset - shoulder_offset}" />
<xacro:property name="wrist_2_length" value="${d5}" />
<xacro:property name="wrist_3_length" value="${d6}" />
<!--property name="shoulder_height" value="0.089159" /-->
<!--property name="shoulder_offset" value="0.13585" /--> <!-- shoulder_offset - elbow_offset + wrist_1_length = 0.10915 -->
<!--property name="upper_arm_length" value="0.42500" /-->
<!--property name="elbow_offset" value="0.1197" /--> <!-- CAD measured -->
<!--property name="forearm_length" value="0.39225" /-->
<!--property name="wrist_1_length" value="0.093" /--> <!-- CAD measured -->
<!--property name="wrist_2_length" value="0.09465" /--> <!-- In CAD this distance is 0.930, but in the spec it is 0.09465 -->
<!--property name="wrist_3_length" value="0.0823" /-->
<xacro:property name="shoulder_radius" value="0.060" /> <!-- manually measured -->
<xacro:property name="upper_arm_radius" value="0.054" /> <!-- manually measured -->
<xacro:property name="elbow_radius" value="0.060" /> <!-- manually measured -->
<xacro:property name="forearm_radius" value="0.040" /> <!-- manually measured -->
<xacro:property name="wrist_radius" value="0.045" /> <!-- manually measured -->
<link name="${prefix}base_link" >
<visual>
<geometry>
......
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