1<mujoco model="MPL"> 2 <!-- 3 This file and the .stl mesh files referenced from it have been derived by Roboti LLC from the model of the Modular Prosthetic Limb developed by The Johns Hopkins University / Applied Physics Laboratory. The modifications are as follows: the original meshes have been replaced with their convex hulls; the original URDF model has been converted to the MJCF format and a number of MJCF-specific fields have been added. 4 5 The Johns Hopkins University / Applied Physics Laboratory has given Roboti LLC permission to distribute the modified model under the following license: 6 7 ========================= 8 9 (C) 2013 The Johns Hopkins University / Applied Physics Laboratory All Rights Reserved. 10 11 Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at 12 13 http://www.apache.org/licenses/LICENSE-2.0 14 15 Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License. 16 17 ======================== 18 19 The modifications made by Roboti LLC are also licensed under the Apache License version 2.0. 20 --> 21 22 <compiler angle="radian" meshdir="mesh/" texturedir="texture/"/> 23 <option timestep="0.002" iterations="50" apirate="50"/> 24 <size njmax="600" nconmax="150" nstack="300000"/> 25 26 <default> 27 <default class="MPL"> 28 <geom material="MatMesh" contype="1" conaffinity="1" condim="4" friction="1 .5 0.5" margin="0.001"/> 29 <joint limited="true" damping="0.2" armature=".01"/> 30 <site material="MatTouch" type="ellipsoid" group="3"/> 31 <position ctrllimited="true" kp="10"/> 32 </default> 33 34 <default class="IMU"> 35 <site material="MatIMU" type="box" group="4"/> 36 </default> 37 38 <default class="free"> 39 <joint type="free" damping="0" armature="0" limited="false"/> 40 </default> 41 </default> 42 43 <statistic extent="1" center="0 -0.2 0.2"/> 44 45 <visual> 46 <quality shadowsize="2048"/> 47 <map fogstart="6" fogend="10"/> 48 <headlight diffuse=".6 .6 .6" specular="0 0 0"/> 49 </visual> 50 51 <asset> 52 <mesh name="index0" file="index0_collision.stl"/> 53 <mesh name="index1" file="index1_collision.stl"/> 54 <mesh name="index2" file="index2_collision.stl"/> 55 <mesh name="index3" file="index3_collision.stl"/> 56 <mesh name="middle0" file="middle0_collision.stl"/> 57 <mesh name="middle1" file="middle1_collision.stl"/> 58 <mesh name="middle2" file="middle2_collision.stl"/> 59 <mesh name="middle3" file="middle3_collision.stl"/> 60 <mesh name="palm" file="palm_collision.stl"/> 61 <mesh name="pinky0" file="pinky0_collision.stl"/> 62 <mesh name="pinky1" file="pinky1_collision.stl"/> 63 <mesh name="pinky2" file="pinky2_collision.stl"/> 64 <mesh name="pinky3" file="pinky3_collision.stl"/> 65 <mesh name="ring0" file="ring0_collision.stl"/> 66 <mesh name="ring1" file="ring1_collision.stl"/> 67 <mesh name="ring2" file="ring2_collision.stl"/> 68 <mesh name="ring3" file="ring3_collision.stl"/> 69 <mesh name="thumb0" file="thumb0_collision.stl"/> 70 <mesh name="thumb1" file="thumb1_collision.stl"/> 71 <mesh name="thumb2" file="thumb2_collision.stl"/> 72 <mesh name="thumb3" file="thumb3_collision.stl"/> 73 <mesh name="wristx" file="wristx_collision.stl"/> 74 <mesh name="wristy" file="wristy_collision.stl"/> 75 <mesh name="wristz" file="wristz_collision.stl"/> 76 77 <texture type="skybox" builtin="gradient" rgb1=".4 .6 .8" rgb2="0 0 0" 78 width="100" height="100"/> 79 <texture name="groundplane" type="2d" builtin="checker" rgb1=".2 .3 .4" rgb2=".1 .2 .3" 80 width="100" height="100"/> 81 <texture name="skin" type="cube" file="skin.png"/> 82 <texture name="marble2d" type="2d" file="marble.png"/> 83 <texture name="marblecube" type="cube" file="marble.png"/> 84 85 <material name="groundplane" texture="groundplane" texrepeat="10 10"/> 86 <material name="table2d" texture="marble2d" reflectance="0.3" rgba=".8 .8 .8 1"/> 87 <material name="tablecube" texture="marblecube" rgba=".8 .8 .8 1"/> 88 <material name="MatTouch" rgba=".3 .9 .3 .3"/> 89 <material name="MatIMU" rgba=".1 .1 .9 1"/> 90 <material name="MatMesh" texture="skin"/> 91 </asset> 92 93 <contact> 94 <exclude body1="wristz" body2="wristy"/> 95 <exclude body1="wristx" body2="thumb0"/> 96 <exclude body1="palm" body2="thumb1"/> 97 <exclude body1="palm" body2="index1"/> 98 <exclude body1="palm" body2="middle1"/> 99 <exclude body1="palm" body2="ring1"/> 100 <exclude body1="palm" body2="pinky1"/> 101 </contact> 102 103 <worldbody> 104 105 106 <!-- ======= ROBOT ======= --> 107 <body childclass="MPL" name="wristy" pos="0 0 0"> 108 <inertial pos="-7.08369e-005 -0.0217787 -0.000286168" quat="0.707488 0.00581744 -0.0107421 0.70662" mass="0.0272932" diaginertia="2.46813e-005 1.77029e-005 1.71079e-005" /> 109 <geom type="mesh" mesh="wristy"/> 110 <joint type="free"/> 111 <body name="wristx" pos="-3.36826e-005 -0.0476452 0.00203763"> 112 <inertial pos="0.00139174 -0.00975189 -0.00252668" quat="-0.0729226 0.705959 0.0352732 0.703605" mass="0.010691" diaginertia="5.04455e-006 4.25035e-006 3.25677e-006" /> 113 <joint name="wrist_UDEV" damping="0.4" type="hinge" pos="0 0 0" axis="0 0 -1" range="-0.261 0.785"/> 114 <geom type="mesh" mesh="wristx"/> 115 <body name="wristz" pos="0.0001872 -0.03 -0.002094"> 116 <inertial pos="0.000579016 -0.00125952 0.000455968" quat="0.527723 0.475346 0.521597 0.472749" mass="0.00602247" diaginertia="1.58133e-006 1.43102e-006 1.26861e-006" /> 117 <joint name="wrist_FLEX" damping="0.4" type="hinge" pos="0 0 0" axis="1 0 0" range="-1.04 1.04"/> 118 <geom type="mesh" mesh="wristz"/> 119 120 <!-- ======= PALM ======= --> 121 <body name="palm" pos="0.025625 0 0"> 122 <inertial pos="-0.0217876 -0.0376147 0.00276997" quat="-0.146373 0.723094 0.0985561 0.66783" mass="0.119867" diaginertia="0.000123088 0.000100082 6.89467e-005" /> 123 <geom type="mesh" mesh="palm"/> 124 <site name="palm_thumb" pos="-0.0052 -0.0438 -0.0182" size=".017 .03 .01"/> 125 <site name="palm_pinky" pos="-0.0358 -0.0401 -0.0183" size=".017 .03 .01"/> 126 <site name="palm_side" pos="-0.0604 -0.0329 -0.0048" size=".01 .03 .015"/> 127 <site name="palm_back" pos="-0.0246 -0.0446 0.018" size=".03 .035 .015"/> 128 129 <!-- ======= THUMB ======= --> 130 <body name="thumb0" pos="0.00835752 -0.0206978 -0.010093" quat="0.990237 0.0412644 -0.0209178 -0.13149"> 131 <inertial pos="0.00863339 -0.000156884 -0.000945846" quat="0.408795 0.551643 0.541079 0.485602" mass="0.00336696" diaginertia="4.50769e-007 4.48758e-007 2.35017e-007" /> 132 <joint name="thumb_ABD" type="hinge" pos="0 0 0" axis="0 1 0" range="0 2.07"/> 133 <geom type="mesh" mesh="thumb0"/> 134 <body name="thumb1" pos="0.0209172 -0.00084 0.0014476"> 135 <inertial pos="0.019024 0.000361131 -0.000186763" quat="0.5208 0.469572 0.484571 0.522934" mass="0.00596213" diaginertia="9.88001e-007 9.45125e-007 5.32989e-007" /> 136 <joint name="thumb_MCP" type="hinge" pos="0 0 0" axis="0 0 -1" range="0 1.03"/> 137 <geom type="mesh" mesh="thumb1"/> 138 <site name="thumb_proximal" pos="0.0173 -0.008 0.0009" size=".015 .0075 .01"/> 139 <body name="thumb2" pos="0.0335 0 -0.0007426"> 140 <inertial pos="0.0188965 0.000375725 0.00065381" quat="0.502274 0.484638 0.475673 0.535333" mass="0.00599792" diaginertia="9.96692e-007 9.64948e-007 5.14416e-007" /> 141 <joint name="thumb_PIP" type="hinge" pos="0 0 0" axis="0 0 -1" range="0 1.03"/> 142 <geom type="mesh" mesh="thumb2"/> 143 <site name="thumb_medial" pos="0.0182 -0.008 0.0015" size=".015 .0075 .01"/> 144 <body name="thumb3" pos="0.0335 0 0.0010854"> 145 <inertial pos="0.0188965 0.000375725 0.00065381" quat="0.502274 0.484638 0.475673 0.535333" mass="0.00599792" diaginertia="9.96692e-007 9.64948e-007 5.14416e-007" /> 146 <joint name="thumb_DIP" type="hinge" pos="0 0 0" axis="0 0 -1" range="-0.819 1.28"/> 147 <geom type="mesh" mesh="thumb3"/> 148 <site name="thumb_distal" pos="0.0156 -0.007 0.0003" size=".015 .0075 .01" axisangle="0 0 1 0.2"/> 149 <site class="IMU" name="thumb_IMU" pos="0.0099 -0.00052 0" quat=".5 .5 .5 .5" size=".003 .003 .003"/> 150 </body> 151 </body> 152 </body> 153 </body> 154 155 <!-- ======= INDEX ======= --> 156 <body name="index0" pos="0.00986485 -0.0658 0.00101221" quat="0.996195 0 0.0871557 0"> 157 <inertial pos="-0.000142572 -0.00548494 0.000206145" quat="0.699132 0.714861 -0.000723869 0.013694" mass="0.00295579" diaginertia="4.22462e-007 4.02281e-007 1.93868e-007" /> 158 <joint name="index_ABD" type="hinge" pos="0 0 0" axis="0 0 1" range="0 0.345"/> 159 <geom type="mesh" mesh="index0"/> 160 <body name="index1" pos="6.26e-005 -0.018 0"> 161 <inertial pos="0.000406487 -0.0213125 0.000655609" quat="0.698452 0.715642 -0.00415384 0.0023049" mass="0.00478235" diaginertia="8.18599e-007 7.95693e-007 3.06254e-007" /> 162 <joint name="index_MCP" type="hinge" pos="0 0 0" axis="1 0 0" range="-0.785 1.57"/> 163 <geom type="mesh" mesh="index1"/> 164 <site name="index_proximal" pos="0 -0.0235 -0.007" size=".009 .015 .0075"/> 165 <body name="index2" pos="0.001086 -0.0435 0.0005"> 166 <inertial pos="-0.000841462 -0.012689 0.000572665" quat="0.734882 0.677481 -0.028511 0.0124827" mass="0.00344764" diaginertia="3.63962e-007 3.59059e-007 1.05304e-007" /> 167 <joint name="index_PIP" type="hinge" pos="0 0 0" axis="1 0 0" range="0 1.72"/> 168 <geom type="mesh" mesh="index2"/> 169 <site name="index_medial" pos="0 -0.009 -0.0047" size=".0075 .01 .006"/> 170 <body name="index3" pos="-0.000635 -0.0245 0"> 171 <inertial pos="4.32004e-005 -0.0125318 0.000903476" quat="0.516251 0.4829 -0.483241 0.516498" mass="0.00274415" diaginertia="1.19635e-007 1.09202e-007 7.77873e-008" /> 172 <joint name="index_DIP" type="hinge" pos="0 0 0" axis="1 0 0" range="0 1.38"/> 173 <geom type="mesh" mesh="index3"/> 174 <site name="index_distal" pos="0 -0.0132 -0.0038" size=".0075 .01 .006"/> 175 <site class="IMU" name="index_IMU" pos="0 -0.0093 0.00063" quat=".5 .5 -.5 .5" size=".003 .003 .003"/> 176 </body> 177 </body> 178 </body> 179 </body> 180 181 <!-- ======= MIDDLE ======= --> 182 <body name="middle0" pos="-0.012814 -0.0779014 0.00544608" quat="-3.14 0.0436194 0 0"> 183 <inertial pos="-0.000142567 -0.00548493 0.000206162" quat="0.699131 0.714862 -0.000723874 0.013694" mass="0.00295579" diaginertia="4.22461e-007 4.02281e-007 1.93868e-007" /> 184 <!--<joint name="middle0" type="hinge" pos="0 0 0" range="-0.345 0" axis="0 0 -1" />--> 185 <geom type="mesh" mesh="middle0"/> 186 <body name="middle1" pos="6.26e-005 -0.018 0"> 187 <inertial pos="0.000406411 -0.0213125 0.00065565" quat="0.698451 0.715642 -0.00415503 0.00230486" mass="0.00478229" diaginertia="8.18595e-007 7.9569e-007 3.06253e-007" /> 188 <joint name="middle_MCP" type="hinge" pos="0 0 0" axis="1 0 0" range="-0.785 1.57"/> 189 <geom type="mesh" mesh="middle1"/> 190 <site name="middle_proximal" pos="0 -0.025 -0.007" size=".009 .015 .0075"/> 191 <body name="middle2" pos="0.001086 -0.0435 0.0005"> 192 <inertial pos="-0.000841444 -0.012689 0.00057266" quat="0.734883 0.677482 -0.0284727 0.0124412" mass="0.00344765" diaginertia="3.63962e-007 3.5906e-007 1.05304e-007" /> 193 <joint name="middle_PIP" type="hinge" pos="0 0 0" axis="1 0 0" range="0 1.73"/> 194 <geom type="mesh" mesh="middle2"/> 195 <site name="middle_medial" pos="0 -0.0146 -0.0047" size=".0075 .01 .006"/> 196 <body name="middle3" pos="-0.000635 -0.0245 0"> 197 <inertial pos="4.31236e-005 -0.0125318 0.000903446" quat="0.516263 0.482913 -0.483228 0.516487" mass="0.00274417" diaginertia="1.19635e-007 1.09202e-007 7.77884e-008" /> 198 <joint name="middle_DIP" type="hinge" pos="0 0 0" axis="1 0 0" range="0 1.38"/> 199 <geom type="mesh" mesh="middle3"/> 200 <site name="middle_distal" pos="0 -0.0129 -0.0038" size=".0075 .01 .006"/> 201 <site class="IMU" name="middle_IMU" pos="0 -0.0093 0.00063" quat=".5 .5 -.5 .5" size=".003 .003 .003"/> 202 </body> 203 </body> 204 </body> 205 </body> 206 207 <!-- ======= RING ======= --> 208 <body name="ring0" pos="-0.0354928 -0.0666999 0.00151221" quat="0.996195 0 -0.0871557 0"> 209 <inertial pos="-0.000142559 -0.00548494 0.000206147" quat="0.699132 0.714861 -0.000720946 0.013691" mass="0.00295579" diaginertia="4.22462e-007 4.02281e-007 1.93868e-007" /> 210 <joint name="ring_ABD" type="hinge" pos="0 0 0" axis="0 0 -1" range="0 0.345"/> 211 <geom type="mesh" mesh="ring0"/> 212 <body name="ring1" pos="6.26e-005 -0.018 0"> 213 <inertial pos="0.000406447 -0.0213125 0.00065563" quat="0.698451 0.715642 -0.00415675 0.00230715" mass="0.00478232" diaginertia="8.18597e-007 7.95692e-007 3.06254e-007" /> 214 <joint name="ring_MCP" type="hinge" pos="0 0 0" axis="1 0 0" range="-0.785 1.57"/> 215 <geom type="mesh" mesh="ring1"/> 216 <site name="ring_proximal" pos="0 -0.0259 -0.007" size=".009 .015 .0075"/> 217 <body name="ring2" pos="0.001086 -0.0435 0.0005"> 218 <inertial pos="-0.000841518 -0.012689 0.000572674" quat="0.73488 0.677478 -0.0285773 0.0125557" mass="0.00344767" diaginertia="3.63963e-007 3.59061e-007 1.05305e-007" /> 219 <joint name="ring_PIP" type="hinge" pos="0 0 0" axis="1 0 0" range="0 1.72"/> 220 <geom type="mesh" mesh="ring2"/> 221 <site name="ring_medial" pos="0 -0.0137 -0.0047" size=".0075 .01 .006"/> 222 <body name="ring3" pos="-0.000635 -0.0245 0"> 223 <inertial pos="4.31973e-005 -0.0125318 0.000903457" quat="0.516255 0.482902 -0.483238 0.516495" mass="0.00274416" diaginertia="1.19635e-007 1.09202e-007 7.77877e-008" /> 224 <joint name="ring_DIP" type="hinge" pos="0 0 0" axis="1 0 0" range="0 1.38"/> 225 <geom type="mesh" mesh="ring3"/> 226 <site name="ring_distal" pos="0 -0.0117 -0.0038" size=".0075 .01 .006"/> 227 <site class="IMU" name="ring_IMU" pos="0 -0.0093 0.00063" quat=".5 .5 -.5 .5" size=".003 .003 .003"/> 228 </body> 229 </body> 230 </body> 231 </body> 232 233 <!-- ======= LITTLE ======= --> 234 <body name="pinky0" pos="-0.0562459 -0.0554001 -0.00563858" quat="0.996195 0 -0.0871557 0"> 235 <inertial pos="-0.000142559 -0.00538484 0.000206147" quat="0.699132 0.714861 -0.000721037 0.0136911" mass="0.00295579" diaginertia="4.22462e-007 4.02281e-007 1.93868e-007" /> 236 <joint name="pinky_ABD" type="hinge" pos="0 0 0" axis="0 0 -1" range="0 0.345"/> 237 <geom type="mesh" mesh="pinky0"/> 238 <body name="pinky1" pos="6.26e-005 -0.0178999 0"> 239 <inertial pos="0.000458624 -0.0160478 0.000924735" quat="0.685529 0.72723 0.021252 -0.0270914" mass="0.0034099" diaginertia="4.03391e-007 3.84061e-007 2.19866e-007" /> 240 <joint name="pinky_MCP" type="hinge" pos="0 0 0" axis="1 0 0" range="-0.785 1.57"/> 241 <geom type="mesh" mesh="pinky1"/> 242 <site name="pinky_proximal" pos="0 -0.021 -0.0066" size=".009 .013 .0075"/> 243 <body name="pinky2" pos="0.000578 -0.033 0.0005"> 244 <inertial pos="-0.000270832 -0.00914628 0.000738493" quat="0.746786 0.664476 -4.11065e-005 -0.0279675" mass="0.00250622" diaginertia="1.79089e-007 1.75934e-007 7.44543e-008" /> 245 <joint name="pinky_PIP" type="hinge" pos="0 0 0" axis="1 0 0" range="0 1.72"/> 246 <geom type="mesh" mesh="pinky2"/> 247 <site name="pinky_medial" pos="0 -0.0117 -0.0047" size=".0075 .01 .006"/> 248 <body name="pinky3" pos="-4.78e-005 -0.0175 0"> 249 <inertial pos="3.85026e-005 -0.0125047 0.000912295" quat="0.516037 0.484447 -0.483043 0.515448" mass="0.00273265" diaginertia="1.19141e-007 1.08629e-007 7.77271e-008" /> 250 <joint name="pinky_DIP" type="hinge" pos="0 0 0" axis="1 0 0" range="0 1.38"/> 251 <geom type="mesh" mesh="pinky3"/> 252 <site name="pinky_distal" pos="0 -0.0121 -0.0038" size=".0075 .01 .006"/> 253 <site class="IMU" name="pinky_IMU" pos="0 -0.0093 0.00063" quat=".5 .5 -.5 .5" size=".003 .003 .003"/> 254 </body> 255 </body> 256 </body> 257 </body> 258 </body> 259 </body> 260 </body> 261 </body> 262 263 </worldbody> 264 265 266 <sensor> 267 <jointpos name="Sjp_wrist_PRO" joint="wrist_PRO"/> 268 <jointpos name="Sjp_wrist_UDEV" joint="wrist_UDEV"/> 269 <jointpos name="Sjp_wrist_FLEX" joint="wrist_FLEX"/> 270 <jointpos name="Sjp_thumb_ABD" joint="thumb_ABD"/> 271 <jointpos name="Sjp_thumb_MCP" joint="thumb_MCP"/> 272 <jointpos name="Sjp_thumb_PIP" joint="thumb_PIP"/> 273 <jointpos name="Sjp_thumb_DIP" joint="thumb_DIP"/> 274 <jointpos name="Sjp_index_ABD" joint="index_ABD"/> 275 <jointpos name="Sjp_index_MCP" joint="index_MCP"/> 276 <jointpos name="Sjp_index_PIP" joint="index_PIP"/> 277 <jointpos name="Sjp_index_DIP" joint="index_DIP"/> 278 <jointpos name="Sjp_middle_MCP" joint="middle_MCP"/> 279 <jointpos name="Sjp_middle_PIP" joint="middle_PIP"/> 280 <jointpos name="Sjp_middle_DIP" joint="middle_DIP"/> 281 <jointpos name="Sjp_ring_ABD" joint="ring_ABD"/> 282 <jointpos name="Sjp_ring_MCP" joint="ring_MCP"/> 283 <jointpos name="Sjp_ring_PIP" joint="ring_PIP"/> 284 <jointpos name="Sjp_ring_DIP" joint="ring_DIP"/> 285 <jointpos name="Sjp_pinky_ABD" joint="pinky_ABD"/> 286 <jointpos name="Sjp_pinky_MCP" joint="pinky_MCP"/> 287 <jointpos name="Sjp_pinky_PIP" joint="pinky_PIP"/> 288 <jointpos name="Sjp_pinky_DIP" joint="pinky_DIP"/> 289 290 <jointvel name="Sjv_wrist_PRO" joint="wrist_PRO"/> 291 <jointvel name="Sjv_wrist_UDEV" joint="wrist_UDEV"/> 292 <jointvel name="Sjv_wrist_FLEX" joint="wrist_FLEX"/> 293 <jointvel name="Sjv_thumb_ABD" joint="thumb_ABD"/> 294 <jointvel name="Sjv_thumb_MCP" joint="thumb_MCP"/> 295 <jointvel name="Sjv_thumb_PIP" joint="thumb_PIP"/> 296 <jointvel name="Sjv_thumb_DIP" joint="thumb_DIP"/> 297 <jointvel name="Sjv_index_ABD" joint="index_ABD"/> 298 <jointvel name="Sjv_index_MCP" joint="index_MCP"/> 299 <jointvel name="Sjv_index_PIP" joint="index_PIP"/> 300 <jointvel name="Sjv_index_DIP" joint="index_DIP"/> 301 <jointvel name="Sjv_middle_MCP" joint="middle_MCP"/> 302 <jointvel name="Sjv_middle_PIP" joint="middle_PIP"/> 303 <jointvel name="Sjv_middle_DIP" joint="middle_DIP"/> 304 <jointvel name="Sjv_ring_ABD" joint="ring_ABD"/> 305 <jointvel name="Sjv_ring_MCP" joint="ring_MCP"/> 306 <jointvel name="Sjv_ring_PIP" joint="ring_PIP"/> 307 <jointvel name="Sjv_ring_DIP" joint="ring_DIP"/> 308 <jointvel name="Sjv_pinky_ABD" joint="pinky_ABD"/> 309 <jointvel name="Sjv_pinky_MCP" joint="pinky_MCP"/> 310 <jointvel name="Sjv_pinky_PIP" joint="pinky_PIP"/> 311 <jointvel name="Sjv_pinky_DIP" joint="pinky_DIP"/> 312 313 <actuatorpos name="Sap_wrist_PRO" actuator="A_wrist_PRO" /> 314 <actuatorpos name="Sap_wrist_UDEV" actuator="A_wrist_UDEV" /> 315 <actuatorpos name="Sap_wrist_FLEX" actuator="A_wrist_FLEX" /> 316 <actuatorpos name="Sap_thumb_ABD" actuator="A_thumb_ABD" /> 317 <actuatorpos name="Sap_thumb_MCP" actuator="A_thumb_MCP" /> 318 <actuatorpos name="Sap_thumb_PIP" actuator="A_thumb_PIP" /> 319 <actuatorpos name="Sap_thumb_DIP" actuator="A_thumb_DIP" /> 320 <actuatorpos name="Sap_index_ABD" actuator="A_index_ABD" /> 321 <actuatorpos name="Sap_index_MCP" actuator="A_index_MCP" /> 322 <actuatorpos name="Sap_middle_MCP" actuator="A_middle_MCP"/> 323 <actuatorpos name="Sap_ring_MCP" actuator="A_ring_MCP" /> 324 <actuatorpos name="Sap_pinky_ABD" actuator="A_pinky_ABD" /> 325 <actuatorpos name="Sap_pinky_MCP" actuator="A_pinky_MCP" /> 326 327 <actuatorvel name="Sav_wrist_PRO" actuator="A_wrist_PRO" /> 328 <actuatorvel name="Sav_wrist_UDEV" actuator="A_wrist_UDEV"/> 329 <actuatorvel name="Sav_wrist_FLEX" actuator="A_wrist_FLEX"/> 330 <actuatorvel name="Sav_thumb_ABD" actuator="A_thumb_ABD" /> 331 <actuatorvel name="Sav_thumb_MCP" actuator="A_thumb_MCP" /> 332 <actuatorvel name="Sav_thumb_PIP" actuator="A_thumb_PIP" /> 333 <actuatorvel name="Sav_thumb_DIP" actuator="A_thumb_DIP" /> 334 <actuatorvel name="Sav_index_ABD" actuator="A_index_ABD" /> 335 <actuatorvel name="Sav_index_MCP" actuator="A_index_MCP" /> 336 <actuatorvel name="Sav_middle_MCP" actuator="A_middle_MCP"/> 337 <actuatorvel name="Sav_ring_MCP" actuator="A_ring_MCP" /> 338 <actuatorvel name="Sav_pinky_ABD" actuator="A_pinky_ABD" /> 339 <actuatorvel name="Sav_pinky_MCP" actuator="A_pinky_MCP" /> 340 341 <actuatorfrc name="Saf_wrist_PRO" actuator="A_wrist_PRO"/> 342 <actuatorfrc name="Saf_wrist_UDEV" actuator="A_wrist_UDEV"/> 343 <actuatorfrc name="Saf_wrist_FLEX" actuator="A_wrist_FLEX"/> 344 <actuatorfrc name="Saf_thumb_ABD" actuator="A_thumb_ABD"/> 345 <actuatorfrc name="Saf_thumb_MCP" actuator="A_thumb_MCP"/> 346 <actuatorfrc name="Saf_thumb_PIP" actuator="A_thumb_PIP"/> 347 <actuatorfrc name="Saf_thumb_DIP" actuator="A_thumb_DIP"/> 348 <actuatorfrc name="Saf_index_ABD" actuator="A_index_ABD"/> 349 <actuatorfrc name="Saf_index_MCP" actuator="A_index_MCP"/> 350 <actuatorfrc name="Saf_middle_MCP" actuator="A_middle_MCP"/> 351 <actuatorfrc name="Saf_ring_MCP" actuator="A_ring_MCP"/> 352 <actuatorfrc name="Saf_pinky_ABD" actuator="A_pinky_ABD"/> 353 <actuatorfrc name="Saf_pinky_MCP" actuator="A_pinky_MCP"/> 354 355 <accelerometer name="S_thumb_IMU" site="thumb_IMU"/> 356 <accelerometer name="S_index_IMU" site="index_IMU"/> 357 <accelerometer name="S_middle_IMU" site="middle_IMU"/> 358 <accelerometer name="S_ring_IMU" site="ring_IMU"/> 359 <accelerometer name="S_pinky_IMU" site="pinky_IMU"/> 360 361 <gyro site="thumb_IMU"/> 362 <gyro site="index_IMU"/> 363 <gyro site="middle_IMU"/> 364 <gyro site="ring_IMU"/> 365 <gyro site="pinky_IMU"/> 366 367 <touch name="S_palm_thumb" site="palm_thumb"/> 368 <touch name="S_palm_pinky" site="palm_pinky"/> 369 <touch name="S_palm_side" site="palm_side"/> 370 <touch name="S_palm_back" site="palm_back"/> 371 <touch name="S_thumb_proximal" site="thumb_proximal"/> 372 <touch name="S_thumb_medial" site="thumb_medial"/> 373 <touch name="S_thumb_distal" site="thumb_distal"/> 374 <touch name="S_index_proximal" site="index_proximal"/> 375 <touch name="S_index_medial" site="index_medial"/> 376 <touch name="S_index_distal" site="index_distal"/> 377 <touch name="S_middle_proximal" site="middle_proximal"/> 378 <touch name="S_middle_medial" site="middle_medial"/> 379 <touch name="S_middle_distal" site="middle_distal"/> 380 <touch name="S_ring_proximal" site="ring_proximal"/> 381 <touch name="S_ring_medial" site="ring_medial"/> 382 <touch name="S_ring_distal" site="ring_distal"/> 383 <touch name="S_pinky_proximal" site="pinky_proximal"/> 384 <touch name="S_pinky_medial" site="pinky_medial"/> 385 <touch name="S_pinky_distal" site="pinky_distal"/> 386 </sensor> 387 388 389 <tendon> 390 <!--Index coupler tendons--> 391 <fixed name="T_index32_cpl" range="0 1"> 392 <joint joint="index_DIP" coef="0.00705"/> 393 <joint joint="index_PIP" coef="-0.00805"/> 394 </fixed> 395 <fixed name="T_index21_cpl" range="0 1"> 396 <joint joint="index_PIP" coef="0.010"/> 397 <joint joint="index_MCP" coef="-0.010"/> 398 </fixed> 399 400 <!--Middle coupler tendons--> 401 <fixed name="T_middle32_cpl"> 402 <joint joint="middle_DIP" coef="0.00705"/> 403 <joint joint="middle_PIP" coef="-0.00805"/> 404 </fixed> 405 <fixed name="T_middle21_cpl"> 406 <joint joint="middle_PIP" coef="0.010"/> 407 <joint joint="middle_MCP" coef="-0.010"/> 408 </fixed> 409 410 <!--Ring coupler tendons--> 411 <fixed name="T_ring32_cpl"> 412 <joint joint="ring_DIP" coef="0.00705"/> 413 <joint joint="ring_PIP" coef="-0.00805"/> 414 </fixed> 415 <fixed name="T_ring21_cpl"> 416 <joint joint="ring_PIP" coef="0.010"/> 417 <joint joint="ring_MCP" coef="-0.010"/> 418 </fixed> 419 420 <!--Little coupler tendons--> 421 <fixed name="T_pinky32_cpl"> 422 <joint joint="pinky_DIP" coef="0.00705"/> 423 <joint joint="pinky_PIP" coef="-0.00805"/> 424 </fixed> 425 <fixed name="T_pinky21_cpl"> 426 <joint joint="pinky_PIP" coef="0.010"/> 427 <joint joint="pinky_MCP" coef="-0.010"/> 428 </fixed> 429 430 </tendon> 431 432 433 <equality> 434 <weld body1="mocap" body2="forearm" solref="0.01 1" solimp=".9 .9 0.01"/> 435 436 <!-- DIP-PIP-MCP Couplings --> 437 <tendon name="E_index32_cpl" tendon1="T_index32_cpl"/> 438 <tendon name="E_index21_cpl" tendon1="T_index21_cpl"/> 439 <tendon name="E_middle32_cpl" tendon1="T_middle32_cpl"/> 440 <tendon name="E_middle21_cpl" tendon1="T_middle21_cpl"/> 441 <tendon name="E_ring32_cpl" tendon1="T_ring32_cpl"/> 442 <tendon name="E_ring21_cpl" tendon1="T_ring21_cpl"/> 443 <tendon name="E_pinky32_cpl" tendon1="T_pinky32_cpl"/> 444 <tendon name="E_pinky21_cpl" tendon1="T_pinky21_cpl"/> 445 446 <!-- AD-AB Coupling --> 447 <joint name="ring_pinky_cpl" joint1="ring_ABD" joint2="pinky_ABD" polycoef="0 0.5 0 0 0"/> 448 </equality> 449 450 451 <actuator> 452 <!-- Wrist --> 453 <position name="A_wrist_PRO" class="MPL" joint="wrist_PRO" ctrlrange="-1.57 1.57"/> 454 <position name="A_wrist_UDEV" class="MPL" joint="wrist_UDEV" ctrlrange="-0.26 0.79"/> 455 <position name="A_wrist_FLEX" class="MPL" joint="wrist_FLEX" ctrlrange="-1 1"/> 456 457 <!-- Thumb --> 458 <position name="A_thumb_ABD" class="MPL" joint="thumb_ABD" ctrlrange="0 2.1"/> 459 <position name="A_thumb_MCP" class="MPL" joint="thumb_MCP" ctrlrange="0 1.0"/> 460 <position name="A_thumb_PIP" class="MPL" joint="thumb_PIP" ctrlrange="0 1.0"/> 461 <position name="A_thumb_DIP" class="MPL" joint="thumb_DIP" ctrlrange="-0.82 1.3"/> 462 463 <!-- Fingers --> 464 <position name="A_index_ABD" class="MPL" joint="index_ABD" ctrlrange="0 0.34"/> 465 <position name="A_index_MCP" class="MPL" joint="index_MCP" ctrlrange="0 1.6"/> 466 <position name="A_middle_MCP" class="MPL" joint="middle_MCP" ctrlrange="0 1.6"/> 467 <position name="A_ring_MCP" class="MPL" joint="ring_MCP" ctrlrange="0 1.6"/> 468 <position name="A_pinky_ABD" class="MPL" joint="pinky_ABD" ctrlrange="0 0.34"/> 469 <position name="A_pinky_MCP" class="MPL" joint="pinky_MCP" ctrlrange="0 1.6"/> 470 </actuator> 471</mujoco> 472