Skip to content

Commit

Permalink
新增单独自适应夹爪/Pro自适应夹爪URDF模型文件
Browse files Browse the repository at this point in the history
  • Loading branch information
wangWking committed Sep 12, 2024
1 parent d9de0f5 commit eebe4b3
Show file tree
Hide file tree
Showing 16 changed files with 7,188 additions and 0 deletions.
311 changes: 311 additions & 0 deletions mycobot_description/urdf/adaptive_gripper/gripper_base.dae

Large diffs are not rendered by default.

254 changes: 254 additions & 0 deletions mycobot_description/urdf/adaptive_gripper/gripper_left1.dae

Large diffs are not rendered by default.

197 changes: 197 additions & 0 deletions mycobot_description/urdf/adaptive_gripper/gripper_left2.dae

Large diffs are not rendered by default.

197 changes: 197 additions & 0 deletions mycobot_description/urdf/adaptive_gripper/gripper_left3.dae

Large diffs are not rendered by default.

254 changes: 254 additions & 0 deletions mycobot_description/urdf/adaptive_gripper/gripper_right1.dae

Large diffs are not rendered by default.

197 changes: 197 additions & 0 deletions mycobot_description/urdf/adaptive_gripper/gripper_right2.dae

Large diffs are not rendered by default.

197 changes: 197 additions & 0 deletions mycobot_description/urdf/adaptive_gripper/gripper_right3.dae

Large diffs are not rendered by default.

Original file line number Diff line number Diff line change
@@ -0,0 +1,166 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="firefighter" >

<xacro:property name="width" value=".2" />

<link name="gripper_base">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/adaptive_gripper/gripper_base.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.012 " rpy = " 0 0 0"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/adaptive_gripper/gripper_base.dae"/>
</geometry>
<origin xyz = "0.0 0 -0.012 " rpy = " 0 0 0"/>
</collision>
</link>

<link name="gripper_left1">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/adaptive_gripper/gripper_left1.dae"/>
</geometry>
<origin xyz = "0.039 -0.0133 -0.012 " rpy = " 0 0 0"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/adaptive_gripper/gripper_left1.dae"/>
</geometry>
<origin xyz = "0.039 -0.0133 -0.012 " rpy = " 0 0 0"/>
</collision>
</link>

<link name="gripper_left2">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/adaptive_gripper/gripper_left2.dae"/>
</geometry>
<origin xyz = "0.005 -0.0195 -0.012 " rpy = " 0 0 0"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/adaptive_gripper/gripper_left2.dae"/>
</geometry>
<origin xyz = "0.005 -0.0195 -0.012 " rpy = " 0 0 0"/>
</collision>
</link>

<link name="gripper_left3">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/adaptive_gripper/gripper_left3.dae"/>
</geometry>
<origin xyz = "0.012 0.0025 -0.012 " rpy = " 0 0 0"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/adaptive_gripper/gripper_left3.dae"/>
</geometry>
<origin xyz = "0.012 0.0025 -0.012 " rpy = " 0 0 0"/>
</collision>
</link>

<link name="gripper_right1">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/adaptive_gripper/gripper_right1.dae"/>
</geometry>
<origin xyz = "-0.039 -0.0133 -0.012 " rpy = " 0 0 0"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/adaptive_gripper/gripper_right1.dae"/>
</geometry>
<origin xyz = "-0.039 -0.0133 -0.012 " rpy = " 0 0 0"/>
</collision>
</link>

<link name="gripper_right2">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/adaptive_gripper/gripper_right2.dae"/>
</geometry>
<origin xyz = "-0.005 -0.0195 -0.012 " rpy = " 0 0 0"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/adaptive_gripper/gripper_right2.dae"/>
</geometry>
<origin xyz = "-0.005 -0.0195 -0.012 " rpy = " 0 0 0"/>
</collision>
</link>

<link name="gripper_right3">
<visual>
<geometry>
<mesh filename="package://mycobot_description/urdf/adaptive_gripper/gripper_right3.dae"/>
</geometry>
<origin xyz = "-0.012 0.0025 -0.012 " rpy = " 0 0 0"/>
</visual>
<collision>
<geometry>
<mesh filename="package://mycobot_description/urdf/adaptive_gripper/gripper_right3.dae"/>
</geometry>
<origin xyz = "-0.012 0.0025 -0.012" rpy = " 0 0 0"/>
</collision>
</link>


<joint name="gripper_controller" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-0.7" upper = "0.15" velocity = "0"/>
<parent link="gripper_base"/>
<child link="gripper_left3"/>
<origin xyz= "-0.012 0.005 0" rpy = "0 0 0"/>
</joint>

<joint name="gripper_base_to_gripper_left2" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-0.8" upper = "0.5" velocity = "0"/>
<parent link="gripper_base"/>
<child link="gripper_left2"/>
<origin xyz= "-0.005 0.027 0" rpy = "0 0 0"/>
<mimic joint="gripper_controller" multiplier="1.0" offset="0" />
</joint>

<joint name="gripper_left3_to_gripper_left1" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-0.5" upper = "0.5" velocity = "0"/>
<parent link="gripper_left3"/>
<child link="gripper_left1"/>
<origin xyz= "-0.027 0.016 0" rpy = "0 0 0"/>
<mimic joint="gripper_controller" multiplier="-1.0" offset="0" />
</joint>

<joint name="gripper_base_to_gripper_right3" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-0.15" upper = "0.7" velocity = "0"/>
<parent link="gripper_base"/>
<child link="gripper_right3"/>
<origin xyz= "0.012 0.005 0" rpy = "0 0 0"/>
<mimic joint="gripper_controller" multiplier="-1.0" offset="0" />
</joint>

<joint name="gripper_base_to_gripper_right2" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-0.5" upper = "0.8" velocity = "0"/>
<parent link="gripper_base"/>
<child link="gripper_right2"/>
<origin xyz= "0.005 0.027 0" rpy = "0 0 0"/>
<mimic joint="gripper_controller" multiplier="-1.0" offset="0" />
</joint>

<joint name="gripper_right3_to_gripper_right1" type="revolute">
<axis xyz="0 0 1"/>
<limit effort = "1000.0" lower = "-0.5" upper = "0.5" velocity = "0"/>
<parent link="gripper_right3"/>
<child link="gripper_right1"/>
<origin xyz= "0.027 0.016 0" rpy = "0 0 0"/>
<mimic joint="gripper_controller" multiplier="1.0" offset="0" />
</joint>

</robot>

Loading

0 comments on commit eebe4b3

Please sign in to comment.