-
Notifications
You must be signed in to change notification settings - Fork 86
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
Showing
9 changed files
with
4,450 additions
and
1 deletion.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
2,015 changes: 2,015 additions & 0 deletions
2,015
mycobot_description/urdf/pro_adaptive_gripper/new_gripper/gripper_base.dae
Large diffs are not rendered by default.
Oops, something went wrong.
497 changes: 497 additions & 0 deletions
497
mycobot_description/urdf/pro_adaptive_gripper/new_gripper/gripper_left1.dae
Large diffs are not rendered by default.
Oops, something went wrong.
293 changes: 293 additions & 0 deletions
293
mycobot_description/urdf/pro_adaptive_gripper/new_gripper/gripper_left2.dae
Large diffs are not rendered by default.
Oops, something went wrong.
344 changes: 344 additions & 0 deletions
344
mycobot_description/urdf/pro_adaptive_gripper/new_gripper/gripper_left3.dae
Large diffs are not rendered by default.
Oops, something went wrong.
497 changes: 497 additions & 0 deletions
497
mycobot_description/urdf/pro_adaptive_gripper/new_gripper/gripper_right1.dae
Large diffs are not rendered by default.
Oops, something went wrong.
288 changes: 288 additions & 0 deletions
288
mycobot_description/urdf/pro_adaptive_gripper/new_gripper/gripper_right2.dae
Large diffs are not rendered by default.
Oops, something went wrong.
344 changes: 344 additions & 0 deletions
344
mycobot_description/urdf/pro_adaptive_gripper/new_gripper/gripper_right3.dae
Large diffs are not rendered by default.
Oops, something went wrong.
167 changes: 167 additions & 0 deletions
167
...t_description/urdf/pro_adaptive_gripper/new_gripper/mycobot_pro_adaptive_gripper_new.urdf
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,167 @@ | ||
<?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/pro_adaptive_gripper/new_gripper/gripper_base.dae"/> | ||
</geometry> | ||
<origin xyz = "-0.02 0.012 -0.018 " rpy = " 1.5708 0 1.5708"/> | ||
</visual> | ||
<collision> | ||
<geometry> | ||
<mesh filename="package://mycobot_description/urdf/pro_adaptive_gripper/new_gripper/gripper_base.dae"/> | ||
</geometry> | ||
<origin xyz = "-0.02 0.012 -0.018 " rpy = " 1.5708 0 1.5708"/> | ||
</collision> | ||
</link> | ||
|
||
<link name="gripper_left1"> | ||
<visual> | ||
<geometry> | ||
<mesh filename="package://mycobot_description/urdf/pro_adaptive_gripper/new_gripper/gripper_left1.dae"/> | ||
</geometry> | ||
<origin xyz = "0.048 -0.035 -0.003 " rpy = " 1.5708 0 1.5708"/> | ||
</visual> | ||
<collision> | ||
<geometry> | ||
<mesh filename="package://mycobot_description/urdf/pro_adaptive_gripper/new_gripper/gripper_left1.dae"/> | ||
</geometry> | ||
<origin xyz = "0.048 -0.035 -0.003 " rpy = " 1.5708 0 1.5708"/> | ||
</collision> | ||
</link> | ||
|
||
<link name="gripper_left2"> | ||
<visual> | ||
<geometry> | ||
<mesh filename="package://mycobot_description/urdf/pro_adaptive_gripper/new_gripper/gripper_left2.dae"/> | ||
</geometry> | ||
<origin xyz = "0.026 0.022 -0.018 " rpy = " 1.5708 0 1.5708"/> | ||
</visual> | ||
<collision> | ||
<geometry> | ||
<mesh filename="package://mycobot_description/urdf/pro_adaptive_gripper/new_gripper/gripper_left2.dae"/> | ||
</geometry> | ||
<origin xyz = "0.026 0.022 -0.018 " rpy = " 1.5708 0 1.5708"/> | ||
</collision> | ||
</link> | ||
|
||
<link name="gripper_left3"> | ||
<visual> | ||
<geometry> | ||
<mesh filename="package://mycobot_description/urdf/pro_adaptive_gripper/new_gripper/gripper_left3.dae"/> | ||
</geometry> | ||
<origin xyz = "0.0 0.0 -0.018 " rpy = " 1.5708 0 1.5708"/> | ||
|
||
</visual> | ||
<collision> | ||
<geometry> | ||
<mesh filename="package://mycobot_description/urdf/pro_adaptive_gripper/new_gripper/gripper_left3.dae"/> | ||
</geometry> | ||
<origin xyz = "0.0 0.0 -0.018 " rpy = " 1.5708 0 1.5708"/> | ||
</collision> | ||
</link> | ||
|
||
<link name="gripper_right1"> | ||
<visual> | ||
<geometry> | ||
<mesh filename="package://mycobot_description/urdf/pro_adaptive_gripper/new_gripper/gripper_right1.dae"/> | ||
</geometry> | ||
<origin xyz = "-0.086 -0.036 -0.003 " rpy = " 1.5708 0 1.5708"/> | ||
</visual> | ||
<collision> | ||
<geometry> | ||
<mesh filename="package://mycobot_description/urdf/pro_adaptive_gripper/new_gripper/gripper_right1.dae"/> | ||
</geometry> | ||
<origin xyz = "-0.086 -0.036 -0.003 " rpy = " 1.5708 0 1.5708"/> | ||
</collision> | ||
</link> | ||
|
||
<link name="gripper_right2"> | ||
<visual> | ||
<geometry> | ||
<mesh filename="package://mycobot_description/urdf/pro_adaptive_gripper/new_gripper/gripper_right2.dae"/> | ||
</geometry> | ||
<origin xyz = "-0.062 0.0224 -0.018 " rpy = " 1.5708 0 1.5708"/> | ||
</visual> | ||
<collision> | ||
<geometry> | ||
<mesh filename="package://mycobot_description/urdf/pro_adaptive_gripper/new_gripper/gripper_right2.dae"/> | ||
</geometry> | ||
<origin xyz = "-0.062 0.0224 -0.018 " rpy = " 1.5708 0 1.5708"/> | ||
</collision> | ||
</link> | ||
|
||
<link name="gripper_right3"> | ||
<visual> | ||
<geometry> | ||
<mesh filename="package://mycobot_description/urdf/pro_adaptive_gripper/new_gripper/gripper_right3.dae"/> | ||
</geometry> | ||
<origin xyz = "-0.034 0.0 -0.018 " rpy = " 1.5708 0 1.5708"/> | ||
|
||
</visual> | ||
<collision> | ||
<geometry> | ||
<mesh filename="package://mycobot_description/urdf/pro_adaptive_gripper/new_gripper/gripper_right3.dae"/> | ||
</geometry> | ||
<origin xyz = "-0.034 0.0 -0.018 " rpy = " 1.5708 0 1.5708"/> | ||
</collision> | ||
</link> | ||
|
||
<joint name="gripper_controller" type="revolute"> | ||
<axis xyz="0 0 1"/> | ||
<limit effort = "1000.0" lower = "-1.11" upper = "0" velocity = "0"/> | ||
<parent link="gripper_base"/> | ||
<child link="gripper_left3"/> | ||
<origin xyz= "-0.018 0.015 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.047 -0.01 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.05 0.035 -0.015" 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.3" upper = "0.7" velocity = "0"/> | ||
<parent link="gripper_base"/> | ||
<child link="gripper_right3"/> | ||
<origin xyz= "0.016 0.014 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.044 -0.01 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.052 0.035 -0.015" rpy = "0 0 0"/> | ||
<mimic joint="gripper_controller" multiplier="1.0" offset="0" /> | ||
</joint> | ||
|
||
|
||
</robot> |