Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Kr300 r2700-2 support #239

Open
wants to merge 5 commits into
base: melodic-devel
Choose a base branch
from
Open
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
3 changes: 2 additions & 1 deletion kuka_experimental/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
<exec_depend>kuka_kr150_support</exec_depend>
<exec_depend>kuka_kr16_support</exec_depend>
<exec_depend>kuka_kr210_support</exec_depend>
<exec_depend>kuka_kr300_support</exec_depend>
<exec_depend>kuka_kr5_support</exec_depend>
<exec_depend>kuka_kr6_support</exec_depend>
<exec_depend>kuka_lbr_iiwa_support</exec_depend>
Expand All @@ -29,4 +30,4 @@
<export>
<metapackage/>
</export>
</package>
</package>
14 changes: 14 additions & 0 deletions kuka_kr300_support/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
cmake_minimum_required(VERSION 3.0.2)
project(kuka_kr300_support)

find_package(catkin REQUIRED)

catkin_package()

if (CATKIN_ENABLE_TESTING)
find_package(roslaunch REQUIRED)
roslaunch_add_file_check(test/roslaunch_test.xml)
endif()

install(DIRECTORY config launch meshes urdf
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
1 change: 1 addition & 0 deletions kuka_kr300_support/config/joint_names_kr300r2700_2.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
controller_joint_names: ['joint_a1', 'joint_a2', 'joint_a3', 'joint_a4', 'joint_a5', 'joint_a6']
3 changes: 3 additions & 0 deletions kuka_kr300_support/launch/load_kr300r2700_2.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
<launch>
<param name="robot_description" command="$(find xacro)/xacro '$(find kuka_kr300_support)/urdf/kr300r2700_2.xacro'"/>
</launch>
8 changes: 8 additions & 0 deletions kuka_kr300_support/launch/test_kr300r2700_2.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
<launch>
<include file="$(find kuka_kr300_support)/launch/load_kr300r2700_2.launch"/>
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
<param name="use_gui" value="true"/>
</node>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find industrial_robot_client)/config/robot_state_visualize.rviz" required="true"/>
</launch>
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
142 changes: 142 additions & 0 deletions kuka_kr300_support/meshes/kr300r2700_2/visual/base_link.dae

Large diffs are not rendered by default.

115 changes: 115 additions & 0 deletions kuka_kr300_support/meshes/kr300r2700_2/visual/link_1.dae

Large diffs are not rendered by default.

115 changes: 115 additions & 0 deletions kuka_kr300_support/meshes/kr300r2700_2/visual/link_2.dae

Large diffs are not rendered by default.

141 changes: 141 additions & 0 deletions kuka_kr300_support/meshes/kr300r2700_2/visual/link_3.dae

Large diffs are not rendered by default.

115 changes: 115 additions & 0 deletions kuka_kr300_support/meshes/kr300r2700_2/visual/link_4.dae

Large diffs are not rendered by default.

115 changes: 115 additions & 0 deletions kuka_kr300_support/meshes/kr300r2700_2/visual/link_5.dae

Large diffs are not rendered by default.

89 changes: 89 additions & 0 deletions kuka_kr300_support/meshes/kr300r2700_2/visual/link_6.dae

Large diffs are not rendered by default.

47 changes: 47 additions & 0 deletions kuka_kr300_support/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
<?xml version="1.0"?>
<package format="2">
<name>kuka_kr300_support</name>
<version>0.1.0</version>
<description>
<p>
ROS-Industrial support for the KUKA KR 300 (and variants).
</p>
<p>
This package contains configuration data, 3D models and launch files
for KUKA KR 300 manipulators. This currently includes the r2700_2 only.
</p>
<p><b>Specifications</b>:</p>
<ul>
<li>KR 300 r2700_2 - Default</li>
</ul>
<p> Joint limits and maximum joint velocities are based on the information found in the online <a href="https://www.kuka.com/-/media/kuka-downloads/imported/8350ff3ca11642998dbdc81dcc2ed44c/0000325893_en.pdf">datasheet</a>. All urdfs are based on the default motion and joint velocity limits, unless noted otherwise. </p>
<p>
Before using any of the configuration files and / or meshes included
in this package, be sure to check they are correct for the particular
robot model and configuration you intend to use them with.
</p>
<p>
<b>NB</b>: this package currently uses non-valid inertia parameters. </p>
</description>
<author>Shaun Edwards</author>
<maintainer email="[email protected]">Iñigo Moreno</maintainer>
<license>BSD</license>

<url type="website">http://wiki.ros.org/kuka_kr300_support</url>
<url type="bugtracker">https://github.com/ros-industrial/kuka_experimental/issues</url>
<url type="repository">https://github.com/ros-industrial/kuka_experimental</url>

<buildtool_depend>catkin</buildtool_depend>

<test_depend>roslaunch</test_depend>

<exec_depend>industrial_robot_client</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/>
</export>
</package>
9 changes: 9 additions & 0 deletions kuka_kr300_support/test/roslaunch_test.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
<launch>
<group ns="load_kr300r2700_2__">
<include file="$(find kuka_kr300_support)/launch/load_kr300r2700_2.launch"/>
</group>

<group ns="test_kr300r2700_2__">
<include file="$(find kuka_kr300_support)/launch/test_kr300r2700_2.launch"/>
</group>
</launch>
5 changes: 5 additions & 0 deletions kuka_kr300_support/urdf/kr300r2700_2.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
<?xml version="1.0"?>
<robot name="kuka_kr300" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:include filename="$(find kuka_kr300_support)/urdf/kr300r2700_2_macro.xacro"/>
<xacro:kuka_kr300r2700_2 prefix=""/>
</robot>
218 changes: 218 additions & 0 deletions kuka_kr300_support/urdf/kr300r2700_2_macro.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,218 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">

<xacro:macro name="kuka_kr300r2700_2" params="prefix">
<!-- links -->
<link name="${prefix}base_link">
<inertial>
<origin xyz="-0.027804 0.00039112 0.14035" rpy="0 0 0"/>
<mass value="1572.9"/>
<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="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr300_support/meshes/kr300r2700_2/visual/base_link.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr300_support/meshes/kr300r2700_2/collision/base_link.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_1">
<inertial>
<origin xyz="-0.036811 -0.024697 0.56577" rpy="0 0 0"/>
<mass value="1385.5"/>
<inertia ixx="90.873" ixy="33.809" ixz="17.159" iyy="147.03" iyz="0.063634" izz="168.19"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr300_support/meshes/kr300r2700_2/visual/link_1.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr300_support/meshes/kr300r2700_2/collision/link_1.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_2">
<inertial>
<origin xyz="0.016923 -0.19196 0.44751" rpy="0 0 0"/>
<mass value="958.62"/>
<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="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr300_support/meshes/kr300r2700_2/visual/link_2.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr300_support/meshes/kr300r2700_2/collision/link_2.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_3">
<inertial>
<origin xyz="0.18842 0.18344 -0.042799" rpy="0 0 0"/>
<mass value="710.03"/>
<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="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr300_support/meshes/kr300r2700_2/visual/link_3.dae"/>
</geometry>
<material name="">
<color rgba="0.75294 0.75294 0.75294 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr300_support/meshes/kr300r2700_2/collision/link_3.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_4">
<inertial>
<origin xyz="0.27146 -0.007326 5.2775E-05" rpy="0 0 0"/>
<mass value="173.73"/>
<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="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr300_support/meshes/kr300r2700_2/visual/link_4.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr300_support/meshes/kr300r2700_2/collision/link_4.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_5">
<inertial>
<origin xyz="0.04379 0.025984 3.5491E-07" rpy="0 0 0"/>
<mass value="72.17"/>
<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="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr300_support/meshes/kr300r2700_2/visual/link_5.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr300_support/meshes/kr300r2700_2/collision/link_5.stl"/>
</geometry>
</collision>
</link>
<link name="${prefix}link_6">
<inertial>
<origin xyz="-0.017956 -1.5237E-05 0.00015484" rpy="0 0 0"/>
<mass value="6.3154"/>
<inertia ixx="0.031746" ixy="1.7673E-07" ixz="-6.6558E-06" iyy="0.016686" iyz="1.4304E-07" izz="0.016723"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr300_support/meshes/kr300r2700_2/visual/link_6.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr300_support/meshes/kr300r2700_2/collision/link_6.stl"/>
</geometry>
</collision>
</link>
<!-- 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 0 0.245" rpy="0 0 0"/>
<parent link="${prefix}base_link"/>
<child link="${prefix}link_1"/>
<axis xyz="0 0 1"/>
<limit lower="${radians(-185)}" upper="${radians(185)}" effort="0" velocity="${radians(105)}"/>
</joint>
<joint name="${prefix}joint_a2" type="revolute">
<origin xyz="0.33 0.09 0.4" rpy="0 0 0"/>
<parent link="${prefix}link_1"/>
<child link="${prefix}link_2"/>
<axis xyz="0 1 0"/>
<limit lower="${radians(-55)}" upper="${radians(85)}" effort="0" velocity="${radians(101)}"/>
</joint>
<joint name="${prefix}joint_a3" type="revolute">
<origin xyz="0 -0.195 1.15" rpy="0 0 0"/>
<parent link="${prefix}link_2"/>
<child link="${prefix}link_3"/>
<axis xyz="0 1 0"/>
<limit lower="${radians(-210)}" upper="${radians(78)}" effort="0" velocity="${radians(107)}"/>
</joint>
<joint name="${prefix}joint_a4" type="revolute">
<origin xyz="0.8685 0.105 0.115" rpy="0 0 0"/>
<parent link="${prefix}link_3"/>
<child link="${prefix}link_4"/>
<axis xyz="1 0 0"/>
<limit lower="${radians(-350)}" upper="${radians(350)}" effort="0" velocity="${radians(140)}"/>
</joint>
<joint name="${prefix}joint_a5" type="revolute">
<origin xyz="0.3515 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_4"/>
<child link="${prefix}link_5"/>
<axis xyz="0 1 0"/>
<limit lower="${radians(-122.5)}" upper="${radians(122.5)}" effort="0" velocity="${radians(113)}"/>
</joint>
<joint name="${prefix}joint_a6" type="revolute">
<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(-350)}" upper="${radians(350)}" effort="0" velocity="${radians(180)}"/>
</joint>
<joint name="${prefix}link_6-flange" type="fixed">
<parent link="${prefix}link_6"/>
<child link="${prefix}flange"/>
<origin xyz="0.04 0 0" 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">
<parent link="${prefix}link_1"/>
<child link="${prefix}Link1"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
</joint>
</xacro:macro>
</robot>