Skip to content

Commit bcfd504

Browse files
author
tatp-yf
committed
fix gripper
1 parent cf96632 commit bcfd504

File tree

2 files changed

+28
-20
lines changed

2 files changed

+28
-20
lines changed

assets/synthnova_assets/robots/galbot_one_foxtrot_description/galbot_one_foxtrot.xml

Lines changed: 14 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -367,12 +367,13 @@
367367
<body name="left_gripper_l_finger_link" pos="0.045 0 0" quat="0.811985797423278 0.0 0.0 0.5836771922757332">
368368
<inertial pos="0.016809 0.0019094 0" quat="1.0 0.0 0.0 0.0" mass="0.015957" diaginertia="5.5426e-07 1.8538e-06 1.5262e-06" />
369369
<joint name="left_gripper_l_finger_joint" type="hinge" range="-6.28 6.28" axis="0 0 1" />
370-
<geom name="left_gripper_l_finger_link_collision_0" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="l_link_3_zhitao_convex_decomposition_0.stl" class="collision" />
370+
<!-- <geom name="left_gripper_l_finger_link_collision_0" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="l_link_3_zhitao_convex_decomposition_0.stl" class="collision" />
371371
<geom name="left_gripper_l_finger_link_collision_1" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="l_link_3_zhitao_convex_decomposition_1.stl" class="collision" />
372372
<geom name="left_gripper_l_finger_link_collision_2" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="l_link_3_zhitao_convex_decomposition_2.stl" class="collision" />
373373
<geom name="left_gripper_l_finger_link_collision_3" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="l_link_3_zhitao_convex_decomposition_3.stl" class="collision" />
374374
<geom name="left_gripper_l_finger_link_collision_4" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="l_link_3_zhitao_convex_decomposition_4.stl" class="collision" />
375-
<geom name="left_gripper_l_finger_link_collision_5" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="l_link_3_zhitao_convex_decomposition_5.stl" class="collision" />
375+
<geom name="left_gripper_l_finger_link_collision_5" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="l_link_3_zhitao_convex_decomposition_5.stl" class="collision" /> -->
376+
<geom name="left_gripper_l_finger_link_collision" pos=".035 0.005 0" type="box" size=".03 .002 .008" class="collision" rgba="0 0 1 1"/>
376377
<geom pos="0 0 0" quat="1 0 0 0" type="mesh" class="visual" name="left_gripper_l_finger_link_visual_0" mesh="l_link_3_zhitao_0" material="l_link_2_light_silver" />
377378
<geom pos="0 0 0" quat="1 0 0 0" type="mesh" class="visual" name="left_gripper_l_finger_link_visual_1" mesh="l_link_3_zhitao_1" material="l_link_2_metal_aluminum" />
378379
<geom pos="0 0 0" quat="1 0 0 0" type="mesh" class="visual" name="left_gripper_l_finger_link_visual_2" mesh="l_link_3_zhitao_2" material="base_link_plastic_black" />
@@ -388,12 +389,13 @@
388389
<body name="left_gripper_r_finger_link" pos="0.045 0 0" quat="0.811985797423278 0.0 0.0 -0.5836771922757332">
389390
<inertial pos="0.016809 -0.0019094 0" quat="1.0 0.0 0.0 0.0" mass="0.015957" diaginertia="5.5426e-07 1.8538e-06 1.5262e-06" />
390391
<joint name="left_gripper_r_finger_joint" type="hinge" range="-6.28 6.28" axis="0 0 1" />
391-
<geom name="left_gripper_r_finger_link_collision_0" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="r_link_3_zhitao_convex_decomposition_0.stl" class="collision" />
392+
<!-- <geom name="left_gripper_r_finger_link_collision_0" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="r_link_3_zhitao_convex_decomposition_0.stl" class="collision" />
392393
<geom name="left_gripper_r_finger_link_collision_1" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="r_link_3_zhitao_convex_decomposition_1.stl" class="collision" />
393394
<geom name="left_gripper_r_finger_link_collision_2" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="r_link_3_zhitao_convex_decomposition_2.stl" class="collision" />
394395
<geom name="left_gripper_r_finger_link_collision_3" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="r_link_3_zhitao_convex_decomposition_3.stl" class="collision" />
395396
<geom name="left_gripper_r_finger_link_collision_4" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="r_link_3_zhitao_convex_decomposition_4.stl" class="collision" />
396-
<geom name="left_gripper_r_finger_link_collision_5" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="r_link_3_zhitao_convex_decomposition_5.stl" class="collision" />
397+
<geom name="left_gripper_r_finger_link_collision_5" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="r_link_3_zhitao_convex_decomposition_5.stl" class="collision" /> -->
398+
<geom name="left_gripper_r_finger_link_collision" pos=".035 -0.005 0" type="box" size=".03 .002 .008" class="collision" rgba="0 0 1 1"/>
397399
<geom pos="0 0 0" quat="1 0 0 0" type="mesh" class="visual" name="left_gripper_r_finger_link_visual_0" mesh="r_link_3_zhitao_0" material="l_link_2_light_silver" />
398400
<geom pos="0 0 0" quat="1 0 0 0" type="mesh" class="visual" name="left_gripper_r_finger_link_visual_1" mesh="r_link_3_zhitao_1" material="l_link_2_metal_aluminum" />
399401
<geom pos="0 0 0" quat="1 0 0 0" type="mesh" class="visual" name="left_gripper_r_finger_link_visual_2" mesh="r_link_3_zhitao_2" material="base_link_plastic_black" />
@@ -650,12 +652,13 @@
650652
<body name="right_gripper_l_finger_link" pos="0.045 0 0" quat="0.811985797423278 0.0 0.0 0.5836771922757332">
651653
<inertial pos="0.016809 0.0019094 0" quat="1.0 0.0 0.0 0.0" mass="0.015957" diaginertia="5.5426e-07 1.8538e-06 1.5262e-06" />
652654
<joint name="right_gripper_l_finger_joint" type="hinge" range="-6.28 6.28" axis="0 0 1" />
653-
<geom name="right_gripper_l_finger_link_collision_0" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="l_link_3_zhitao_convex_decomposition_0.stl" class="collision" />
655+
<!-- <geom name="right_gripper_l_finger_link_collision_0" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="l_link_3_zhitao_convex_decomposition_0.stl" class="collision" />
654656
<geom name="right_gripper_l_finger_link_collision_1" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="l_link_3_zhitao_convex_decomposition_1.stl" class="collision" />
655657
<geom name="right_gripper_l_finger_link_collision_2" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="l_link_3_zhitao_convex_decomposition_2.stl" class="collision" />
656658
<geom name="right_gripper_l_finger_link_collision_3" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="l_link_3_zhitao_convex_decomposition_3.stl" class="collision" />
657659
<geom name="right_gripper_l_finger_link_collision_4" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="l_link_3_zhitao_convex_decomposition_4.stl" class="collision" />
658-
<geom name="right_gripper_l_finger_link_collision_5" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="l_link_3_zhitao_convex_decomposition_5.stl" class="collision" />
660+
<geom name="right_gripper_l_finger_link_collision_5" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="l_link_3_zhitao_convex_decomposition_5.stl" class="collision" /> -->
661+
<geom name="right_gripper_l_finger_link_collision" pos=".035 0.005 0" type="box" size=".03 .002 .008" class="collision" rgba="0 0 1 1"/>
659662
<geom pos="0 0 0" quat="1 0 0 0" type="mesh" class="visual" name="right_gripper_l_finger_link_visual_0" mesh="l_link_3_zhitao_0" material="l_link_2_light_silver" />
660663
<geom pos="0 0 0" quat="1 0 0 0" type="mesh" class="visual" name="right_gripper_l_finger_link_visual_1" mesh="l_link_3_zhitao_1" material="l_link_2_metal_aluminum" />
661664
<geom pos="0 0 0" quat="1 0 0 0" type="mesh" class="visual" name="right_gripper_l_finger_link_visual_2" mesh="l_link_3_zhitao_2" material="base_link_plastic_black" />
@@ -671,12 +674,13 @@
671674
<body name="right_gripper_r_finger_link" pos="0.045 0 0" quat="0.811985797423278 0.0 0.0 -0.5836771922757332">
672675
<inertial pos="0.016809 -0.0019094 0" quat="1.0 0.0 0.0 0.0" mass="0.015957" diaginertia="5.5426e-07 1.8538e-06 1.5262e-06" />
673676
<joint name="right_gripper_r_finger_joint" type="hinge" range="-6.28 6.28" axis="0 0 1" />
674-
<geom name="right_gripper_r_finger_link_collision_0" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="r_link_3_zhitao_convex_decomposition_0.stl" class="collision" />
677+
<!-- <geom name="right_gripper_r_finger_link_collision_0" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="r_link_3_zhitao_convex_decomposition_0.stl" class="collision" />
675678
<geom name="right_gripper_r_finger_link_collision_1" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="r_link_3_zhitao_convex_decomposition_1.stl" class="collision" />
676679
<geom name="right_gripper_r_finger_link_collision_2" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="r_link_3_zhitao_convex_decomposition_2.stl" class="collision" />
677680
<geom name="right_gripper_r_finger_link_collision_3" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="r_link_3_zhitao_convex_decomposition_3.stl" class="collision" />
678681
<geom name="right_gripper_r_finger_link_collision_4" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="r_link_3_zhitao_convex_decomposition_4.stl" class="collision" />
679-
<geom name="right_gripper_r_finger_link_collision_5" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="r_link_3_zhitao_convex_decomposition_5.stl" class="collision" />
682+
<geom name="right_gripper_r_finger_link_collision_5" pos="0 0 0" quat="1.0 0.0 0.0 0.0" type="mesh" mesh="r_link_3_zhitao_convex_decomposition_5.stl" class="collision" /> -->
683+
<geom name="right_gripper_r_finger_link_collision" pos=".035 -0.005 0" type="box" size=".03 .002 .008" class="collision" rgba="0 0 1 1"/>
680684
<geom pos="0 0 0" quat="1 0 0 0" type="mesh" class="visual" name="right_gripper_r_finger_link_visual_0" mesh="r_link_3_zhitao_0" material="l_link_2_light_silver" />
681685
<geom pos="0 0 0" quat="1 0 0 0" type="mesh" class="visual" name="right_gripper_r_finger_link_visual_1" mesh="r_link_3_zhitao_1" material="l_link_2_metal_aluminum" />
682686
<geom pos="0 0 0" quat="1 0 0 0" type="mesh" class="visual" name="right_gripper_r_finger_link_visual_2" mesh="r_link_3_zhitao_2" material="base_link_plastic_black" />
@@ -1373,9 +1377,9 @@
13731377
<joint joint1="left_gripper_r_knuckle_joint" joint2="left_gripper_l_finger_joint" polycoef="0 -1 0 0 0" solimp="0.95 0.99 0.001 " solref="0.001 1" />
13741378
<joint joint1="left_gripper_r_knuckle_joint" joint2="left_gripper_r_finger_joint" polycoef="0 1 0 0 0" solimp="0.95 0.99 0.001 " solref="0.001 1" />
13751379
<joint joint1="right_gripper_r_knuckle_joint" joint2="right_gripper_l_knuckle_joint" polycoef="0 1 0 0 0" solimp="0.95 0.99 0.001 " solref="0.001 1" />
1376-
<joint joint1="right_gripper_r_knuckle_joint" joint2="right_gripper_l_inner_knuckle_joint" polycoef="0 1 0 0 0" solimp="0.95 0.99 0.001 " solref="0.001 1" />
1380+
<joint joint1="right_gripper_l_knuckle_joint" joint2="right_gripper_l_inner_knuckle_joint" polycoef="0 1 0 0 0" solimp="0.95 0.99 0.001 " solref="0.001 1" />
13771381
<joint joint1="right_gripper_r_knuckle_joint" joint2="right_gripper_r_inner_knuckle_joint" polycoef="0 -1 0 0 0" solimp="0.95 0.99 0.001 " solref="0.001 1" />
1378-
<joint joint1="right_gripper_r_knuckle_joint" joint2="right_gripper_l_finger_joint" polycoef="0 -1 0 0 0" solimp="0.95 0.99 0.001 " solref="0.001 1" />
1382+
<joint joint1="right_gripper_l_knuckle_joint" joint2="right_gripper_l_finger_joint" polycoef="0 -1 0 0 0" solimp="0.95 0.99 0.001 " solref="0.001 1" />
13791383
<joint joint1="right_gripper_r_knuckle_joint" joint2="right_gripper_r_finger_joint" polycoef="0 1 0 0 0" solimp="0.95 0.99 0.001 " solref="0.001 1" />
13801384
</equality>
13811385

0 commit comments

Comments
 (0)