More merge conflicts. Taking main changes then will integrate mine.
125 lines
5.8 KiB
XML
125 lines
5.8 KiB
XML
<mujoco model="xarm7 hand">
|
|
<compiler angle="radian" autolimits="true" meshdir="assets"/>
|
|
|
|
<option integrator="implicitfast"/>
|
|
|
|
<asset>
|
|
<material name="white" rgba="1 1 1 1"/>
|
|
<material name="black" rgba="0.149 0.149 0.149 1"/>
|
|
|
|
<mesh file="base_link.stl"/>
|
|
<mesh file="left_outer_knuckle.stl"/>
|
|
<mesh file="left_finger.stl"/>
|
|
<mesh file="left_inner_knuckle.stl"/>
|
|
<mesh file="right_outer_knuckle.stl"/>
|
|
<mesh file="right_finger.stl"/>
|
|
<mesh file="right_inner_knuckle.stl"/>
|
|
</asset>
|
|
|
|
<default>
|
|
<default class="xarm7_hand">
|
|
<geom type="mesh" material="black"/>
|
|
<joint range="0 0.85" axis="1 0 0" armature="0.1" frictionloss="1"/>
|
|
<site size="0.001" rgba="1 0 0 1" group="4"/>
|
|
<general biastype="affine" forcerange="-50 50" ctrlrange="0 255" gainprm="0.333" biasprm="0 -100 -10"/>
|
|
<default class="spring_link">
|
|
<joint stiffness="0.05" springref="2.62" damping="0.00125"/>
|
|
</default>
|
|
<default class="driver">
|
|
<joint armature="0.005" damping="0.1" solreflimit="0.005 1"/>
|
|
</default>
|
|
<default class="follower">
|
|
<joint solreflimit="0.005 1"/>
|
|
</default>
|
|
<default class="visual">
|
|
<geom type="mesh" contype="0" conaffinity="0" group="2"/>
|
|
</default>
|
|
<default class="collision">
|
|
<geom type="mesh" group="3"/>
|
|
<default class="pad_box1">
|
|
<geom type="box" friction="0.7" solimp="0.95 0.99 0.001" solref="0.004 1" mass="0" priority="1" size="0.015 0.002 0.0095" rgba="0.0 0.1 0.7 1"/>
|
|
</default>
|
|
<default class="pad_box2">
|
|
<geom type="box" friction="0.6" solimp="0.95 0.99 0.001" solref="0.004 1" mass="0" priority="1" size="0.015 0.002 0.0095" rgba="0.0 0.5 0.5 1"/>
|
|
</default>
|
|
</default>
|
|
</default>
|
|
</default>
|
|
|
|
<worldbody>
|
|
<body name="xarm_gripper_base_link" childclass="xarm7_hand">
|
|
<inertial pos="-0.00065489 -0.0018497 0.048028" quat="0.997403 -0.0717512 -0.0061836 0.000477479" mass="0.54156"
|
|
diaginertia="0.000471093 0.000332307 0.000254799"/>
|
|
<geom mesh="base_link" material="white"/>
|
|
<body name="left_outer_knuckle" pos="0 0.035 0.059098">
|
|
<inertial pos="0 0.021559 0.015181" quat="0.47789 0.87842 0 0" mass="0.033618"
|
|
diaginertia="1.9111e-05 1.79089e-05 1.90167e-06"/>
|
|
<joint name="left_driver_joint" class="driver"/>
|
|
<geom material="black" mesh="left_outer_knuckle"/>
|
|
<body name="left_finger" pos="0 0.035465 0.042039">
|
|
<inertial pos="0 -0.016413 0.029258" quat="0.697634 0.115353 -0.115353 0.697634" mass="0.048304"
|
|
diaginertia="1.88037e-05 1.7493e-05 3.56792e-06"/>
|
|
<joint name="left_finger_joint" axis="-1 0 0" class="follower"/>
|
|
<geom class="visual" material="black" mesh="left_finger"/>
|
|
<geom class="pad_box1" name="left_finger_pad_1" pos="0 -0.024003 0.032"/>
|
|
<geom class="pad_box2" name="left_finger_pad_2" pos="0 -0.024003 0.050"/>
|
|
</body>
|
|
</body>
|
|
<body name="left_inner_knuckle" pos="0 0.02 0.074098">
|
|
<inertial pos="1.86601e-06 0.0220468 0.0261335" quat="0.664139 -0.242732 0.242713 0.664146" mass="0.0230126"
|
|
diaginertia="8.34216e-06 6.0949e-06 2.75601e-06"/>
|
|
<joint name="left_inner_knuckle_joint" class="spring_link"/>
|
|
<geom material="black" mesh="left_inner_knuckle"/>
|
|
</body>
|
|
<body name="right_outer_knuckle" pos="0 -0.035 0.059098">
|
|
<inertial pos="0 -0.021559 0.015181" quat="0.87842 0.47789 0 0" mass="0.033618"
|
|
diaginertia="1.9111e-05 1.79089e-05 1.90167e-06"/>
|
|
<joint name="right_driver_joint" axis="-1 0 0" class="driver"/>
|
|
<geom material="black" mesh="right_outer_knuckle"/>
|
|
<body name="right_finger" pos="0 -0.035465 0.042039">
|
|
<inertial pos="0 0.016413 0.029258" quat="0.697634 -0.115356 0.115356 0.697634" mass="0.048304"
|
|
diaginertia="1.88038e-05 1.7493e-05 3.56779e-06"/>
|
|
<joint name="right_finger_joint" class="follower"/>
|
|
<geom class="visual" material="black" mesh="right_finger"/>
|
|
<geom class="pad_box1" name="right_finger_pad_1" pos="0 0.024003 0.032"/>
|
|
<geom class="pad_box2" name="right_finger_pad_2" pos="0 0.024003 0.050"/>
|
|
</body>
|
|
</body>
|
|
<body name="right_inner_knuckle" pos="0 -0.02 0.074098">
|
|
<inertial pos="1.866e-06 -0.022047 0.026133" quat="0.66415 0.242702 -0.242721 0.664144" mass="0.023013"
|
|
diaginertia="8.34209e-06 6.0949e-06 2.75601e-06"/>
|
|
<joint name="right_inner_knuckle_joint" axis="-1 0 0" class="spring_link"/>
|
|
<geom material="black" mesh="right_inner_knuckle"/>
|
|
</body>
|
|
</body>
|
|
</worldbody>
|
|
|
|
<contact>
|
|
<exclude body1="right_inner_knuckle" body2="right_outer_knuckle"/>
|
|
<exclude body1="right_inner_knuckle" body2="right_finger"/>
|
|
<exclude body1="left_inner_knuckle" body2="left_outer_knuckle"/>
|
|
<exclude body1="left_inner_knuckle" body2="left_finger"/>
|
|
<exclude body1="left_inner_knuckle" body2="xarm_gripper_base_link"/>
|
|
<exclude body1="right_inner_knuckle" body2="xarm_gripper_base_link"/>
|
|
<exclude body1="left_outer_knuckle" body2="xarm_gripper_base_link"/>
|
|
<exclude body1="right_outer_knuckle" body2="xarm_gripper_base_link"/>
|
|
</contact>
|
|
|
|
<tendon>
|
|
<fixed name="split">
|
|
<joint joint="right_driver_joint" coef="0.5"/>
|
|
<joint joint="left_driver_joint" coef="0.5"/>
|
|
</fixed>
|
|
</tendon>
|
|
|
|
<equality>
|
|
<connect anchor="0 0.015 0.015" body1="right_finger" body2="right_inner_knuckle" solref="0.005 1"/>
|
|
<connect anchor="0 -0.015 0.015" body1="left_finger" body2="left_inner_knuckle" solref="0.005 1"/>
|
|
<joint joint1="left_driver_joint" joint2="right_driver_joint" polycoef="0 1 0 0 0" solref="0.005 1"/>
|
|
</equality>
|
|
|
|
<actuator>
|
|
<general class="xarm7_hand" name="fingers_actuator" tendon="split"/>
|
|
</actuator>
|
|
</mujoco>
|