Skip to content

Commit

Permalink
Include a new link called flange to the available robot descriptions (r…
Browse files Browse the repository at this point in the history
…os-industrial#195)

* Following REP199, include a new link called flange to attach EEFs instead of the previous tool0

* Replace pi and DEG2RAD xacro properties with radians()
  • Loading branch information
andreflorindo authored Sep 28, 2021
1 parent 132187b commit 652600d
Show file tree
Hide file tree
Showing 9 changed files with 165 additions and 90 deletions.
18 changes: 13 additions & 5 deletions kuka_kr10_support/urdf/kr10r1100sixx_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -109,8 +109,8 @@
</geometry>
</collision>
</link>
<!-- This frame corresponds to the $FLANGE coordinate system in KUKA KRC controllers. -->
<link name="${prefix}tool0"/>
<!-- Following REP199, this frame shall be use to attach EEF or other equipment -->
<link name="${prefix}flange" />

<joint name="${prefix}joint_a1" type="revolute">
<origin xyz="0 0 0.400" rpy="0 0 0"/>
Expand Down Expand Up @@ -154,10 +154,10 @@
<axis xyz="-1 0 0"/>
<limit effort="0" lower="${radians(-350)}" upper="${radians(350)}" velocity="${radians(492)}"/>
</joint>
<joint name="${prefix}joint_a6-tool0" type="fixed">
<joint name="${prefix}joint_a6-flange" type="fixed">
<parent link="${prefix}link_6"/>
<child link="${prefix}tool0"/>
<origin xyz="0 0 0" rpy="0 ${radians(90)} 0"/>
<child link="${prefix}flange"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
</joint>

<!-- ROS base_link to KUKA $ROBROOT coordinate system transform -->
Expand All @@ -167,5 +167,13 @@
<parent link="${prefix}base_link"/>
<child link="${prefix}base"/>
</joint>

<!-- This frame corresponds to the $TOOL coordinate system in KUKA KRC controllers -->
<link name="${prefix}tool0" />
<joint name="${prefix}flange-tool0" type="fixed">
<parent link="${prefix}flange"/>
<child link="${prefix}tool0"/>
<origin xyz="0 0 0" rpy="0 ${radians(90)} 0"/>
</joint>
</xacro:macro>
</robot>
32 changes: 18 additions & 14 deletions kuka_kr120_support/urdf/kr120r2500pro_macro.xacro
Original file line number Diff line number Diff line change
@@ -1,8 +1,6 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">

<xacro:property name="DEG2RAD" value="0.017453292519943295"/>

<xacro:macro name="kuka_kr120r2500pro" params="prefix">
<!-- LINKS -->
<!-- base link -->
Expand Down Expand Up @@ -145,9 +143,8 @@
</geometry>
</collision>
</link>
<!-- tool 0 -->
<!-- This frame corresponds to the $FLANGE coordinate system in KUKA KRC controllers. -->
<link name="${prefix}tool0"/>
<!-- Following REP199, this frame shall be use to attach EEF or other equipment -->
<link name="${prefix}flange" />
<!-- END LINKS -->

<!-- JOINTS -->
Expand All @@ -157,53 +154,53 @@
<parent link="${prefix}base_link"/>
<child link="${prefix}link_1"/>
<axis xyz="0 0 -1"/>
<limit effort="0" lower="${-DEG2RAD * 185}" upper="${DEG2RAD * 185}" velocity="${DEG2RAD * 156}"/>
<limit effort="0" lower="${-radians(185)}" upper="${radians(185)}" velocity="${radians(156)}"/>
</joint>
<!-- joint 2 (A2) -->
<joint name="${prefix}joint_a2" type="revolute">
<origin xyz="0.35 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_1"/>
<child link="${prefix}link_2"/>
<axis xyz="0 1 0"/>
<limit effort="0" lower="${-DEG2RAD * 155}" upper="${DEG2RAD * 35}" velocity="${DEG2RAD * 156}"/>
<limit effort="0" lower="${-radians(155)}" upper="${radians(35)}" velocity="${radians(156)}"/>
</joint>
<!-- joint 3 (A3) -->
<joint name="${prefix}joint_a3" type="revolute">
<origin xyz="1.150 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_2"/>
<child link="${prefix}link_3"/>
<axis xyz="0 1 0"/>
<limit effort="0" lower="${-DEG2RAD * 130}" upper="${DEG2RAD * 154}" velocity="${DEG2RAD * 156}"/>
<limit effort="0" lower="${-radians(130)}" upper="${radians(154)}" velocity="${radians(156)}"/>
</joint>
<!-- joint 4 (A4) -->
<joint name="${prefix}joint_a4" type="revolute">
<origin xyz="1.0 0 -0.041" rpy="0 0 0"/>
<parent link="${prefix}link_3"/>
<child link="${prefix}link_4"/>
<axis xyz="-1 0 0"/>
<limit effort="0" lower="${-DEG2RAD * 350}" upper="${DEG2RAD * 350}" velocity="${DEG2RAD * 330}"/>
<limit effort="0" lower="${-radians(350)}" upper="${radians(350)}" velocity="${radians(330)}"/>
</joint>
<!-- joint 5 (A5) -->
<joint name="${prefix}joint_a5" type="revolute">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_4"/>
<child link="${prefix}link_5"/>
<axis xyz="0 1 0"/>
<limit effort="0" lower="${-DEG2RAD * 130}" upper="${DEG2RAD * 130}" velocity="${DEG2RAD * 330}"/>
<limit effort="0" lower="${-radians(130)}" upper="${radians(130)}" velocity="${radians(330)}"/>
</joint>
<!-- joint 6 (A6) -->
<joint name="${prefix}joint_a6" type="revolute">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_5"/>
<child link="${prefix}link_6"/>
<axis xyz="-1 0 0"/>
<limit effort="0" lower="${-DEG2RAD * 350}" upper="${DEG2RAD * 350}" velocity="${DEG2RAD * 615}"/>
<limit effort="0" lower="${-radians(350)}" upper="${radians(350)}" velocity="${radians(615)}"/>
</joint>
<!-- tool frame - fixed frame -->
<joint name="${prefix}joint_a6-tool0" type="fixed">
<joint name="${prefix}joint_a6-flange" type="fixed">
<parent link="${prefix}link_6"/>
<child link="${prefix}tool0"/>
<origin xyz="0.215 0 0" rpy="0 ${DEG2RAD * 90} 0"/>
<child link="${prefix}flange"/>
<origin xyz="0.215 0 0" rpy="0 0 0"/>
</joint>
<!-- END JOINTS -->

Expand All @@ -215,6 +212,13 @@
<child link="${prefix}base"/>
</joint>

<!-- This frame corresponds to the $TOOL coordinate system in KUKA KRC controllers -->
<link name="${prefix}tool0" />
<joint name="${prefix}flange-tool0" type="fixed">
<parent link="${prefix}flange"/>
<child link="${prefix}tool0"/>
<origin xyz="0 0 0" rpy="0 ${radians(90)} 0"/>
</joint>
</xacro:macro>
</robot>

Expand Down
24 changes: 16 additions & 8 deletions kuka_kr150_support/urdf/kr150_2_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -109,8 +109,8 @@
</collision>
</link>
<!-- tool link -->
<!-- This frame corresponds to the $FLANGE coordinate system in KUKA KRC controllers. -->
<link name="${prefix}tool0"/>
<!-- This frame corresponds to the $TOOL coordinate system in KUKA KRC controllers. -->
<link name="${prefix}flange"/>
<!-- END LINKS -->

<!-- JOINTS -->
Expand Down Expand Up @@ -163,19 +163,27 @@
<limit effort="0" lower="${radians(-350)}" upper="${radians(350)}" velocity="${radians(238)}"/>
</joint>
<!-- tool frame - fixed frame -->
<joint name="${prefix}joint_a6-tool0" type="fixed">
<joint name="${prefix}joint_a6-flange" type="fixed">
<parent link="${prefix}link_6"/>
<child link="${prefix}tool0"/>
<origin xyz="0 0 0" rpy="0 ${pi/2} 0"/>
<child link="${prefix}flange"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
</joint>
<!-- END JOINTS -->

<!-- ROS base_link to KUKA $ROBROOT coordinate system transform -->
<link name="${prefix}base" />
<joint name="${prefix}base_link-base" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="${prefix}base_link" />
<child link="${prefix}base" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="${prefix}base_link"/>
<child link="${prefix}base"/>
</joint>

<!-- This frame corresponds to the $TOOL coordinate system in KUKA KRC controllers -->
<link name="${prefix}tool0" />
<joint name="${prefix}flange-tool0" type="fixed">
<parent link="${prefix}flange"/>
<child link="${prefix}tool0"/>
<origin xyz="0 0 0" rpy="0 ${radians(90)} 0"/>
</joint>

</xacro:macro>
Expand Down
18 changes: 13 additions & 5 deletions kuka_kr16_support/urdf/kr16_2_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -144,8 +144,8 @@
</collision>
</link>
<!-- tool 0 -->
<!-- This frame corresponds to the $FLANGE coordinate system in KUKA KRC controllers. -->
<link name="${prefix}tool0"/>
<!-- Following REP199, this frame shall be use to attach EEF or other equipment -->
<link name="${prefix}flange" />
<!-- END LINKS -->

<!-- JOINTS -->
Expand Down Expand Up @@ -198,10 +198,10 @@
<limit effort="0" lower="${radians(-350)}" upper="${radians(350)}" velocity="${radians(615)}"/>
</joint>
<!-- tool frame - fixed frame -->
<joint name="${prefix}joint_a6-tool0" type="fixed">
<joint name="${prefix}joint_a6-flange" type="fixed">
<parent link="${prefix}link_6"/>
<child link="${prefix}tool0"/>
<origin xyz="0.158 0 0" rpy="0 ${radians(90)} 0"/>
<child link="${prefix}flange"/>
<origin xyz="0.158 0 0" rpy="0 0 0"/>
</joint>
<!-- END JOINTS -->

Expand All @@ -213,5 +213,13 @@
<child link="${prefix}base"/>
</joint>

<!-- This frame corresponds to the $TOOL coordinate system in KUKA KRC controllers -->
<link name="${prefix}tool0" />
<joint name="${prefix}flange-tool0" type="fixed">
<parent link="${prefix}flange"/>
<child link="${prefix}tool0"/>
<origin xyz="0 0 0" rpy="0 ${radians(90)} 0"/>
</joint>

</xacro:macro>
</robot>
51 changes: 32 additions & 19 deletions kuka_kr210_support/urdf/kr210l150_macro.xacro
Original file line number Diff line number Diff line change
@@ -1,8 +1,5 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<property name="pi" value="3.141592654"/>
<!--degrees to radians-->
<property name="deg" value="0.017453293"/>

<xacro:macro name="kuka_kr210l150" params="prefix">
<!-- links -->
Expand All @@ -13,7 +10,7 @@
<inertia ixx="89.282" ixy="-0.47721" ixz="0.85562" iyy="107.51" iyz="0.0067576" izz="172.02"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="${-pi/2} 0 0"/>
<origin xyz="0 0 0" rpy="${-radians(90)} 0 0"/>
<geometry>
<mesh filename="package://kuka_kr210_support/meshes/kr210l150/visual/base_link.dae"/>
</geometry>
Expand All @@ -22,7 +19,7 @@
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="${-pi/2} 0 0"/>
<origin xyz="0 0 0" rpy="${-radians(90)} 0 0"/>
<geometry>
<mesh filename="package://kuka_kr210_support/meshes/kr210l150/collision/base_link.stl"/>
</geometry>
Expand Down Expand Up @@ -57,7 +54,7 @@
<inertia ixx="180.42" ixy="-0.83462" ixz="0.32549" iyy="177.68" iyz="-20.82" izz="20.495"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="${-pi/2} 0 0"/>
<origin xyz="0 0 0" rpy="${-radians(90)} 0 0"/>
<geometry>
<mesh filename="package://kuka_kr210_support/meshes/kr210l150/visual/link_2.dae"/>
</geometry>
Expand All @@ -79,7 +76,7 @@
<inertia ixx="11.887" ixy="-0.12154" ixz="-1.3604" iyy="98.805" iyz="-0.056505" izz="96.251"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="${-pi/2} 0 0"/>
<origin xyz="0 0 0" rpy="${-radians(90)} 0 0"/>
<geometry>
<mesh filename="package://kuka_kr210_support/meshes/kr210l150/visual/link_3.dae"/>
</geometry>
Expand All @@ -101,7 +98,7 @@
<inertia ixx="1.8001" ixy="-0.18515" ixz="0.00051232" iyy="5.514" iyz="0.00070469" izz="6.3498"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="${-pi/2} 0 0"/>
<origin xyz="0 0 0" rpy="${-radians(90)} 0 0"/>
<geometry>
<mesh filename="package://kuka_kr210_support/meshes/kr210l150/visual/link_4.dae"/>
</geometry>
Expand All @@ -123,7 +120,7 @@
<inertia ixx="0.3938" ixy="-0.085332" ixz="1.7223E-06" iyy="0.68945" iyz="-7.0292E-06" izz="0.67292"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="${-pi/2} 0 0"/>
<origin xyz="0 0 0" rpy="${-radians(90)} 0 0"/>
<geometry>
<mesh filename="package://kuka_kr210_support/meshes/kr210l150/visual/link_5.dae"/>
</geometry>
Expand Down Expand Up @@ -160,58 +157,74 @@
</geometry>
</collision>
</link>
<!-- This frame corresponds to the $FLANGE coordinate system in KUKA KRC controllers. -->
<link name="${prefix}tool0"/>
<!-- This frame corresponds to the $TOOL coordinate system in KUKA KRC controllers. -->
<link name="${prefix}flange"/>

<!-- joints -->
<joint name="${prefix}joint_a1" type="revolute">
<origin xyz="-0.00262 0.00097586 0.33099" rpy="0 0 0"/>
<parent link="${prefix}base_link"/>
<child link="${prefix}link_1"/>
<axis xyz="0 0 1"/>
<limit lower="${-185*deg}" upper="${185*deg}" effort="0" velocity="${123*deg}"/>
<limit lower="${radians(-185)}" upper="${radians(185)}" effort="0" velocity="${radians(123)}"/>
</joint>
<joint name="${prefix}joint_a2" type="revolute">
<origin xyz="0.35277 -0.037476 0.4192" rpy="0 0 0"/>
<parent link="${prefix}link_1"/>
<child link="${prefix}link_2"/>
<axis xyz="0 1 0"/>
<limit lower="${-45*deg}" upper="${85*deg}" effort="0" velocity="${115*deg}"/>
<limit lower="${radians(-45)}" upper="${radians(85)}" effort="0" velocity="${radians(115)}"/>
</joint>
<joint name="${prefix}joint_a3" type="revolute">
<origin xyz="-9.8483E-05 -0.1475 1.2499" rpy="0 0 0"/>
<parent link="${prefix}link_2"/>
<child link="${prefix}link_3"/>
<axis xyz="0 1 0"/>
<limit lower="${-210*deg}" upper="${(155-90)*deg}" effort="0" velocity="${112*deg}"/>
<limit lower="${radians(-210)}" upper="${radians(65)}" effort="0" velocity="${radians(112)}"/>
</joint>
<joint name="${prefix}joint_a4" type="revolute">
<origin xyz="0.95795 0.184 -0.055059" rpy="0 0 0"/>
<parent link="${prefix}link_3"/>
<child link="${prefix}link_4"/>
<axis xyz="1 0 0"/>
<limit lower="${-350*deg}" upper="${350*deg}" effort="0" velocity="${179*deg}"/>
<limit lower="${radians(-350)}" upper="${radians(350)}" effort="0" velocity="${radians(179)}"/>
</joint>
<joint name="${prefix}joint_a5" type="revolute">
<origin xyz="0.542 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_4"/>
<child link="${prefix}link_5"/>
<axis xyz="0 1 0"/>
<limit lower="${-125*deg}" upper="${125*deg}" effort="0" velocity="${172*deg}"/>
<limit lower="${radians(-125)}" upper="${radians(125)}" effort="0" velocity="${radians(172)}"/>
</joint>
<joint name="${prefix}joint_a6" type="revolute">
<origin xyz="0.1925 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_5"/>
<child link="${prefix}link_6"/>
<axis xyz="1 0 0"/>
<limit lower="${-350*deg}" upper="${350*deg}" effort="0" velocity="${219*deg}"/>
<limit lower="${radians(-350)}" upper="${radians(350)}" effort="0" velocity="${radians(219)}"/>
</joint>
<joint name="${prefix}link_6-tool0" type="fixed">
<joint name="${prefix}link_6-flange" type="fixed">
<parent link="${prefix}link_6"/>
<child link="${prefix}tool0"/>
<child link="${prefix}flange"/>
<origin xyz="0.0375 0 -0.00023924" rpy="0 0 0"/>
</joint>

<!-- ROS base_link to KUKA $ROBROOT coordinate system transform -->
<link name="${prefix}base" />
<joint name="${prefix}base_link-base" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="${prefix}base_link"/>
<child link="${prefix}base"/>
</joint>

<!-- This frame corresponds to the $TOOL coordinate system in KUKA KRC controllers -->
<link name="${prefix}tool0" />
<joint name="${prefix}flange-tool0" type="fixed">
<parent link="${prefix}flange"/>
<child link="${prefix}tool0"/>
<origin xyz="0 0 0" rpy="0 ${radians(90)} 0"/>
</joint>

<!-- rename 'Link1' to 'link_1', maintain bw-compatibility -->
<link name="${prefix}Link1"/>
<joint name="${prefix}Link1-link_1" type="fixed">
Expand Down
Loading

0 comments on commit 652600d

Please sign in to comment.