Skip to content
GitLab
Menu
Projects
Groups
Snippets
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
bigprint
universal_robot
Commits
4dc05496
Unverified
Commit
4dc05496
authored
Jul 02, 2019
by
G.A. vd. Hoorn
Committed by
GitHub
Jul 02, 2019
Browse files
Merge pull request #426 from fmauch/inertia
corrected dimensions and positions of inertias
parents
f0ad9f47
62011b0d
Changes
6
Hide whitespace changes
Inline
Side-by-side
ur_description/urdf/ur10.urdf.xacro
View file @
4dc05496
...
...
@@ -60,6 +60,7 @@
<!-- 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 -->
<xacro:property
name=
"upper_arm_inertia_offset"
value=
"0.045"
/>
<!-- measured from model -->
<!-- link lengths used in model -->
<xacro:property
name=
"shoulder_height"
value=
"${d1}"
/>
...
...
@@ -150,7 +151,7 @@
</geometry>
</collision>
<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"
/>
<origin
xyz=
"0.0
${-upper_arm_inertia_offset}
${-a2/2.0}"
rpy=
"0 0 0"
/>
</xacro:cylinder_inertial>
</link>
...
...
@@ -216,7 +217,7 @@
</geometry>
</collision>
<xacro:cylinder_inertial
radius=
"0.075"
length=
"0.12"
mass=
"${wrist_1_mass}"
>
<origin
xyz=
"0.0
0.0
0.0"
rpy=
"0 0 0"
/>
<origin
xyz=
"0.0
${wrist_1_length}
0.0"
rpy=
"0 0 0"
/>
</xacro:cylinder_inertial>
</link>
...
...
@@ -249,7 +250,7 @@
</geometry>
</collision>
<xacro:cylinder_inertial
radius=
"0.075"
length=
"0.12"
mass=
"${wrist_2_mass}"
>
<origin
xyz=
"0.0 0.0
0.0
"
rpy=
"0 0 0"
/>
<origin
xyz=
"0.0 0.0
${wrist_2_length}
"
rpy=
"0 0 0"
/>
</xacro:cylinder_inertial>
</link>
...
...
@@ -281,8 +282,8 @@
<mesh
filename=
"package://ur_description/meshes/ur10/collision/wrist3.stl"
/>
</geometry>
</collision>
<xacro:cylinder_inertial
radius=
"0.0
7
5"
length=
"0.
12
"
mass=
"${wrist_3_mass}"
>
<origin
xyz=
"0.0
0.0
0.0"
rpy=
"
0
0 0"
/>
<xacro:cylinder_inertial
radius=
"0.0
4
5"
length=
"0.
0305
"
mass=
"${wrist_3_mass}"
>
<origin
xyz=
"0.0
${wrist_3_length - 0.0305/2}
0.0"
rpy=
"
${pi/2}
0 0"
/>
</xacro:cylinder_inertial>
</link>
...
...
ur_description/urdf/ur3.urdf.xacro
View file @
4dc05496
...
...
@@ -215,7 +215,7 @@
</geometry>
</collision>
<xacro:cylinder_inertial
radius=
"0.075"
length=
"0.12"
mass=
"${wrist_1_mass}"
>
<origin
xyz=
"0.0
0.0
0.0"
rpy=
"0 0 0"
/>
<origin
xyz=
"0.0
${wrist_1_length}
0.0"
rpy=
"0 0 0"
/>
</xacro:cylinder_inertial>
</link>
...
...
@@ -248,7 +248,7 @@
</geometry>
</collision>
<xacro:cylinder_inertial
radius=
"0.075"
length=
"0.12"
mass=
"${wrist_2_mass}"
>
<origin
xyz=
"0.0 0.0
0.0
"
rpy=
"0 0 0"
/>
<origin
xyz=
"0.0 0.0
${wrist_2_length}
"
rpy=
"0 0 0"
/>
</xacro:cylinder_inertial>
</link>
...
...
@@ -280,8 +280,8 @@
<mesh
filename=
"package://ur_description/meshes/ur3/collision/wrist3.stl"
/>
</geometry>
</collision>
<xacro:cylinder_inertial
radius=
"0.0
75
"
length=
"0.
12
"
mass=
"${wrist_3_mass}"
>
<origin
xyz=
"0.0 0.0 0.0"
rpy=
"
0
0 0"
/>
<xacro:cylinder_inertial
radius=
"0.0
32
"
length=
"0.
04
"
mass=
"${wrist_3_mass}"
>
<origin
xyz=
"0.0
${wrist_3_length -
0.0
2}
0.0"
rpy=
"
${pi/2}
0 0"
/>
</xacro:cylinder_inertial>
</link>
...
...
ur_description/urdf/ur5.urdf.xacro
View file @
4dc05496
...
...
@@ -198,8 +198,8 @@
<mesh
filename=
"package://ur_description/meshes/ur5/collision/forearm.stl"
/>
</geometry>
</collision>
<xacro:cylinder_inertial
radius=
"0.06"
length=
"
0.5
"
mass=
"${forearm_mass}"
>
<origin
xyz=
"0.0 0.0
0.25
"
rpy=
"0 0 0"
/>
<xacro:cylinder_inertial
radius=
"0.06"
length=
"
${-a3}
"
mass=
"${forearm_mass}"
>
<origin
xyz=
"0.0 0.0
${-a3/2}
"
rpy=
"0 0 0"
/>
</xacro:cylinder_inertial>
</link>
...
...
@@ -231,8 +231,8 @@
<mesh
filename=
"package://ur_description/meshes/ur5/collision/wrist1.stl"
/>
</geometry>
</collision>
<xacro:cylinder_inertial
radius=
"0.6"
length=
"0.12"
mass=
"${wrist_1_mass}"
>
<origin
xyz=
"0.0
0.0
0.0"
rpy=
"0 0 0"
/>
<xacro:cylinder_inertial
radius=
"0.
0
6"
length=
"0.12"
mass=
"${wrist_1_mass}"
>
<origin
xyz=
"0.0
${wrist_1_length}
0.0"
rpy=
"0 0 0"
/>
</xacro:cylinder_inertial>
</link>
...
...
@@ -264,8 +264,8 @@
<mesh
filename=
"package://ur_description/meshes/ur5/collision/wrist2.stl"
/>
</geometry>
</collision>
<xacro:cylinder_inertial
radius=
"0.6"
length=
"0.12"
mass=
"${wrist_2_mass}"
>
<origin
xyz=
"0.0 0.0
0.0
"
rpy=
"0 0 0"
/>
<xacro:cylinder_inertial
radius=
"0.
0
6"
length=
"0.12"
mass=
"${wrist_2_mass}"
>
<origin
xyz=
"0.0 0.0
${wrist_2_length}
"
rpy=
"0 0 0"
/>
</xacro:cylinder_inertial>
</link>
...
...
@@ -297,8 +297,8 @@
<mesh
filename=
"package://ur_description/meshes/ur5/collision/wrist3.stl"
/>
</geometry>
</collision>
<xacro:cylinder_inertial
radius=
"0.
6
"
length=
"0.
12
"
mass=
"${wrist_3_mass}"
>
<origin
xyz=
"0.0
0.0
0.0"
rpy=
"
0
0 0"
/>
<xacro:cylinder_inertial
radius=
"0.
0375
"
length=
"0.
0345
"
mass=
"${wrist_3_mass}"
>
<origin
xyz=
"0.0
${wrist_3_length - 0.0345/2}
0.0"
rpy=
"
${pi/2}
0 0"
/>
</xacro:cylinder_inertial>
</link>
...
...
ur_e_description/urdf/ur10e.urdf.xacro
View file @
4dc05496
...
...
@@ -215,7 +215,7 @@
</geometry>
</collision>
<xacro:cylinder_inertial
radius=
"0.075"
length=
"0.12"
mass=
"${wrist_1_mass}"
>
<origin
xyz=
"0.0
0.0
0.0"
rpy=
"0 0 0"
/>
<origin
xyz=
"0.0
${wrist_1_length}
0.0"
rpy=
"0 0 0"
/>
</xacro:cylinder_inertial>
</link>
...
...
@@ -248,7 +248,7 @@
</geometry>
</collision>
<xacro:cylinder_inertial
radius=
"0.075"
length=
"0.12"
mass=
"${wrist_2_mass}"
>
<origin
xyz=
"0.0 0.0
0.0
"
rpy=
"0 0 0"
/>
<origin
xyz=
"0.0 0.0
${wrist_2_length}
"
rpy=
"0 0 0"
/>
</xacro:cylinder_inertial>
</link>
...
...
@@ -280,8 +280,8 @@
<mesh
filename=
"package://ur_e_description/meshes/ur10e/collision/wrist3.stl"
/>
</geometry>
</collision>
<xacro:cylinder_inertial
radius=
"0.0
7
5"
length=
"0.
12
"
mass=
"${wrist_3_mass}"
>
<origin
xyz=
"0.0
0.0
0.0"
rpy=
"
0
0 0"
/>
<xacro:cylinder_inertial
radius=
"0.0
4
5"
length=
"0.
05
"
mass=
"${wrist_3_mass}"
>
<origin
xyz=
"0.0
${wrist_3_length - 0.05/2}
0.0"
rpy=
"
${pi/2}
0 0"
/>
</xacro:cylinder_inertial>
</link>
...
...
ur_e_description/urdf/ur3e.urdf.xacro
View file @
4dc05496
...
...
@@ -214,7 +214,7 @@
</geometry>
</collision>
<xacro:cylinder_inertial
radius=
"0.075"
length=
"0.12"
mass=
"${wrist_1_mass}"
>
<origin
xyz=
"0.0
0.0
0.0"
rpy=
"0 0 0"
/>
<origin
xyz=
"0.0
${wrist_1_length}
0.0"
rpy=
"0 0 0"
/>
</xacro:cylinder_inertial>
</link>
...
...
@@ -247,7 +247,7 @@
</geometry>
</collision>
<xacro:cylinder_inertial
radius=
"0.075"
length=
"0.12"
mass=
"${wrist_2_mass}"
>
<origin
xyz=
"0.0 0.0
0.0
"
rpy=
"0 0 0"
/>
<origin
xyz=
"0.0 0.0
${wrist_2_length}
"
rpy=
"0 0 0"
/>
</xacro:cylinder_inertial>
</link>
...
...
@@ -279,8 +279,8 @@
<mesh
filename=
"package://ur_e_description/meshes/ur3e/collision/wrist3.stl"
/>
</geometry>
</collision>
<xacro:cylinder_inertial
radius=
"0.0
75
"
length=
"0.
1
2"
mass=
"${wrist_3_mass}"
>
<origin
xyz=
"0.0
0.0
0.0"
rpy=
"
0
0 0"
/>
<xacro:cylinder_inertial
radius=
"0.0
32
"
length=
"0.
04
2"
mass=
"${wrist_3_mass}"
>
<origin
xyz=
"0.0
${wrist_3_length - 0.021}
0.0"
rpy=
"
${pi/2}
0 0"
/>
</xacro:cylinder_inertial>
</link>
...
...
ur_e_description/urdf/ur5e.urdf.xacro
View file @
4dc05496
...
...
@@ -164,8 +164,8 @@
<mesh
filename=
"package://ur_e_description/meshes/ur5e/collision/upperarm.stl"
/>
</geometry>
</collision>
<xacro:cylinder_inertial
radius=
"0.06"
length=
"
0.56
"
mass=
"${upper_arm_mass}"
>
<origin
xyz=
"0.0 0.0
0.28
"
rpy=
"0 0 0"
/>
<xacro:cylinder_inertial
radius=
"0.06"
length=
"
${upper_arm_length}
"
mass=
"${upper_arm_mass}"
>
<origin
xyz=
"0.0 0.0
${upper_arm_length/2}
"
rpy=
"0 0 0"
/>
</xacro:cylinder_inertial>
</link>
...
...
@@ -197,8 +197,8 @@
<mesh
filename=
"package://ur_e_description/meshes/ur5e/collision/forearm.stl"
/>
</geometry>
</collision>
<xacro:cylinder_inertial
radius=
"0.06"
length=
"
0.5
"
mass=
"${forearm_mass}"
>
<origin
xyz=
"0.0 0.0
0.25
"
rpy=
"0 0 0"
/>
<xacro:cylinder_inertial
radius=
"0.06"
length=
"
${forearm_length}
"
mass=
"${forearm_mass}"
>
<origin
xyz=
"0.0 0.0
${forearm_length/2}
"
rpy=
"0 0 0"
/>
</xacro:cylinder_inertial>
</link>
...
...
@@ -230,8 +230,8 @@
<mesh
filename=
"package://ur_e_description/meshes/ur5e/collision/wrist1.stl"
/>
</geometry>
</collision>
<xacro:cylinder_inertial
radius=
"0.6"
length=
"0.12"
mass=
"${wrist_1_mass}"
>
<origin
xyz=
"0.0
0.0
0.0"
rpy=
"0 0 0"
/>
<xacro:cylinder_inertial
radius=
"0.
0
6"
length=
"0.12"
mass=
"${wrist_1_mass}"
>
<origin
xyz=
"0.0
${wrist_1_length}
0.0"
rpy=
"0 0 0"
/>
</xacro:cylinder_inertial>
</link>
...
...
@@ -263,8 +263,8 @@
<mesh
filename=
"package://ur_e_description/meshes/ur5e/collision/wrist2.stl"
/>
</geometry>
</collision>
<xacro:cylinder_inertial
radius=
"0.6"
length=
"0.12"
mass=
"${wrist_2_mass}"
>
<origin
xyz=
"0.0 0.0
0.0
"
rpy=
"0 0 0"
/>
<xacro:cylinder_inertial
radius=
"0.
0
6"
length=
"0.12"
mass=
"${wrist_2_mass}"
>
<origin
xyz=
"0.0 0.0
${wrist_2_length}
"
rpy=
"0 0 0"
/>
</xacro:cylinder_inertial>
</link>
...
...
@@ -296,8 +296,8 @@
<mesh
filename=
"package://ur_e_description/meshes/ur5e/collision/wrist3.stl"
/>
</geometry>
</collision>
<xacro:cylinder_inertial
radius=
"0.
6
"
length=
"0.
12
"
mass=
"${wrist_3_mass}"
>
<origin
xyz=
"0.0
0.0
0.0"
rpy=
"
0
0 0"
/>
<xacro:cylinder_inertial
radius=
"0.
0375
"
length=
"0.
0458
"
mass=
"${wrist_3_mass}"
>
<origin
xyz=
"0.0
${wrist_3_length - 0.0458/2}
0.0"
rpy=
"
${pi/2}
0 0"
/>
</xacro:cylinder_inertial>
</link>
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
.
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment