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 description for LBR IIWA 7 R800 #31

Open
wants to merge 6 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
5 changes: 5 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -50,3 +50,8 @@ qtcreator-*

# Catkin custom files
CATKIN_IGNORE

# blender temp saves
*.blend1
# mac osx DS_Store files
*.DS_Store
3 changes: 3 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,3 @@
<launch>
<param name="robot_description" command="$(find xacro)/xacro.py '$(find kuka_lbr_iiwa_support)/urdf/lbr_iiwa_7_r800.xacro'" />
</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.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.

Large diffs are not rendered by default.

Large diffs are not rendered by default.

Large diffs are not rendered by default.

Large diffs are not rendered by default.

Large diffs are not rendered by default.

Large diffs are not rendered by default.

Large diffs are not rendered by default.

Large diffs are not rendered by default.

265 changes: 265 additions & 0 deletions kuka_lbr_iiwa_support/meshes/lbr_iiwa_7_r800/visual/base_link.dae

Large diffs are not rendered by default.

265 changes: 265 additions & 0 deletions kuka_lbr_iiwa_support/meshes/lbr_iiwa_7_r800/visual/link_1.dae

Large diffs are not rendered by default.

235 changes: 235 additions & 0 deletions kuka_lbr_iiwa_support/meshes/lbr_iiwa_7_r800/visual/link_2.dae

Large diffs are not rendered by default.

337 changes: 337 additions & 0 deletions kuka_lbr_iiwa_support/meshes/lbr_iiwa_7_r800/visual/link_3.dae

Large diffs are not rendered by default.

301 changes: 301 additions & 0 deletions kuka_lbr_iiwa_support/meshes/lbr_iiwa_7_r800/visual/link_4.dae

Large diffs are not rendered by default.

337 changes: 337 additions & 0 deletions kuka_lbr_iiwa_support/meshes/lbr_iiwa_7_r800/visual/link_5.dae

Large diffs are not rendered by default.

301 changes: 301 additions & 0 deletions kuka_lbr_iiwa_support/meshes/lbr_iiwa_7_r800/visual/link_6.dae

Large diffs are not rendered by default.

301 changes: 301 additions & 0 deletions kuka_lbr_iiwa_support/meshes/lbr_iiwa_7_r800/visual/link_7.dae

Large diffs are not rendered by default.

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://ros.org/wiki/xacro">
<xacro:include filename="$(find kuka_lbr_iiwa_support)/urdf/lbr_iiwa_7_r800_macro.xacro"/>
<xacro:kuka_lbr_iiwa_7_r800 prefix=""/>
</robot>
187 changes: 187 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,187 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<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.dae" />
</geometry>
</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.dae" />
</geometry>
</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.dae" />
</geometry>
</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.dae" />
</geometry>
</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.dae" />
</geometry>
</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.dae" />
</geometry>
</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.dae" />
</geometry>
</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>
<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/link_7.dae" />
</geometry>
</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_7.stl" />
</geometry>
</collision>
</link>
<link name="${prefix}tool0" />
<!-- end of link list -->

<!-- joint list -->
<joint name="${prefix}joint_a1" type="revolute">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="${prefix}base_link" />
<child link="${prefix}link_1" />
<axis xyz="0 0 1" />
<limit lower="-2.9668" upper="2.9668" effort="0" velocity="1.4834" />
</joint>
<joint name="${prefix}joint_a2" type="revolute">
<origin xyz="-0.00043624 0 0.34" rpy="0 0 0" />
<parent link="${prefix}link_1" />
<child link="${prefix}link_2" />
<axis xyz="0 1 0" />
<limit lower="-2.0942" upper="2.0942" effort="0" velocity="1.4834" />
</joint>
<joint name="${prefix}joint_a3" type="revolute">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="${prefix}link_2" />
<child link="${prefix}link_3" />
<axis xyz="0 0 1" />
<limit lower="-2.9668" upper="2.9668" effort="0" velocity="1.7452" />
</joint>
<joint name="${prefix}joint_a4" type="revolute">
<origin xyz="0.00043624 0 0.40" rpy="0 0 0" />
<parent link="${prefix}link_3" />
<child link="${prefix}link_4" />
<axis xyz="0 -1 0" />
<limit lower="-2.0942" upper="2.0942" effort="0" velocity="1.3089" />
</joint>
<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 0 1" />
<limit lower="-2.9668" upper="2.9668" effort="0" velocity="2.2688" />
</joint>
<joint name="${prefix}joint_a6" type="revolute">
<origin xyz="0 0 0.4" rpy="0 0 0" />
<parent link="${prefix}link_5" />
<child link="${prefix}link_6" />
<axis xyz="0 1 0" />
<limit lower="-2.0942" upper="2.0942" effort="0" velocity="2.356" />
</joint>
<joint name="${prefix}joint_a7" type="revolute">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="${prefix}link_6" />
<child link="${prefix}link_7" />
<axis xyz="0 0 1" />
<limit lower="-3.0541" upper="3.0541" effort="0" velocity="2.356" />
</joint>
<joint name="${prefix}joint_a7-tool0" type="fixed">
<origin xyz="0 0 0.126" 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>