Skip to content

Commit

Permalink
Removed mount_flange link and applied changes to tool0
Browse files Browse the repository at this point in the history
  • Loading branch information
Levi-Armstrong committed Feb 17, 2015
1 parent 41966cf commit 24f5530
Show file tree
Hide file tree
Showing 6 changed files with 12 additions and 72 deletions.
22 changes: 2 additions & 20 deletions abb_irb2400_support/urdf/irb2400.urdf
Expand Up @@ -119,71 +119,53 @@
<material name="yellow"/>
</collision>
</link>
<link name="mount_flange"/>
<link name="tool0"/>
<joint name="joint_1" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="base_link"/>
<child link="link_1"/>
<axis xyz="0 0 1"/>
<limit effort="0" lower="-3.1416" upper="3.1416" velocity="2.618"/>
<calibration falling="0" rising="0"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="joint_2" type="revolute">
<origin rpy="0 0 0" xyz="0.1 0 0.615"/>
<parent link="link_1"/>
<child link="link_2"/>
<axis xyz="0 1 0"/>
<limit effort="0" lower="-1.7453" upper="1.9199" velocity="2.618"/>
<calibration falling="0" rising="0"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="joint_3" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0.705"/>
<parent link="link_2"/>
<child link="link_3"/>
<axis xyz="0 1 0"/>
<limit effort="0" lower="-1.0472" upper="1.1345" velocity="2.618"/>
<calibration falling="0" rising="0"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="joint_4" type="revolute">
<origin rpy="0 0 0" xyz="0.258 0 0.135"/>
<parent link="link_3"/>
<child link="link_4"/>
<axis xyz="1 0 0"/>
<limit effort="0" lower="-3.49" upper="3.49" velocity="6.2832"/>
<calibration falling="0" rising="0"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="joint_5" type="revolute">
<origin rpy="0 0 0" xyz="0.497 0 0"/>
<parent link="link_4"/>
<child link="link_5"/>
<axis xyz="0 1 0"/>
<limit effort="0" lower="-2.0944" upper="2.0944" velocity="6.2832"/>
<calibration falling="0" rising="0"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="joint_6" type="revolute">
<origin rpy="0 0 0" xyz="0.085 0 0"/>
<parent link="link_5"/>
<child link="link_6"/>
<axis xyz="1 0 0"/>
<limit effort="0" lower="-6.9813" upper="6.9813" velocity="7.854"/>
<calibration falling="0" rising="0"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="joint_6-mount_flange" type="fixed">
<joint name="joint_6-tool0" type="fixed">
<parent link="link_6"/>
<child link="mount_flange"/>
<origin rpy="0 1.57079632679 0" xyz="0 0 0"/>
</joint>
<joint name="mount_flange-tool0" type="fixed">
<parent link="mount_flange"/>
<child link="tool0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="0 1.57079632679 0" xyz="0 0 0"/>
</joint>
<link name="base"/>
<joint name="base_link-base" type="fixed">
Expand Down
22 changes: 2 additions & 20 deletions abb_irb2400_support/urdf/irb2400_macro.xacro
Expand Up @@ -117,7 +117,6 @@
<material name="yellow"/>
</collision>
</link>
<link name="${prefix}mount_flange"/>
<link name="${prefix}tool0"/>
<!-- end of link list -->

Expand All @@ -128,63 +127,46 @@
<child link="${prefix}link_1"/>
<axis xyz="0 0 1"/>
<limit lower="-3.1416" upper="3.1416" effort="0" velocity="2.618"/>
<calibration rising="0" falling="0"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="${prefix}joint_2" type="revolute">
<origin xyz="0.1 0 0.615" rpy="0 0 0"/>
<parent link="${prefix}link_1"/>
<child link="${prefix}link_2"/>
<axis xyz="0 1 0"/>
<limit lower="-1.7453" upper="1.9199" effort="0" velocity="2.618"/>
<calibration rising="0" falling="0"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="${prefix}joint_3" type="revolute">
<origin xyz="0 0 0.705" rpy="0 0 0"/>
<parent link="${prefix}link_2"/>
<child link="${prefix}link_3"/>
<axis xyz="0 1 0"/>
<limit lower="-1.0472" upper="1.1345" effort="0" velocity="2.618"/>
<calibration rising="0" falling="0"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="${prefix}joint_4" type="revolute">
<origin xyz="0.258 0 0.135" rpy="0 0 0"/>
<parent link="${prefix}link_3"/>
<child link="${prefix}link_4"/>
<axis xyz="1 0 0"/>
<limit lower="-3.49" upper="3.49" effort="0" velocity="6.2832"/>
<calibration rising="0" falling="0"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="${prefix}joint_5" type="revolute">
<origin xyz="0.497 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_4"/>
<child link="${prefix}link_5"/>
<axis xyz="0 1 0"/>
<limit lower="-2.0944" upper="2.0944" effort="0" velocity="6.2832"/>
<calibration rising="0" falling="0"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="${prefix}joint_6" type="revolute">
<origin xyz="0.085 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_5"/>
<child link="${prefix}link_6"/>
<axis xyz="1 0 0"/>
<limit lower="-6.9813" upper="6.9813" effort="0" velocity="7.854"/>
<calibration rising="0" falling="0"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="${prefix}joint_6-mount_flange" type="fixed">
<joint name="${prefix}joint_6-tool0" type="fixed">
<parent link="${prefix}link_6"/>
<child link="${prefix}mount_flange"/>
<origin xyz="0 0 0" rpy="0 1.57079632679 0"/>
</joint>
<joint name="${prefix}mount_flange-tool0" type="fixed">
<parent link="${prefix}mount_flange"/>
<child link="${prefix}tool0"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<origin xyz="0 0 0" rpy="0 1.57079632679 0"/>
</joint>
<!-- end of joint list -->

Expand Down
10 changes: 2 additions & 8 deletions abb_irb5400_support/urdf/irb5400.urdf
Expand Up @@ -122,7 +122,6 @@
<material name="yellow"/>
</collision>
</link>
<link name="mount_flange"/>
<link name="tool0"/>
<joint name="joint1" type="revolute">
<parent link="base_link"/>
Expand Down Expand Up @@ -174,15 +173,10 @@
<axis xyz="1 0 0"/>
<limit effort="100" lower="-6.0" upper="6.0" velocity="9.3375"/>
</joint>
<joint name="joint_6-mount_flange" type="fixed">
<joint name="joint_6-tool0" type="fixed">
<parent link="link_6"/>
<child link="mount_flange"/>
<origin rpy="0 1.57079632679 0" xyz="0 0 0"/>
</joint>
<joint name="mount_flange-tool0" type="fixed">
<parent link="mount_flange"/>
<child link="tool0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="0 1.57079632679 0" xyz="0 0 0"/>
</joint>
<link name="base"/>
<joint name="base_link-base" type="fixed">
Expand Down
10 changes: 2 additions & 8 deletions abb_irb5400_support/urdf/irb5400_macro.xacro
Expand Up @@ -120,7 +120,6 @@
<material name="yellow"/>
</collision>
</link>
<link name="${prefix}mount_flange"/>
<link name="${prefix}tool0"/>
<!-- end of link list -->

Expand Down Expand Up @@ -175,15 +174,10 @@
<axis xyz="1 0 0"/>
<limit lower="-6.0" upper="6.0" effort="100" velocity="9.3375"/>
</joint>
<joint name="${prefix}joint_6-mount_flange" type="fixed">
<joint name="${prefix}joint_6-tool0" type="fixed">
<parent link="${prefix}link_6"/>
<child link="${prefix}mount_flange"/>
<origin xyz="0 0 0" rpy="0 1.57079632679 0"/>
</joint>
<joint name="${prefix}mount_flange-tool0" type="fixed">
<parent link="${prefix}mount_flange"/>
<child link="${prefix}tool0"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<origin xyz="0 0 0" rpy="0 1.57079632679 0"/>
</joint>
<!-- end of joint list -->

Expand Down
10 changes: 2 additions & 8 deletions abb_irb6600_support/urdf/irb6640.urdf
Expand Up @@ -106,7 +106,6 @@
<material name="orange"/>
</visual>
</link>
<link name="mount_flange"/>
<link name="tool0"/>
<link name="link_cylinder">
<collision name="collision">
Expand Down Expand Up @@ -178,15 +177,10 @@
<child link="link_6"/>
<limit effort="0" lower="-6.283" upper="6.283" velocity="3.3161"/>
</joint>
<joint name="joint_6-mount_flange" type="fixed">
<joint name="joint_6-tool0" type="fixed">
<parent link="link_6"/>
<child link="mount_flange"/>
<origin rpy="0 1.57079632679 0" xyz=".055 0 0"/>
</joint>
<joint name="mount_flange-tool0" type="fixed">
<parent link="mount_flange"/>
<child link="tool0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="0 1.57079632679 0" xyz=".055 0 0"/>
</joint>
<joint name="joint_cylinder" type="fixed">
<origin rpy="0 -0.170 0" xyz="-0.365 -0.1895 0.405"/>
Expand Down
10 changes: 2 additions & 8 deletions abb_irb6600_support/urdf/irb6640_macro.xacro
Expand Up @@ -104,7 +104,6 @@
<material name="orange"/>
</visual>
</link>
<link name="${prefix}mount_flange"/>
<link name="${prefix}tool0"/>

<!--Cylinder and piston -->
Expand Down Expand Up @@ -181,15 +180,10 @@
<child link="${prefix}link_6"/>
<limit effort="0" lower="-6.283" upper="6.283" velocity="3.3161"/>
</joint>
<joint type="fixed" name="${prefix}joint_6-mount_flange">
<joint type="fixed" name="${prefix}joint_6-tool0">
<parent link="${prefix}link_6"/>
<child link="${prefix}mount_flange"/>
<origin xyz=".055 0 0" rpy="0 1.57079632679 0"/>
</joint>
<joint type="fixed" name="${prefix}mount_flange-tool0">
<parent link="${prefix}mount_flange"/>
<child link="${prefix}tool0"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<origin xyz=".055 0 0" rpy="0 1.57079632679 0"/>
</joint>
<joint type="fixed" name="${prefix}joint_cylinder">
<origin xyz="-0.365 -0.1895 0.405" rpy="0 -0.170 0"/>
Expand Down

0 comments on commit 24f5530

Please sign in to comment.