diff --git a/.gitmodules b/.gitmodules
deleted file mode 100644
index ec18480ca747bad81c65d49f66de8fee807d9eff..0000000000000000000000000000000000000000
--- a/.gitmodules
+++ /dev/null
@@ -1,3 +0,0 @@
-[submodule "franka_description"]
-	path = franka_description
-	url = https://github.com/frankaemika/franka_description.git
diff --git a/CHANGELOG.md b/CHANGELOG.md
index 7e39d86d90fe94905a1a3e191b78e01d9be163b2..fda27b5c0eaafb54f870ed66bdd46e5fc213c216 100644
--- a/CHANGELOG.md
+++ b/CHANGELOG.md
@@ -1,5 +1,11 @@
 # CHANGELOG
 
+## 0.1.1 - UNRELEASED
+
+  * Integrate `franka_description` as subdirectory
+  * Fix dependencies on libfranka
+  * Fix RViz config file path in `franka_visualization`
+
 ## 0.1.0 - 2017-09-15
 
   * Initial release
diff --git a/franka_control/package.xml b/franka_control/package.xml
index 1d147fc43bb97d3c2dcc61c1fd86907a868d4e68..e4937458ce7b38ea708d18d5ac37d5760d6cf858 100644
--- a/franka_control/package.xml
+++ b/franka_control/package.xml
@@ -1,7 +1,7 @@
 <?xml version="1.0"?>
 <package format="2">
   <name>franka_control</name>
-  <version>0.1.0</version>
+  <version>0.1.1</version>
   <description>franka_control provides a hardware node to control a Franka Emika research robot</description>
   <maintainer email="info@franka.de">Franka Emika GmbH</maintainer>
   <license>Apache 2.0</license>
@@ -15,7 +15,7 @@
 
   <build_depend>message_generation</build_depend>
 
-  <depend>Franka</depend>
+  <depend>libfranka</depend>
   <depend>actionlib</depend>
   <depend>actionlib_msgs</depend>
   <depend>controller_interface</depend>
diff --git a/franka_description b/franka_description
deleted file mode 160000
index 37b05181deb2d27a8ebcfee1e0d4a6871902682e..0000000000000000000000000000000000000000
--- a/franka_description
+++ /dev/null
@@ -1 +0,0 @@
-Subproject commit 37b05181deb2d27a8ebcfee1e0d4a6871902682e
diff --git a/franka_description/CMakeLists.txt b/franka_description/CMakeLists.txt
new file mode 100644
index 0000000000000000000000000000000000000000..001965b76afc1f9901ce1b44dcd99da560ff7ebc
--- /dev/null
+++ b/franka_description/CMakeLists.txt
@@ -0,0 +1,5 @@
+cmake_minimum_required(VERSION 2.8.3)
+project(franka_description)
+
+find_package(catkin REQUIRED)
+catkin_package(CATKIN_DEPENDS xacro)
diff --git a/franka_description/mainpage.dox b/franka_description/mainpage.dox
new file mode 100644
index 0000000000000000000000000000000000000000..941d0bf97714038b58c39c7dcd816e901e22c023
--- /dev/null
+++ b/franka_description/mainpage.dox
@@ -0,0 +1,6 @@
+/**
+ * @mainpage
+ * @htmlinclude "manifest.html"
+ *
+ * Overview page for Franka Emika research robots: https://frankaemika.github.io
+ */
diff --git a/franka_description/meshes/hand.STL b/franka_description/meshes/hand.STL
new file mode 100644
index 0000000000000000000000000000000000000000..8febaf09ea131e1e99400373e78ce9b5b8cd22f0
Binary files /dev/null and b/franka_description/meshes/hand.STL differ
diff --git a/franka_description/meshes/hand_collision.STL b/franka_description/meshes/hand_collision.STL
new file mode 100644
index 0000000000000000000000000000000000000000..a26b3a8b653005f5d8c2181072ff2254fc69ded6
Binary files /dev/null and b/franka_description/meshes/hand_collision.STL differ
diff --git a/franka_description/meshes/leftfinger.STL b/franka_description/meshes/leftfinger.STL
new file mode 100644
index 0000000000000000000000000000000000000000..94499af550a9124f9ba42df6a3f0093e154276de
Binary files /dev/null and b/franka_description/meshes/leftfinger.STL differ
diff --git a/franka_description/meshes/leftfinger_collision.STL b/franka_description/meshes/leftfinger_collision.STL
new file mode 100644
index 0000000000000000000000000000000000000000..ebe96016b36270bfc3d04fea7d73820b9c3ca337
Binary files /dev/null and b/franka_description/meshes/leftfinger_collision.STL differ
diff --git a/franka_description/meshes/link0.STL b/franka_description/meshes/link0.STL
new file mode 100644
index 0000000000000000000000000000000000000000..fdc9c851e7f398df480d55c4fb317cd7de51a6e4
Binary files /dev/null and b/franka_description/meshes/link0.STL differ
diff --git a/franka_description/meshes/link0_collision.STL b/franka_description/meshes/link0_collision.STL
new file mode 100644
index 0000000000000000000000000000000000000000..ce2c676ce995c89c9215cf209a531ba97988bc9e
Binary files /dev/null and b/franka_description/meshes/link0_collision.STL differ
diff --git a/franka_description/meshes/link1.STL b/franka_description/meshes/link1.STL
new file mode 100644
index 0000000000000000000000000000000000000000..cd77aa34ce217375e0ae16bece1d1711bf1c0750
Binary files /dev/null and b/franka_description/meshes/link1.STL differ
diff --git a/franka_description/meshes/link1_collision.STL b/franka_description/meshes/link1_collision.STL
new file mode 100644
index 0000000000000000000000000000000000000000..2c76e20fb84ef1480c767780ac5c826f33c1b45d
Binary files /dev/null and b/franka_description/meshes/link1_collision.STL differ
diff --git a/franka_description/meshes/link2.STL b/franka_description/meshes/link2.STL
new file mode 100644
index 0000000000000000000000000000000000000000..5edc9538579ecbb58a0375bc672935a6cb0adefa
Binary files /dev/null and b/franka_description/meshes/link2.STL differ
diff --git a/franka_description/meshes/link2_collision.STL b/franka_description/meshes/link2_collision.STL
new file mode 100644
index 0000000000000000000000000000000000000000..cec1a6b88f2dec33d8e2386673b5a98e9ff4a981
Binary files /dev/null and b/franka_description/meshes/link2_collision.STL differ
diff --git a/franka_description/meshes/link3.STL b/franka_description/meshes/link3.STL
new file mode 100644
index 0000000000000000000000000000000000000000..f7fcf64166c8708adb2dbc0fa233f7a1e046a4bb
Binary files /dev/null and b/franka_description/meshes/link3.STL differ
diff --git a/franka_description/meshes/link3_collision.STL b/franka_description/meshes/link3_collision.STL
new file mode 100644
index 0000000000000000000000000000000000000000..49c6db8e101f327286a6eecbfccad1ff7443e6dc
Binary files /dev/null and b/franka_description/meshes/link3_collision.STL differ
diff --git a/franka_description/meshes/link4.STL b/franka_description/meshes/link4.STL
new file mode 100644
index 0000000000000000000000000000000000000000..24c1e9bf27205fec698e14e16dbef9fcff3fb5b5
Binary files /dev/null and b/franka_description/meshes/link4.STL differ
diff --git a/franka_description/meshes/link4_collision.STL b/franka_description/meshes/link4_collision.STL
new file mode 100644
index 0000000000000000000000000000000000000000..83011cb1a3ffb71872a2e0af3c793c6114d4282d
Binary files /dev/null and b/franka_description/meshes/link4_collision.STL differ
diff --git a/franka_description/meshes/link5.STL b/franka_description/meshes/link5.STL
new file mode 100644
index 0000000000000000000000000000000000000000..63b436664f7cc68c4fe909b73e84955d7a9502ed
Binary files /dev/null and b/franka_description/meshes/link5.STL differ
diff --git a/franka_description/meshes/link5_collision.STL b/franka_description/meshes/link5_collision.STL
new file mode 100644
index 0000000000000000000000000000000000000000..892991c06d6c1047b797c3ab0f7a6152c9cced9e
Binary files /dev/null and b/franka_description/meshes/link5_collision.STL differ
diff --git a/franka_description/meshes/link6.STL b/franka_description/meshes/link6.STL
new file mode 100644
index 0000000000000000000000000000000000000000..c7af114f90121c21c3796cced8409a294ed7fe52
Binary files /dev/null and b/franka_description/meshes/link6.STL differ
diff --git a/franka_description/meshes/link6_collision.STL b/franka_description/meshes/link6_collision.STL
new file mode 100644
index 0000000000000000000000000000000000000000..d1c2e60a6531a854073151a88499de97ea01cf10
Binary files /dev/null and b/franka_description/meshes/link6_collision.STL differ
diff --git a/franka_description/meshes/link7.STL b/franka_description/meshes/link7.STL
new file mode 100644
index 0000000000000000000000000000000000000000..ec6ca1031a0fdf305764401a009016f163f51986
Binary files /dev/null and b/franka_description/meshes/link7.STL differ
diff --git a/franka_description/meshes/link7_collision.STL b/franka_description/meshes/link7_collision.STL
new file mode 100644
index 0000000000000000000000000000000000000000..e7030990b4b93271550034ea7f844d1186b5b96e
Binary files /dev/null and b/franka_description/meshes/link7_collision.STL differ
diff --git a/franka_description/meshes/rightfinger.STL b/franka_description/meshes/rightfinger.STL
new file mode 100644
index 0000000000000000000000000000000000000000..8f7d669cc225720ad748cf063a0d48f32b5376c4
Binary files /dev/null and b/franka_description/meshes/rightfinger.STL differ
diff --git a/franka_description/meshes/rightfinger_collision.STL b/franka_description/meshes/rightfinger_collision.STL
new file mode 100644
index 0000000000000000000000000000000000000000..b19fa4a40520056192f64b4b3b909579b9e397ad
Binary files /dev/null and b/franka_description/meshes/rightfinger_collision.STL differ
diff --git a/franka_description/package.xml b/franka_description/package.xml
new file mode 100644
index 0000000000000000000000000000000000000000..03c970ad5999570c3fd39a4031dbe760129f943d
--- /dev/null
+++ b/franka_description/package.xml
@@ -0,0 +1,17 @@
+<?xml version="1.0"?>
+<package format="2">
+  <name>franka_description</name>
+  <version>0.1.1</version>
+  <description>franka_description contains URDF files and meshes of Franka Emika robots</description>
+  <maintainer email="info@franka.de">Franka Emika GmbH</maintainer>
+  <license>Apache 2.0</license>
+
+  <url type="website">http://wiki.ros.org/franka_description</url>
+  <url type="repository">https://github.com/frankaemika/franka_ros</url>
+  <url type="bugtracker">https://github.com/frankaemika/franka_ros/issues</url>
+  <author>Franka Emika GmbH</author>
+
+  <buildtool_depend>catkin</buildtool_depend>
+
+  <exec_depend>xacro</exec_depend>
+</package>
diff --git a/franka_description/robots/hand.urdf.xacro b/franka_description/robots/hand.urdf.xacro
new file mode 100644
index 0000000000000000000000000000000000000000..643fc608f05f2bd79f0212e01e1a01086d02bd57
--- /dev/null
+++ b/franka_description/robots/hand.urdf.xacro
@@ -0,0 +1,5 @@
+<?xml version="1.0" encoding="utf-8"?>
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="hand">
+  <xacro:include filename="hand.xacro"/>
+  <xacro:hand ns="panda"/>
+</robot>
diff --git a/franka_description/robots/hand.xacro b/franka_description/robots/hand.xacro
new file mode 100644
index 0000000000000000000000000000000000000000..95ac3897ad6e01b412b9ade0eaf5268f46d9d768
--- /dev/null
+++ b/franka_description/robots/hand.xacro
@@ -0,0 +1,75 @@
+<?xml version="1.0" encoding="utf-8"?>
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="hand">
+  <xacro:macro name="hand" params="connected_to:='' ns:='' rpy:='0 0 0' xyz:='0 0 0' ">
+    <xacro:unless value="${connected_to == ''}">
+      <joint name="${ns}_hand_joint" type="fixed">
+        <parent link="${connected_to}"/>
+        <child link="${ns}_hand"/>
+        <origin xyz="${xyz}" rpy="${rpy}"/>
+      </joint>
+    </xacro:unless>
+    <link name="${ns}_hand">
+      <visual>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://franka_description/meshes/hand.STL"/>
+        </geometry>
+        <material name="">
+          <color rgba="1 1 1 1"/>
+        </material>
+      </visual>
+      <collision>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://franka_description/meshes/hand_collision.STL"/>
+        </geometry>
+      </collision>
+    </link>
+    <link name="${ns}_leftfinger">
+      <visual>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://franka_description/meshes/leftfinger.STL"/>
+        </geometry>
+        <material name="">
+          <color rgba="1 1 1 1"/>
+        </material>
+      </visual>
+      <collision>
+        <geometry>
+          <mesh filename="package://franka_description/meshes/leftfinger_collision.STL"/>
+        </geometry>
+      </collision>
+    </link>
+    <link name="${ns}_rightfinger">
+      <visual>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://franka_description/meshes/rightfinger.STL"/>
+        </geometry>
+        <material name="">
+          <color rgba="1 1 1 1"/>
+        </material>
+      </visual>
+      <collision>
+        <geometry>
+          <mesh filename="package://franka_description/meshes/rightfinger_collision.STL"/>
+        </geometry>
+      </collision>
+    </link>
+    <joint name="${ns}_finger_joint1" type="prismatic">
+      <parent link="${ns}_hand"/>
+      <child link="${ns}_leftfinger"/>
+      <origin xyz="0 0 0.0584" rpy="0 0 0"/>
+      <axis xyz="0 1 0"/>
+      <limit effort="20" lower="-0.001" upper="0.04" velocity="0.3"/>
+    </joint>
+    <joint name="${ns}_finger_joint2" type="prismatic">
+      <parent link="${ns}_hand"/>
+      <child link="${ns}_rightfinger"/>
+      <origin xyz="0 0 0.0584" rpy="0 0 0"/>
+      <axis xyz="0 -1 0"/>
+      <limit effort="20" lower="-0.001" upper="0.04" velocity="0.3"/>
+    </joint>
+  </xacro:macro>
+</robot>
diff --git a/franka_description/robots/panda_arm.urdf.xacro b/franka_description/robots/panda_arm.urdf.xacro
new file mode 100644
index 0000000000000000000000000000000000000000..cfb3c2346656bc8f4cb66918756c2cfebe0f4dac
--- /dev/null
+++ b/franka_description/robots/panda_arm.urdf.xacro
@@ -0,0 +1,5 @@
+<?xml version='1.0' encoding='utf-8'?>
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda">
+  <xacro:include filename="$(find franka_description)/robots/panda_arm.xacro" />
+  <xacro:panda_arm />
+</robot>
diff --git a/franka_description/robots/panda_arm.xacro b/franka_description/robots/panda_arm.xacro
new file mode 100644
index 0000000000000000000000000000000000000000..c2fbf260ae971843ad90791227112bc36c072126
--- /dev/null
+++ b/franka_description/robots/panda_arm.xacro
@@ -0,0 +1,211 @@
+<?xml version='1.0' encoding='utf-8'?>
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda">
+  <xacro:macro name="panda_arm" params="arm_id:='panda' description_pkg:='franka_description' connected_to:='' xyz:='0 0 0' rpy:='0 0 0'">
+    <xacro:unless value="${not connected_to}">
+      <joint name="${arm_id}_joint_${connected_to}" type="fixed">
+        <parent link="${connected_to}"/>
+        <child link="${arm_id}_link0"/>
+        <origin rpy="${rpy}" xyz="${xyz}"/>
+      </joint>
+    </xacro:unless>
+    <link name="${arm_id}_link0">
+      <visual>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://${description_pkg}/meshes/link0.STL"/>
+        </geometry>
+        <material name="">
+          <color rgba="1 1 1 1"/>
+        </material>
+      </visual>
+      <collision>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://${description_pkg}/meshes/link0_collision.STL"/>
+        </geometry>
+      </collision>
+    </link>
+    <link name="${arm_id}_link1">
+      <visual>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://${description_pkg}/meshes/link1.STL"/>
+        </geometry>
+        <material name="">
+          <color rgba="1 1 1 1"/>
+        </material>
+      </visual>
+      <collision>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://${description_pkg}/meshes/link1_collision.STL"/>
+        </geometry>
+      </collision>
+    </link>
+    <joint name="${arm_id}_joint1" type="revolute">
+      <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.818745" soft_upper_limit="2.818745"/>
+      <origin rpy="0 0 0" xyz="0 0 0.333"/>
+      <parent link="${arm_id}_link0"/>
+      <child link="${arm_id}_link1"/>
+      <axis xyz="0 0 1"/>
+      <limit effort="87" lower="-2.9671" upper="2.9671" velocity="2.5"/>
+    </joint>
+    <link name="${arm_id}_link2">
+      <visual>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://${description_pkg}/meshes/link2.STL"/>
+        </geometry>
+        <material name="">
+          <color rgba="1 1 1 1"/>
+        </material>
+      </visual>
+      <collision>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://${description_pkg}/meshes/link2_collision.STL"/>
+        </geometry>
+      </collision>
+    </link>
+    <joint name="${arm_id}_joint2" type="revolute">
+      <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-1.74097" soft_upper_limit="1.74097"/>
+      <origin rpy="-1.570796326794897 0 0" xyz="0 0 0"/>
+      <parent link="${arm_id}_link1"/>
+      <child link="${arm_id}_link2"/>
+      <axis xyz="0 0 1"/>
+      <limit effort="87" lower="-1.8326" upper="1.8326" velocity="2.5"/>
+    </joint>
+    <link name="${arm_id}_link3">
+      <visual>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://${description_pkg}/meshes/link3.STL"/>
+        </geometry>
+        <material name="">
+          <color rgba="1 1 1 1"/>
+        </material>
+      </visual>
+      <collision>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://${description_pkg}/meshes/link3_collision.STL"/>
+        </geometry>
+      </collision>
+    </link>
+    <joint name="${arm_id}_joint3" type="revolute">
+      <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.818745" soft_upper_limit="2.818745"/>
+      <origin rpy="1.570796326794897 0 0" xyz="0 -0.316 0"/>
+      <parent link="${arm_id}_link2"/>
+      <child link="${arm_id}_link3"/>
+      <axis xyz="0 0 1"/>
+      <limit effort="87" lower="-2.9671" upper="2.9671" velocity="2.5"/>
+    </joint>
+    <link name="${arm_id}_link4">
+      <visual>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://${description_pkg}/meshes/link4.STL"/>
+        </geometry>
+        <material name="">
+          <color rgba="1 1 1 1"/>
+        </material>
+      </visual>
+      <collision>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://${description_pkg}/meshes/link4_collision.STL"/>
+        </geometry>
+      </collision>
+    </link>
+    <joint name="${arm_id}_joint4" type="revolute">
+      <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.98452" soft_upper_limit="0.082935"/>
+      <origin rpy="1.570796326794897 0 0" xyz="0.0825 0 0"/>
+      <parent link="${arm_id}_link3"/>
+      <child link="${arm_id}_link4"/>
+      <axis xyz="0 0 1"/>
+      <limit effort="87" lower="-3.1416" upper="0.0873" velocity="2.5"/>
+    </joint>
+    <link name="${arm_id}_link5">
+      <visual>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://${description_pkg}/meshes/link5.STL"/>
+        </geometry>
+        <material name="">
+          <color rgba="1 1 1 1"/>
+        </material>
+      </visual>
+      <collision>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://${description_pkg}/meshes/link5_collision.STL"/>
+        </geometry>
+      </collision>
+    </link>
+    <joint name="${arm_id}_joint5" type="revolute">
+      <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.818745" soft_upper_limit="2.818745"/>
+      <origin rpy="-1.570796326794897 0 0" xyz="-0.0825 0.384 0"/>
+      <parent link="${arm_id}_link4"/>
+      <child link="${arm_id}_link5"/>
+      <axis xyz="0 0 1"/>
+      <limit effort="12" lower="-2.9671" upper="2.9671" velocity="3"/>
+    </joint>
+    <link name="${arm_id}_link6">
+      <visual>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://${description_pkg}/meshes/link6.STL"/>
+        </geometry>
+        <material name="">
+          <color rgba="1 1 1 1"/>
+        </material>
+      </visual>
+      <collision>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://${description_pkg}/meshes/link6_collision.STL"/>
+        </geometry>
+      </collision>
+    </link>
+    <joint name="${arm_id}_joint6" type="revolute">
+      <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-0.082935" soft_upper_limit="3.631185"/>
+      <origin rpy="1.570796326794897 0 0" xyz="0 0 0"/>
+      <parent link="${arm_id}_link5"/>
+      <child link="${arm_id}_link6"/>
+      <axis xyz="0 0 1"/>
+      <limit effort="12" lower="-0.0873" upper="3.8223" velocity="3"/>
+    </joint>
+    <link name="${arm_id}_link7">
+      <visual>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://${description_pkg}/meshes/link7.STL"/>
+        </geometry>
+        <material name="">
+          <color rgba="1 1 1 1"/>
+        </material>
+      </visual>
+      <collision>
+        <origin rpy="0 0 0" xyz="0 0 0"/>
+        <geometry>
+          <mesh filename="package://${description_pkg}/meshes/link7_collision.STL"/>
+        </geometry>
+      </collision>
+    </link>
+    <joint name="${arm_id}_joint7" type="revolute">
+      <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.818745" soft_upper_limit="2.818745"/>
+      <origin rpy="1.570796326794897 0 0" xyz="0.088 0 0"/>
+      <parent link="${arm_id}_link6"/>
+      <child link="${arm_id}_link7"/>
+      <axis xyz="0 0 1"/>
+      <limit effort="12" lower="-2.9671" upper="2.9671" velocity="3"/>
+    </joint>
+    <link name="${arm_id}_link8"/>
+    <joint name="${arm_id}_joint8" type="fixed">
+      <origin rpy="0 0 0" xyz="0 0 0.107"/>
+      <parent link="${arm_id}_link7"/>
+      <child link="${arm_id}_link8"/>
+      <axis xyz="0 0 0"/>
+    </joint>
+  </xacro:macro>
+</robot>
diff --git a/franka_description/robots/panda_arm_hand.urdf.xacro b/franka_description/robots/panda_arm_hand.urdf.xacro
new file mode 100644
index 0000000000000000000000000000000000000000..4c0f2fcea82ddc1e99dcd85a760a9ede37313b3d
--- /dev/null
+++ b/franka_description/robots/panda_arm_hand.urdf.xacro
@@ -0,0 +1,7 @@
+<?xml version="1.0" encoding="utf-8"?>
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda">
+  <xacro:include filename="$(find franka_description)/robots/panda_arm.xacro"/>
+  <xacro:include filename="$(find franka_description)/robots/hand.xacro"/>
+  <xacro:panda_arm />
+  <xacro:hand ns="panda" rpy="0 0 ${-pi/4}" connected_to="panda_link8"/>
+</robot>
diff --git a/franka_description/rosdoc.yaml b/franka_description/rosdoc.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..96ee597ef5cacd0f223f676c738f396f0810b78c
--- /dev/null
+++ b/franka_description/rosdoc.yaml
@@ -0,0 +1,2 @@
+- builder: doxygen
+  javadoc_autobrief: YES
diff --git a/franka_example_controllers/package.xml b/franka_example_controllers/package.xml
index 3c181fe79aa6aa5acc411ac22ac07a4273abe9f6..cab14e4e720210fad1f32e32292419a28505f435 100644
--- a/franka_example_controllers/package.xml
+++ b/franka_example_controllers/package.xml
@@ -1,7 +1,7 @@
 <?xml version="1.0"?>
 <package format="2">
   <name>franka_example_controllers</name>
-  <version>0.1.0</version>
+  <version>0.1.1</version>
   <description>The franka_example_controllers package</description>
   <maintainer email="info@franka.de">Franka Emika GmbH</maintainer>
   <license>Apache 2.0</license>
diff --git a/franka_gripper/package.xml b/franka_gripper/package.xml
index e03f800d43e30432064e9e62d0afa8674b40542f..eb41a2cbf7a310460240cab82bc970c8f625029c 100644
--- a/franka_gripper/package.xml
+++ b/franka_gripper/package.xml
@@ -1,7 +1,7 @@
 <?xml version="1.0"?>
 <package format="2">
   <name>franka_gripper</name>
-  <version>0.1.0</version>
+  <version>0.1.1</version>
   <description>This package implements the franka gripper of type Franka Hand for the use in ros</description>
   <maintainer email="info@franka.de">Franka Emika GmbH</maintainer>
   <license>Apache 2.0</license>
@@ -15,7 +15,7 @@
 
   <depend>roscpp</depend>
   <depend>message_generation</depend>
-  <depend>Franka</depend>
+  <depend>libfranka</depend>
   <depend>control_msgs</depend>
   <depend>actionlib</depend>
   <depend>sensor_msgs</depend>
diff --git a/franka_hw/package.xml b/franka_hw/package.xml
index 4654603b7e568537f61a64db663af534ef1f323a..74195a9f26d509b31d490a2b4aecae368937a17c 100644
--- a/franka_hw/package.xml
+++ b/franka_hw/package.xml
@@ -1,7 +1,7 @@
 <?xml version="1.0"?>
 <package format="2">
   <name>franka_hw</name>
-  <version>0.1.0</version>
+  <version>0.1.1</version>
   <description>franka_hw provides hardware interfaces for using Franka Emika research robots with ros_control</description>
   <maintainer email="info@franka.de">Franka Emika GmbH</maintainer>
   <license>Apache 2.0</license>
@@ -13,7 +13,7 @@
 
   <buildtool_depend>catkin</buildtool_depend>
 
-  <depend>Franka</depend>
+  <depend>libfranka</depend>
   <depend>controller_interface</depend>
   <depend>hardware_interface</depend>
   <depend>joint_limits_interface</depend>
diff --git a/franka_msgs/package.xml b/franka_msgs/package.xml
index bbe272e5633c3963139025156049e931dab632b9..fcfb412cc1ae4d4ed1a8c15a7a887d09d7df5d1a 100644
--- a/franka_msgs/package.xml
+++ b/franka_msgs/package.xml
@@ -1,7 +1,7 @@
 <?xml version="1.0"?>
 <package format="2">
   <name>franka_msgs</name>
-  <version>0.1.0</version>
+  <version>0.1.1</version>
   <description>franka_msgs provides messages specific to Franka Emika research robots</description>
   <maintainer email="info@franka.de">Franka Emika GmbH</maintainer>
   <license>Apache 2.0</license>
diff --git a/franka_ros/package.xml b/franka_ros/package.xml
index 56d5835817905348b6d94ba83f0fa4c449daf0f6..f6552f2be588dd02ba1c8b27cb6c54abbfff1172 100644
--- a/franka_ros/package.xml
+++ b/franka_ros/package.xml
@@ -1,7 +1,7 @@
 <?xml version="1.0"?>
 <package format="2">
   <name>franka_ros</name>
-  <version>0.1.0</version>
+  <version>0.1.1</version>
   <description>franka_ros is a metapackage for all Franka Emika ROS packages</description>
   <maintainer email="info@franka.de">Franka Emika GmbH</maintainer>
   <license>Apache 2.0</license>
diff --git a/franka_visualization/launch/franka_visualization.launch b/franka_visualization/launch/franka_visualization.launch
index 99fe15ae2236afc9a14e877a867c194618996c8a..93ab4741931e04c1079130dd6c90e498bcdba464 100644
--- a/franka_visualization/launch/franka_visualization.launch
+++ b/franka_visualization/launch/franka_visualization.launch
@@ -3,19 +3,22 @@
 <launch>
   <arg name="load_gripper" default="true" />
   <arg name="robot_ip" default="robot.franka.de" />
-  
+
   <param unless="$(arg load_gripper)" name="robot_description" command="$(find xacro)/xacro --inorder $(find franka_description)/robots/panda_arm.urdf.xacro" />
   <param if="$(arg load_gripper)" name="robot_description" command="$(find xacro)/xacro --inorder $(find franka_description)/robots/panda_arm_hand.urdf.xacro" />
+
   <node name="franka_joint_state_publisher" pkg="franka_visualization" type="franka_joint_state_publisher" output="screen">
     <rosparam command="load" file="$(find franka_visualization)/param/robot_read_settings.yaml" />
     <param name="robot_ip" value="$(arg robot_ip)" />
   </node>
+
   <node name="joint_state_publisher" type="joint_state_publisher" pkg="joint_state_publisher" output="screen">
     <param if="$(arg load_gripper)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find franka_description)/robots/panda_arm_hand.urdf.xacro'" />
     <param unless="$(arg load_gripper)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find franka_description)/robots/panda_arm.urdf.xacro'" />
     <rosparam  param="source_list">[franka_joint_state_publisher/joint_states] </rosparam>
     <param  if="$(arg load_gripper)" name="publish_default_positions" value="true" />
-  </node>  
+  </node>
+
   <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
-  <node pkg="rviz" type="rviz" output="screen" name="rviz" args="-d $(find franka_description)/rviz/franka_description.rviz"/>
+  <node pkg="rviz" type="rviz" output="screen" name="rviz" args="-d $(find franka_visualization)/launch/franka_visualization.rviz"/>
 </launch>
diff --git a/franka_visualization/launch/franka_visualization.rviz b/franka_visualization/launch/franka_visualization.rviz
new file mode 100644
index 0000000000000000000000000000000000000000..07c4f7ffe621006022132808b51562feab5a9c86
--- /dev/null
+++ b/franka_visualization/launch/franka_visualization.rviz
@@ -0,0 +1,187 @@
+Panels:
+  - Class: rviz/Displays
+    Help Height: 89
+    Name: Displays
+    Property Tree Widget:
+      Expanded:
+        - /Global Options1
+        - /Status1
+      Splitter Ratio: 0.5
+    Tree Height: 746
+  - Class: rviz/Selection
+    Name: Selection
+  - Class: rviz/Tool Properties
+    Expanded:
+      - /2D Pose Estimate1
+      - /2D Nav Goal1
+      - /Publish Point1
+    Name: Tool Properties
+    Splitter Ratio: 0.588679016
+  - Class: rviz/Views
+    Expanded:
+      - /Current View1
+    Name: Views
+    Splitter Ratio: 0.5
+  - Class: rviz/Time
+    Experimental: false
+    Name: Time
+    SyncMode: 0
+    SyncSource: ""
+Visualization Manager:
+  Class: ""
+  Displays:
+    - Alpha: 0.5
+      Cell Size: 1
+      Class: rviz/Grid
+      Color: 160; 160; 164
+      Enabled: true
+      Line Style:
+        Line Width: 0.0299999993
+        Value: Lines
+      Name: Grid
+      Normal Cell Count: 0
+      Offset:
+        X: 0
+        Y: 0
+        Z: 0
+      Plane: XY
+      Plane Cell Count: 10
+      Reference Frame: <Fixed Frame>
+      Value: true
+    - Alpha: 1
+      Class: rviz/RobotModel
+      Collision Enabled: false
+      Enabled: true
+      Links:
+        All Links Enabled: true
+        Expand Joint Details: false
+        Expand Link Details: false
+        Expand Tree: false
+        Link Tree Style: Links in Alphabetic Order
+        panda_hand:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        panda_leftfinger:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        panda_link0:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        panda_link1:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        panda_link2:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        panda_link3:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        panda_link4:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        panda_link5:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        panda_link6:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        panda_link7:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        panda_link8:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        panda_rightfinger:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+      Name: RobotModel
+      Robot Description: robot_description
+      TF Prefix: ""
+      Update Interval: 0
+      Value: true
+      Visual Enabled: true
+  Enabled: true
+  Global Options:
+    Background Color: 48; 48; 48
+    Fixed Frame: panda_link0
+    Frame Rate: 30
+  Name: root
+  Tools:
+    - Class: rviz/Interact
+      Hide Inactive Objects: true
+    - Class: rviz/MoveCamera
+    - Class: rviz/Select
+    - Class: rviz/FocusCamera
+    - Class: rviz/Measure
+    - Class: rviz/SetInitialPose
+      Topic: /initialpose
+    - Class: rviz/SetGoal
+      Topic: /move_base_simple/goal
+    - Class: rviz/PublishPoint
+      Single click: true
+      Topic: /clicked_point
+  Value: true
+  Views:
+    Current:
+      Class: rviz/Orbit
+      Distance: 3.39362764
+      Enable Stereo Rendering:
+        Stereo Eye Separation: 0.0599999987
+        Stereo Focal Distance: 1
+        Swap Stereo Eyes: false
+        Value: false
+      Focal Point:
+        X: -0.139062241
+        Y: 0.151414081
+        Z: 0.0437288694
+      Focal Shape Fixed Size: true
+      Focal Shape Size: 0.0500000007
+      Invert Z Axis: false
+      Name: Current View
+      Near Clip Distance: 0.00999999978
+      Pitch: 0.485397696
+      Target Frame: <Fixed Frame>
+      Value: Orbit (rviz)
+      Yaw: 0.500398219
+    Saved: ~
+Window Geometry:
+  Displays:
+    collapsed: false
+  Height: 1059
+  Hide Left Dock: false
+  Hide Right Dock: false
+  QMainWindow State: 000000ff00000000fd00000004000000000000016a00000384fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006f00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000004100000384000000f300fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000384fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000004100000384000000bb00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000077e0000003efc0100000002fb0000000800540069006d006501000000000000077e0000027600fffffffb0000000800540069006d00650100000000000004500000000000000000000004f90000038400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+  Selection:
+    collapsed: false
+  Time:
+    collapsed: false
+  Tool Properties:
+    collapsed: false
+  Views:
+    collapsed: false
+  Width: 1918
+  X: 1920
+  Y: 19
diff --git a/franka_visualization/package.xml b/franka_visualization/package.xml
index 7ce0492d7476e3ee634209e472793966fb4b98b6..413cb216dc53be7f63c9ccf61b037f61d6ac45d6 100644
--- a/franka_visualization/package.xml
+++ b/franka_visualization/package.xml
@@ -1,7 +1,7 @@
 <?xml version="1.0"?>
 <package format="2">
   <name>franka_visualization</name>
-  <version>0.1.0</version>
+  <version>0.1.1</version>
   <description>This package contains visualization tools for Franka Emika.</description>
   <maintainer email="info@franka.de">Franka Emika GmbH</maintainer>
   <license>Apache 2.0</license>
@@ -15,7 +15,7 @@
 
   <depend>sensor_msgs</depend>
   <depend>roscpp</depend>
-  <depend>Franka</depend>
+  <depend>libfranka</depend>
   
   <exec_depend>xacro</exec_depend>
 </package>
diff --git a/panda_moveit_config/package.xml b/panda_moveit_config/package.xml
index b679caff81af43c130234efc972fd7f419b6c5d4..b28e0d4982304411a27da4294f24d78b49bfa038 100644
--- a/panda_moveit_config/package.xml
+++ b/panda_moveit_config/package.xml
@@ -1,7 +1,7 @@
 <?xml version="1.0"?>
 <package format="2">
   <name>panda_moveit_config</name>
-  <version>0.1.0</version>
+  <version>0.1.1</version>
   <description> A partly automatically generated package with all the configuration and launch files for using Panda research with MoveIt!</description>
   <maintainer email="info@franka.de">Franka Emika GmbH</maintainer>
   <license>Apache 2.0</license>