Skip to content
This repository has been archived by the owner on Oct 9, 2019. It is now read-only.

Fix robotiq gripper 140 urdf #23

Merged
merged 1 commit into from
Jan 25, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
24 changes: 12 additions & 12 deletions robotiq_140_gripper_description/urdf/robotiq_140.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -231,42 +231,42 @@
<parent link="robotiq_arg2f_base_link"/>
<child link="left_outer_knuckle"/>
<axis xyz="-1 0 0"/>
<limit effort="1000" lower="0" upper="0.875" velocity="2.0"/>
<limit effort="1000" lower="0" upper="0.78" velocity="2.0"/>
</joint>
<joint name="right_outer_knuckle_joint" type="revolute">
<origin rpy="2.31 0 3.14159265359" xyz="0 0.030601 0.054905"/>
<parent link="robotiq_arg2f_base_link"/>
<child link="right_outer_knuckle"/>
<axis xyz="-1 0 0"/>
<limit effort="1000" lower="0" upper="0.875" velocity="2.0"/>
<limit effort="1000" lower="0" upper="0.78" velocity="2.0"/>
</joint>
<joint name="left_inner_knuckle_joint" type="revolute">
<origin rpy="2.29 0 0" xyz="0 -0.0127 0.06142"/>
<origin rpy="2.31 0 0" xyz="0 -0.0127 0.06142"/>
<parent link="robotiq_arg2f_base_link"/>
<child link="left_inner_knuckle"/>
<axis xyz="-1 0 0"/>
<limit effort="1000" lower="0" upper="0.87" velocity="2.0"/>
<limit effort="1000" lower="0" upper="0.78" velocity="2.0"/>
</joint>
<joint name="right_inner_knuckle_joint" type="revolute">
<origin rpy="2.29 0 -3.14159265359" xyz="0 0.0127 0.06142"/>
<origin rpy="2.31 0 -3.14159265359" xyz="0 0.0127 0.06142"/>
<parent link="robotiq_arg2f_base_link"/>
<child link="right_inner_knuckle"/>
<axis xyz="-1 0 0"/>
<limit effort="1000" lower="0" upper="0.87" velocity="2.0"/>
<limit effort="1000" lower="0" upper="0.78" velocity="2.0"/>
</joint>
<joint name="left_outer_finger_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0.01821998610742 0.0260018192872234"/>
<parent link="left_outer_knuckle"/>
<child link="left_outer_finger"/>
<axis xyz="-1 0 0"/>
<limit effort="1000" lower="0.1" upper="0.875" velocity="2.0"/>
<limit effort="1000" lower="-0.875" upper="-0.0075" velocity="2.0"/>
</joint>
<joint name="right_outer_finger_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0.01821998610742 0.0260018192872234"/>
<parent link="right_outer_knuckle"/>
<child link="right_outer_finger"/>
<axis xyz="-1 0 0"/>
<limit effort="1000" lower="0.1" upper="0.875" velocity="2.0"/>
<limit effort="1000" lower="-0.875" upper="-0.0075" velocity="2.0"/>
</joint>
<joint name="left_inner_finger_joint" type="revolute">
<origin rpy="-.725 0 0" xyz="0 0.0817554015893473 -0.0282203446692936"/>
Expand All @@ -285,8 +285,8 @@
<gazebo>
<joint name="left_inner_finger_knuckle_joint" type="revolute">
<pose frame="">0 0.006 -0.018 0 0 0</pose>
<parent>mara::left_inner_knuckle</parent>
<child>mara::left_inner_finger</child>
<parent>robotiq_140::left_inner_knuckle</parent>
<child>robotiq_140::left_inner_finger</child>
<axis>
<xyz>1 0 0</xyz>
<limit>
Expand All @@ -299,8 +299,8 @@
</joint>
<joint name="right_inner_finger_knuckle_joint" type="revolute">
<pose frame="">0 0.006 -0.018 0 0 0</pose>
<parent>mara::right_inner_knuckle</parent>
<child>mara::right_inner_finger</child>
<parent>robotiq_140::right_inner_knuckle</parent>
<child>robotiq_140::right_inner_finger</child>
<axis>
<xyz>-1 0 0</xyz>
<limit>
Expand Down
20 changes: 10 additions & 10 deletions robotiq_140_gripper_description/urdf/robotiq_140.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -287,47 +287,47 @@
<parent link="robotiq_arg2f_base_link" />
<child link="left_outer_knuckle" />
<axis xyz="-1 0 0" />
<limit lower="0" upper="0.875" velocity="2.0" effort="1000" />
<limit lower="0" upper="0.78" velocity="2.0" effort="1000" />
</joint>

<joint name="right_outer_knuckle_joint" type="revolute">
<origin xyz="0 0.030601 0.054905" rpy="2.31 0 3.14159265359" />
<parent link="robotiq_arg2f_base_link" />
<child link="right_outer_knuckle" />
<axis xyz="-1 0 0" />
<limit lower="0" upper="0.875" velocity="2.0" effort="1000" />
<limit lower="0" upper="0.78" velocity="2.0" effort="1000" />
</joint>

<joint name="left_inner_knuckle_joint" type="revolute">
<origin xyz="0 -0.0127 0.06142" rpy="2.29 0 0" />
<parent link="robotiq_arg2f_base_link" />
<child link="left_inner_knuckle" />
<axis xyz="-1 0 0" />
<limit lower="0" upper="0.87" velocity="2.0" effort="1000" />
<limit lower="0" upper="0.78" velocity="2.0" effort="1000" />
</joint>

<joint name="right_inner_knuckle_joint" type="revolute">
<origin xyz="0 0.0127 0.06142" rpy="2.29 0 -3.14159265359" />
<parent link="robotiq_arg2f_base_link" />
<child link="right_inner_knuckle" />
<axis xyz="-1 0 0" />
<limit lower="0" upper="0.87" velocity="2.0" effort="1000" />
<limit lower="0" upper="0.78" velocity="2.0" effort="1000" />
</joint>

<joint name="left_outer_finger_joint" type="revolute">
<origin xyz="0 0.01821998610742 0.0260018192872234" rpy="0 0 0" />
<parent link="left_outer_knuckle" />
<child link="left_outer_finger" />
<axis xyz="-1 0 0" />
<limit lower="0.1" upper="0.875" velocity="2.0" effort="1000" />
<limit lower="-0.875" upper="-0.0075" velocity="2.0" effort="1000" />
</joint>

<joint name="right_outer_finger_joint" type="revolute">
<origin xyz="0 0.01821998610742 0.0260018192872234" rpy="0 0 0" />
<parent link="right_outer_knuckle" />
<child link="right_outer_finger" />
<axis xyz="-1 0 0" />
<limit lower="0.1" upper="0.875" velocity="2.0" effort="1000" />
<limit lower="-0.875" upper="-0.0075" velocity="2.0" effort="1000" />
</joint>

<joint name="left_inner_finger_joint" type="revolute">
Expand All @@ -349,8 +349,8 @@
<gazebo>
<joint name="left_inner_finger_knuckle_joint" type="revolute">
<pose frame="">0 0.006 -0.018 0 0 0</pose>
<parent>mara::left_inner_knuckle</parent>
<child>mara::left_inner_finger</child>
<parent>robotiq_140::left_inner_knuckle</parent>
<child>robotiq_140::left_inner_finger</child>
<axis>
<xyz>1 0 0</xyz>
<limit>
Expand All @@ -364,8 +364,8 @@

<joint name="right_inner_finger_knuckle_joint" type="revolute">
<pose frame="">0 0.006 -0.018 0 0 0</pose>
<parent>mara::right_inner_knuckle</parent>
<child>mara::right_inner_finger</child>
<parent>robotiq_140::right_inner_knuckle</parent>
<child>robotiq_140::right_inner_finger</child>
<axis>
<xyz>-1 0 0</xyz>
<limit>
Expand Down