Skip to content

Commit

Permalink
Modifications to meet ABB ROS package standards
Browse files Browse the repository at this point in the history
  • Loading branch information
marip8 committed Dec 5, 2018
1 parent 4311c28 commit 73f7eae
Show file tree
Hide file tree
Showing 6 changed files with 20 additions and 21 deletions.
Binary file modified abb_irb6700_support/meshes/irb6700/collision/link_1.stl
Binary file not shown.
Binary file modified abb_irb6700_support/meshes/irb6700/collision/link_6.stl
Binary file not shown.
Binary file modified abb_irb6700_support/meshes/irb6700/visual/link_1.stl
Binary file not shown.
Binary file modified abb_irb6700_support/meshes/irb6700/visual/link_6.stl
Binary file not shown.
19 changes: 9 additions & 10 deletions abb_irb6700_support/package.xml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<package>
<package format="2">
<name>abb_irb6700_support</name>
<version>0.1.0</version>
<description>
Expand All @@ -8,12 +8,11 @@
</p>
<p>
This package contains configuration data, 3D models and launch files
for ABB IRB 52 manipulators. This currently includes the 7/1.2 and
7/1.45 variants.
for ABB IRB 6700 manipulators. This currently includes the variant 235/2.65.
</p>
<p>
Joint limits and max joint velocities are based on the information in the
<a href="https://search-ext.abb.com/library/Download.aspx?DocumentID=3HAC044265-001&amp;LanguageCode=en&amp;DocumentPartId=&amp;Action=Launch">
<a href="https://library.e.abb.com/public/f69fdf358ddc4264b2d86c02b019ec0e/3HAC044265%20PS%20IRB%206700-en.pdf">
ABB IRB 6700 product specification document</a> All URDFs / XACROs are based on the
default motion and joint velocity limits, unless noted otherwise (ie:
no support for high speed joints, extended / limited motion ranges or
Expand All @@ -36,12 +35,12 @@
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roslaunch</build_depend>

<run_depend>abb_driver</run_depend>
<run_depend>abb_resources</run_depend>
<run_depend>joint_state_publisher</run_depend>
<run_depend>robot_state_publisher</run_depend>
<run_depend>rviz</run_depend>
<run_depend>xacro</run_depend>
<exec_depend>abb_driver</exec_depend>
<exec_depend>abb_resources</exec_depend>
<exec_depend>joint_state_publisher</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>rviz</exec_depend>
<exec_depend>xacro</exec_depend>

<export>
<architecture_independent/>
Expand Down
22 changes: 11 additions & 11 deletions abb_irb6700_support/urdf/irb6700_235_265_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -150,14 +150,14 @@
<link name="${prefix}tool0"/>

<joint name="${prefix}joint_1" type="revolute">
<origin xyz="0 0 0.288" rpy="0 0 0" />
<origin xyz="0 0 0.78" rpy="0 0 0" />
<parent link="${prefix}base_link" />
<child link="${prefix}link_1" />
<axis xyz="0 0 1" />
<limit lower="-${radians(170)}" upper="${radians(170)}" effort="0" velocity="${radians(100)}" />
</joint>
<joint name="${prefix}joint_2" type="revolute">
<origin xyz="0.32 0 0.492" rpy="0 0 0" />
<origin xyz="0.32 0 0" rpy="0 0 0" />
<parent link="${prefix}link_1" />
<child link="${prefix}link_2" />
<axis xyz="0 1 0" />
Expand Down Expand Up @@ -185,39 +185,39 @@
<limit lower="-${radians(130)}" upper="${radians(130)}" effort="0" velocity="${radians(120)}" />
</joint>
<joint name="${prefix}joint_6" type="revolute">
<origin xyz="0.165 0 0" rpy="0 0 0" />
<origin xyz="0.2 0 0" rpy="0 0 0" />
<parent link="${prefix}link_5" />
<child link="${prefix}link_6" />
<axis xyz="1 0 0" />
<limit lower="-${radians(360)}" upper="${radians(360)}" effort="0" velocity="${radians(190)}" />
</joint>
<joint name="${prefix}tool_joint" type="fixed">
<origin xyz="0.035 0 0" rpy="0 ${radians(90)} 0" />
<joint name="${prefix}joint_6_tool0" type="fixed">
<origin xyz="0 0 0" rpy="0 ${radians(90)} 0" />
<parent link="${prefix}link_6" />
<child link="${prefix}tool0" />
<axis xyz="0 0 0" />
</joint>
<joint name="${prefix}cylinder_joint" type="revolute">
<origin xyz="-0.349 -0.194 0.35" rpy="0 0 0" />
<origin xyz="-0.349 -0.194 -0.142" rpy="0 0 0" />
<parent link="${prefix}link_1" />
<child link="${prefix}cylinder" />
<axis xyz="0 1 0" />
<mimic joint="${prefix}joint_2" multiplier="-0.25"/>
<limit lower="-3" upper="3" effort="0" velocity="100" />
<limit lower="-${radians(65*0.25)}" upper="${radians(85*0.25)}" effort="0" velocity="100" />
</joint>
<joint name="${prefix}piston_joint" type="prismatic">
<origin xyz="0 0 0" rpy="0.20897 0 -${radians(90)}" />
<parent link="${prefix}cylinder" />
<child link="${prefix}piston" />
<axis xyz="0 1 0" />
<mimic joint="${prefix}joint_2" multiplier="0.15"/>
<limit lower="-3" upper="3" effort="0" velocity="100" />
</joint>-->
<limit lower="-0.25" upper="0.25" effort="0" velocity="100" />
</joint>

<!-- ROS base_link to ABB World Coordinates transform -->
<link name="${prefix}base" />
<link name="${prefix}base"/>
<joint name="${prefix}base_link_base" type="fixed">
<origin xyz="0 0 0.780" rpy="0 0 0"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="${prefix}base_link"/>
<child link="${prefix}base"/>
</joint>
Expand Down

0 comments on commit 73f7eae

Please sign in to comment.