|
| 1 | +<mujoco model="Dual_wrist_camera"> |
| 2 | + <compiler angle="radian" meshdir="assets" autolimits="true"/> |
| 3 | + |
| 4 | + <option cone="elliptic" impratio="10"/> |
| 5 | + |
| 6 | + <asset> |
| 7 | + |
| 8 | + <material name="metal" rgba="0.58 0.58 0.58 1"/> |
| 9 | + <material name="silicone" rgba="0.1882 0.1882 0.1882 1"/> |
| 10 | + <material name="black" rgba="0.149 0.149 0.149 1"/> |
| 11 | + |
| 12 | + <mesh file="base.stl"/> |
| 13 | + <mesh file="base_coupling.stl"/> |
| 14 | + <mesh file="c-a01-85-open.stl"/> |
| 15 | + <mesh file="driver.stl"/> |
| 16 | + <mesh file="coupler.stl"/> |
| 17 | + <mesh file="spring_link.stl"/> |
| 18 | + <mesh file="follower.stl"/> |
| 19 | + <mesh file="tongue.stl"/> |
| 20 | + </asset> |
| 21 | + |
| 22 | + |
| 23 | + <default> |
| 24 | + <default class="2f85"> |
| 25 | + <mesh scale="0.001 0.001 0.001"/> |
| 26 | + <general biastype="affine"/> |
| 27 | + |
| 28 | + <joint axis="0 0 1"/> |
| 29 | + <default class="driver"> |
| 30 | + <joint range="0 0.9" armature="0.005" damping="0.1" solimplimit="0.95 0.99 0.001" solreflimit="0.005 1"/> |
| 31 | + </default> |
| 32 | + <default class="follower"> |
| 33 | + <joint range="-0.872664 0.9" armature="0.001" solimplimit="0.95 0.99 0.001" solreflimit="0.005 1"/> |
| 34 | + </default> |
| 35 | + <default class="spring_link"> |
| 36 | + <joint range="-0.29670597283 0.9" armature="0.001" stiffness="0.05" springref="2.62" damping="0.00125"/> |
| 37 | + </default> |
| 38 | + <default class="coupler"> |
| 39 | + <joint range="-1.57 0" armature="0.001" solimplimit="0.95 0.99 0.001" solreflimit="0.005 1"/> |
| 40 | + </default> |
| 41 | + |
| 42 | + <default class="visual"> |
| 43 | + <geom type="mesh" contype="0" conaffinity="0" group="2" material="black"/> |
| 44 | + </default> |
| 45 | + <default class="collision"> |
| 46 | + <geom type="mesh" group="3"/> |
| 47 | + <default class="pad_box1"> |
| 48 | + <geom mass="1e-6" type="box" pos="0.043258 0 0.12" size="0.002 0.011 0.009375" friction="0.7" |
| 49 | + solimp="0.95 0.99 0.001" solref="0.004 1" priority="1" rgba="0.55 0.55 0.55 1"/> |
| 50 | + </default> |
| 51 | + <default class="pad_box2"> |
| 52 | + <geom mass="1e-6" type="box" pos="0.043258 0 0.13875" size="0.002 0.011 0.009375" friction="0.6" |
| 53 | + solimp="0.95 0.99 0.001" solref="0.004 1" priority="1" rgba="0.45 0.45 0.45 1"/> |
| 54 | + </default> |
| 55 | + </default> |
| 56 | + </default> |
| 57 | + </default> |
| 58 | + |
| 59 | + |
| 60 | + <worldbody> |
| 61 | + <body name="base" childclass="2f85"> |
| 62 | + <inertial mass="0.777441" pos="0 -2.70394e-05 0.0354675" quat="1 -0.00152849 0 0" |
| 63 | + diaginertia="0.000260285 0.000225381 0.000152708"/> |
| 64 | + <geom class="visual" pos="0 0 0.0108" quat="0 0 0 1" mesh="base"/> |
| 65 | + <geom class="visual" pos="0 0 0.004" quat="1 -1 0 0" mesh="base_coupling"/> |
| 66 | + <geom class="visual" pos="0 0 0.0108" quat="1 0 0 0" material="metal" mesh="c-a01-85-open"/> |
| 67 | + <geom class="collision" mesh="base"/> |
| 68 | + <!-- Left-hand side 4-bar linkage --> |
| 69 | + <body name="left_driver" pos="-0.0306011 0.00475 0.0657045" quat="1 -1 0 0"> |
| 70 | + <inertial mass="0.00899563" pos="0 0.0177547 0.00107314" quat="0.681301 0.732003 0 0" |
| 71 | + diaginertia="1.72352e-06 1.60906e-06 3.22006e-07"/> |
| 72 | + <joint name="left_driver_joint" class="driver"/> |
| 73 | + <geom class="visual" pos="0.0306011 0.0549045 -0.0047" quat="1 1 0 0" material="metal" mesh="driver"/> |
| 74 | + <geom class="collision" pos="0.0306011 0.0549045 -0.0047" quat="1 1 0 0" mesh="driver"/> |
| 75 | + <body name="left_coupler" pos="-0.0314249 0.00453223 -0.0102" quat="0 0 0 1"> |
| 76 | + <inertial mass="0.0140974" pos="0 0.00301209 0.0232175" quat="0.705636 -0.0455904 0.0455904 0.705636" |
| 77 | + diaginertia="4.16206e-06 3.52216e-06 8.88131e-07"/> |
| 78 | + <geom class="visual" pos="-0.062026 -0.0503723 0.0055" quat="1 -1 0 0" mesh="coupler"/> |
| 79 | + <geom class="collision" pos="-0.062026 -0.0503723 0.0055" quat="1 -1 0 0" mesh="coupler"/> |
| 80 | + </body> |
| 81 | + </body> |
| 82 | + <body name="left_spring_link" pos="-0.0127 -0.012 0.07222" quat="1 -1 0 0"> |
| 83 | + <inertial mass="0.0221642" pos="-8.65005e-09 0.0181624 0.0212658" quat="0.663403 -0.244737 0.244737 0.663403" |
| 84 | + diaginertia="8.96853e-06 6.71733e-06 2.63931e-06"/> |
| 85 | + <joint name="left_spring_link_joint" class="spring_link"/> |
| 86 | + <geom class="visual" pos="0.0127 0.06142 0.01205" quat="1 1 0 0" type="mesh" mesh="spring_link"/> |
| 87 | + <geom class="collision" pos="0.0127 0.06142 0.01205" quat="1 1 0 0" type="mesh" mesh="spring_link"/> |
| 88 | + <body name="left_follower" pos="-0.0382079 -0.0425003 0.00295" quat="0 -1 -1.90231e-05 0"> |
| 89 | + <inertial mass="0.0125222" pos="0 -0.011046 0.0124786" quat="1 0.1664 0 0" |
| 90 | + diaginertia="2.67415e-06 2.4559e-06 6.02031e-07"/> |
| 91 | + <joint name="left_follower" class="follower"/> |
| 92 | + <geom class="visual" pos="0.0509079 -0.10392 -0.0091" quat="1 -1 0 0" type="mesh" mesh="follower"/> |
| 93 | + <geom class="visual" pos="0.0509079 -0.10392 -0.0091" quat="1 -1 0 0" type="mesh" material="metal" mesh="tongue"/> |
| 94 | + <geom class="collision" pos="0.0509079 -0.10392 -0.0091" quat="1 -1 0 0" type="mesh" mesh="follower"/> |
| 95 | + <geom class="collision" pos="0.0509079 -0.10392 -0.0091" quat="1 -1 0 0" type="mesh" mesh="tongue"/> |
| 96 | + <body name="left_pad" pos="-0.0377897 -0.103916 -0.0091" quat="1 -1 0 0" > |
| 97 | + <geom class="pad_box1" name="left_pad1"/> |
| 98 | + <geom class="pad_box2" name="left_pad2"/> |
| 99 | + </body> |
| 100 | + </body> |
| 101 | + </body> |
| 102 | + <!-- Right-hand side 4-bar linkage --> |
| 103 | + <body name="right_driver" pos="0.0306011 -0.00475 0.0657045" quat="0 0 -1 1"> |
| 104 | + <inertial mass="0.00899563" pos="2.96931e-12 0.0177547 0.00107314" quat="0.681301 0.732003 0 0" |
| 105 | + diaginertia="1.72352e-06 1.60906e-06 3.22006e-07"/> |
| 106 | + <joint name="right_driver_joint" class="driver"/> |
| 107 | + <geom class="visual" pos="0.0306011 0.0549045 -0.0047" quat="1 1 0 0" material="metal" mesh="driver"/> |
| 108 | + <geom class="collision" pos="0.0306011 0.0549045 -0.0047" quat="1 1 0 0" mesh="driver"/> |
| 109 | + <body name="right_coupler" pos="-0.0314249 0.00453223 -0.0102" quat="0 0 0 1"> |
| 110 | + <inertial mass="0.0140974" pos="0 0.00301209 0.0232175" quat="0.705636 -0.0455904 0.0455904 0.705636" |
| 111 | + diaginertia="4.16206e-06 3.52216e-06 8.88131e-07"/> |
| 112 | + <geom class="visual" pos="-0.062026 -0.0503723 0.0055" quat="1 -1 0 0" mesh="coupler"/> |
| 113 | + <geom class="collision" pos="-0.062026 -0.0503723 0.0055" quat="1 -1 0 0" mesh="coupler"/> |
| 114 | + </body> |
| 115 | + </body> |
| 116 | + <body name="right_spring_link" pos="0.0127 0.012 0.07222" quat="0 0 -1 1"> |
| 117 | + <inertial mass="0.0221642" pos="-8.65005e-09 0.0181624 0.0212658" quat="0.663403 -0.244737 0.244737 0.663403" |
| 118 | + diaginertia="8.96853e-06 6.71733e-06 2.63931e-06"/> |
| 119 | + <joint name="right_spring_link_joint" class="spring_link"/> |
| 120 | + <geom class="visual" pos="0.0127 0.06142 0.01205" quat="1 1 0 0" mesh="spring_link"/> |
| 121 | + <geom class="collision" pos="0.0127 0.06142 0.01205" quat="1 1 0 0" mesh="spring_link"/> |
| 122 | + <body name="right_follower" pos="-0.0382079 -0.0425003 0.00295" quat="0 -1 0 0"> |
| 123 | + <inertial mass="0.0125222" pos="0 -0.011046 0.0124786" quat="1 0.1664 0 0" |
| 124 | + diaginertia="2.67415e-06 2.4559e-06 6.02031e-07"/> |
| 125 | + <joint name="right_follower_joint" class="follower"/> |
| 126 | + <geom class="visual" pos="0.0509079 -0.10392 -0.0091" quat="1 -1 0 0" material="metal" mesh="tongue"/> |
| 127 | + <geom class="visual" pos="0.0509079 -0.10392 -0.0091" quat="1 -1 0 0" mesh="follower"/> |
| 128 | + <geom class="collision" pos="0.0509079 -0.10392 -0.0091" quat="1 -1 0 0" mesh="tongue"/> |
| 129 | + <geom class="collision" pos="0.0509079 -0.10392 -0.0091" quat="1 -1 0 0" mesh="follower"/> |
| 130 | + <body name="right_pad" pos="-0.0377897 -0.103916 -0.0091" quat="1 -1 0 0" > |
| 131 | + <geom class="pad_box1" name="right_pad1"/> |
| 132 | + <geom class="pad_box2" name="right_pad2"/> |
| 133 | + </body> |
| 134 | + </body> |
| 135 | + </body> |
| 136 | + </body> |
| 137 | + </worldbody> |
| 138 | + |
| 139 | + <contact> |
| 140 | + <exclude body1="base" body2="left_driver"/> |
| 141 | + <exclude body1="base" body2="right_driver"/> |
| 142 | + <exclude body1="base" body2="left_spring_link"/> |
| 143 | + <exclude body1="base" body2="right_spring_link"/> |
| 144 | + <exclude body1="right_coupler" body2="right_follower"/> |
| 145 | + <exclude body1="left_coupler" body2="left_follower"/> |
| 146 | + </contact> |
| 147 | + |
| 148 | + <!-- |
| 149 | + This adds stability to the model by having a tendon that distributes the forces between both |
| 150 | + joints, such that the equality constraint doesn't have to do that much work in order to equalize |
| 151 | + both joints. Since both joints share the same sign, we split the force between both equally by |
| 152 | + setting coef=0.485 |
| 153 | + --> |
| 154 | + <tendon> |
| 155 | + <fixed name="split"> |
| 156 | + <joint joint="right_driver_joint" coef="0.485"/> |
| 157 | + <joint joint="left_driver_joint" coef="0.485"/> |
| 158 | + </fixed> |
| 159 | + </tendon> |
| 160 | + |
| 161 | + <equality> |
| 162 | + <connect anchor="-0.0179014 -0.00651468 0.0044" body1="right_follower" body2="right_coupler" solimp="0.95 0.99 0.001" solref="0.005 1"/> |
| 163 | + <connect anchor="-0.0179014 -0.00651468 0.0044" body1="left_follower" body2="left_coupler" solimp="0.95 0.99 0.001" solref="0.005 1"/> |
| 164 | + <joint joint1="right_driver_joint" joint2="left_driver_joint" polycoef="0 1 0 0 0" solimp="0.95 0.99 0.001" |
| 165 | + solref="0.005 1"/> |
| 166 | + </equality> |
| 167 | + |
| 168 | + <!-- |
| 169 | + The general actuator below is a customized position actuator (with some damping) where |
| 170 | + gainprm[0] != kp (see http://mujoco.org/book/modeling.html#position). |
| 171 | + The reason why gainprm[0] != kp is because the control input range has to be re-scaled to |
| 172 | + [0, 255]. The joint range is currently set at [0, 0.8], the control range is [0, 255] and |
| 173 | + kp = 100. Tau = Kp * scale * control_input - Kp * error, max(Kp * scale * control_input) = 0.8, |
| 174 | + hence scale = 0.8 * 100 / 255 |
| 175 | + --> |
| 176 | + <actuator> |
| 177 | + <general class="2f85" name="fingers_actuator" tendon="split" forcerange="-5 5" ctrlrange="0 255" |
| 178 | + gainprm="0.3137255 0 0" biasprm="0 -100 -10"/> |
| 179 | + </actuator> |
| 180 | + |
| 181 | +</mujoco> |
0 commit comments