|
| 1 | +<mujoco model="panda"> |
| 2 | + <compiler angle="radian" meshdir="assets" autolimits="true"/> |
| 3 | + |
| 4 | + <default> |
| 5 | + <default class="panda"> |
| 6 | + <material specular="0.5" shininess="0.25"/> |
| 7 | + <joint armature="0.1" damping="1" axis="0 0 1" range="-2.8973 2.8973"/> |
| 8 | + <general dyntype="none" biastype="affine" ctrlrange="-2.8973 2.8973" forcerange="-87 87"/> |
| 9 | + <position forcerange="-100 100"/> |
| 10 | + <default class="finger"> |
| 11 | + <joint axis="0 1 0" type="slide" range="0 0.04"/> |
| 12 | + </default> |
| 13 | + |
| 14 | + <default class="visual"> |
| 15 | + <geom type="mesh" contype="0" conaffinity="0" group="2"/> |
| 16 | + </default> |
| 17 | + <default class="collision"> |
| 18 | + <geom group="3" type="mesh" contype="0" conaffinity="0"/> |
| 19 | + <default class="primitive_collision"> |
| 20 | + <geom group="3" type="box" contype="0" conaffinity="0" |
| 21 | + condim="3" solimp="0.99 0.995 0.01" solref="0.01 1" friction="1 0.005 0.0001"/> |
| 22 | + <default class="fingertip_pad_collision_1"> |
| 23 | + <geom type="box" size="0.011 0.0075 0.01" pos="0 0.0185 0.011"/> |
| 24 | + </default> |
| 25 | + <default class="fingertip_pad_collision_2"> |
| 26 | + <geom type="box" size="0.011 0.0044 0.0019" pos="0 0.0068 0.0022"/> |
| 27 | + </default> |
| 28 | + <default class="fingertip_pad_collision_3"> |
| 29 | + <geom type="box" size="0.00875 0.0035 0.01175" pos="0 0.0159 0.02835" quat="1 0.25 0 0"/> |
| 30 | + </default> |
| 31 | + <default class="fingertip_pad_collision_4"> |
| 32 | + <geom type="box" size="0.00875 0.0076 0.00825" pos="0 0.00758 0.04525" conaffinity="3"/> |
| 33 | + </default> |
| 34 | + </default> |
| 35 | + </default> |
| 36 | + </default> |
| 37 | + </default> |
| 38 | + |
| 39 | + <asset> |
| 40 | + <material class="panda" name="white" rgba="1 1 1 1"/> |
| 41 | + <material class="panda" name="off_white" rgba="0.901961 0.921569 0.929412 1"/> |
| 42 | + <material class="panda" name="black" rgba="0.25 0.25 0.25 1"/> |
| 43 | + <material class="panda" name="green" rgba="0 1 0 1"/> |
| 44 | + <material class="panda" name="light_blue" rgba="0.039216 0.541176 0.780392 1"/> |
| 45 | + |
| 46 | + <!-- Collision meshes --> |
| 47 | + <mesh name="link0_c" file="link0.stl"/> |
| 48 | + <mesh name="link1_c" file="link1.stl"/> |
| 49 | + <mesh name="link2_c" file="link2.stl"/> |
| 50 | + <mesh name="link3_c" file="link3.stl"/> |
| 51 | + <mesh name="link4_c" file="link4.stl"/> |
| 52 | + <mesh name="link5_c0" file="link5_collision_0.obj"/> |
| 53 | + <mesh name="link5_c1" file="link5_collision_1.obj"/> |
| 54 | + <mesh name="link5_c2" file="link5_collision_2.obj"/> |
| 55 | + <mesh name="link6_c" file="link6.stl"/> |
| 56 | + <mesh name="link7_c" file="link7.stl"/> |
| 57 | + <mesh name="hand_c" file="hand.stl"/> |
| 58 | + |
| 59 | + <!-- Visual meshes --> |
| 60 | + <mesh file="link0_0.obj"/> |
| 61 | + <mesh file="link0_1.obj"/> |
| 62 | + <mesh file="link0_2.obj"/> |
| 63 | + <mesh file="link0_3.obj"/> |
| 64 | + <mesh file="link0_4.obj"/> |
| 65 | + <mesh file="link0_5.obj"/> |
| 66 | + <mesh file="link0_7.obj"/> |
| 67 | + <mesh file="link0_8.obj"/> |
| 68 | + <mesh file="link0_9.obj"/> |
| 69 | + <mesh file="link0_10.obj"/> |
| 70 | + <mesh file="link0_11.obj"/> |
| 71 | + <mesh file="link1.obj"/> |
| 72 | + <mesh file="link2.obj"/> |
| 73 | + <mesh file="link3_0.obj"/> |
| 74 | + <mesh file="link3_1.obj"/> |
| 75 | + <mesh file="link3_2.obj"/> |
| 76 | + <mesh file="link3_3.obj"/> |
| 77 | + <mesh file="link4_0.obj"/> |
| 78 | + <mesh file="link4_1.obj"/> |
| 79 | + <mesh file="link4_2.obj"/> |
| 80 | + <mesh file="link4_3.obj"/> |
| 81 | + <mesh file="link5_0.obj"/> |
| 82 | + <mesh file="link5_1.obj"/> |
| 83 | + <mesh file="link5_2.obj"/> |
| 84 | + <mesh file="link6_0.obj"/> |
| 85 | + <mesh file="link6_1.obj"/> |
| 86 | + <mesh file="link6_2.obj"/> |
| 87 | + <mesh file="link6_3.obj"/> |
| 88 | + <mesh file="link6_4.obj"/> |
| 89 | + <mesh file="link6_5.obj"/> |
| 90 | + <mesh file="link6_6.obj"/> |
| 91 | + <mesh file="link6_7.obj"/> |
| 92 | + <mesh file="link6_8.obj"/> |
| 93 | + <mesh file="link6_9.obj"/> |
| 94 | + <mesh file="link6_10.obj"/> |
| 95 | + <mesh file="link6_11.obj"/> |
| 96 | + <mesh file="link6_12.obj"/> |
| 97 | + <mesh file="link6_13.obj"/> |
| 98 | + <mesh file="link6_14.obj"/> |
| 99 | + <mesh file="link6_15.obj"/> |
| 100 | + <mesh file="link6_16.obj"/> |
| 101 | + <mesh file="link7_0.obj"/> |
| 102 | + <mesh file="link7_1.obj"/> |
| 103 | + <mesh file="link7_2.obj"/> |
| 104 | + <mesh file="link7_3.obj"/> |
| 105 | + <mesh file="link7_4.obj"/> |
| 106 | + <mesh file="link7_5.obj"/> |
| 107 | + <mesh file="link7_6.obj"/> |
| 108 | + <mesh file="link7_7.obj"/> |
| 109 | + <mesh file="hand_0.obj"/> |
| 110 | + <mesh file="hand_1.obj"/> |
| 111 | + <mesh file="hand_2.obj"/> |
| 112 | + <mesh file="hand_3.obj"/> |
| 113 | + <mesh file="hand_4.obj"/> |
| 114 | + <mesh file="finger_0.obj"/> |
| 115 | + <mesh file="finger_1.obj"/> |
| 116 | + </asset> |
| 117 | + |
| 118 | + <worldbody> |
| 119 | + <light name="top" pos="0 0 2" mode="trackcom"/> |
| 120 | + <body name="link0" childclass="panda"> |
| 121 | + <inertial mass="0.629769" pos="-0.041018 -0.00014 0.049974" |
| 122 | + fullinertia="0.00315 0.00388 0.004285 8.2904e-7 0.00015 8.2299e-6"/> |
| 123 | + <geom mesh="link0_0" material="off_white" class="visual"/> |
| 124 | + <geom mesh="link0_1" material="black" class="visual"/> |
| 125 | + <geom mesh="link0_2" material="off_white" class="visual"/> |
| 126 | + <geom mesh="link0_3" material="black" class="visual"/> |
| 127 | + <geom mesh="link0_4" material="off_white" class="visual"/> |
| 128 | + <geom mesh="link0_5" material="black" class="visual"/> |
| 129 | + <geom mesh="link0_7" material="white" class="visual"/> |
| 130 | + <geom mesh="link0_8" material="white" class="visual"/> |
| 131 | + <geom mesh="link0_9" material="black" class="visual"/> |
| 132 | + <geom mesh="link0_10" material="off_white" class="visual"/> |
| 133 | + <geom mesh="link0_11" material="white" class="visual"/> |
| 134 | + <geom mesh="link0_c" class="collision"/> |
| 135 | + <body name="link1" pos="0 0 0.333"> |
| 136 | + <inertial mass="4.970684" pos="0.003875 0.002081 -0.04762" |
| 137 | + fullinertia="0.70337 0.70661 0.0091170 -0.00013900 0.0067720 0.019169"/> |
| 138 | + <joint name="joint1" damping="40"/> |
| 139 | + <geom material="white" mesh="link1" class="visual"/> |
| 140 | + <geom mesh="link1_c" class="collision"/> |
| 141 | + <body name="link2" quat="1 -1 0 0"> |
| 142 | + <inertial mass="0.646926" pos="-0.003141 -0.02872 0.003495" |
| 143 | + fullinertia="0.0079620 2.8110e-2 2.5995e-2 -3.925e-3 1.0254e-2 7.04e-4"/> |
| 144 | + <joint name="joint2" range="-1.7628 1.7628" damping="40"/> |
| 145 | + <geom material="white" mesh="link2" class="visual"/> |
| 146 | + <geom mesh="link2_c" class="collision"/> |
| 147 | + <body name="link3" pos="0 -0.316 0" quat="1 1 0 0"> |
| 148 | + <joint name="joint3" damping="40"/> |
| 149 | + <inertial mass="3.228604" pos="2.7518e-2 3.9252e-2 -6.6502e-2" |
| 150 | + fullinertia="3.7242e-2 3.6155e-2 1.083e-2 -4.761e-3 -1.1396e-2 -1.2805e-2"/> |
| 151 | + <geom mesh="link3_0" material="white" class="visual"/> |
| 152 | + <geom mesh="link3_1" material="white" class="visual"/> |
| 153 | + <geom mesh="link3_2" material="white" class="visual"/> |
| 154 | + <geom mesh="link3_3" material="black" class="visual"/> |
| 155 | + <geom mesh="link3_c" class="collision"/> |
| 156 | + <body name="link4" pos="0.0825 0 0" quat="1 1 0 0"> |
| 157 | + <inertial mass="3.587895" pos="-5.317e-2 1.04419e-1 2.7454e-2" |
| 158 | + fullinertia="2.5853e-2 1.9552e-2 2.8323e-2 7.796e-3 -1.332e-3 8.641e-3"/> |
| 159 | + <joint name="joint4" range="-3.0718 -0.0698" damping="40"/> |
| 160 | + <geom mesh="link4_0" material="white" class="visual"/> |
| 161 | + <geom mesh="link4_1" material="white" class="visual"/> |
| 162 | + <geom mesh="link4_2" material="black" class="visual"/> |
| 163 | + <geom mesh="link4_3" material="white" class="visual"/> |
| 164 | + <geom mesh="link4_c" class="collision"/> |
| 165 | + <body name="link5" pos="-0.0825 0.384 0" quat="1 -1 0 0"> |
| 166 | + <inertial mass="1.225946" pos="-1.1953e-2 4.1065e-2 -3.8437e-2" |
| 167 | + fullinertia="3.5549e-2 2.9474e-2 8.627e-3 -2.117e-3 -4.037e-3 2.29e-4"/> |
| 168 | + <joint name="joint5" damping="2"/> |
| 169 | + <geom mesh="link5_0" material="black" class="visual"/> |
| 170 | + <geom mesh="link5_1" material="white" class="visual"/> |
| 171 | + <geom mesh="link5_2" material="white" class="visual"/> |
| 172 | + <geom mesh="link5_c0" class="collision"/> |
| 173 | + <geom mesh="link5_c1" class="collision"/> |
| 174 | + <geom mesh="link5_c2" class="collision"/> |
| 175 | + <body name="link6" quat="1 1 0 0"> |
| 176 | + <inertial mass="1.666555" pos="6.0149e-2 -1.4117e-2 -1.0517e-2" |
| 177 | + fullinertia="1.964e-3 4.354e-3 5.433e-3 1.09e-4 -1.158e-3 3.41e-4"/> |
| 178 | + <joint name="joint6" range="-0.0175 3.7525" damping="2"/> |
| 179 | + <geom mesh="link6_0" material="off_white" class="visual"/> |
| 180 | + <geom mesh="link6_1" material="white" class="visual"/> |
| 181 | + <geom mesh="link6_2" material="black" class="visual"/> |
| 182 | + <geom mesh="link6_3" material="white" class="visual"/> |
| 183 | + <geom mesh="link6_4" material="white" class="visual"/> |
| 184 | + <geom mesh="link6_5" material="white" class="visual"/> |
| 185 | + <geom mesh="link6_6" material="white" class="visual"/> |
| 186 | + <geom mesh="link6_7" material="light_blue" class="visual"/> |
| 187 | + <geom mesh="link6_8" material="light_blue" class="visual"/> |
| 188 | + <geom mesh="link6_9" material="black" class="visual"/> |
| 189 | + <geom mesh="link6_10" material="black" class="visual"/> |
| 190 | + <geom mesh="link6_11" material="white" class="visual"/> |
| 191 | + <geom mesh="link6_12" material="green" class="visual"/> |
| 192 | + <geom mesh="link6_13" material="white" class="visual"/> |
| 193 | + <geom mesh="link6_14" material="black" class="visual"/> |
| 194 | + <geom mesh="link6_15" material="black" class="visual"/> |
| 195 | + <geom mesh="link6_16" material="white" class="visual"/> |
| 196 | + <geom mesh="link6_c" class="collision"/> |
| 197 | + <body name="link7" pos="0.088 0 0" quat="1 1 0 0"> |
| 198 | + <inertial mass="7.35522e-01" pos="1.0517e-2 -4.252e-3 6.1597e-2" |
| 199 | + fullinertia="1.2516e-2 1.0027e-2 4.815e-3 -4.28e-4 -1.196e-3 -7.41e-4"/> |
| 200 | + <joint name="joint7" damping="2"/> |
| 201 | + <geom mesh="link7_0" material="white" class="visual"/> |
| 202 | + <geom mesh="link7_1" material="black" class="visual"/> |
| 203 | + <geom mesh="link7_2" material="black" class="visual"/> |
| 204 | + <geom mesh="link7_3" material="black" class="visual"/> |
| 205 | + <geom mesh="link7_4" material="black" class="visual"/> |
| 206 | + <geom mesh="link7_5" material="black" class="visual"/> |
| 207 | + <geom mesh="link7_6" material="black" class="visual"/> |
| 208 | + <geom mesh="link7_7" material="white" class="visual"/> |
| 209 | + <geom mesh="link7_c" class="collision"/> |
| 210 | + <body name="hand" pos="0 0 0.107" quat="0.9238795 0 0 -0.3826834"> |
| 211 | + <inertial mass="0.73" pos="-0.01 0 0.03" diaginertia="0.001 0.0025 0.0017"/> |
| 212 | + <geom mesh="hand_0" material="off_white" class="visual"/> |
| 213 | + <geom mesh="hand_1" material="black" class="visual"/> |
| 214 | + <geom mesh="hand_2" material="black" class="visual"/> |
| 215 | + <geom mesh="hand_3" material="white" class="visual"/> |
| 216 | + <geom mesh="hand_4" material="off_white" class="visual"/> |
| 217 | + <geom mesh="hand_c" class="collision"/> |
| 218 | + <geom name="hand_capsule" type="capsule" |
| 219 | + class="collision" conaffinity="1" size="0.04 0.06" |
| 220 | + quat="1 1 0 0" pos="0 0 0.03"/> |
| 221 | + <site name="gripper" pos="0 0 0.1"/> |
| 222 | + <body name="left_finger" pos="0 0 0.0584"> |
| 223 | + <inertial mass="0.015" pos="0 0 0" diaginertia="2.375e-6 2.375e-6 7.5e-7"/> |
| 224 | + <joint name="finger_joint1" class="finger" damping="10"/> |
| 225 | + <geom mesh="finger_0" material="off_white" class="visual"/> |
| 226 | + <geom mesh="finger_1" material="black" class="visual"/> |
| 227 | + <geom mesh="finger_0" class="collision"/> |
| 228 | + <geom class="fingertip_pad_collision_1"/> |
| 229 | + <geom class="fingertip_pad_collision_2"/> |
| 230 | + <geom class="fingertip_pad_collision_3"/> |
| 231 | + <geom name="left_finger_pad" class="fingertip_pad_collision_4"/> |
| 232 | + </body> |
| 233 | + <body name="right_finger" pos="0 0 0.0584" quat="0 0 0 1"> |
| 234 | + <inertial mass="0.015" pos="0 0 0" diaginertia="2.375e-6 2.375e-6 7.5e-7"/> |
| 235 | + <joint name="finger_joint2" class="finger" damping="10"/> |
| 236 | + <geom mesh="finger_0" material="off_white" class="visual"/> |
| 237 | + <geom mesh="finger_1" material="black" class="visual"/> |
| 238 | + <geom mesh="finger_0" class="collision"/> |
| 239 | + <geom class="fingertip_pad_collision_1"/> |
| 240 | + <geom class="fingertip_pad_collision_2"/> |
| 241 | + <geom class="fingertip_pad_collision_3"/> |
| 242 | + <geom name="right_finger_pad" class="fingertip_pad_collision_4"/> |
| 243 | + </body> |
| 244 | + </body> |
| 245 | + </body> |
| 246 | + </body> |
| 247 | + </body> |
| 248 | + </body> |
| 249 | + </body> |
| 250 | + </body> |
| 251 | + </body> |
| 252 | + </body> |
| 253 | + </worldbody> |
| 254 | + |
| 255 | + <equality> |
| 256 | + <joint joint1="finger_joint1" joint2="finger_joint2" solimp="0.95 0.99 0.001" solref="0.005 1"/> |
| 257 | + </equality> |
| 258 | + |
| 259 | + <actuator> |
| 260 | + <position class="panda" name="actuator1" joint="joint1" kp="1000" kv="20" |
| 261 | + ctrlrange="-2.8973 2.8973"/> |
| 262 | + <position class="panda" name="actuator2" joint="joint2" kp="1000" kv="20" |
| 263 | + ctrlrange="-1.7628 1.7628"/> |
| 264 | + <position class="panda" name="actuator3" joint="joint3" kp="750" kv="4" |
| 265 | + ctrlrange="-2.8973 2.8973"/> |
| 266 | + <position class="panda" name="actuator4" joint="joint4" kp="750" kv="4" |
| 267 | + ctrlrange="-3.0718 -0.0698"/> |
| 268 | + <position class="panda" name="actuator5" joint="joint5" kp="300" kv="2" |
| 269 | + forcerange="-12 12" ctrlrange="-2.8973 2.8973"/> |
| 270 | + <position class="panda" name="actuator6" joint="joint6" kp="300" kv="2" forcerange="-12 12" |
| 271 | + ctrlrange="-0.0175 3.7525"/> |
| 272 | + <position class="panda" name="actuator7" joint="joint7" kp="300" kv="2" forcerange="-12 12"/> |
| 273 | + <general class="panda" name="actuator8" joint="finger_joint1" |
| 274 | + ctrlrange="0 0.04" gainprm="350 0 0" biasprm="0 -350 -10" forcerange="-200 200"/> |
| 275 | + </actuator> |
| 276 | +</mujoco> |
0 commit comments