-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathjaco.xml
166 lines (131 loc) · 8.67 KB
/
jaco.xml
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
<!-- ======================================================
This file is part of MuJoCo.
Copyright 2009-2016 Roboti LLC.
Model :: Jaco Arm from Kinova Robotics
Source : www.github.com/Kinovarobotics
Downloaded : July 25, 2015
Mujoco :: Advanced physics simulation engine
Source : www.roboti.us
Version : 1.31
Released : 23Apr16
Author :: Vikash Kumar
Contacts : kumar@roboti.us
Last edits : 30Apr16, 30Nov15, 26Sept'15, 26July'15
====================================================== -->
<mujoco model="jaco(v1.31)">
<compiler angle="radian" meshdir="meshes/" />
<option>
<flag gravity="disable"/>
</option>
<asset>
<mesh file="jaco_link_base.stl"/>
<mesh file="jaco_link_1.stl"/>
<mesh file="jaco_link_2.stl"/>
<mesh file="jaco_link_3.stl"/>
<mesh file="jaco_link_4.stl"/>
<mesh file="jaco_link_5.stl"/>
<mesh file="jaco_link_hand.stl"/>
<mesh file="jaco_link_finger_1.stl"/>
<mesh file="jaco_link_finger_2.stl"/>
<mesh file="jaco_link_finger_3.stl"/>
<texture type="skybox" builtin="gradient" rgb1=".2 .3 .4" rgb2="0 0 0"
width="100" height="100"/>
<texture name="groundplane" type="2d" builtin="checker" rgb1=".25 .26 .25"
rgb2=".22 .22 .22" width="100" height="100" mark="none" markrgb=".8 .8 .8"/>
<material name="MatViz" specular="1" shininess=".1" reflectance="0.5" rgba=".07 .07 .1 1"/>
<material name="MatGnd" texture="groundplane" texrepeat="5 5" specular="1" shininess=".3" reflectance="0.00001"/>
</asset>
<default>
<geom margin="0.001"/>
<joint limited="false" damping="0.2" armature=".01"/>
<!--geom class for visual and collision geometry-->
<default class ="vizNcoll">
<geom material="MatViz" type="mesh" group="0" contype="1" conaffinity="0"/>
<joint pos="0 0 0" type="hinge"/>
</default>
<default class ="ground">
<geom material="MatGnd" type="plane" contype="0" conaffinity="1"/>
</default>
</default>
<worldbody>
<light directional="true" cutoff="60" exponent="1" diffuse="1 1 1" specular=".1 .1 .1" pos="1 1 1.5" dir="-1 -1 -1.3"/>
<geom name="ground" class="ground" pos="0 0 0" size="2 2 1"/>
<body name="jaco_link_base" childclass="vizNcoll" pos="0 0 0.25">
<inertial pos="-3.14012e-008 0.000451919 0.0770704" quat="1 -0.000920048 6.51183e-006 5.62643e-005" mass="0.787504" diaginertia="0.00187445 0.00186316 0.000676952" />
<geom mesh="jaco_link_base"/>
<geom type="capsule" pos="0 0 -0.125" size=".045 0.125"/>
<body name="jaco_link_1" childclass="vizNcoll" pos="0 0 0.1535" quat="0 0 1 0">
<inertial pos="-1.14317e-006 0.0102141 -0.0637045" quat="0.702792 0.0778988 -0.0778994 0.702813" mass="0.613151" diaginertia="0.00149348 0.00144012 0.000401632" />
<joint name="jaco_joint_1" axis="0 0 -1" />
<geom mesh="jaco_link_1"/>
<body name="jaco_link_2" pos="0 0 -0.1185" quat="0 0 0.707107 0.707107">
<inertial pos="0.206657 -1.55187e-007 -0.030675" quat="8.97411e-006 0.707331 5.06696e-006 0.706883" mass="1.85031" diaginertia="0.0402753 0.0398125 0.00121953" />
<joint name="jaco_joint_2" axis="0 0 1" />
<geom mesh="jaco_link_2"/>
<body name="jaco_link_3" pos="0.41 0 0" quat="0 0.707107 0.707107 0">
<inertial pos="0.0847979 -1.18469e-007 -0.020283" quat="2.33799e-005 0.694869 1.96996e-005 0.719136" mass="0.70372" diaginertia="0.00386732 0.00373181 0.000358773" />
<joint name="jaco_joint_3" axis="0 0 -1" />
<geom mesh="jaco_link_3"/>
<body name="jaco_link_4" pos="0.207 0 -0.01125" quat="0 0.707107 0 -0.707107">
<inertial pos="0.00914824 4.53141e-008 -0.0370941" quat="0.971237 -1.92989e-005 -0.238115 3.23646e-005" mass="0.227408" diaginertia="0.000176463 0.00017225 0.000108303" />
<joint name="jaco_joint_4" axis="0 0 -1" />
<geom mesh="jaco_link_4"/>
<body name="jaco_link_5" pos="0.0343 0 -0.06588" quat="0.887011 0 -0.461749 0">
<inertial pos="0.00914824 4.53141e-008 -0.0370941" quat="0.971237 -1.92989e-005 -0.238115 3.23646e-005" mass="0.227408" diaginertia="0.000176463 0.00017225 0.000108303" />
<joint name="jaco_joint_5" axis="0 0 -1" />
<geom mesh="jaco_link_5"/>
<body name="jaco_link_hand" pos="0.0343 0 -0.06588" quat="0.627211 -0.326506 -0.326506 0.627211">
<inertial pos="0.0036132 -6.2241e-005 -0.0583749" quat="0.669114 -0.237618 -0.23799 0.66271" mass="0.58074" diaginertia="0.000817146 0.000671192 0.000606807" />
<joint name="jaco_joint_6" axis="0 0 -1" />
<geom mesh="jaco_link_hand" rgba=".13 .13 .13 1"/>
<!-- site here for position -->
<!-- <site pos="0.0 0 0" type="sphere" rgba=".9 .9 .0 1" size="0.05" />
<site pos="0.2 0 0" type="sphere" rgba=".9 .0 .0 1" size="0.05" />
<site pos="0 0.2 0" type="sphere" rgba=".0 .9 .0 1" size="0.05" />
<site pos="0 0 0.2" type="sphere" rgba=".0 .0 .9 1" size="0.05" /> -->
<site name="end-1" pos="0.0 0 -0.2" type="sphere" rgba=".9 .9 .9 1" size="0.05" />
<body name="jaco_link_finger_1" pos="-0.03978 0 -0.10071" quat="-0.414818 -0.329751 -0.663854 0.52772">
<inertial pos="0.0485761 -0.000715511 2.09499e-008" quat="0.507589 0.507348 0.492543 0.492294" mass="0.0379077" diaginertia="4.00709e-005 4.00528e-005 2.156e-006" />
<joint name="jaco_joint_finger_1" limited="true" axis="0 0 1" range="0 0.698132"/>
<geom mesh="jaco_link_finger_1"/>
</body>
<body name="jaco_link_finger_2" pos="0.03569 -0.0216 -0.10071" quat="0.625248 -0.567602 0.434845 0.312735">
<inertial pos="0.0485761 -0.000715511 2.09499e-008" quat="0.507589 0.507348 0.492543 0.492294" mass="0.0379077" diaginertia="4.00709e-005 4.00528e-005 2.156e-006" />
<joint name="jaco_joint_finger_2" limited="true" axis="0 0 1" range="0 0.698132"/>
<geom mesh="jaco_link_finger_2"/>
</body>
<body name="jaco_link_finger_3" pos="0.03569 0.0216 -0.10071" quat="0.561254 -0.620653 0.321748 0.443014">
<inertial pos="0.0485761 -0.000715511 2.09499e-008" quat="0.507589 0.507348 0.492543 0.492294" mass="0.0379077" diaginertia="4.00709e-005 4.00528e-005 2.156e-006" />
<joint name="jaco_joint_finger_3" limited="true" axis="0 0 1" range="0 0.698132"/>
<geom mesh="jaco_link_finger_3"/>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
<!-- target point -->
<!-- <site pos="0.0 0 0" type="sphere" rgba=".9 .9 .0 1" size="0.05" />
<site pos="0.2 0 0" type="sphere" rgba=".9 .0 .0 1" size="0.05" />
<site pos="0 0.2 0" type="sphere" rgba=".0 .9 .0 1" size="0.05" />
<site pos="0 0 0.2" type="sphere" rgba=".0 .0 .9 1" size="0.05" /> -->
<site pos="0.1 0.4 0.5" type="sphere" rgba=".9 .9 .9 1" size="0.05" />
</worldbody>
<sensor>
<framepos objname="end-1" objtype="site"/>
</sensor>
<actuator>
<!-- ================= Torque actuators (Weren't present in the URDF. Added seperately)================= /-->
<motor joint='jaco_joint_1' name='Ajaco_joint_1' gear="50"/>
<motor joint='jaco_joint_2' name='Ajaco_joint_2' gear="100"/>
<motor joint='jaco_joint_3' name='Ajaco_joint_3' gear="100"/>
<motor joint='jaco_joint_4' name='Ajaco_joint_4' gear="50"/>
<motor joint='jaco_joint_5' name='Ajaco_joint_5' gear="50"/>
<motor joint='jaco_joint_6' name='Ajaco_joint_6' gear="50"/>
<motor joint='jaco_joint_finger_1' name='Ajaco_joint_finger_1' gear='10'/>
<motor joint='jaco_joint_finger_2' name='Ajaco_joint_finger_2' gear='10'/>
<motor joint='jaco_joint_finger_3' name='Ajaco_joint_finger_3' gear='10'/>
</actuator>
</mujoco>