Initial commit
This commit is contained in:
42
arm_1dof/demo_human_col/meshes/distal.mtl
Normal file
42
arm_1dof/demo_human_col/meshes/distal.mtl
Normal file
@@ -0,0 +1,42 @@
|
||||
# Blender MTL File: 'skeleton_combined_fingers.blend'
|
||||
# Material Count: 4
|
||||
|
||||
newmtl mymaterial.024
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.031
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.034
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.035
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
25996
arm_1dof/demo_human_col/meshes/distal.obj
Normal file
25996
arm_1dof/demo_human_col/meshes/distal.obj
Normal file
File diff suppressed because it is too large
Load Diff
22
arm_1dof/demo_human_col/meshes/forearm.mtl
Normal file
22
arm_1dof/demo_human_col/meshes/forearm.mtl
Normal file
@@ -0,0 +1,22 @@
|
||||
# Blender MTL File: 'skeleton_combined_fingers.blend'
|
||||
# Material Count: 2
|
||||
|
||||
newmtl mymaterial.037
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.038
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
1996
arm_1dof/demo_human_col/meshes/forearm.obj
Normal file
1996
arm_1dof/demo_human_col/meshes/forearm.obj
Normal file
File diff suppressed because it is too large
Load Diff
132
arm_1dof/demo_human_col/meshes/hand.mtl
Normal file
132
arm_1dof/demo_human_col/meshes/hand.mtl
Normal file
@@ -0,0 +1,132 @@
|
||||
# Blender MTL File: 'skeleton_combined_fingers.blend'
|
||||
# Material Count: 13
|
||||
|
||||
newmtl mymaterial.008
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.009
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.010
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.011
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.012
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.013
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.014
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.016
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.017
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.018
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.019
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.039
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.044
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
168006
arm_1dof/demo_human_col/meshes/hand.obj
Normal file
168006
arm_1dof/demo_human_col/meshes/hand.obj
Normal file
File diff suppressed because it is too large
Load Diff
70
arm_1dof/demo_human_col/meshes/hand_col.dae
Normal file
70
arm_1dof/demo_human_col/meshes/hand_col.dae
Normal file
File diff suppressed because one or more lines are too long
42
arm_1dof/demo_human_col/meshes/middle.mtl
Normal file
42
arm_1dof/demo_human_col/meshes/middle.mtl
Normal file
@@ -0,0 +1,42 @@
|
||||
# Blender MTL File: 'skeleton_combined_fingers.blend'
|
||||
# Material Count: 4
|
||||
|
||||
newmtl mymaterial.023
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.025
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.027
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.033
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
20254
arm_1dof/demo_human_col/meshes/middle.obj
Normal file
20254
arm_1dof/demo_human_col/meshes/middle.obj
Normal file
File diff suppressed because it is too large
Load Diff
70
arm_1dof/demo_human_col/meshes/middle_col.dae
Normal file
70
arm_1dof/demo_human_col/meshes/middle_col.dae
Normal file
File diff suppressed because one or more lines are too long
42
arm_1dof/demo_human_col/meshes/proximal.mtl
Normal file
42
arm_1dof/demo_human_col/meshes/proximal.mtl
Normal file
@@ -0,0 +1,42 @@
|
||||
# Blender MTL File: 'skeleton_combined_fingers.blend'
|
||||
# Material Count: 4
|
||||
|
||||
newmtl mymaterial.022
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.026
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.030
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.032
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
49733
arm_1dof/demo_human_col/meshes/proximal.obj
Normal file
49733
arm_1dof/demo_human_col/meshes/proximal.obj
Normal file
File diff suppressed because it is too large
Load Diff
70
arm_1dof/demo_human_col/meshes/proximal_col.dae
Normal file
70
arm_1dof/demo_human_col/meshes/proximal_col.dae
Normal file
File diff suppressed because one or more lines are too long
261
arm_1dof/demo_human_col/meshes/skeleton.dae
Normal file
261
arm_1dof/demo_human_col/meshes/skeleton.dae
Normal file
File diff suppressed because one or more lines are too long
62
arm_1dof/demo_human_col/meshes/skeleton.mtl
Normal file
62
arm_1dof/demo_human_col/meshes/skeleton.mtl
Normal file
@@ -0,0 +1,62 @@
|
||||
# Blender MTL File: 'skeleton_combined_fingers.blend'
|
||||
# Material Count: 6
|
||||
|
||||
newmtl mymaterial
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.001
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.002
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.004
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.040
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
|
||||
newmtl mymaterial.041
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
68928
arm_1dof/demo_human_col/meshes/skeleton.obj
Normal file
68928
arm_1dof/demo_human_col/meshes/skeleton.obj
Normal file
File diff suppressed because it is too large
Load Diff
12
arm_1dof/demo_human_col/meshes/thumb_1.mtl
Normal file
12
arm_1dof/demo_human_col/meshes/thumb_1.mtl
Normal file
@@ -0,0 +1,12 @@
|
||||
# Blender MTL File: 'skeleton_combined_fingers.blend'
|
||||
# Material Count: 1
|
||||
|
||||
newmtl mymaterial.015
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
14521
arm_1dof/demo_human_col/meshes/thumb_1.obj
Normal file
14521
arm_1dof/demo_human_col/meshes/thumb_1.obj
Normal file
File diff suppressed because it is too large
Load Diff
12
arm_1dof/demo_human_col/meshes/thumb_2.mtl
Normal file
12
arm_1dof/demo_human_col/meshes/thumb_2.mtl
Normal file
@@ -0,0 +1,12 @@
|
||||
# Blender MTL File: 'skeleton_combined_fingers.blend'
|
||||
# Material Count: 1
|
||||
|
||||
newmtl mymaterial.021
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
9941
arm_1dof/demo_human_col/meshes/thumb_2.obj
Normal file
9941
arm_1dof/demo_human_col/meshes/thumb_2.obj
Normal file
File diff suppressed because it is too large
Load Diff
12
arm_1dof/demo_human_col/meshes/thumb_3.mtl
Normal file
12
arm_1dof/demo_human_col/meshes/thumb_3.mtl
Normal file
@@ -0,0 +1,12 @@
|
||||
# Blender MTL File: 'skeleton_combined_fingers.blend'
|
||||
# Material Count: 1
|
||||
|
||||
newmtl mymaterial.020
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
8791
arm_1dof/demo_human_col/meshes/thumb_3.obj
Normal file
8791
arm_1dof/demo_human_col/meshes/thumb_3.obj
Normal file
File diff suppressed because it is too large
Load Diff
12
arm_1dof/demo_human_col/meshes/upper_arm.mtl
Normal file
12
arm_1dof/demo_human_col/meshes/upper_arm.mtl
Normal file
@@ -0,0 +1,12 @@
|
||||
# Blender MTL File: 'skeleton_combined_fingers.blend'
|
||||
# Material Count: 1
|
||||
|
||||
newmtl mymaterial.003
|
||||
Ns 225.000000
|
||||
Ka 1.000000 1.000000 1.000000
|
||||
Kd 0.800000 0.800000 0.800000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
Ke 0.000000 0.000000 0.000000
|
||||
Ni 1.450000
|
||||
d 1.000000
|
||||
illum 2
|
||||
1491
arm_1dof/demo_human_col/meshes/upper_arm.obj
Normal file
1491
arm_1dof/demo_human_col/meshes/upper_arm.obj
Normal file
File diff suppressed because it is too large
Load Diff
15
arm_1dof/demo_human_col/model.config
Normal file
15
arm_1dof/demo_human_col/model.config
Normal file
@@ -0,0 +1,15 @@
|
||||
<?xml version="1.0"?>
|
||||
<model>
|
||||
<name>Demonstrator Human Model</name>
|
||||
<version>1.0</version>
|
||||
<sdf version='1.5'>skeleton.sdf</sdf>
|
||||
|
||||
<author>
|
||||
<name>Michael Zechmair</name>
|
||||
<email>m.zechmair@maastrichtuniversity.nl</email>
|
||||
</author>
|
||||
|
||||
<description>
|
||||
Upper half of human skeleton with actuated right arm, hand, and fingers. Fingers are joined together
|
||||
</description>
|
||||
</model>
|
||||
463
arm_1dof/demo_human_col/skeleton.sdf
Normal file
463
arm_1dof/demo_human_col/skeleton.sdf
Normal file
@@ -0,0 +1,463 @@
|
||||
<?xml version='1.0'?>
|
||||
<sdf version="1.5">
|
||||
<model name="skeleton">
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<link name="skeleton">
|
||||
<pose>-0.02371838688850403 -0.006475403904914856 1.7455708980560303 1.5707963705062866 -0.0 0.0</pose>
|
||||
<inertial>
|
||||
<inertia>
|
||||
<ixx>0.0001</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.0001</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.0001</izz>
|
||||
</inertia>
|
||||
<mass>0.20000000298023224</mass>
|
||||
</inertial>
|
||||
<visual name="visual">
|
||||
<pose>0 0 0 -1.5757 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh><uri>model://demo_human_col/meshes/skeleton.dae</uri></mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision name="collision">
|
||||
<pose>0 0 0 -1.5757 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh><uri>model://demo_human_col/meshes/skeleton.dae</uri></mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<link name="upper_arm">
|
||||
<pose>-0.017282448709011078 -0.1665889173746109 1.6547614336013794 1.5707963705062866 -0.0 0.0</pose>
|
||||
<inertial>
|
||||
<inertia>
|
||||
<ixx>0.0001</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.0001</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.0001</izz>
|
||||
</inertia>
|
||||
<mass>0.19999998807907104</mass>
|
||||
</inertial>
|
||||
<visual name="visual">
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh><uri>model://demo_human_col/meshes/upper_arm.obj</uri></mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision name="collision">
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh><uri>model://demo_human_col/meshes/upper_arm.obj</uri></mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<link name="forearm">
|
||||
<pose>-0.015147986821830273 -0.19349825382232666 1.3854427337646484 1.5707963705062866 -0.0 0.0</pose>
|
||||
<inertial>
|
||||
<inertia>
|
||||
<ixx>0.0001</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.0001</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.0001</izz>
|
||||
</inertia>
|
||||
<mass>0.19999998807907104</mass>
|
||||
</inertial>
|
||||
<visual name="visual">
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh><uri>model://demo_human_col/meshes/forearm.obj</uri></mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision name="collision">
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh><uri>model://demo_human_col/meshes/forearm.obj</uri></mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<link name="hand">
|
||||
<pose>0.00017236836720257998 -0.22414515912532806 1.2197521924972534 1.5707963705062866 -0.0 0.0</pose>
|
||||
<inertial>
|
||||
<inertia>
|
||||
<ixx>0.0001</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.0001</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.0001</izz>
|
||||
</inertia>
|
||||
<mass>0.19999998807907104</mass>
|
||||
</inertial>
|
||||
<visual name="visual">
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh><uri>model://demo_human_col/meshes/hand.obj</uri></mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision name="collision">
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh><uri>model://demo_human_col/meshes/hand_col.dae</uri></mesh>
|
||||
</geometry>
|
||||
<surface>
|
||||
<friction>
|
||||
<ode>
|
||||
<mu>10</mu>
|
||||
<mu2>10</mu2>
|
||||
</ode>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
</link>
|
||||
<link name="thumb_1">
|
||||
<pose>0.01882072165608406 -0.2590509057044983 1.2172046899795532 1.5707963705062866 -0.0 0.0</pose>
|
||||
<inertial>
|
||||
<inertia>
|
||||
<ixx>0.0001</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.0001</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.0001</izz>
|
||||
</inertia>
|
||||
<mass>0.19999998807907104</mass>
|
||||
</inertial>
|
||||
<visual name="visual">
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh><uri>model://demo_human_col/meshes/thumb_1.obj</uri></mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<!--<collision name="collision">
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh><uri>model://demo_human_col/meshes/thumb_1.obj</uri></mesh>
|
||||
</geometry>
|
||||
</collision>-->
|
||||
</link>
|
||||
<link name="thumb_2">
|
||||
<pose>0.035507991909980774 -0.2781006395816803 1.1910896301269531 1.5707963705062866 2.980238988925521e-08 -3.7253098383871475e-09</pose>
|
||||
<inertial>
|
||||
<inertia>
|
||||
<ixx>0.0001</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.0001</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.0001</izz>
|
||||
</inertia>
|
||||
<mass>0.19999998807907104</mass>
|
||||
</inertial>
|
||||
<visual name="visual">
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh><uri>model://demo_human_col/meshes/thumb_2.obj</uri></mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<!--<collision name="collision">
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh><uri>model://demo_human_col/meshes/thumb_2.obj</uri></mesh>
|
||||
</geometry>
|
||||
</collision>-->
|
||||
</link>
|
||||
<link name="thumb_3">
|
||||
<pose>0.04606077820062637 -0.29002290964126587 1.1742767095565796 1.5381336212158203 -0.012799005955457687 -0.015970906242728233</pose>
|
||||
<inertial>
|
||||
<inertia>
|
||||
<ixx>0.0001</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.0001</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.0001</izz>
|
||||
</inertia>
|
||||
<mass>0.19999998807907104</mass>
|
||||
</inertial>
|
||||
<visual name="visual">
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh><uri>model://demo_human_col/meshes/thumb_3.obj</uri></mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<!--<collision name="collision">
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh><uri>model://demo_human_col/meshes/thumb_3.obj</uri></mesh>
|
||||
</geometry>
|
||||
</collision>-->
|
||||
</link>
|
||||
<link name="proximal">
|
||||
<pose>0.004435993731021881 -0.23311419785022736 1.1511282920837402 1.5707964897155762 0.049396030604839325 1.5318446511258799e-09</pose>
|
||||
<inertial>
|
||||
<inertia>
|
||||
<ixx>0.0001</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.0001</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.0001</izz>
|
||||
</inertia>
|
||||
<mass>0.19999998807907104</mass>
|
||||
</inertial>
|
||||
<visual name="visual">
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh><uri>model://demo_human_col/meshes/proximal.obj</uri></mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision name="collision">
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh><uri>model://demo_human_col/meshes/proximal_col.dae</uri></mesh>
|
||||
</geometry>
|
||||
<surface>
|
||||
<friction>
|
||||
<ode>
|
||||
<mu>10</mu>
|
||||
<mu2>10</mu2>
|
||||
</ode>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
</link>
|
||||
<link name="middle">
|
||||
<pose>0.01475201454013586 -0.23537978529930115 1.1197322607040405 1.5707963705062866 -0.12925152480602264 -1.8796277034827114e-10</pose>
|
||||
<inertial>
|
||||
<inertia>
|
||||
<ixx>0.0001</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.0001</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.0001</izz>
|
||||
</inertia>
|
||||
<mass>0.19999998807907104</mass>
|
||||
</inertial>
|
||||
<visual name="visual">
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh><uri>model://demo_human_col/meshes/middle.obj</uri></mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision name="collision">
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh><uri>model://demo_human_col/meshes/middle_col.dae</uri></mesh>
|
||||
</geometry>
|
||||
<surface>
|
||||
<friction>
|
||||
<ode>
|
||||
<mu>10</mu>
|
||||
<mu2>10</mu2>
|
||||
</ode>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
</link>
|
||||
<link name="distal">
|
||||
<pose>0.024000873789191246 -0.2371281534433365 1.1017308235168457 1.5707963705062866 -0.14935961365699768 4.265647834955644e-09</pose>
|
||||
<inertial>
|
||||
<inertia>
|
||||
<ixx>0.0001</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.0001</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.0001</izz>
|
||||
</inertia>
|
||||
<mass>0.19999998807907104</mass>
|
||||
</inertial>
|
||||
<visual name="visual">
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh><uri>model://demo_human_col/meshes/distal.obj</uri></mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision name="collision">
|
||||
<pose>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh><uri>model://demo_human_col/meshes/distal.obj</uri></mesh>
|
||||
</geometry>
|
||||
<surface>
|
||||
<friction>
|
||||
<ode>
|
||||
<mu>10</mu>
|
||||
<mu2>10</mu2>
|
||||
</ode>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<!-- <joint name="world_root" type="fixed">
|
||||
<parent>world</parent>
|
||||
<child>skeleton</child>
|
||||
</joint> -->
|
||||
<joint name="shoulder_joint" type="revolute">
|
||||
<parent>skeleton</parent>
|
||||
<child>upper_arm</child>
|
||||
<pose>-0.0002625510096549988 0.1382385492324829 0.0034110769629478455 5.479091100824007e-07 -4.2146872658577195e-08 -1.570796251296997</pose>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-0.1</lower>
|
||||
<upper>0.7853981852531433</upper>
|
||||
</limit>
|
||||
</axis>
|
||||
<dynamics>
|
||||
<spring_reference>0.4</spring_reference>
|
||||
<spring_stiffness>20</spring_stiffness>
|
||||
<damping>4</damping>
|
||||
</dynamics>
|
||||
</joint>
|
||||
<joint name="elbow_joint" type="revolute">
|
||||
<parent>upper_arm</parent>
|
||||
<child>forearm</child>
|
||||
<pose>0.003702986752614379 0.11655723303556442 -0.035798244178295135 5.479091100824007e-07 -4.2146872658577195e-08 -1.570796251296997</pose>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>0.0</lower>
|
||||
<upper>1.5707963705062866</upper>
|
||||
</limit>
|
||||
</axis>
|
||||
<dynamics>
|
||||
<spring_reference>0.2</spring_reference>
|
||||
<spring_stiffness>5</spring_stiffness>
|
||||
<damping>1</damping>
|
||||
</dynamics>
|
||||
</joint>
|
||||
<joint name="hand_joint_1" type="fixed">
|
||||
<parent>forearm</parent>
|
||||
<child>hand</child>
|
||||
<pose>-0.003728454699739814 0.04303407669067383 -0.002157732844352722 5.479091100824007e-07 -4.2146872658577195e-08 -1.570796251296997</pose>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>0.0</lower>
|
||||
<upper>1.5707963705062866</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>10</spring_stiffness>
|
||||
<damping>1</damping>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<joint name="proximal_joint" type="revolute">
|
||||
<parent>hand</parent>
|
||||
<child>proximal</child>
|
||||
<pose>-0.006849215365946293 0.01723306067287922 -0.006170365028083324 0.18470512330532074 -0.15172354876995087 -1.2801685333251953</pose>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>0.0</lower>
|
||||
<!-- <upper>2.268928028</upper> -->
|
||||
<upper>2.0</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>2.0</spring_reference>
|
||||
<spring_stiffness>0.5</spring_stiffness>
|
||||
<damping>0.01</damping>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<joint name="thumb_joint_01" type="fixed">
|
||||
<parent>hand</parent>
|
||||
<child>thumb_1</child>
|
||||
<pose>-0.01046721264719963 0.01605987548828125 -0.016701191663742065 -2.392087459564209 -0.6794252395629883 -0.9853883385658264</pose>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-0.7853981852531433</lower>
|
||||
<upper>0.7853981852531433</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>1</spring_stiffness>
|
||||
<damping>0.1</damping>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<joint name="thumb_joint_12" type="fixed">
|
||||
<parent>thumb_1</parent>
|
||||
<child>thumb_2</child>
|
||||
<pose>-0.007540013175457716 0.013107539154589176 -0.009685487486422062 -1.7563650608062744 -0.576974093914032 -1.0101017951965332</pose>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>0.0</lower>
|
||||
<upper>1.5707963705062866</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>1</spring_stiffness>
|
||||
<damping>0.1</damping>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<joint name="thumb_joint_23" type="fixed">
|
||||
<parent>thumb_2</parent>
|
||||
<child>thumb_3</child>
|
||||
<pose>-0.004397843033075333 0.006628620438277721 -0.00488283671438694 -1.7522913217544556 -0.5405974984169006 -1.0248005390167236</pose>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>0.0</lower>
|
||||
<upper>1.5707963705062866</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>1</spring_stiffness>
|
||||
<damping>0.1</damping>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<joint name="middle_joint" type="revolute">
|
||||
<parent>proximal</parent>
|
||||
<child>middle</child>
|
||||
<pose>-0.005126905627548695 0.008538579568266869 -0.001958192093297839 0.18470518290996552 -0.1517234593629837 -1.4588162899017334</pose>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>0.0</lower>
|
||||
<upper>1.5707963705062866</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>1.57</spring_reference>
|
||||
<spring_stiffness>0.5</spring_stiffness>
|
||||
<damping>0.1</damping>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<joint name="distal_joint" type="revolute">
|
||||
<parent>middle</parent>
|
||||
<child>distal</child>
|
||||
<pose>-0.0028767052572220564 0.0012630047276616096 -0.0008793922024779022 0.18470518290996552 -0.1517234444618225 -1.4789243936538696</pose>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>0.0</lower>
|
||||
<upper>1.5707963705062866</upper>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<spring_reference>1.57</spring_reference>
|
||||
<spring_stiffness>0.5</spring_stiffness>
|
||||
<damping>0.01</damping>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
<plugin name="CapMaterial" filename="ModelCapacitivePropertiesPlugin.so">
|
||||
<RelativePermittivity>100000.0</RelativePermittivity>
|
||||
<!-- <CylLength></CylLength>
|
||||
<CylRadius></CylRadius>
|
||||
<NumWedges></NumWedges> -->
|
||||
</plugin>
|
||||
</model>
|
||||
</sdf>
|
||||
238
arm_1dof/demo_human_col/skeleton.urdf
Normal file
238
arm_1dof/demo_human_col/skeleton.urdf
Normal file
@@ -0,0 +1,238 @@
|
||||
<?xml version="1.0" ?>
|
||||
<robot name="skeleton">
|
||||
<joint name="skeleton__shoulder_joint" type="revolute">
|
||||
<parent link="skeleton__skeleton"/>
|
||||
<child link="skeleton__upper_arm"/>
|
||||
<origin xyz="-0.01754 -0.17 1.793" rpy="1.59151 1.57079 0.02072"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit lower="-0.1" upper="0.7853981852531433" effort="0.0" velocity="0.0"/>
|
||||
</joint>
|
||||
<joint name="skeleton__elbow_joint" type="revolute">
|
||||
<parent link="skeleton__upper_arm"/>
|
||||
<child link="skeleton__forearm"/>
|
||||
<origin xyz="0.29099 0.0061 -0.0123" rpy="0 0 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit lower="0.0" upper="1.5707963705062866" effort="0.0" velocity="0.0"/>
|
||||
</joint>
|
||||
<joint name="skeleton__hand_joint_1" type="fixed">
|
||||
<parent link="skeleton__forearm"/>
|
||||
<child link="skeleton__hand"/>
|
||||
<origin xyz="0.23921 0.00788 0.06428" rpy="0 0 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit lower="0.0" upper="1.5707963705062866" effort="0.0" velocity="0.0"/>
|
||||
</joint>
|
||||
<joint name="skeleton__proximal_joint" type="revolute">
|
||||
<parent link="skeleton__hand"/>
|
||||
<child link="skeleton__proximal"/>
|
||||
<origin xyz="0.0941 0.002 0.00495" rpy="0.1847 -0.15172 0.24123"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit lower="0.0" upper="2.0" effort="0.0" velocity="0.0"/>
|
||||
</joint>
|
||||
<joint name="skeleton__thumb_joint_01" type="fixed">
|
||||
<parent link="skeleton__hand"/>
|
||||
<child link="skeleton__thumb_1"/>
|
||||
<origin xyz="0.02952 0.01191 0.02036" rpy="-2.39208 -0.67942 0.5854"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit lower="-0.7853981852531433" upper="0.7853981852531433" effort="0.0" velocity="0.0"/>
|
||||
</joint>
|
||||
<joint name="skeleton__thumb_joint_12" type="fixed">
|
||||
<parent link="skeleton__thumb_1"/>
|
||||
<child link="skeleton__thumb_2"/>
|
||||
<origin xyz="0.04365 0.00098 0.00148" rpy="0.61859 -0.06067 0.08498"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit lower="0.0" upper="1.5707963705062866" effort="0.0" velocity="0.0"/>
|
||||
</joint>
|
||||
<joint name="skeleton__thumb_joint_23" type="fixed">
|
||||
<parent link="skeleton__thumb_2"/>
|
||||
<child link="skeleton__thumb_3"/>
|
||||
<origin xyz="0.03175 0.0012 -0.00069" rpy="0 0 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit lower="0.0" upper="1.5707963705062866" effort="0.0" velocity="0.0"/>
|
||||
</joint>
|
||||
<joint name="skeleton__middle_joint" type="revolute">
|
||||
<parent link="skeleton__proximal"/>
|
||||
<child link="skeleton__middle"/>
|
||||
<origin xyz="0.04285 0 0" rpy="0 0 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit lower="0.0" upper="1.5707963705062866" effort="0.0" velocity="0.0"/>
|
||||
</joint>
|
||||
<joint name="skeleton__distal_joint" type="revolute">
|
||||
<parent link="skeleton__middle"/>
|
||||
<child link="skeleton__distal"/>
|
||||
<origin xyz="0.02734 0.00572 -0.00241" rpy="0 0 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit lower="0.0" upper="1.5707963705062866" effort="0.0" velocity="0.0"/>
|
||||
</joint>
|
||||
<link name="skeleton__skeleton">
|
||||
<inertial>
|
||||
<mass value="0.20000000298023224"/>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||
</inertial>
|
||||
<collision name="skeleton__collision">
|
||||
<origin xyz="-0.02371 -0.00647 1.74557" rpy="-0.0049 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://meshes/skeleton.dae" scale="1.0 1.0 1.0"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="skeleton__visual">
|
||||
<origin xyz="-0.02371 -0.00647 1.74557" rpy="-0.0049 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://meshes/skeleton.dae" scale="1.0 1.0 1.0"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<link name="skeleton__upper_arm">
|
||||
<inertial>
|
||||
<mass value="0.19999998807907104"/>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||
</inertial>
|
||||
<collision name="skeleton__collision">
|
||||
<origin xyz="0.13823 0.00026 -0.00341" rpy="0 0 1.57079"/>
|
||||
<geometry>
|
||||
<mesh filename="package://demo_human_col/meshes/upper_arm.obj" scale="1.0 1.0 1.0"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="skeleton__visual">
|
||||
<origin xyz="0.13823 0.00026 -0.00341" rpy="0 0 1.57079"/>
|
||||
<geometry>
|
||||
<mesh filename="package://demo_human_col/meshes/upper_arm.obj" scale="1.0 1.0 1.0"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<link name="skeleton__forearm">
|
||||
<inertial>
|
||||
<mass value="0.19999998807907104"/>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||
</inertial>
|
||||
<collision name="skeleton__collision">
|
||||
<origin xyz="0.11655 -0.0037 0.03579" rpy="0 0 1.57079"/>
|
||||
<geometry>
|
||||
<mesh filename="package://demo_human_col/meshes/forearm.obj" scale="1.0 1.0 1.0"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="skeleton__visual">
|
||||
<origin xyz="0.11655 -0.0037 0.03579" rpy="0 0 1.57079"/>
|
||||
<geometry>
|
||||
<mesh filename="package://demo_human_col/meshes/forearm.obj" scale="1.0 1.0 1.0"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<link name="skeleton__hand">
|
||||
<inertial>
|
||||
<mass value="0.19999998807907104"/>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||
</inertial>
|
||||
<collision name="skeleton__collision">
|
||||
<origin xyz="0.04303 0.00372 0.00215" rpy="0 0 1.57079"/>
|
||||
<geometry>
|
||||
<mesh filename="package://meshes/hand_col.dae" scale="1.0 1.0 1.0"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="skeleton__visual">
|
||||
<origin xyz="0.04303 0.00372 0.00215" rpy="0 0 1.57079"/>
|
||||
<geometry>
|
||||
<mesh filename="package://demo_human_col/meshes/hand.obj" scale="1.0 1.0 1.0"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<link name="skeleton__thumb_1">
|
||||
<inertial>
|
||||
<mass value="0.19999998807907104"/>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||
</inertial>
|
||||
<visual name="skeleton__visual">
|
||||
<origin xyz="0.0254 -0.00053 -0.00079" rpy="-3.1294 -0.96488 -0.71552"/>
|
||||
<geometry>
|
||||
<mesh filename="package://demo_human_col/meshes/thumb_1.obj" scale="1.0 1.0 1.0"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<link name="skeleton__thumb_2">
|
||||
<inertial>
|
||||
<mass value="0.19999998807907104"/>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||
</inertial>
|
||||
<visual name="skeleton__visual">
|
||||
<origin xyz="0.01794 0.00023 -0.00055" rpy="1.91061 -1.08836 0.28141"/>
|
||||
<geometry>
|
||||
<mesh filename="package://demo_human_col/meshes/thumb_2.obj" scale="1.0 1.0 1.0"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<link name="skeleton__thumb_3">
|
||||
<inertial>
|
||||
<mass value="0.19999998807907104"/>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||
</inertial>
|
||||
<visual name="skeleton__visual">
|
||||
<origin xyz="0.00932 -0.00015 0.00029" rpy="1.91527 -1.09474 0.23923"/>
|
||||
<geometry>
|
||||
<mesh filename="package://demo_human_col/meshes/thumb_3.obj" scale="1.0 1.0 1.0"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<link name="skeleton__proximal">
|
||||
<inertial>
|
||||
<mass value="0.19999998807907104"/>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||
</inertial>
|
||||
<collision name="skeleton__collision">
|
||||
<origin xyz="0.01919 0.0022 0.00295" rpy="0.09206 0.2203 1.27627"/>
|
||||
<geometry>
|
||||
<mesh filename="package://meshes/proximal_col.dae" scale="1.0 1.0 1.0"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="skeleton__visual">
|
||||
<origin xyz="0.01919 0.0022 0.00295" rpy="0.09206 0.2203 1.27627"/>
|
||||
<geometry>
|
||||
<mesh filename="package://demo_human_col/meshes/proximal.obj" scale="1.0 1.0 1.0"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<link name="skeleton__middle">
|
||||
<inertial>
|
||||
<mass value="0.19999998807907104"/>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||
</inertial>
|
||||
<collision name="skeleton__collision">
|
||||
<origin xyz="0.00925 0.00417 -0.0002" rpy="0.13008 0.20044 1.45783"/>
|
||||
<geometry>
|
||||
<mesh filename="package://meshes/middle_col.dae" scale="1.0 1.0 1.0"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="skeleton__visual">
|
||||
<origin xyz="0.00925 0.00417 -0.0002" rpy="0.13008 0.20044 1.45783"/>
|
||||
<geometry>
|
||||
<mesh filename="package://demo_human_col/meshes/middle.obj" scale="1.0 1.0 1.0"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
<link name="skeleton__distal">
|
||||
<inertial>
|
||||
<mass value="0.19999998807907104"/>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
||||
</inertial>
|
||||
<collision name="skeleton__collision">
|
||||
<origin xyz="0.00163 0.00281 0.00012" rpy="0.1341 0.1978 1.47817"/>
|
||||
<geometry>
|
||||
<mesh filename="package://demo_human_col/meshes/distal.obj" scale="1.0 1.0 1.0"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="skeleton__visual">
|
||||
<origin xyz="0.00163 0.00281 0.00012" rpy="0.1341 0.1978 1.47817"/>
|
||||
<geometry>
|
||||
<mesh filename="package://demo_human_col/meshes/distal.obj" scale="1.0 1.0 1.0"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
</robot>
|
||||
Reference in New Issue
Block a user