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

robot model for lbr_iiwa_7_r800 #117

Open
wants to merge 9 commits into
base: melodic-devel
Choose a base branch
from
23 changes: 8 additions & 15 deletions kuka_lbr_iiwa_support/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,23 +1,16 @@
cmake_minimum_required(VERSION 2.8.3)

project(kuka_lbr_iiwa_support)

find_package(catkin REQUIRED)

catkin_package()

install(DIRECTORY config launch urdf
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})

# temporarily: until sources are moved to other org/rep
install(
DIRECTORY
meshes/lbr_iiwa_14_r820/collision
DESTINATION
${CATKIN_PACKAGE_SHARE_DESTINATION}/meshes/lbr_iiwa_14_r820/)
if (CATKIN_ENABLE_TESTING)
find_package(roslaunch REQUIRED)
roslaunch_add_file_check(test/roslaunch_test_lbr_iiwa_7_r800.xml)
roslaunch_add_file_check(test/roslaunch_test_lbr_iiwa_14_r820.xml)
endif()

# temporarily: until sources are moved to other org/rep
install(
DIRECTORY
meshes/lbr_iiwa_14_r820/visual
DESTINATION
${CATKIN_PACKAGE_SHARE_DESTINATION}/meshes/lbr_iiwa_14_r820/)
install(DIRECTORY config launch meshes urdf
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
5 changes: 5 additions & 0 deletions kuka_lbr_iiwa_support/launch/load_lbr_iiwa_7_r800.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
<?xml version="1.0"?>
<launch>
<arg name="flange_type" default="basic" />
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find kuka_lbr_iiwa_support)/urdf/lbr_iiwa_7_r800.xacro' flange_type:=$(arg flange_type)" />
</launch>
10 changes: 10 additions & 0 deletions kuka_lbr_iiwa_support/launch/test_lbr_iiwa_7_r800.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
<?xml version="1.0"?>
<launch>
<arg name="flange_type" default="basic" />
<include file="$(find kuka_lbr_iiwa_support)/launch/load_lbr_iiwa_7_r800.launch" pass_all_args="true" />
<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.
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.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
<launch>
<group ns="load_lbr_iiwa_14_r820__">
<include file="$(find kuka_lbr_iiwa_support)/launch/load_lbr_iiwa_14_r820.launch"/>
</group>

<group ns="test_lbr_iiwa_14_r820__">
<include file="$(find kuka_lbr_iiwa_support)/launch/test_lbr_iiwa_14_r820.launch"/>
</group>
</launch>
9 changes: 9 additions & 0 deletions kuka_lbr_iiwa_support/test/roslaunch_test_lbr_iiwa_7_r800.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
<launch>
<group ns="load_lbr_iiwa_7_r800__">
<include file="$(find kuka_lbr_iiwa_support)/launch/load_lbr_iiwa_7_r800.launch"/>
</group>

<group ns="test_lbr_iiwa_7_r800__">
<include file="$(find kuka_lbr_iiwa_support)/launch/test_lbr_iiwa_7_r800.launch"/>
</group>
</launch>
5 changes: 5 additions & 0 deletions kuka_lbr_iiwa_support/urdf/lbr_iiwa_7_r800.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
<?xml version="1.0" ?>
<robot name="kuka_lbr_iiwa_7_r800" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:include filename="$(find kuka_lbr_iiwa_support)/urdf/lbr_iiwa_7_r800_macro.xacro"/>
<xacro:kuka_lbr_iiwa_7_r800 prefix=""/>
</robot>
182 changes: 182 additions & 0 deletions kuka_lbr_iiwa_support/urdf/lbr_iiwa_7_r800_macro.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,182 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:include filename="$(find kuka_resources)/urdf/common_materials.xacro"/>
<xacro:include filename="$(find kuka_lbr_iiwa_support)/urdf/lbr_iiwa_flanges_macro.xacro"/>

<!-- current support for the following values: basic, pneumatic_touch -->
<xacro:arg name="flange_type" default="basic" />

<xacro:macro name="kuka_lbr_iiwa_7_r800" params="prefix">
<!-- link list -->
<link name="${prefix}base_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://kuka_lbr_iiwa_support/meshes/lbr_iiwa_7_r800/visual/base_link.stl" />
</geometry>
<xacro:material_kuka_ral_pearly_white />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://kuka_lbr_iiwa_support/meshes/lbr_iiwa_7_r800/collision/base_link.stl" />
</geometry>
</collision>
</link>
<link name="${prefix}link_1">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://kuka_lbr_iiwa_support/meshes/lbr_iiwa_7_r800/visual/link_1.stl" />
</geometry>
<xacro:material_kuka_ral_pearly_white />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://kuka_lbr_iiwa_support/meshes/lbr_iiwa_7_r800/collision/link_1.stl" />
</geometry>
</collision>
</link>
<link name="${prefix}link_2">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://kuka_lbr_iiwa_support/meshes/lbr_iiwa_7_r800/visual/link_2.stl" />
</geometry>
<xacro:material_kuka_ral_pearly_white />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://kuka_lbr_iiwa_support/meshes/lbr_iiwa_7_r800/collision/link_2.stl" />
</geometry>
</collision>
</link>
<link name="${prefix}link_3">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://kuka_lbr_iiwa_support/meshes/lbr_iiwa_7_r800/visual/link_3.stl" />
</geometry>
<xacro:material_kuka_ral_pearly_white />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://kuka_lbr_iiwa_support/meshes/lbr_iiwa_7_r800/collision/link_3.stl" />
</geometry>
</collision>
</link>
<link name="${prefix}link_4">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://kuka_lbr_iiwa_support/meshes/lbr_iiwa_7_r800/visual/link_4.stl" />
</geometry>
<xacro:material_kuka_ral_pearly_white />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://kuka_lbr_iiwa_support/meshes/lbr_iiwa_7_r800/collision/link_4.stl" />
</geometry>
</collision>
</link>
<link name="${prefix}link_5">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://kuka_lbr_iiwa_support/meshes/lbr_iiwa_7_r800/visual/link_5.stl" />
</geometry>
<xacro:material_kuka_ral_pearly_white />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://kuka_lbr_iiwa_support/meshes/lbr_iiwa_7_r800/collision/link_5.stl" />
</geometry>
</collision>
</link>
<link name="${prefix}link_6">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://kuka_lbr_iiwa_support/meshes/lbr_iiwa_7_r800/visual/link_6.stl" />
</geometry>
<xacro:material_kuka_ral_pearly_white />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://kuka_lbr_iiwa_support/meshes/lbr_iiwa_7_r800/collision/link_6.stl" />
</geometry>

</collision>
</link>
<xacro:kuka_lbr_iiwa_flange_link prefix="${prefix}" flange_type="$(arg flange_type)"/>
<link name="${prefix}tool0" />
<!-- end of link list -->

<!-- joint list -->
<joint name="${prefix}joint_a1" type="revolute">
<origin xyz="0 0 0.34" 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(98)}" />
</joint>
<joint name="${prefix}joint_a2" type="revolute">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="${prefix}link_1" />
<child link="${prefix}link_2" />
<axis xyz="0 1 0" />
<limit lower="${radians(-120)}" upper="${radians(120)}" effort="0" velocity="${radians(98)}" />
</joint>
<joint name="${prefix}joint_a3" type="revolute">
<origin xyz="0 0 0.40" rpy="0 0 0" />
<parent link="${prefix}link_2" />
<child link="${prefix}link_3" />
<axis xyz="0 0 1" />
<limit lower="${radians(-170)}" upper="${radians(170)}" effort="0" velocity="${radians(100)}" />
</joint>
<joint name="${prefix}joint_a4" type="revolute">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="${prefix}link_3" />
<child link="${prefix}link_4" />
<axis xyz="0 -1 0" />
<limit lower="${radians(-120)}" upper="${radians(120)}" effort="0" velocity="${radians(130)}" />
</joint>
<joint name="${prefix}joint_a5" type="revolute">
<origin xyz="0 0 0.40" rpy="0 0 0" />
<parent link="${prefix}link_4" />
<child link="${prefix}link_5" />
<axis xyz="0 0 1" />
<limit lower="${radians(-170)}" upper="${radians(170)}" effort="0" velocity="${radians(140)}" />
</joint>
<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="0 1 0" />
<limit lower="${radians(-120)}" upper="${radians(120)}" effort="0" velocity="${radians(180)}" />
</joint>
<xacro:kuka_lbr_iiwa_flange_joint prefix="${prefix}" flange_type="$(arg flange_type)"/>
<joint name="${prefix}joint_a7-tool0" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="${prefix}link_7" />
<child link="${prefix}tool0" />
<axis xyz="0 0 0" />
</joint>
<!-- end of joint list -->

<!-- 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>
</xacro:macro>
</robot>

35 changes: 35 additions & 0 deletions kuka_lbr_iiwa_support/urdf/lbr_iiwa_flanges_macro.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:macro name="kuka_lbr_iiwa_flange_link" params="prefix flange_type" >
<link name="${prefix}link_7">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://kuka_lbr_iiwa_support/meshes/lbr_iiwa_7_r800/visual/flange_${flange_type}.stl" />
</geometry>
<xacro:material_kuka_ral_silver_gray />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://kuka_lbr_iiwa_support/meshes/lbr_iiwa_7_r800/collision/flange_${flange_type}.stl" />
</geometry>
</collision>
</link>
</xacro:macro>

<xacro:macro name="kuka_lbr_iiwa_flange_joint" params="prefix flange_type">
<joint name="${prefix}joint_a7" type="revolute">
<xacro:if value="${flange_type == 'basic'}">
<origin xyz="0 0 0.126" rpy="0 0 0" />
</xacro:if>
<xacro:if value="${flange_type == 'pneumatic_touch'}">
<origin xyz="0 0 0.152" rpy="0 0 0" />
</xacro:if>
<parent link="${prefix}link_6" />
<child link="${prefix}link_7" />
<axis xyz="0 0 1" />
<limit lower="${radians(-175)}" upper="${radians(175)}" effort="0" velocity="${radians(135)}" />
</joint>
</xacro:macro>
</robot>