| <mujoco model="wx250s"> |
| <compiler angle="radian" meshdir="assets" texturedir="assets" autolimits="true"/> |
|
|
| <option integrator="implicitfast" cone="elliptic" impratio="10"/> |
|
|
| <asset> |
| <texture type="2d" file="interbotix_black.png"/> |
| <material name="black" texture="interbotix_black"/> |
|
|
| <mesh file="wx250s_1_base.stl" class="wx250s"/> |
| <mesh file="wx250s_2_shoulder.stl" class="wx250s"/> |
| <mesh file="wx250s_3_upper_arm.stl" class="wx250s"/> |
| <mesh file="wx250s_4_upper_forearm.stl" class="wx250s"/> |
| <mesh file="wx250s_5_lower_forearm.stl" class="wx250s"/> |
| <mesh file="wx250s_6_wrist.stl" class="wx250s"/> |
| <mesh file="wx250s_7_gripper.stl" class="wx250s"/> |
| <mesh file="wx250s_8_gripper_prop.stl" class="wx250s"/> |
| <mesh file="wx250s_9_gripper_bar.stl" class="wx250s"/> |
| <mesh file="wx250s_10_gripper_finger.stl" class="wx250s"/> |
| </asset> |
|
|
| <default> |
| <default class="wx250s"> |
| <mesh scale="0.001 0.001 0.001"/> |
| <joint axis="0 1 0" frictionloss="0.1" armature="0.1"/> |
| <position kp="50" inheritrange="1" dampratio="0.95" forcerange="-35 35"/> |
| <default class="visual"> |
| <geom type="mesh" contype="0" conaffinity="0" density="0" group="2" material="black"/> |
| </default> |
| <default class="collision"> |
| <geom group="3" type="mesh"/> |
| <default class="sphere_collision"> |
| <geom type="sphere" size="0.0006" rgba="1 0 0 1"/> |
| </default> |
| </default> |
| </default> |
| </default> |
|
|
| <worldbody> |
| <light mode="targetbodycom" target="wx250s/gripper_link" pos="1 0 1"/> |
| <body name="wx250s/base_link" childclass="wx250s"> |
| <inertial pos="-0.0380446 0.000613892 0.0193354" quat="0.509292 0.490887 -0.496359 0.503269" mass="0.538736" |
| diaginertia="0.00252518 0.00211519 0.000690737"/> |
| <geom quat="1 0 0 1" mesh="wx250s_1_base" class="visual"/> |
| <geom quat="1 0 0 1" mesh="wx250s_1_base" class="collision"/> |
| <body name="wx250s/shoulder_link" pos="0 0 0.072"> |
| <inertial pos="2.23482e-05 4.14609e-05 0.0066287" quat="0.0130352 0.706387 0.012996 0.707586" mass="0.480879" |
| diaginertia="0.000588946 0.000555655 0.000378999"/> |
| <joint name="waist" axis="0 0 1" range="-3.14158 3.14158"/> |
| <geom pos="0 0 -0.003" quat="1 0 0 1" mesh="wx250s_2_shoulder" class="visual"/> |
| <geom pos="0 0 -0.003" quat="1 0 0 1" mesh="wx250s_2_shoulder" class="collision"/> |
| <body name="wx250s/upper_arm_link" pos="0 0 0.03865"> |
| <inertial pos="0.0171605 2.725e-07 0.191323" quat="0.705539 0.0470667 -0.0470667 0.705539" mass="0.430811" |
| diaginertia="0.00364425 0.003463 0.000399348"/> |
| <joint name="shoulder" range="-1.88496 1.98968"/> |
| <geom quat="1 0 0 1" mesh="wx250s_3_upper_arm" class="visual"/> |
| <geom quat="1 0 0 1" mesh="wx250s_3_upper_arm" class="collision"/> |
| <body name="wx250s/upper_forearm_link" pos="0.04975 0 0.25"> |
| <inertial pos="0.107963 0.000115876 0" quat="0.000980829 0.707106 -0.000980829 0.707106" mass="0.234589" |
| diaginertia="0.000888 0.000887807 3.97035e-05"/> |
| <joint name="elbow" range="-2.14675 1.6057"/> |
| <geom mesh="wx250s_4_upper_forearm" class="visual"/> |
| <geom mesh="wx250s_4_upper_forearm" class="collision"/> |
| <body name="wx250s/lower_forearm_link" pos="0.175 0 0"> |
| <inertial pos="0.0374395 0.00522252 0" quat="-0.0732511 0.703302 0.0732511 0.703302" mass="0.220991" |
| diaginertia="0.0001834 0.000172527 5.88633e-05"/> |
| <joint name="forearm_roll" axis="1 0 0" range="-3.14158 3.14158"/> |
| <geom quat="0 1 0 0" mesh="wx250s_5_lower_forearm" class="visual"/> |
| <geom quat="0 1 0 0" mesh="wx250s_5_lower_forearm" class="collision"/> |
| <body name="wx250s/wrist_link" pos="0.075 0 0"> |
| <inertial pos="0.04236 -1.0663e-05 0.010577" quat="0.608721 0.363497 -0.359175 0.606895" mass="0.084957" |
| diaginertia="3.29057e-05 3.082e-05 2.68343e-05"/> |
| <joint name="wrist_angle" axis="0 1 0" range="-1.74533 2.14675"/> |
| <geom quat="1 0 0 1" mesh="wx250s_6_wrist" class="visual"/> |
| <geom quat="1 0 0 1" mesh="wx250s_6_wrist" class="collision"/> |
| <body name="wx250s/gripper_link" pos="0.065 0 0"> |
| <inertial pos="0.0325296 4.2061e-07 0.0090959" quat="0.546081 0.419626 0.62801 0.362371" |
| mass="0.110084" diaginertia="0.00307592 0.00307326 0.0030332"/> |
| <joint name="wrist_rotate" axis="1 0 0" range="-3.14158 3.14158"/> |
| <geom pos="-0.02 0 0" quat="1 0 0 1" mesh="wx250s_7_gripper" class="visual"/> |
| <geom pos="-0.02 0 0" quat="1 0 0 1" mesh="wx250s_7_gripper" class="collision"/> |
| <geom pos="-0.02 0 0" quat="1 0 0 1" mesh="wx250s_9_gripper_bar" class="visual"/> |
| <geom pos="-0.02 0 0" quat="1 0 0 1" mesh="wx250s_9_gripper_bar" class="collision"/> |
| <body name="wx250s/left_finger_link" pos="0.066 0 0"> |
| <inertial pos="0.013816 0 0" quat="0.705384 0.705384 -0.0493271 -0.0493271" mass="0.016246" |
| diaginertia="4.79509e-06 3.7467e-06 1.48651e-06"/> |
| <joint name="left_finger" axis="0 1 0" type="slide" range="0.015 0.037"/> |
| <geom pos="0 0.005 0" quat="0 0 0 -1" mesh="wx250s_10_gripper_finger" class="visual"/> |
| <geom pos="0 0.005 0" quat="0 0 0 -1" mesh="wx250s_10_gripper_finger" class="collision"/> |
| <geom name="left/left_g0" pos="0.042 -0.009 0.012" class="sphere_collision"/> |
| <geom name="left/left_g1" pos="0.042 -0.009 -0.012" class="sphere_collision"/> |
| </body> |
| <body name="wx250s/right_finger_link" pos="0.066 0 0"> |
| <inertial pos="0.013816 0 0" quat="0.705384 0.705384 0.0493271 0.0493271" mass="0.016246" |
| diaginertia="4.79509e-06 3.7467e-06 1.48651e-06"/> |
| <joint name="right_finger" axis="0 1 0" type="slide" range="-0.037 -0.015"/> |
| <geom pos="0 -0.005 0" quat="0 0 1 0" mesh="wx250s_10_gripper_finger" class="visual"/> |
| <geom pos="0 -0.005 0" quat="0 0 1 0" mesh="wx250s_10_gripper_finger" class="collision"/> |
| <geom name="right/right_g0" pos="0.042 0.009 0.012" class="sphere_collision"/> |
| <geom name="right/right_g1" pos="0.042 0.009 -0.012" class="sphere_collision"/> |
| </body> |
| </body> |
| </body> |
| </body> |
| </body> |
| </body> |
| </body> |
| </body> |
| </worldbody> |
|
|
| <contact> |
| <exclude body1="wx250s/base_link" body2="wx250s/shoulder_link"/> |
| </contact> |
|
|
| <equality> |
| <joint joint1="left_finger" joint2="right_finger" polycoef="0 -1 0 0 0"/> |
| </equality> |
|
|
| <actuator> |
| <position class="wx250s" name="waist" joint="waist"/> |
| <position class="wx250s" name="shoulder" joint="shoulder"/> |
| <position class="wx250s" name="elbow" joint="elbow"/> |
| <position class="wx250s" name="forearm_roll" joint="forearm_roll"/> |
| <position class="wx250s" name="wrist_angle" joint="wrist_angle"/> |
| <position class="wx250s" name="wrist_rotate" joint="wrist_rotate"/> |
| <position class="wx250s" name="gripper" joint="left_finger" kp="200"/> |
| </actuator> |
|
|
| |
| |
| |
| </mujoco> |
|
|