Skip to content

Commit

Permalink
manicure draco3 MuJoCo xml
Browse files Browse the repository at this point in the history
  • Loading branch information
shbang91 committed Aug 19, 2024
1 parent b9a2783 commit 5deddad
Showing 1 changed file with 30 additions and 58 deletions.
88 changes: 30 additions & 58 deletions robot_model/draco/draco_latest_collisions_with_gripper.xml
Original file line number Diff line number Diff line change
Expand Up @@ -105,10 +105,10 @@
<!--<geom size="0.01" pos="-3.50188e-07 -0.05535 -0.073" quat="0.00056309 -0.707104 0.707109 0.000563086" >-->
<body name="l_sake_gripper_link" pos="0 0 0" quat="1 0 0 0">
<inertial pos="5.4498e-05 0.000382544 -0.0372594" mass="0.145" diaginertia="0.001 0.0004628 0.001"/>
<geom name="l_gripper_mount_viz" type="mesh" margin="0.001" mesh="mesh_l_gripper_mount" contype="0" conaffinity="0" group="1" pos="0 0 0" quat="1 0 0 0" material="metal"/>
<geom name="l_gripper_mount_viz" type="mesh" margin="0.001" mesh="mesh_l_gripper_mount" pos="0 0 0" quat="1 0 0 0" material="metal"/>
<body name="left_ezgripper_palm_link" pos="0 0 -0.053" quat="0 1 0 0">
<geom name="l_gripper_geom_base_viz" type="mesh" mesh="mesh_palm_dual" quat="0 0.7071068 0 0.7071068" group="1" material="black"/>
<geom name="l_gripper_geom_base_col" type="box" pos="0 0 0.042" size="0.015 0.04 0.038" group="0"/>
<geom name="l_gripper_geom_base_viz" type="mesh" mesh="mesh_palm_dual" quat="0 0.7071068 0 0.7071068" material="metal"/>
<geom name="l_gripper_geom_base_col" type="box" pos="0 0 0.042" size="0.015 0.04 0.038" group="3"/>
<inertial mass="0.3" diaginertia="0.01 0.01 0.01" pos="0 0 0"/>
<site name="l_gripper_site_left_finger1" pos="0 0.03 0" size="0.01" material="tendon_site"/>
<site name="l_gripper_site_left_finger2" pos="0 0.03 0.062569" size="0.01" material="tendon_site"/>
Expand All @@ -117,21 +117,17 @@

<body name="left_ezgripper_finger_L1_1" pos="0 0.03 0.072569" quat="-0.5 0.5 0.5 0.5">
<joint name="left_ezgripper_knuckle_palm_L1_1" axis="0 1 0" limited="true" range="-1.94 1.94" solimplimit="0.95 0.99 0.001" solreflimit="0.005 1"/>
<geom name="l_gripper_geom_left_finger1" type="mesh" mesh="mesh_finger1" group="1" material="white"/>
<!-- <geom name="geom_left_finger1_col" type="mesh" mesh="mesh_finger1" group="0"/> -->
<geom name="l_gripper_geom_left_finger1_pad" type="box" pos="0.027 0 -0.012" size="0.008 0.014 0.001" group="1" material="black"/>
<!-- <geom name="geom_left_finger1_pad_col" type="box" pos="0.027 0 -0.003" size="0.008 0.014 0.01" group="0" solimp="0 0.95 0.001 0.5 3"/> -->
<geom name="l_gripper_geom_left_finger1_pad_col" type="box" pos="0.027 0 -0.012" size="0.008 0.014 0.001" group="0" />
<geom name="l_gripper_geom_left_finger1" type="mesh" mesh="mesh_finger1" material="white"/>
<geom name="l_gripper_geom_left_finger1_pad" type="box" pos="0.027 0 -0.012" size="0.008 0.014 0.001" material="metal"/>
<geom name="l_gripper_geom_left_finger1_pad_col" type="box" pos="0.027 0 -0.012" size="0.008 0.014 0.001" group="3" />
<inertial mass=".025" diaginertia="0.01 0.01 0.01" pos="0 0 0"/>
<site name="l_gripper_site_left_finger3" pos="0.042 0 0.01" size="0.01" material="tendon_site"/>

<body name="left_ezgripper_finger_L2_1" pos="0.052 0 0">
<joint name="left_ezgripper_knucle_L1_L2_1" axis="0 1 0" limited="true" range="0 1.94" solimplimit="0.95 0.99 0.001" solreflimit="0.005 1" stiffness="0.4" springref="0.0" frictionloss="0.1"/>
<geom name="l_gripper_geom_left_finger2" type="mesh" mesh="mesh_finger2" group="1" material="white"/>
<!-- <geom name="geom_left_finger2_col" type="mesh" mesh="mesh_finger2" group="0"/> -->
<geom name="l_gripper_geom_left_finger2_pad" type="box" pos="0.040 0 0.002" quat="0.9838437 0 -0.1790296 0" size="0.02 0.014 0.001" group="1" material="black"/>
<!-- <geom name="geom_left_finger2_pad_col" type="box" pos="0.040 0 0.011" quat="0.9838437 0 -0.1790296 0" size="0.02 0.014 0.01" group="0" solimp="0 0.95 0.001 0.5 3"/> -->
<geom name="l_gripper_geom_left_finger2_pad_col" type="box" pos="0.040 0 0.002" quat="0.9838437 0 -0.1790296 0" size="0.02 0.014 0.001" group="0"/>
<geom name="l_gripper_geom_left_finger2" type="mesh" mesh="mesh_finger2" material="white"/>
<geom name="l_gripper_geom_left_finger2_pad" type="box" pos="0.040 0 0.002" quat="0.9838437 0 -0.1790296 0" size="0.02 0.014 0.001" material="metal"/>
<geom name="l_gripper_geom_left_finger2_pad_col" type="box" pos="0.040 0 0.002" quat="0.9838437 0 -0.1790296 0" size="0.02 0.014 0.001" group="3"/>
<inertial mass=".025" diaginertia="0.01 0.01 0.01" pos="0 0 0"/>
<site name="l_gripper_site_left_finger4" pos="0.05 0 0.01" size="0.01" material="tendon_site"/>

Expand All @@ -140,27 +136,21 @@

<body name="left_ezgripper_finger_L1_2" pos="0 -0.03 0.072569" quat="0.5 0.5 -0.5 0.5">
<joint name="left_ezgripper_knuckle_palm_L1_2" axis="0 1 0" limited="true" range="-1.94 1.94" solimplimit="0.95 0.99 0.001" solreflimit="0.005 1"/>
<geom name="l_gripper_geom_right_finger1" type="mesh" mesh="mesh_finger1" group="1" material="white"/>
<!-- <geom name="geom_right_finger1_col" type="mesh" mesh="mesh_finger1" group="0"/> -->
<geom name="l_gripper_geom_right_finger1_pad" type="box" pos="0.027 0 -0.012" size="0.008 0.014 0.001" group="1" material="black"/>
<!-- <geom name="geom_right_finger1_pad_col" type="box" pos="0.027 0 -0.003" size="0.008 0.014 0.01" group="0" solimp="0 0.95 0.001 0.5 3"/> -->
<geom name="l_gripper_geom_right_finger1_pad_col" type="box" pos="0.027 0 -0.012" size="0.008 0.014 0.001" group="0"/>
<geom name="l_gripper_geom_right_finger1" type="mesh" mesh="mesh_finger1" material="white"/>
<geom name="l_gripper_geom_right_finger1_pad" type="box" pos="0.027 0 -0.012" size="0.008 0.014 0.001" material="metal"/>
<geom name="l_gripper_geom_right_finger1_pad_col" type="box" pos="0.027 0 -0.012" size="0.008 0.014 0.001" group="3"/>
<inertial mass=".025" diaginertia="0.01 0.01 0.01" pos="0 0 0"/>
<site name="l_gripper_site_right_finger3" pos="0.042 0 0.01" size="0.01" material="tendon_site"/>

<body name="left_ezgripper_finger_L2_2" pos="0.052 0 0">
<joint name="left_ezgripper_knuckle_L1_L2_2" axis="0 1 0" limited="true" range="0 1.94" solimplimit="0.95 0.99 0.001" solreflimit="0.005 1" stiffness="0.4" springref="0.0" frictionloss="0.1"/>
<geom name="l_gripper_geom_right_finger2" type="mesh" mesh="mesh_finger2" group="1" material="white"/>
<!-- <geom name="geom_right_finger2_col" type="mesh" mesh="mesh_finger2" group="0"/> -->
<geom name="l_gripper_geom_right_finger2_pad" type="box" pos="0.040 0 0.002" quat="0.9838437 0 -0.1790296 0" size="0.02 0.014 0.001" group="1" material="black"/>
<!-- <geom name="geom_right_finger2_pad_col" type="box" pos="0.040 0 0.011" quat="0.9838437 0 -0.1790296 0" size="0.02 0.014 0.01" group="0" solimp="0 0.95 0.001 0.5 3"/> -->
<geom name="l_gripper_geom_right_finger2_pad_col" type="box" pos="0.040 0 0.002" quat="0.9838437 0 -0.1790296 0" size="0.02 0.014 0.001" group="0"/>
<geom name="l_gripper_geom_right_finger2" type="mesh" mesh="mesh_finger2" material="white"/>
<geom name="l_gripper_geom_right_finger2_pad" type="box" pos="0.040 0 0.002" quat="0.9838437 0 -0.1790296 0" size="0.02 0.014 0.001" material="metal"/>
<geom name="l_gripper_geom_right_finger2_pad_col" type="box" pos="0.040 0 0.002" quat="0.9838437 0 -0.1790296 0" size="0.02 0.014 0.001" group="3"/>
<inertial mass=".025" diaginertia="0.01 0.01 0.01" pos="0 0 0"/>
<site name="l_gripper_site_right_finger4" pos="0.05 0 0.01" size="0.01" material="tendon_site"/>

</body>
</body>

<body name="left_eef" pos="0 0 0.13" quat="1 0 0 0">
<site name="left_grip_site" pos="0 0 0" size="0.01 0.01 0.01" rgba="1 0 0 0.5" type="sphere" group="1"/>
<!--<site name="ee_x" pos="0.1 0 0" size="0.005 .1" quat="0.707105 0 0.707108 0 " rgba="1 0 0 0" type="cylinder" group="1"/>-->
Expand All @@ -169,10 +159,8 @@
<!-- This site was added for visualization. -->
<!-- <site name="grip_site_cylinder" pos="0 0 0" size="0.005 10" rgba="0 1 0 0.3" type="cylinder" group="1"/> -->
</body>

</body>
</body>

</body>
</body>
</body>
Expand Down Expand Up @@ -211,11 +199,10 @@
<!--<geom size="0.01" pos="-3.50188e-07 0.05535 -0.073" quat="0.00056309 0.707104 0.707109 -0.000563086" >-->
<body name="r_sake_gripper_link" pos="0 0 0" quat="1 0 0 0">
<inertial pos="5.4498e-05 0.000382544 -0.0372594" mass="0.145" diaginertia="0.001 0.0004628 0.001"/>
<geom name="r_gripper_mount_viz" type="mesh" margin="0.001" mesh="mesh_r_gripper_mount" contype="0" conaffinity="0" group="1" pos="0 0 0" quat="1 0 0 0" material="metal"/>
<geom name="r_gripper_mount_viz" type="mesh" margin="0.001" mesh="mesh_r_gripper_mount" pos="0 0 0" quat="1 0 0 0" material="metal"/>
<body name="right_ezgripper_palm_link" pos="0 0 -0.053" quat="0 1 0 0">
<!--<body name="base" quat="1 0 0 0">-->
<geom name="r_gripper_geom_base_viz" type="mesh" mesh="mesh_palm_dual" quat="0 0.7071068 0 0.7071068" group="1" material="black"/>
<geom name="r_gripper_geom_base_col" type="box" pos="0 0 0.042" size="0.015 0.04 0.038" group="0"/>
<geom name="r_gripper_geom_base_viz" type="mesh" mesh="mesh_palm_dual" quat="0 0.7071068 0 0.7071068" material="metal"/>
<geom name="r_gripper_geom_base_col" type="box" pos="0 0 0.042" size="0.015 0.04 0.038" group="3"/>
<inertial mass="0.3" diaginertia="0.01 0.01 0.01" pos="0 0 0"/>
<site name="r_gripper_site_left_finger1" pos="0 0.03 0" size="0.01" material="tendon_site"/>
<site name="r_gripper_site_left_finger2" pos="0 0.03 0.062569" size="0.01" material="tendon_site"/>
Expand All @@ -224,50 +211,37 @@

<body name="right_ezgripper_finger_L1_1" pos="0 0.03 0.072569" quat="-0.5 0.5 0.5 0.5">
<joint name="right_ezgripper_knuckle_palm_L1_1" axis="0 1 0" limited="true" range="-1.94 1.94" solimplimit="0.95 0.99 0.001" solreflimit="0.005 1"/>
<geom name="r_gripper_geom_left_finger1" type="mesh" mesh="mesh_finger1" group="1" material="white"/>
<!-- <geom name="geom_left_finger1_col" type="mesh" mesh="mesh_finger1" group="0"/> -->
<geom name="r_gripper_geom_left_finger1_pad" type="box" pos="0.027 0 -0.012" size="0.008 0.014 0.001" group="1" material="black"/>
<!-- <geom name="geom_left_finger1_pad_col" type="box" pos="0.027 0 -0.003" size="0.008 0.014 0.01" group="0" solimp="0 0.95 0.001 0.5 3"/> -->
<geom name="r_gripper_geom_left_finger1_pad_col" type="box" pos="0.027 0 -0.012" size="0.008 0.014 0.001" group="0" />
<geom name="r_gripper_geom_left_finger1" type="mesh" mesh="mesh_finger1" material="white"/>
<geom name="r_gripper_geom_left_finger1_pad" type="box" pos="0.027 0 -0.012" size="0.008 0.014 0.001" material="metal"/>
<geom name="r_gripper_geom_left_finger1_pad_col" type="box" pos="0.027 0 -0.012" size="0.008 0.014 0.001" group="3" />
<inertial mass=".025" diaginertia="0.01 0.01 0.01" pos="0 0 0"/>
<site name="r_gripper_site_left_finger3" pos="0.042 0 0.01" size="0.01" material="tendon_site"/>

<body name="right_ezgripper_finger_L2_1" pos="0.052 0 0">
<joint name="right_ezgripper_knucle_L1_L2_1" axis="0 1 0" limited="true" range="0 1.94" solimplimit="0.95 0.99 0.001" solreflimit="0.005 1" stiffness="0.4" springref="0.0" frictionloss="0.1"/>
<geom name="r_gripper_geom_left_finger2" type="mesh" mesh="mesh_finger2" group="1" material="white"/>
<!-- <geom name="geom_left_finger2_col" type="mesh" mesh="mesh_finger2" group="0"/> -->
<geom name="r_gripper_geom_left_finger2_pad" type="box" pos="0.040 0 0.002" quat="0.9838437 0 -0.1790296 0" size="0.02 0.014 0.001" group="1" material="black"/>
<!-- <geom name="geom_left_finger2_pad_col" type="box" pos="0.040 0 0.011" quat="0.9838437 0 -0.1790296 0" size="0.02 0.014 0.01" group="0" solimp="0 0.95 0.001 0.5 3"/> -->
<geom name="r_gripper_geom_left_finger2_pad_col" type="box" pos="0.040 0 0.002" quat="0.9838437 0 -0.1790296 0" size="0.02 0.014 0.001" group="0"/>
<geom name="r_gripper_geom_left_finger2" type="mesh" mesh="mesh_finger2" material="white"/>
<geom name="r_gripper_geom_left_finger2_pad" type="box" pos="0.040 0 0.002" quat="0.9838437 0 -0.1790296 0" size="0.02 0.014 0.001" material="metal"/>
<geom name="r_gripper_geom_left_finger2_pad_col" type="box" pos="0.040 0 0.002" quat="0.9838437 0 -0.1790296 0" size="0.02 0.014 0.001" group="3"/>
<inertial mass=".025" diaginertia="0.01 0.01 0.01" pos="0 0 0"/>
<site name="r_gripper_site_left_finger4" pos="0.05 0 0.01" size="0.01" material="tendon_site"/>

</body>
</body>

<body name="right_ezgripper_finger_L1_2" pos="0 -0.03 0.072569" quat="0.5 0.5 -0.5 0.5">
<joint name="right_ezgripper_knuckle_palm_L1_2" axis="0 1 0" limited="true" range="-1.94 1.94" solimplimit="0.95 0.99 0.001" solreflimit="0.005 1"/>
<geom name="r_gripper_geom_right_finger1" type="mesh" mesh="mesh_finger1" group="1" material="white"/>
<!-- <geom name="geom_right_finger1_col" type="mesh" mesh="mesh_finger1" group="0"/> -->
<geom name="r_gripper_geom_right_finger1_pad" type="box" pos="0.027 0 -0.012" size="0.008 0.014 0.001" group="1" material="black"/>
<!-- <geom name="geom_right_finger1_pad_col" type="box" pos="0.027 0 -0.003" size="0.008 0.014 0.01" group="0" solimp="0 0.95 0.001 0.5 3"/> -->
<geom name="r_gripper_geom_right_finger1_pad_col" type="box" pos="0.027 0 -0.012" size="0.008 0.014 0.001" group="0"/>
<geom name="r_gripper_geom_right_finger1" type="mesh" mesh="mesh_finger1" material="white"/>
<geom name="r_gripper_geom_right_finger1_pad" type="box" pos="0.027 0 -0.012" size="0.008 0.014 0.001" material="metal"/>
<geom name="r_gripper_geom_right_finger1_pad_col" type="box" pos="0.027 0 -0.012" size="0.008 0.014 0.001" group="3"/>
<inertial mass=".025" diaginertia="0.01 0.01 0.01" pos="0 0 0"/>
<site name="r_gripper_site_right_finger3" pos="0.042 0 0.01" size="0.01" material="tendon_site"/>

<body name="right_ezgripper_finger_L2_2" pos="0.052 0 0">
<joint name="right_ezgripper_knuckle_L1_L2_2" axis="0 1 0" limited="true" range="0 1.94" solimplimit="0.95 0.99 0.001" solreflimit="0.005 1" stiffness="0.4" springref="0.0" frictionloss="0.1"/>
<geom name="r_gripper_geom_right_finger2" type="mesh" mesh="mesh_finger2" group="1" material="white"/>
<!-- <geom name="geom_right_finger2_col" type="mesh" mesh="mesh_finger2" group="0"/> -->
<geom name="r_gripper_geom_right_finger2_pad" type="box" pos="0.040 0 0.002" quat="0.9838437 0 -0.1790296 0" size="0.02 0.014 0.001" group="1" material="black"/>
<!-- <geom name="geom_right_finger2_pad_col" type="box" pos="0.040 0 0.011" quat="0.9838437 0 -0.1790296 0" size="0.02 0.014 0.01" group="0" solimp="0 0.95 0.001 0.5 3"/> -->
<geom name="r_gripper_geom_right_finger2_pad_col" type="box" pos="0.040 0 0.002" quat="0.9838437 0 -0.1790296 0" size="0.02 0.014 0.001" group="0"/>
<geom name="r_gripper_geom_right_finger2" type="mesh" mesh="mesh_finger2" material="white"/>
<geom name="r_gripper_geom_right_finger2_pad" type="box" pos="0.040 0 0.002" quat="0.9838437 0 -0.1790296 0" size="0.02 0.014 0.001" material="metal"/>
<geom name="r_gripper_geom_right_finger2_pad_col" type="box" pos="0.040 0 0.002" quat="0.9838437 0 -0.1790296 0" size="0.02 0.014 0.001" group="3"/>
<inertial mass=".025" diaginertia="0.01 0.01 0.01" pos="0 0 0"/>
<site name="r_gripper_site_right_finger4" pos="0.05 0 0.01" size="0.01" material="tendon_site"/>

</body>
</body>

<body name="right_eef" pos="0 0 0.13" quat="1 0 0 0">
<site name="right_grip_site" pos="0 0 0" size="0.01 0.01 0.01" rgba="1 0 0 0.5" type="sphere" group="1"/>
<!--<site name="ee_x" pos="0.1 0 0" size="0.005 .1" quat="0.707105 0 0.707108 0 " rgba="1 0 0 0" type="cylinder" group="1"/>-->
Expand All @@ -276,10 +250,8 @@
<!-- This site was added for visualization. -->
<!-- <site name="grip_site_cylinder" pos="0 0 0" size="0.005 10" rgba="0 1 0 0.3" type="cylinder" group="1"/> -->
</body>

</body>
</body>

</body>
</body>
</body>
Expand Down

0 comments on commit 5deddad

Please sign in to comment.