Skip to content

Commit

Permalink
Merge pull request ros-industrial#25 from nilsmelchert/indigo-devel
Browse files Browse the repository at this point in the history
Update rx160 support package
  • Loading branch information
gavanderhoorn authored Mar 22, 2018
2 parents c6b80b0 + d51899f commit 43b1479
Show file tree
Hide file tree
Showing 8 changed files with 72 additions and 26 deletions.
2 changes: 1 addition & 1 deletion staubli_resources/urdf/common_colours.xacro
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<!-- colours based on RAL values supplied by Staubli -->
<!-- all RAL colours converted using http://www.visual-graphics.de/en/customer-care/ral-colours -->

Expand Down
2 changes: 1 addition & 1 deletion staubli_resources/urdf/common_materials.xacro
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:include filename="$(find staubli_resources)/urdf/common_colours.xacro"/>

<!-- default colors for robots -->
Expand Down
2 changes: 1 addition & 1 deletion staubli_rx160_support/launch/load_rx160.launch
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<?xml version="1.0"?>
<launch>
<param name="robot_description" command="$(find xacro)/xacro.py '$(find staubli_rx160_support)/urdf/rx160.xacro'" />
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find staubli_rx160_support)/urdf/rx160.xacro'" />
</launch>
2 changes: 1 addition & 1 deletion staubli_rx160_support/launch/load_rx160l.launch
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<?xml version="1.0" ?>
<launch>
<param name="robot_description" command="$(find xacro)/xacro.py '$(find staubli_rx160_support)/urdf/rx160l.xacro'" />
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find staubli_rx160_support)/urdf/rx160l.xacro'" />
</launch>
2 changes: 1 addition & 1 deletion staubli_rx160_support/urdf/rx160.xacro
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0" ?>

<robot name="staubli_rx160" xmlns:xacro="http://ros.org/wiki/xacro">
<robot name="staubli_rx160" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:include filename="$(find staubli_rx160_support)/urdf/rx160_macro.xacro"/>
<xacro:staubli_rx160 prefix=""/>
</robot>
43 changes: 33 additions & 10 deletions staubli_rx160_support/urdf/rx160_macro.xacro
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:include filename="$(find staubli_resources)/urdf/common_materials.xacro"/>

<xacro:macro name="staubli_rx160" params="prefix">
<!-- links -->
<!-- links: main serial chain -->
<link name="${prefix}base_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
Expand Down Expand Up @@ -158,39 +158,38 @@
izz="0.000021"/>
</inertial>
</link>
<link name="${prefix}tool0"/>

<!-- joints -->
<!-- joints: main serial chain -->
<joint name="${prefix}joint_1" type="revolute">
<origin xyz="0 0 0.55" rpy="0 0 0"/>
<parent link="${prefix}base_link"/>
<child link="${prefix}link_1"/>
<axis xyz="0 0 1"/>
<limit lower="-2.967060" upper="2.967060" effort="692.0" velocity="2.88" />
<limit lower="${radians(-160)}" upper="${radians(160)}" effort="692.0" velocity="${radians(200)}" />
<dynamics damping="0.0" friction="0.0"/>
</joint>
<joint name="${prefix}joint_2" type="revolute">
<origin xyz="0.15 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_1"/>
<child link="${prefix}link_2"/>
<axis xyz="0 1 0"/>
<limit lower="-2.4" upper="2.4" effort="574.0" velocity="2.62" />
<limit lower="${radians(-137.5)}" upper="${radians(137.5)}" effort="574.0" velocity="${radians(200)}" />
<dynamics damping="0.0" friction="0.0"/>
</joint>
<joint name="${prefix}joint_3" type="revolute">
<origin xyz="0 0 0.825" rpy="0 0 0"/>
<parent link="${prefix}link_2"/>
<child link="${prefix}link_3"/>
<axis xyz="0 1 0"/>
<limit lower="-2.62" upper="2.62" effort="242.0" velocity="3.32" />
<limit lower="${radians(-150)}" upper="${radians(150)}" effort="242.0" velocity="${radians(255)}" />
<dynamics damping="0.0" friction="0.0"/>
</joint>
<joint name="${prefix}joint_4" type="revolute">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_3"/>
<child link="${prefix}link_4"/>
<axis xyz="0 0 1"/>
<limit lower="-4.71" upper="4.71" effort="58.0" velocity="5.15" />
<limit lower="${radians(-270)}" upper="${radians(270)}" effort="58.0" velocity="${radians(315)}" />
<dynamics damping="0.0" friction="0.0"/>
</joint>
<joint name="${prefix}joint_5" type="revolute">
Expand All @@ -201,21 +200,45 @@
<!-- from Staubli instruction manual:
(1) effort limit = 58 Nm if axis 6 torque = 0 Nm
(2) effort limit = 29 Nm for maximum torque on axis 6 -->
<limit lower="-1.83" upper="2.09" effort="29.0" velocity="4.54" />
<limit lower="${radians(-105)}" upper="${radians(120)}" effort="29.0" velocity="${radians(360)}" />
<dynamics damping="0.0" friction="0.0"/>
</joint>
<joint name="${prefix}joint_6" type="revolute">
<origin xyz="0 0 0.11" rpy="0 0 0"/>
<parent link="${prefix}link_5"/>
<child link="${prefix}link_6"/>
<axis xyz="0 0 1"/>
<limit lower="-4.71" upper="4.71" effort="29.0" velocity="7.68" />
<limit lower="${radians(-270)}" upper="${radians(270)}" effort="29.0" velocity="${radians(870)}" />
<dynamics damping="0.0" friction="0.0"/>
</joint>
<joint name="${prefix}joint_6-tool0" type="fixed">
<parent link="${prefix}link_6"/>
<child link="${prefix}tool0"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
</joint>

<!-- ROS-Industrial 'base' frame: base_link to Staubli World Coordinates transform -->
<link name="${prefix}base" />
<joint name="${prefix}base_link-base" type="fixed">
<origin xyz="0 0 0.550" rpy="0 0 0"/>
<parent link="${prefix}base_link"/>
<child link="${prefix}base"/>
</joint>

<!-- ROS-Industrial 'flange' frame: attachment point for EEF models -->
<link name="${prefix}flange" />
<joint name="${prefix}joint_6-flange" type="fixed">
<origin xyz="0 0 0" rpy="0 ${radians(-90.0)} 0" />
<parent link="${prefix}link_6" />
<child link="${prefix}flange" />
</joint>

<!-- ROS-Industrial 'tool0' frame: all-zeros tool frame -->
<link name="${prefix}tool0" />
<joint name="${prefix}flange-tool0" type="fixed">
<origin xyz="0 0 0" rpy="0 ${radians(90.0)} 0" />
<parent link="${prefix}flange" />
<child link="${prefix}tool0" />
</joint>
</xacro:macro>
</robot>
2 changes: 1 addition & 1 deletion staubli_rx160_support/urdf/rx160l.xacro
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0" ?>

<robot name="staubli_rx160l" xmlns:xacro="http://ros.org/wiki/xacro">
<robot name="staubli_rx160l" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:include filename="$(find staubli_rx160_support)/urdf/rx160l_macro.xacro"/>
<xacro:staubli_rx160l prefix=""/>
</robot>
43 changes: 33 additions & 10 deletions staubli_rx160_support/urdf/rx160l_macro.xacro
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:include filename="$(find staubli_resources)/urdf/common_materials.xacro"/>

<xacro:macro name="staubli_rx160l" params="prefix">
<!-- links -->
<!-- links: main serial chain -->
<link name="${prefix}base_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
Expand Down Expand Up @@ -158,39 +158,38 @@
izz="0.000021"/>
</inertial>
</link>
<link name="${prefix}tool0"/>

<!-- joints -->
<!-- joints: main serial chain -->
<joint name="${prefix}joint_1" type="revolute">
<origin xyz="0 0 0.55" rpy="0 0 0"/>
<parent link="${prefix}base_link"/>
<child link="${prefix}link_1"/>
<axis xyz="0 0 1"/>
<limit lower="-2.967060" upper="2.967060" effort="692.0" velocity="2.88" />
<limit lower="${radians(-160)}" upper="${radians(160)}" effort="692.0" velocity="${radians(200)}" />
<dynamics damping="0.0" friction="0.0"/>
</joint>
<joint name="${prefix}joint_2" type="revolute">
<origin xyz="0.15 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_1"/>
<child link="${prefix}link_2"/>
<axis xyz="0 1 0"/>
<limit lower="-2.4" upper="2.4" effort="574.0" velocity="2.62" />
<limit lower="${radians(-137.5)}" upper="${radians(137.5)}" effort="574.0" velocity="${radians(200)}" />
<dynamics damping="0.0" friction="0.0"/>
</joint>
<joint name="${prefix}joint_3" type="revolute">
<origin xyz="0 0 0.825" rpy="0 0 0"/>
<parent link="${prefix}link_2"/>
<child link="${prefix}link_3"/>
<axis xyz="0 1 0"/>
<limit lower="-2.62" upper="2.62" effort="242.0" velocity="3.32" />
<limit lower="${radians(-150)}" upper="${radians(150)}" effort="242.0" velocity="${radians(255)}" />
<dynamics damping="0.0" friction="0.0"/>
</joint>
<joint name="${prefix}joint_4" type="revolute">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_3"/>
<child link="${prefix}link_4"/>
<axis xyz="0 0 1"/>
<limit lower="-4.71" upper="4.71" effort="58.0" velocity="5.15" />
<limit lower="${radians(-270)}" upper="${radians(270)}" effort="58.0" velocity="${radians(315)}" />
<dynamics damping="0.0" friction="0.0"/>
</joint>
<joint name="${prefix}joint_5" type="revolute">
Expand All @@ -201,21 +200,45 @@
<!-- from Staubli instruction manual:
(1) effort limit = 58 Nm if axis 6 torque = 0 Nm
(2) effort limit = 29 Nm for maximum torque on axis 6 -->
<limit lower="-1.83" upper="2.09" effort="29.0" velocity="4.54" />
<limit lower="${radians(-105)}" upper="${radians(120)}" effort="29.0" velocity="${radians(360)}" />
<dynamics damping="0.0" friction="0.0"/>
</joint>
<joint name="${prefix}joint_6" type="revolute">
<origin xyz="0 0 0.11" rpy="0 0 0"/>
<parent link="${prefix}link_5"/>
<child link="${prefix}link_6"/>
<axis xyz="0 0 1"/>
<limit lower="-4.71" upper="4.71" effort="29.0" velocity="7.68" />
<limit lower="${radians(-270)}" upper="${radians(270)}" effort="29.0" velocity="${radians(870)}" />
<dynamics damping="0.0" friction="0.0"/>
</joint>
<joint name="${prefix}joint_6-tool0" type="fixed">
<parent link="${prefix}link_6"/>
<child link="${prefix}tool0"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
</joint>

<!-- ROS-Industrial 'base' frame: base_link to Staubli World Coordinates transform -->
<link name="${prefix}base" />
<joint name="${prefix}base_link-base" type="fixed">
<origin xyz="0 0 0.550" rpy="0 0 0"/>
<parent link="${prefix}base_link"/>
<child link="${prefix}base"/>
</joint>

<!-- ROS-Industrial 'flange' frame: attachment point for EEF models -->
<link name="${prefix}flange" />
<joint name="${prefix}joint_6-flange" type="fixed">
<origin xyz="0 0 0" rpy="0 ${radians(-90.0)} 0" />
<parent link="${prefix}link_6" />
<child link="${prefix}flange" />
</joint>

<!-- ROS-Industrial 'tool0' frame: all-zeros tool frame -->
<link name="${prefix}tool0" />
<joint name="${prefix}flange-tool0" type="fixed">
<origin xyz="0 0 0" rpy="0 ${radians(90.0)} 0" />
<parent link="${prefix}flange" />
<child link="${prefix}tool0" />
</joint>
</xacro:macro>
</robot>

0 comments on commit 43b1479

Please sign in to comment.