|
| 1 | +<mujoco model="DOGlove_Ver20241223"> |
| 2 | + <compiler angle="radian"/> |
| 3 | + |
| 4 | + <!-- <visual> |
| 5 | + <headlight diffuse="0.6 0.6 0.6" ambient="0.1 0.1 0.1" specular="0 0 0"/> |
| 6 | + <global azimuth="120" elevation="-20"/> |
| 7 | + </visual> |
| 8 | +
|
| 9 | +
|
| 10 | + <asset> |
| 11 | + <texture name="grid" type="2d" builtin="checker" rgb1=".2 .3 .4" rgb2=".1 0.15 0.2" width="512" height="512" |
| 12 | + mark="cross" markrgb=".8 .8 .8"/> |
| 13 | + <material name="grid" texture="grid" texrepeat="1 1" texuniform="true"/> |
| 14 | + </asset> --> |
| 15 | + |
| 16 | + <visual> |
| 17 | + <headlight diffuse="0.6 0.6 0.6" ambient="0.3 0.3 0.3" specular="0 0 0"/> |
| 18 | + <rgba haze="0.15 0.25 0.35 1"/> |
| 19 | + <global azimuth="60" elevation="-40"/> |
| 20 | + </visual> |
| 21 | + |
| 22 | + <asset> |
| 23 | + <texture type="skybox" builtin="gradient" rgb1="1.0 1.0 1.0" rgb2="0 0 0" width="512" height="3072"/> |
| 24 | + <!-- <texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="1.0 1.0 1.0" rgb2="1.0 1.0 1.0" |
| 25 | + markrgb="0.8 0.8 0.8" width="300" height="300"/> |
| 26 | + <material name="groundplane" texture="groundplane" texuniform="false" texrepeat="5 5" reflectance="0.2"/> --> |
| 27 | + </asset> |
| 28 | + |
| 29 | + <default> |
| 30 | + <default class="finger"> |
| 31 | + <joint damping="0.03"/> |
| 32 | + </default> |
| 33 | + <default class="thumb"> |
| 34 | + <joint damping="0.05"/> |
| 35 | + </default> |
| 36 | + </default> |
| 37 | + |
| 38 | + <asset> |
| 39 | + <mesh name="base_link" file="base_link.STL"/> |
| 40 | + <mesh name="index_split" file="index_split.STL"/> |
| 41 | + <mesh name="index_bend_3" file="index_bend_3.STL"/> |
| 42 | + <mesh name="index_bend_2" file="index_bend_2.STL"/> |
| 43 | + <mesh name="index_bend_1" file="index_bend_1.STL"/> |
| 44 | + <mesh name="middle_split" file="middle_split.STL"/> |
| 45 | + <mesh name="middle_bend_3" file="middle_bend_3.STL"/> |
| 46 | + <mesh name="middle_bend_2" file="middle_bend_2.STL"/> |
| 47 | + <mesh name="middle_bend_1" file="middle_bend_1.STL"/> |
| 48 | + <mesh name="ring_split" file="ring_split.STL"/> |
| 49 | + <mesh name="ring_bend_3" file="ring_bend_3.STL"/> |
| 50 | + <mesh name="ring_bend_2" file="ring_bend_2.STL"/> |
| 51 | + <mesh name="ring_bend_1" file="ring_bend_1.STL"/> |
| 52 | + <mesh name="pinky_split" file="pinky_split.STL"/> |
| 53 | + <mesh name="pinky_bend_3" file="pinky_bend_3.STL"/> |
| 54 | + <mesh name="pinky_bend_2" file="pinky_bend_2.STL"/> |
| 55 | + <mesh name="pinky_bend_1" file="pinky_bend_1.STL"/> |
| 56 | + <mesh name="thumb_mcp" file="thumb_mcp.STL"/> |
| 57 | + <mesh name="thumb_split" file="thumb_split.STL"/> |
| 58 | + <mesh name="thumb_bend_3" file="thumb_bend_3.STL"/> |
| 59 | + <mesh name="thumb_bend_2" file="thumb_bend_2.STL"/> |
| 60 | + <mesh name="thumb_bend_1" file="thumb_bend_1.STL"/> |
| 61 | + </asset> |
| 62 | + |
| 63 | + <worldbody> |
| 64 | + <body name="world_frame" pos="0 0 0"/> |
| 65 | + <geom name="visible_point" type="sphere" size="0.00001" pos="-0.0 0.1 0.3" rgba="1 0 0 1" /> |
| 66 | + <!-- <geom name="board" type="box" size="0.005 0.055 0.032" pos="-0.035 0.07 0.327" rgba="0.752941 0.752941 0.752941 1" /> --> |
| 67 | + <body name="hand" pos="0 0 0.3" euler="2.355 0 0"> |
| 68 | + <body name="palm" pos="0 0 0" gravcomp="1"> |
| 69 | + <geom type="mesh" rgba="0.752941 0.752941 0.752941 1" mesh="base_link"/> |
| 70 | + </body> |
| 71 | + <body name="index_split" pos="-0.085 -0.0601041 -0.104853" quat="0.653281 -0.270598 -0.653281 0.270598" gravcomp="1"> |
| 72 | + <inertial pos="2.01867e-06 0.0196179 -0.0272426" quat="0.644578 0.764538 0.00106342 5.83972e-05" mass="0.0331994" diaginertia="3.66315e-06 3.46048e-06 2.74469e-06"/> |
| 73 | + <joint name="index_split" pos="0 0 0" axis="0 0 1" range="1.57 1.57" class="finger"/> |
| 74 | + <geom type="mesh" rgba="1 0.843 0 1" mesh="index_split"/> |
| 75 | + <body name="index_bend_3" pos="0 0.045 -0.0365" gravcomp="1"> |
| 76 | + <inertial pos="0 0.0302786 -3.00021e-06" quat="0.707188 0.707026 0 0" mass="0.00454938" diaginertia="2.55133e-06 2.46888e-06 9.45809e-08"/> |
| 77 | + <joint name="index_bend_3" pos="0 0 0" axis="1 0 0" range="-1.57 1.16" class="finger"/> |
| 78 | + <geom type="mesh" rgba="0.752941 0.752941 0.752941 1" mesh="index_bend_3"/> |
| 79 | + <body name="index_bend_2" pos="0 0.07 0" gravcomp="1"> |
| 80 | + <inertial pos="-0.000180675 0.03 -0.000190739" quat="0.706203 0.706203 -0.0357435 0.0357435" mass="0.0132915" diaginertia="6.4192e-06 6.29363e-06 7.34581e-07"/> |
| 81 | + <joint name="index_bend_2" pos="0 0 0" axis="1 0 0" range="-2.61 0" class="finger"/> |
| 82 | + <geom type="mesh" rgba="0.752941 0.752941 0.752941 1" mesh="index_bend_2"/> |
| 83 | + <body name="index_bend_1" pos="0 0.06 0" gravcomp="1"> |
| 84 | + <inertial pos="0 0.00880992 0" quat="0.707107 0.707107 0 0" mass="0.0013349" diaginertia="8.22112e-08 7.27871e-08 2.94529e-08"/> |
| 85 | + <joint name="index_bend_1" pos="0 0 0" axis="1 0 0" range="-2.09 0" class="finger"/> |
| 86 | + <geom type="mesh" rgba="0.752941 0.752941 0.752941 1" mesh="index_bend_1"/> |
| 87 | + <site name="index_tip_site" size="0.0001" rgba="1 0 0 1" pos="0 0.045 0"/> |
| 88 | + </body> |
| 89 | + </body> |
| 90 | + </body> |
| 91 | + </body> |
| 92 | + <body name="middle_split" pos="-0.085 -0.0417193 -0.086468" quat="0.653281 -0.270598 -0.653281 0.270598" gravcomp="1"> |
| 93 | + <inertial pos="2.02017e-06 0.0196179 -0.0272426" quat="0.644578 0.764538 0.00106342 5.83909e-05" mass="0.0331994" diaginertia="3.66315e-06 3.46048e-06 2.74469e-06"/> |
| 94 | + <joint name="middle_split" pos="0 0 0" axis="0 0 1" range="-1.57 1.57" class="finger"/> |
| 95 | + <geom type="mesh" rgba="1 0.843 0 1" mesh="middle_split"/> |
| 96 | + <body name="middle_bend_3" pos="0 0.045 -0.0365" gravcomp="1"> |
| 97 | + <inertial pos="0 0.0339728 -2.76667e-06" quat="0.707174 0.70704 0 0" mass="0.00493338" diaginertia="3.35947e-06 3.27293e-06 9.97009e-08"/> |
| 98 | + <joint name="middle_bend_3" pos="0 0 0" axis="1 0 0" range="-1.57 1.15" class="finger"/> |
| 99 | + <geom type="mesh" rgba="0.752941 0.752941 0.752941 1" mesh="middle_bend_3"/> |
| 100 | + <body name="middle_bend_2" pos="0 0.078 0" gravcomp="1"> |
| 101 | + <inertial pos="-0.000171024 0.0325 -0.000394202" quat="0.70617 0.70617 -0.0363796 0.0363796" mass="0.0140415" diaginertia="7.7654e-06 7.63721e-06 7.65219e-07"/> |
| 102 | + <joint name="middle_bend_2" pos="0 0 0" axis="1 0 0" range="-2.44 0" class="finger"/> |
| 103 | + <geom type="mesh" rgba="1 0.843 0 1" mesh="middle_bend_2"/> |
| 104 | + <body name="middle_bend_1" pos="0 0.065 0" gravcomp="1"> |
| 105 | + <inertial pos="0 0.00880992 7.75712e-12" quat="0.707107 0.707107 0 0" mass="0.0013349" diaginertia="8.22112e-08 7.27871e-08 2.94529e-08"/> |
| 106 | + <joint name="middle_bend_1" pos="0 0 0" axis="1 0 0" range="-2.09 0" class="finger"/> |
| 107 | + <geom type="mesh" rgba="0.752941 0.752941 0.752941 1" mesh="middle_bend_1"/> |
| 108 | + <site name="middle_tip_site" size="0.0001" rgba="1 0 0 1" pos="0 0.045 0"/> |
| 109 | + </body> |
| 110 | + </body> |
| 111 | + </body> |
| 112 | + </body> |
| 113 | + <body name="ring_split" pos="-0.085 -0.0233345 -0.0680833" quat="0.653281 -0.270598 -0.653281 0.270598" gravcomp="1"> |
| 114 | + <inertial pos="2.01959e-06 0.0196179 -0.0272426" quat="0.644578 0.764538 0.00106341 5.84011e-05" mass="0.0331994" diaginertia="3.66315e-06 3.46048e-06 2.74469e-06"/> |
| 115 | + <joint name="ring_split" pos="0 0 0" axis="0 0 1" range="-1.57 1.57" class="finger"/> |
| 116 | + <geom type="mesh" rgba="1 0.843 0 1" mesh="ring_split"/> |
| 117 | + <body name="ring_bend_3" pos="0 0.045 -0.0365" gravcomp="1"> |
| 118 | + <inertial pos="0 0.0316581 -2.90816e-06" quat="0.707182 0.707032 0 0" mass="0.00469338" diaginertia="2.83677e-06 2.75279e-06 9.65009e-08"/> |
| 119 | + <joint name="ring_bend_3" pos="0 0 0" axis="1 0 0" range="-1.57 1.15" class="finger"/> |
| 120 | + <geom type="mesh" rgba="0.752941 0.752941 0.752941 1" mesh="ring_bend_3"/> |
| 121 | + <body name="ring_bend_2" pos="0 0.073 0" gravcomp="1"> |
| 122 | + <inertial pos="-0.000180675 0.03 -0.000190739" quat="0.706203 0.706203 -0.0357435 0.0357435" mass="0.0132915" diaginertia="6.4192e-06 6.29363e-06 7.34581e-07"/> |
| 123 | + <joint name="ring_bend_2" pos="0 0 0" axis="1 0 0" range="-2.61 0" class="finger"/> |
| 124 | + <geom type="mesh" rgba="1 0.843 0 1" mesh="ring_bend_2"/> |
| 125 | + <body name="ring_bend_1" pos="0 0.06 0" gravcomp="1"> |
| 126 | + <inertial pos="0 0.00880992 0" quat="0.707107 0.707107 0 0" mass="0.0013349" diaginertia="8.22112e-08 7.27871e-08 2.94529e-08"/> |
| 127 | + <joint name="ring_bend_1" pos="0 0 0" axis="1 0 0" range="-2.09 0" class="finger"/> |
| 128 | + <geom type="mesh" rgba="0.752941 0.752941 0.752941 1" mesh="ring_bend_1"/> |
| 129 | + <site name="ring_tip_site" size="0.0001" rgba="1 0 0 1" pos="0 0.045 0"/> |
| 130 | + </body> |
| 131 | + </body> |
| 132 | + </body> |
| 133 | + </body> |
| 134 | + <body name="pinky_split" pos="-0.085 -0.0049497 -0.049698" quat="0.653281 -0.270597 -0.653283 0.270597" gravcomp="1"> |
| 135 | + <inertial pos="2.02066e-06 0.0196179 -0.0272426" quat="0.644578 0.764537 0.00106342 5.83814e-05" mass="0.0331994" diaginertia="3.66315e-06 3.46048e-06 2.74469e-06"/> |
| 136 | + <joint name="pinky_split" pos="0 0 0" axis="0 0 1" range="-1.57 1.57" class="finger"/> |
| 137 | + <geom type="mesh" rgba="1 0.843 0 1" mesh="pinky_split" class="finger"/> |
| 138 | + <body name="pinky_bend_3" pos="0 0.045 -0.0365" gravcomp="1"> |
| 139 | + <inertial pos="0 0.0279974 -3.1673e-06" quat="0.707198 0.707015 0 0" mass="0.00430938" diaginertia="2.12046e-06 2.04057e-06 9.13809e-08"/> |
| 140 | + <joint name="pinky_bend_3" pos="0 0 0" axis="1 0 0" range="-1.57 1.14" class="finger"/> |
| 141 | + <geom type="mesh" rgba="0.752941 0.752941 0.752941 1" mesh="pinky_bend_3"/> |
| 142 | + <body name="pinky_bend_2" pos="0 0.065 0" gravcomp="1"> |
| 143 | + <inertial pos="-0.000191479 0.0275 3.706e-05" quat="0.706227 0.706227 -0.0352657 0.0352657" mass="0.0125415" diaginertia="5.23792e-06 5.11619e-06 7.02709e-07"/> |
| 144 | + <joint name="pinky_bend_2" pos="0 0 0" axis="1 0 0" range="-2.44 0" class="finger"/> |
| 145 | + <geom type="mesh" rgba="1 0.843 0 1" mesh="pinky_bend_2"/> |
| 146 | + <body name="pinky_bend_1" pos="0 0.055 0" gravcomp="1"> |
| 147 | + <inertial pos="0 0.00880992 0" quat="0.707107 0.707107 0 0" mass="0.0013349" diaginertia="8.22112e-08 7.27871e-08 2.94529e-08"/> |
| 148 | + <joint name="pinky_bend_1" pos="0 0 0" axis="1 0 0" range="-2.09 0" class="finger"/> |
| 149 | + <geom type="mesh" rgba="0.752941 0.752941 0.752941 1" mesh="pinky_bend_1"/> |
| 150 | + <site name="pinky_tip_site" size="0.0001" rgba="1 0 0 1" pos="0 0.045 0"/> |
| 151 | + </body> |
| 152 | + </body> |
| 153 | + </body> |
| 154 | + </body> |
| 155 | + <body name="thumb_mcp" pos="-0.0475 -0.092589 -0.07964" quat="0.499998 -0.5 -0.500002 0.5" gravcomp="1"> |
| 156 | + <inertial pos="-0.0166424 4.56217e-12 0" quat="0 0.707107 0 0.707107" mass="0.0023739" diaginertia="3.75289e-07 3.63646e-07 4.40152e-08"/> |
| 157 | + <joint name="thumb_mcp" pos="0 0 0" axis="0 1 0" range="-3.14 1.57" class="thumb"/> |
| 158 | + <geom type="mesh" rgba="0.752941 0.752941 0.752941 1" mesh="thumb_mcp"/> |
| 159 | + <body name="thumb_split" pos="-0.031 0 0.0075" gravcomp="1"> |
| 160 | + <inertial pos="7.69025e-06 0.0124342 0.00469169" quat="0.746026 0.665916 -0.000293726 0.000952804" mass="0.0433016" diaginertia="7.83009e-06 7.13377e-06 4.98698e-06"/> |
| 161 | + <joint name="thumb_split" pos="0 0 0" axis="0 0 -1" range="-1.57 1.57" class="thumb"/> |
| 162 | + <geom type="mesh" rgba="1 0.843 0 1" mesh="thumb_split"/> |
| 163 | + <body name="thumb_bend_3" pos="0 0.04 -0.0045" gravcomp="1"> |
| 164 | + <inertial pos="0 0.0213294 3.80263e-06" quat="0.706966 0.707248 0 0" mass="0.00358938" diaginertia="1.1359e-06 1.06369e-06 8.17809e-08"/> |
| 165 | + <joint name="thumb_bend_3" pos="0 0 0" axis="1 0 0" range="-1.57 1.54" class="thumb"/> |
| 166 | + <geom type="mesh" rgba="0.752941 0.752941 0.752941 1" mesh="thumb_bend_3"/> |
| 167 | + <body name="thumb_bend_2" pos="-0.002 0.05 0" gravcomp="1"> |
| 168 | + <inertial pos="0.00223918 0.02 0.000862215" quat="0.706246 0.706246 0.0348769 -0.0348769" mass="0.0100405" diaginertia="2.58082e-06 2.47797e-06 5.90239e-07"/> |
| 169 | + <joint name="thumb_bend_2" pos="0 0 0" axis="1 0 0" range="-2.44 0" class="thumb"/> |
| 170 | + <geom type="mesh" rgba="0.752941 0.752941 0.752941 1" mesh="thumb_bend_2"/> |
| 171 | + <body name="thumb_bend_1" pos="0.002 0.04 0" gravcomp="1"> |
| 172 | + <inertial pos="0 0.00880992 0" quat="0.707107 0.707107 0 0" mass="0.0013349" diaginertia="8.22112e-08 7.27871e-08 2.94529e-08"/> |
| 173 | + <joint name="thumb_bend_1" pos="0 0 0" axis="1 0 0" range="-1.83 0" class="thumb"/> |
| 174 | + <geom type="mesh" rgba="0.752941 0.752941 0.752941 1" mesh="thumb_bend_1"/> |
| 175 | + <site name="thumb_tip_site" size="0.0001" rgba="1 0 0 1" pos="0 0.05 0"/> |
| 176 | + </body> |
| 177 | + </body> |
| 178 | + </body> |
| 179 | + </body> |
| 180 | + </body> |
| 181 | + </body> |
| 182 | + <light pos="0 0 1.5" directional="true"/> |
| 183 | + <!-- <geom name="floor" size="1 1 0.01" type="plane" material="grid"/> --> |
| 184 | + <!-- <geom name="floor" size="1 1 0.01" type="plane" material="groundplane"/> --> |
| 185 | + </worldbody> |
| 186 | + |
| 187 | + <contact> |
| 188 | + |
| 189 | + <exclude body1="palm" body2="index_split"/> |
| 190 | + <exclude body1="palm" body2="middle_split"/> |
| 191 | + <exclude body1="palm" body2="ring_split"/> |
| 192 | + <exclude body1="palm" body2="pinky_split"/> |
| 193 | + <exclude body1="palm" body2="thumb_split"/> |
| 194 | + <exclude body1="palm" body2="thumb_mcp"/> |
| 195 | + |
| 196 | + </contact> |
| 197 | + |
| 198 | + <actuator> |
| 199 | + <position name="index_split" joint="index_split" kp="1" ctrlrange="-1.57 1.57"/> |
| 200 | + <position name="index_bend_3" joint="index_bend_3" kp="1" ctrlrange="-1.57 1.16"/> |
| 201 | + <position name="index_bend_2" joint="index_bend_2" kp="1" ctrlrange="-2.61 0"/> |
| 202 | + <position name="index_bend_1" joint="index_bend_1" kp="1" ctrlrange="-2.09 0"/> |
| 203 | + <position name="middle_split" joint="middle_split" kp="1" ctrlrange="-1.57 1.57"/> |
| 204 | + <position name="middle_bend_3" joint="middle_bend_3" kp="1" ctrlrange="-1.57 1.15"/> |
| 205 | + <position name="middle_bend_2" joint="middle_bend_2" kp="1" ctrlrange="-2.44 0"/> |
| 206 | + <position name="middle_bend_1" joint="middle_bend_1" kp="1" ctrlrange="-2.09 0"/> |
| 207 | + <position name="ring_split" joint="ring_split" kp="1" ctrlrange="-1.57 1.57"/> |
| 208 | + <position name="ring_bend_3" joint="ring_bend_3" kp="1" ctrlrange="-1.57 1.15"/> |
| 209 | + <position name="ring_bend_2" joint="ring_bend_2" kp="1" ctrlrange="-2.61 0"/> |
| 210 | + <position name="ring_bend_1" joint="ring_bend_1" kp="1" ctrlrange="-2.09 0"/> |
| 211 | + <position name="pinky_split" joint="pinky_split" kp="1" ctrlrange="-1.57 1.57"/> |
| 212 | + <position name="pinky_bend_3" joint="pinky_bend_3" kp="1" ctrlrange="-1.57 1.14"/> |
| 213 | + <position name="pinky_bend_2" joint="pinky_bend_2" kp="1" ctrlrange="-2.44 0"/> |
| 214 | + <position name="pinky_bend_1" joint="pinky_bend_1" kp="1" ctrlrange="-2.09 0"/> |
| 215 | + <position name="thumb_mcp" joint="thumb_mcp" kp="1" ctrlrange="-3.14 1.57"/> |
| 216 | + <position name="thumb_split" joint="thumb_split" kp="1" ctrlrange="-1.57 1.57"/> |
| 217 | + <position name="thumb_bend_3" joint="thumb_bend_3" kp="1" ctrlrange="-1.57 1.54"/> |
| 218 | + <position name="thumb_bend_2" joint="thumb_bend_2" kp="1" ctrlrange="-2.44 0"/> |
| 219 | + <position name="thumb_bend_1" joint="thumb_bend_1" kp="1" ctrlrange="-1.83 0"/> |
| 220 | + </actuator> |
| 221 | + |
| 222 | + |
| 223 | +</mujoco> |
0 commit comments