From a5150b3bac6f0a68d17bcab2ad2f495d31fff6d8 Mon Sep 17 00:00:00 2001
From: Nikolaus Vahrenkamp <vahrenkamp@kit.edu>
Date: Wed, 29 Oct 2014 21:46:57 +0100
Subject: [PATCH] Moved gui plugins form ArmarXGui

---
 CMakeLists.txt                                |    1 +
 source/RobotAPI/CMakeLists.txt                |    1 +
 source/RobotAPI/gui_plugins/CMakeLists.txt    |   10 +
 .../gui_plugins/HandUnitPlugin/CMakeLists.txt |   38 +
 .../HandUnitPlugin/HandUnitConfigDialog.cpp   |   38 +
 .../HandUnitPlugin/HandUnitConfigDialog.h     |   51 +
 .../HandUnitPlugin/HandUnitConfigDialog.ui    |   92 ++
 .../HandUnitPlugin/HandUnitGuiPlugin.cpp      |  157 +++
 .../HandUnitPlugin/HandUnitGuiPlugin.h        |  131 +++
 .../HandUnitPlugin/HandUnitGuiPlugin.ui       |   94 ++
 .../HapticUnitPlugin/CMakeLists.txt           |   46 +
 .../HapticUnitConfigDialog.cpp                |   38 +
 .../HapticUnitPlugin/HapticUnitConfigDialog.h |   51 +
 .../HapticUnitConfigDialog.ui                 |   92 ++
 .../HapticUnitPlugin/HapticUnitGuiPlugin.cpp  |  177 +++
 .../HapticUnitPlugin/HapticUnitGuiPlugin.h    |  135 +++
 .../HapticUnitPlugin/HapticUnitGuiPlugin.ui   |   25 +
 .../HapticUnitPlugin/MatrixDisplayWidget.cpp  |   73 ++
 .../HapticUnitPlugin/MatrixDisplayWidget.h    |   67 ++
 .../HapticUnitPlugin/MatrixDisplayWidget.ui   |   19 +
 .../KinematicUnitPlugin/CMakeLists.txt        |   46 +
 .../KinematicUnitConfigDialog.cpp             |   93 ++
 .../KinematicUnitConfigDialog.h               |   72 ++
 .../KinematicUnitConfigDialog.ui              |  129 +++
 .../KinematicUnitGuiPlugin.cpp                | 1019 +++++++++++++++++
 .../KinematicUnitGuiPlugin.h                  |  227 ++++
 .../kinematicunitguiplugin.ui                 |  365 ++++++
 .../PlatformUnitPlugin/CMakeLists.txt         |   39 +
 .../PlatformUnitConfigDialog.cpp              |   38 +
 .../PlatformUnitConfigDialog.h                |   51 +
 .../PlatformUnitConfigDialog.ui               |   92 ++
 .../PlatformUnitGuiPlugin.cpp                 |  115 ++
 .../PlatformUnitGuiPlugin.h                   |  123 ++
 .../PlatformUnitGuiPlugin.ui                  |  115 ++
 .../ArmarXPlotter/ArmarXPlotter.cpp           |  387 +++++++
 .../ArmarXPlotter/ArmarXPlotter.h             |  138 +++
 .../ArmarXPlotter/ArmarXPlotter.ui            |  120 ++
 .../ArmarXPlotter/ArmarXPlotterDialog.cpp     |  189 +++
 .../ArmarXPlotter/ArmarXPlotterDialog.h       |   99 ++
 .../ArmarXPlotter/ArmarXPlotterDialog.ui      |  260 +++++
 .../ArmarXTCPMover/TCPMover.cpp               |  392 +++++++
 .../ArmarXTCPMover/TCPMover.h                 |  137 +++
 .../ArmarXTCPMover/TCPMover.ui                |  525 +++++++++
 .../SensorActorWidgetsPlugin/CMakeLists.txt   |   69 ++
 .../SensorActorWidgetsPlugin.cpp              |   39 +
 .../SensorActorWidgetsPlugin.h                |   49 +
 46 files changed, 6264 insertions(+)
 create mode 100644 source/RobotAPI/gui_plugins/CMakeLists.txt
 create mode 100644 source/RobotAPI/gui_plugins/HandUnitPlugin/CMakeLists.txt
 create mode 100644 source/RobotAPI/gui_plugins/HandUnitPlugin/HandUnitConfigDialog.cpp
 create mode 100644 source/RobotAPI/gui_plugins/HandUnitPlugin/HandUnitConfigDialog.h
 create mode 100644 source/RobotAPI/gui_plugins/HandUnitPlugin/HandUnitConfigDialog.ui
 create mode 100644 source/RobotAPI/gui_plugins/HandUnitPlugin/HandUnitGuiPlugin.cpp
 create mode 100644 source/RobotAPI/gui_plugins/HandUnitPlugin/HandUnitGuiPlugin.h
 create mode 100644 source/RobotAPI/gui_plugins/HandUnitPlugin/HandUnitGuiPlugin.ui
 create mode 100644 source/RobotAPI/gui_plugins/HapticUnitPlugin/CMakeLists.txt
 create mode 100644 source/RobotAPI/gui_plugins/HapticUnitPlugin/HapticUnitConfigDialog.cpp
 create mode 100644 source/RobotAPI/gui_plugins/HapticUnitPlugin/HapticUnitConfigDialog.h
 create mode 100644 source/RobotAPI/gui_plugins/HapticUnitPlugin/HapticUnitConfigDialog.ui
 create mode 100644 source/RobotAPI/gui_plugins/HapticUnitPlugin/HapticUnitGuiPlugin.cpp
 create mode 100644 source/RobotAPI/gui_plugins/HapticUnitPlugin/HapticUnitGuiPlugin.h
 create mode 100644 source/RobotAPI/gui_plugins/HapticUnitPlugin/HapticUnitGuiPlugin.ui
 create mode 100644 source/RobotAPI/gui_plugins/HapticUnitPlugin/MatrixDisplayWidget.cpp
 create mode 100644 source/RobotAPI/gui_plugins/HapticUnitPlugin/MatrixDisplayWidget.h
 create mode 100644 source/RobotAPI/gui_plugins/HapticUnitPlugin/MatrixDisplayWidget.ui
 create mode 100644 source/RobotAPI/gui_plugins/KinematicUnitPlugin/CMakeLists.txt
 create mode 100644 source/RobotAPI/gui_plugins/KinematicUnitPlugin/KinematicUnitConfigDialog.cpp
 create mode 100644 source/RobotAPI/gui_plugins/KinematicUnitPlugin/KinematicUnitConfigDialog.h
 create mode 100644 source/RobotAPI/gui_plugins/KinematicUnitPlugin/KinematicUnitConfigDialog.ui
 create mode 100644 source/RobotAPI/gui_plugins/KinematicUnitPlugin/KinematicUnitGuiPlugin.cpp
 create mode 100644 source/RobotAPI/gui_plugins/KinematicUnitPlugin/KinematicUnitGuiPlugin.h
 create mode 100644 source/RobotAPI/gui_plugins/KinematicUnitPlugin/kinematicunitguiplugin.ui
 create mode 100644 source/RobotAPI/gui_plugins/PlatformUnitPlugin/CMakeLists.txt
 create mode 100644 source/RobotAPI/gui_plugins/PlatformUnitPlugin/PlatformUnitConfigDialog.cpp
 create mode 100644 source/RobotAPI/gui_plugins/PlatformUnitPlugin/PlatformUnitConfigDialog.h
 create mode 100644 source/RobotAPI/gui_plugins/PlatformUnitPlugin/PlatformUnitConfigDialog.ui
 create mode 100644 source/RobotAPI/gui_plugins/PlatformUnitPlugin/PlatformUnitGuiPlugin.cpp
 create mode 100644 source/RobotAPI/gui_plugins/PlatformUnitPlugin/PlatformUnitGuiPlugin.h
 create mode 100644 source/RobotAPI/gui_plugins/PlatformUnitPlugin/PlatformUnitGuiPlugin.ui
 create mode 100644 source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotter.cpp
 create mode 100644 source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotter.h
 create mode 100644 source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotter.ui
 create mode 100644 source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotterDialog.cpp
 create mode 100644 source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotterDialog.h
 create mode 100644 source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotterDialog.ui
 create mode 100644 source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.cpp
 create mode 100644 source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.h
 create mode 100644 source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.ui
 create mode 100644 source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/CMakeLists.txt
 create mode 100644 source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/SensorActorWidgetsPlugin.cpp
 create mode 100644 source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/SensorActorWidgetsPlugin.h

diff --git a/CMakeLists.txt b/CMakeLists.txt
index 27938ddc1..1e8ca5feb 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -9,6 +9,7 @@ find_package("ArmarXCore" REQUIRED
 include(${ArmarXCore_USE_FILE})
 
 armarx_project("RobotAPI")
+depends_on_armarx_package(ArmarXGui "OPTIONAL")
 
 add_subdirectory(source)
 
diff --git a/source/RobotAPI/CMakeLists.txt b/source/RobotAPI/CMakeLists.txt
index 32014297c..1397fba29 100644
--- a/source/RobotAPI/CMakeLists.txt
+++ b/source/RobotAPI/CMakeLists.txt
@@ -3,5 +3,6 @@ add_subdirectory(applications)
 add_subdirectory(components)
 add_subdirectory(statecharts)
 add_subdirectory(libraries)
+add_subdirectory(gui_plugins)
 
 
diff --git a/source/RobotAPI/gui_plugins/CMakeLists.txt b/source/RobotAPI/gui_plugins/CMakeLists.txt
new file mode 100644
index 000000000..93cb2fb67
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/CMakeLists.txt
@@ -0,0 +1,10 @@
+add_subdirectory(KinematicUnitPlugin)
+
+add_subdirectory(HandUnitPlugin)
+add_subdirectory(PlatformUnitPlugin)
+add_subdirectory(SensorActorWidgetsPlugin)
+add_subdirectory(HapticUnitPlugin)
+
+#add_subdirectory(ObjectExaminerPlugin)
+
+
diff --git a/source/RobotAPI/gui_plugins/HandUnitPlugin/CMakeLists.txt b/source/RobotAPI/gui_plugins/HandUnitPlugin/CMakeLists.txt
new file mode 100644
index 000000000..cb8eb84ba
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/HandUnitPlugin/CMakeLists.txt
@@ -0,0 +1,38 @@
+armarx_set_target("HandUnitUnitGuiPlugin")
+
+find_package(Qt4 COMPONENTS QtCore QtGui QUIET)
+armarx_build_if(QT_FOUND "Qt not available")
+
+find_package(Simox QUIET)
+find_package(ArmarXGui QUIET)
+
+armarx_build_if(ArmarXGui_FOUND "ArmarXGui not available")
+armarx_build_if(Simox_FOUND "Simox not available")
+
+include(${QT_USE_FILE})
+
+
+file(GLOB SOURCES HandUnitGuiPlugin.cpp
+     HandUnitConfigDialog.cpp)
+file(GLOB HEADERS HandUnitGuiPlugin.h
+     HandUnitConfigDialog.h)
+
+set(GUI_MOC_HDRS
+    HandUnitGuiPlugin.h
+    HandUnitConfigDialog.h
+)
+
+set(GUI_UIS
+    HandUnitGuiPlugin.ui
+    HandUnitConfigDialog.ui
+)
+
+set(COMPONENT_LIBS RobotAPIUnits ArmarXInterfaces ${Simox_LIBRARIES})
+
+set(LIB_VERSION    0.1.0)
+set(LIB_SOVERSION  0)
+
+if (ArmarXGui_FOUND)
+	armarx_gui_library(HandUnitGuiPlugin "${SOURCES}" "${GUI_MOC_HDRS}" "${GUI_UIS}" "" "${COMPONENT_LIBS}" "${LIB_VERSION}" "${LIB_SOVERSION}")
+endif()
+
diff --git a/source/RobotAPI/gui_plugins/HandUnitPlugin/HandUnitConfigDialog.cpp b/source/RobotAPI/gui_plugins/HandUnitPlugin/HandUnitConfigDialog.cpp
new file mode 100644
index 000000000..12bcce40d
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/HandUnitPlugin/HandUnitConfigDialog.cpp
@@ -0,0 +1,38 @@
+/*
+* This file is part of ArmarX.
+*
+* ArmarX is free software; you can redistribute it and/or modify
+* it under the terms of the GNU Lesser General Public License as
+* published by the Free Software Foundation; either version 2 of
+* the License, or (at your option) any later version.
+*
+* ArmarX is distributed in the hope that it will be useful, but
+* WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+* GNU Lesser General Public License for more details.
+*
+* You should have received a copy of the GNU General Public License
+* along with this program. If not, see <http://www.gnu.org/licenses/>.
+*
+* @package    ArmarX::
+* @author     Nikolaus Vahrenkamp ( vahrenkamp at kit dot edu)
+* @date       2012
+* @copyright  http://www.gnu.org/licenses/gpl.txt
+*             GNU General Public License
+*/
+
+#include "HandUnitConfigDialog.h"
+#include "ui_HandUnitConfigDialog.h"
+
+armarx::HandUnitConfigDialog::HandUnitConfigDialog(QWidget *parent) :
+    QDialog(parent),
+    ui(new Ui::HandUnitConfigDialog)
+{
+    ui->setupUi(this);
+}
+
+armarx::HandUnitConfigDialog::~HandUnitConfigDialog()
+{
+    delete ui;
+}
+
diff --git a/source/RobotAPI/gui_plugins/HandUnitPlugin/HandUnitConfigDialog.h b/source/RobotAPI/gui_plugins/HandUnitPlugin/HandUnitConfigDialog.h
new file mode 100644
index 000000000..5fd1f2486
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/HandUnitPlugin/HandUnitConfigDialog.h
@@ -0,0 +1,51 @@
+/*
+* This file is part of ArmarX.
+*
+* ArmarX is free software; you can redistribute it and/or modify
+* it under the terms of the GNU Lesser General Public License as
+* published by the Free Software Foundation; either version 2 of
+* the License, or (at your option) any later version.
+*
+* ArmarX is distributed in the hope that it will be useful, but
+* WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+* GNU Lesser General Public License for more details.
+*
+* You should have received a copy of the GNU General Public License
+* along with this program. If not, see <http://www.gnu.org/licenses/>.
+*
+* @package    ArmarX::
+* @author     Nikolaus Vahrenkamp ( vahrenkamp at kit dot edu)
+* @date       2012
+* @copyright  http://www.gnu.org/licenses/gpl.txt
+*             GNU General Public License
+*/
+
+#ifndef _ARMARXGUI_PLUGINS_HANDUNITCONFIGDIALOG_H
+#define _ARMARXGUI_PLUGINS_HANDUNITCONFIGDIALOG_H
+
+#include <QDialog>
+
+namespace Ui {
+    class HandUnitConfigDialog;
+}
+
+namespace armarx
+{
+    class HandUnitConfigDialog :
+        public QDialog
+    {
+        Q_OBJECT
+
+    public:
+        explicit HandUnitConfigDialog(QWidget *parent = 0);
+        ~HandUnitConfigDialog();
+
+    private:
+        Ui::HandUnitConfigDialog *ui;
+
+        friend class HandUnitWidget;
+    };
+}
+
+#endif
diff --git a/source/RobotAPI/gui_plugins/HandUnitPlugin/HandUnitConfigDialog.ui b/source/RobotAPI/gui_plugins/HandUnitPlugin/HandUnitConfigDialog.ui
new file mode 100644
index 000000000..672e7d189
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/HandUnitPlugin/HandUnitConfigDialog.ui
@@ -0,0 +1,92 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>HandUnitConfigDialog</class>
+ <widget class="QDialog" name="HandUnitConfigDialog">
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>527</width>
+    <height>113</height>
+   </rect>
+  </property>
+  <property name="windowTitle">
+   <string>Dialog</string>
+  </property>
+  <layout class="QGridLayout" name="gridLayout_2">
+   <item row="3" column="0">
+    <widget class="QDialogButtonBox" name="buttonBox">
+     <property name="orientation">
+      <enum>Qt::Horizontal</enum>
+     </property>
+     <property name="standardButtons">
+      <set>QDialogButtonBox::Cancel|QDialogButtonBox::Ok</set>
+     </property>
+    </widget>
+   </item>
+   <item row="0" column="0">
+    <layout class="QGridLayout" name="gridLayout">
+     <item row="0" column="1">
+      <widget class="QLineEdit" name="editHandUnitName"/>
+     </item>
+     <item row="0" column="0">
+      <widget class="QLabel" name="labelHandUnitName">
+       <property name="text">
+        <string>HandUnit</string>
+       </property>
+      </widget>
+     </item>
+     <item row="1" column="1">
+      <widget class="QLineEdit" name="editHandName"/>
+     </item>
+     <item row="1" column="0">
+      <widget class="QLabel" name="labelHandName">
+       <property name="text">
+        <string>Hand Name</string>
+       </property>
+      </widget>
+     </item>
+    </layout>
+   </item>
+  </layout>
+ </widget>
+ <tabstops>
+  <tabstop>editHandUnitName</tabstop>
+  <tabstop>buttonBox</tabstop>
+ </tabstops>
+ <resources/>
+ <connections>
+  <connection>
+   <sender>buttonBox</sender>
+   <signal>accepted()</signal>
+   <receiver>HandUnitConfigDialog</receiver>
+   <slot>accept()</slot>
+   <hints>
+    <hint type="sourcelabel">
+     <x>248</x>
+     <y>254</y>
+    </hint>
+    <hint type="destinationlabel">
+     <x>157</x>
+     <y>274</y>
+    </hint>
+   </hints>
+  </connection>
+  <connection>
+   <sender>buttonBox</sender>
+   <signal>rejected()</signal>
+   <receiver>HandUnitConfigDialog</receiver>
+   <slot>reject()</slot>
+   <hints>
+    <hint type="sourcelabel">
+     <x>316</x>
+     <y>260</y>
+    </hint>
+    <hint type="destinationlabel">
+     <x>286</x>
+     <y>274</y>
+    </hint>
+   </hints>
+  </connection>
+ </connections>
+</ui>
diff --git a/source/RobotAPI/gui_plugins/HandUnitPlugin/HandUnitGuiPlugin.cpp b/source/RobotAPI/gui_plugins/HandUnitPlugin/HandUnitGuiPlugin.cpp
new file mode 100644
index 000000000..dbd2fa78e
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/HandUnitPlugin/HandUnitGuiPlugin.cpp
@@ -0,0 +1,157 @@
+#include "HandUnitGuiPlugin.h"
+#include "HandUnitConfigDialog.h"
+#include "ui_HandUnitConfigDialog.h"
+
+#include <Core/core/system/ArmarXDataPath.h>
+#include <Core/observers/variant/SingleTypeVariantList.h>
+
+
+// Qt headers
+#include <Qt>
+#include <QtGlobal>
+#include <QtGui/QPushButton>
+#include <QtGui/QComboBox>
+
+using namespace armarx;
+
+
+HandUnitGuiPlugin::HandUnitGuiPlugin()
+{
+    addWidget<HandUnitWidget>();
+}
+
+
+HandUnitWidget::HandUnitWidget() :
+    handName(""),
+    preshapeName(""),
+    handUnitProxyName("")
+{
+    // init gui
+    ui.setupUi(getWidget());
+    ui.stateOpen->setChecked(true);
+}
+
+
+void HandUnitWidget::onInitObserver()
+{
+    usingProxy(handUnitProxyName);
+    usingTopic(handName + "State");
+    ARMARX_WARNING << "Listening on Topic: " << handName + "State";
+}
+
+
+void HandUnitWidget::onConnectObserver()
+{
+    connectSlots();
+    handUnitProxy = getProxy<HandUnitInterfacePrx>(handUnitProxyName);
+
+    SingleTypeVariantListPtr preshapeStrings = SingleTypeVariantListPtr::dynamicCast(handUnitProxy->getShapeNames());
+    QStringList list;
+    int preshapeCount = preshapeStrings->getSize();
+    for (int i = 0; i < preshapeCount; ++i)
+    {
+        std::string shape = ((preshapeStrings->getVariant(i))->get<std::string>());
+        list << QString::fromStdString(shape);
+    }
+    ui.comboPreshapes->addItems(list);
+}
+
+
+void HandUnitWidget::onExitObserver()
+{
+}
+
+
+QPointer<QDialog> HandUnitWidget::getConfigDialog(QWidget* parent)
+{
+    if(!dialog)
+    {
+        dialog = new HandUnitConfigDialog(parent);
+    }
+    dialog->ui->editHandUnitName->setText(QString::fromStdString(handUnitProxyName));
+    dialog->ui->editHandName->setText(QString::fromStdString(handName));
+    return qobject_cast<HandUnitConfigDialog*>(dialog);
+}
+
+
+ void HandUnitWidget::configured()
+ {
+     handUnitProxyName = dialog->ui->editHandUnitName->text().toStdString();
+     handName = dialog->ui->editHandName->text().toStdString();
+ }
+
+
+void HandUnitWidget::loadSettings(QSettings *settings)
+{
+    handUnitProxyName = settings->value("handUnitProxyName", QString::fromStdString(handUnitProxyName)).toString().toStdString();
+    handName = settings->value("handName", QString::fromStdString(handName)).toString().toStdString();
+}
+
+
+void HandUnitWidget::saveSettings(QSettings *settings)
+{
+    settings->setValue("handUnitProxyName", QString::fromStdString(handUnitProxyName));
+    settings->setValue("handName", QString::fromStdString(handName));
+}
+
+
+void HandUnitWidget::connectSlots()
+{
+    connect(ui.buttonOpen, SIGNAL(clicked()), this, SLOT(openHand()));
+    connect(ui.buttonClose, SIGNAL(clicked()), this, SLOT(closeHand()));
+    connect(ui.buttonPreshape, SIGNAL(clicked()), this, SLOT(preshapeHand()));
+    connect(ui.comboPreshapes, SIGNAL(currentIndexChanged(const QString&)), this, SLOT(selectPreshape(const QString&)));
+}
+
+
+void HandUnitWidget::openHand()
+{
+    ARMARX_VERBOSE << "Open hand not longer supported, use shapes...";
+    //handUnitProxy->open();
+}
+
+
+void HandUnitWidget::closeHand()
+{
+    ARMARX_VERBOSE << "Close hand not longer supported, use shapes...";
+    //handUnitProxy->close();
+}
+
+
+void HandUnitWidget::preshapeHand()
+{
+    handUnitProxy->setShape(preshapeName);
+}
+
+
+void HandUnitWidget::selectPreshape(const QString& preshapeString)
+{
+    preshapeName = preshapeString.toStdString();
+}
+
+/*
+void  HandUnitWidget::reportHandOpened(bool isLeftHand, const ::Ice::Current&)
+{
+    ui.stateOpen->setChecked(true);
+}
+
+
+void  HandUnitWidget::reportHandClosed(bool isLeftHand, const ::Ice::Current&)
+{
+    ui.stateClosed->setChecked(true);
+}
+*/
+
+void  HandUnitWidget::reportHandShaped(const std::string& handName, const std::string& handShapeName, const ::Ice::Current&)
+{
+    ui.statePreshaped->setChecked(true);
+}
+
+
+void HandUnitWidget::reportNewHandShapeName(const std::string& handName, const std::string& handShapeName, const::Ice::Current&)
+{
+
+}
+
+Q_EXPORT_PLUGIN2(armar3_gui_HandUnitGuiPlugin, HandUnitGuiPlugin)
+
diff --git a/source/RobotAPI/gui_plugins/HandUnitPlugin/HandUnitGuiPlugin.h b/source/RobotAPI/gui_plugins/HandUnitPlugin/HandUnitGuiPlugin.h
new file mode 100644
index 000000000..ad453ca79
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/HandUnitPlugin/HandUnitGuiPlugin.h
@@ -0,0 +1,131 @@
+/*
+* This file is part of ArmarX.
+*
+* ArmarX is free software; you can redistribute it and/or modify
+* it under the terms of the GNU Lesser General Public License as
+* published by the Free Software Foundation; either version 2 of
+* the License, or (at your option) any later version.
+*
+* ArmarX is distributed in the hope that it will be useful, but
+* WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+* GNU Lesser General Public License for more details.
+*
+* You should have received a copy of the GNU General Public License
+* along with this program. If not, see <http://www.gnu.org/licenses/>.
+*
+* @package    ArmarX::Component::ObjectExaminerGuiPlugin
+* @author     Nikolaus Vahrenkamp ( vahrenkamp at kit dot edu)
+* @copyright  2012
+* @license    http://www.gnu.org/licenses/gpl.txt
+*             GNU General Public License
+
+*/
+
+#ifndef _ARMARXGUI_PLUGINS_HANDUNITWIDGET_H
+#define _ARMARXGUI_PLUGINS_HANDUNITWIDGET_H
+
+/* ArmarX headers */
+#include "ui_HandUnitGuiPlugin.h"
+#include <Core/core/Component.h>
+#include <Core/observers/Observer.h>
+#include <Gui/ArmarXGuiLib/ArmarXGuiPlugin.h>
+#include <Gui/ArmarXGuiLib/ArmarXComponentWidgetController.h>
+
+#include <RobotAPI/interface/units/HandUnitInterface.h>
+
+/* Qt headers */
+#include <QtGui/QMainWindow>
+
+#include <string>
+
+
+namespace armarx
+{
+    class HandUnitConfigDialog;
+
+    /**
+      \class HandUnitGuiPlugin
+      \brief With this plugin the HandUnit can be controlled.
+      \ingroup ArmarXGuiPlugins
+
+      \see HandUnitWidget
+      */
+    class HandUnitGuiPlugin :
+            public ArmarXGuiPlugin
+    {
+    public:
+        HandUnitGuiPlugin();
+        QString getPluginName()
+        {
+            return "HandUnitGuiPlugin";
+        }
+    };
+
+    /**
+      \class HandUnitWidget
+      \brief With this widget the HandUnit can be controlled.
+      \ingroup ArmarXGuiPlugins
+
+      \see HandUnitGuiPlugin
+      */
+    class HandUnitWidget :
+            public ArmarXComponentWidgetController,
+            public HandUnitListener,
+            virtual public Observer
+    {
+        Q_OBJECT
+    public:
+        HandUnitWidget();
+        ~HandUnitWidget()
+        {}
+
+        // inherited from Observer
+        virtual std::string getDefaultName() const { return "HandUnitGUI"; }
+        virtual void onInitObserver();
+        virtual void onConnectObserver();
+        virtual void onExitObserver();
+
+        // slice interface implementation
+        //virtual void reportHandClosed(bool isLeftHand, const ::Ice::Current& = ::Ice::Current());
+        //virtual void reportHandOpened(bool isLeftHand, const ::Ice::Current& = ::Ice::Current());
+        virtual void reportHandShaped(const std::string& handName, const std::string& handShapeName, const ::Ice::Current& = ::Ice::Current());
+        virtual void reportNewHandShapeName(const std::string& handName, const std::string& handShapeName, const ::Ice::Current& = ::Ice::Current());
+
+        // inherited of ArmarXWidget
+        virtual QString getWidgetName() const
+        {
+            return getDefaultName().c_str();
+        }
+
+        QPointer<QDialog> getConfigDialog(QWidget* parent = 0);
+        virtual void loadSettings(QSettings * settings);
+        virtual void saveSettings(QSettings * settings);
+        void configured();
+
+    public slots:
+
+        void openHand();
+        void closeHand();
+        void preshapeHand();
+        void selectPreshape(const QString& preshapeString);
+
+    protected:
+        void connectSlots();
+
+        Ui::HandUnitGuiPlugin ui;
+
+    private:
+        std::string handName;
+        std::string preshapeName;
+
+        std::string handUnitProxyName;
+        HandUnitInterfacePrx handUnitProxy;
+
+        QPointer<QWidget> __widget;
+        QPointer<HandUnitConfigDialog> dialog;
+    };
+    typedef boost::shared_ptr<HandUnitWidget> HandUnitGuiPluginPtr;
+}
+
+#endif
diff --git a/source/RobotAPI/gui_plugins/HandUnitPlugin/HandUnitGuiPlugin.ui b/source/RobotAPI/gui_plugins/HandUnitPlugin/HandUnitGuiPlugin.ui
new file mode 100644
index 000000000..d4a673fca
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/HandUnitPlugin/HandUnitGuiPlugin.ui
@@ -0,0 +1,94 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>HandUnitGuiPlugin</class>
+ <widget class="QWidget" name="HandUnitGuiPlugin">
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>338</width>
+    <height>210</height>
+   </rect>
+  </property>
+  <property name="sizePolicy">
+   <sizepolicy hsizetype="Minimum" vsizetype="Minimum">
+    <horstretch>0</horstretch>
+    <verstretch>0</verstretch>
+   </sizepolicy>
+  </property>
+  <property name="windowTitle">
+   <string>Form</string>
+  </property>
+  <widget class="QWidget" name="layoutWidget">
+   <property name="geometry">
+    <rect>
+     <x>9</x>
+     <y>9</y>
+     <width>321</width>
+     <height>191</height>
+    </rect>
+   </property>
+   <layout class="QGridLayout" name="gridLayout">
+    <item row="1" column="1">
+     <widget class="QPushButton" name="buttonOpen">
+      <property name="text">
+       <string>Open</string>
+      </property>
+     </widget>
+    </item>
+    <item row="0" column="0">
+     <widget class="QComboBox" name="comboPreshapes"/>
+    </item>
+    <item row="2" column="1">
+     <widget class="QPushButton" name="buttonClose">
+      <property name="text">
+       <string>Close</string>
+      </property>
+     </widget>
+    </item>
+    <item row="0" column="1">
+     <widget class="QPushButton" name="buttonPreshape">
+      <property name="text">
+       <string>Preshape</string>
+      </property>
+     </widget>
+    </item>
+    <item row="1" column="0" rowspan="2">
+     <widget class="QGroupBox" name="handstateGroupBox">
+      <property name="title">
+       <string>Handstate</string>
+      </property>
+      <property name="checkable">
+       <bool>false</bool>
+      </property>
+      <layout class="QVBoxLayout" name="verticalLayout">
+       <item>
+        <widget class="QRadioButton" name="stateOpen">
+         <property name="text">
+          <string>Open</string>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QRadioButton" name="stateClosed">
+         <property name="text">
+          <string>Closed</string>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QRadioButton" name="statePreshaped">
+         <property name="text">
+          <string>Preshaped</string>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </widget>
+    </item>
+   </layout>
+  </widget>
+ </widget>
+ <resources/>
+ <connections/>
+</ui>
diff --git a/source/RobotAPI/gui_plugins/HapticUnitPlugin/CMakeLists.txt b/source/RobotAPI/gui_plugins/HapticUnitPlugin/CMakeLists.txt
new file mode 100644
index 000000000..cfcc61b5f
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/HapticUnitPlugin/CMakeLists.txt
@@ -0,0 +1,46 @@
+armarx_set_target("HapticUnitUnitGuiPlugin")
+
+find_package(Qt4 COMPONENTS QtCore QtGui QUIET)
+armarx_build_if(QT_FOUND "Qt not available")
+
+find_package(Simox QUIET)
+find_package(ArmarXGui QUIET)
+
+armarx_build_if(ArmarXGui_FOUND "ArmarXGui not available")
+armarx_build_if(Simox_FOUND "Simox not available")
+
+find_package(Eigen3 QUIET)
+armarx_build_if(Eigen3_FOUND "Eigen3 not available")
+include_directories(${Eigen3_INCLUDE_DIR})
+
+include(${QT_USE_FILE})
+
+include(${ArmarXGui_CMAKE_DIR}/ArmarXGui.cmake)
+
+file(GLOB SOURCES HapticUnitGuiPlugin.cpp
+     HapticUnitConfigDialog.cpp
+     MatrixDisplayWidget.cpp)
+file(GLOB HEADERS HapticUnitGuiPlugin.h
+     HapticUnitConfigDialog.h
+     MatrixDisplayWidget.h)
+
+set(GUI_MOC_HDRS
+    HapticUnitGuiPlugin.h
+    HapticUnitConfigDialog.h
+    MatrixDisplayWidget.h
+)
+
+set(GUI_UIS
+    HapticUnitGuiPlugin.ui
+    HapticUnitConfigDialog.ui
+    MatrixDisplayWidget.ui
+)
+
+set(COMPONENT_LIBS RobotAPIUnits ArmarXInterfaces ArmarXCoreEigen3Variants ${Simox_LIBRARIES})
+
+set(LIB_VERSION    0.1.0)
+set(LIB_SOVERSION  0)
+
+if (ArmarXGui_FOUND)
+	armarx_gui_library(HapticUnitGuiPlugin "${SOURCES}" "${GUI_MOC_HDRS}" "${GUI_UIS}" "" "${COMPONENT_LIBS}" "${LIB_VERSION}" "${LIB_SOVERSION}")
+endif()
diff --git a/source/RobotAPI/gui_plugins/HapticUnitPlugin/HapticUnitConfigDialog.cpp b/source/RobotAPI/gui_plugins/HapticUnitPlugin/HapticUnitConfigDialog.cpp
new file mode 100644
index 000000000..55aefcec1
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/HapticUnitPlugin/HapticUnitConfigDialog.cpp
@@ -0,0 +1,38 @@
+/*
+* This file is part of ArmarX.
+*
+* ArmarX is free software; you can redistribute it and/or modify
+* it under the terms of the GNU Lesser General Public License as
+* published by the Free Software Foundation; either version 2 of
+* the License, or (at your option) any later version.
+*
+* ArmarX is distributed in the hope that it will be useful, but
+* WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+* GNU Lesser General Public License for more details.
+*
+* You should have received a copy of the GNU General Public License
+* along with this program. If not, see <http://www.gnu.org/licenses/>.
+*
+* @package    ArmarX::
+* @author     Nikolaus Vahrenkamp ( vahrenkamp at kit dot edu)
+* @date       2012
+* @copyright  http://www.gnu.org/licenses/gpl.txt
+*             GNU General Public License
+*/
+
+#include "HapticUnitConfigDialog.h"
+#include "ui_HapticUnitConfigDialog.h"
+
+armarx::HapticUnitConfigDialog::HapticUnitConfigDialog(QWidget *parent) :
+    QDialog(parent),
+    ui(new Ui::HapticUnitConfigDialog)
+{
+    ui->setupUi(this);
+}
+
+armarx::HapticUnitConfigDialog::~HapticUnitConfigDialog()
+{
+    delete ui;
+}
+
diff --git a/source/RobotAPI/gui_plugins/HapticUnitPlugin/HapticUnitConfigDialog.h b/source/RobotAPI/gui_plugins/HapticUnitPlugin/HapticUnitConfigDialog.h
new file mode 100644
index 000000000..1e7f3f94a
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/HapticUnitPlugin/HapticUnitConfigDialog.h
@@ -0,0 +1,51 @@
+/*
+* This file is part of ArmarX.
+*
+* ArmarX is free software; you can redistribute it and/or modify
+* it under the terms of the GNU Lesser General Public License as
+* published by the Free Software Foundation; either version 2 of
+* the License, or (at your option) any later version.
+*
+* ArmarX is distributed in the hope that it will be useful, but
+* WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+* GNU Lesser General Public License for more details.
+*
+* You should have received a copy of the GNU General Public License
+* along with this program. If not, see <http://www.gnu.org/licenses/>.
+*
+* @package    ArmarX::
+* @author     Nikolaus Vahrenkamp ( vahrenkamp at kit dot edu)
+* @date       2012
+* @copyright  http://www.gnu.org/licenses/gpl.txt
+*             GNU General Public License
+*/
+
+#ifndef _ARMARXGUI_PLUGINS_HapticUnitCONFIGDIALOG_H
+#define _ARMARXGUI_PLUGINS_HapticUnitCONFIGDIALOG_H
+
+#include <QDialog>
+
+namespace Ui {
+    class HapticUnitConfigDialog;
+}
+
+namespace armarx
+{
+    class HapticUnitConfigDialog :
+        public QDialog
+    {
+        Q_OBJECT
+
+    public:
+        explicit HapticUnitConfigDialog(QWidget *parent = 0);
+        ~HapticUnitConfigDialog();
+
+    private:
+        Ui::HapticUnitConfigDialog *ui;
+
+        //friend class HapticUnitWidget;
+    };
+}
+
+#endif
diff --git a/source/RobotAPI/gui_plugins/HapticUnitPlugin/HapticUnitConfigDialog.ui b/source/RobotAPI/gui_plugins/HapticUnitPlugin/HapticUnitConfigDialog.ui
new file mode 100644
index 000000000..741b94b0a
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/HapticUnitPlugin/HapticUnitConfigDialog.ui
@@ -0,0 +1,92 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>HapticUnitConfigDialog</class>
+ <widget class="QDialog" name="HapticUnitConfigDialog">
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>527</width>
+    <height>113</height>
+   </rect>
+  </property>
+  <property name="windowTitle">
+   <string>Dialog</string>
+  </property>
+  <layout class="QGridLayout" name="gridLayout_2">
+   <item row="3" column="0">
+    <widget class="QDialogButtonBox" name="buttonBox">
+     <property name="orientation">
+      <enum>Qt::Horizontal</enum>
+     </property>
+     <property name="standardButtons">
+      <set>QDialogButtonBox::Cancel|QDialogButtonBox::Ok</set>
+     </property>
+    </widget>
+   </item>
+   <item row="0" column="0">
+    <layout class="QGridLayout" name="gridLayout">
+     <item row="0" column="1">
+      <widget class="QLineEdit" name="editHapticUnitName"/>
+     </item>
+     <item row="0" column="0">
+      <widget class="QLabel" name="labelHapticUnitName">
+       <property name="text">
+        <string>HapticUnit</string>
+       </property>
+      </widget>
+     </item>
+     <item row="1" column="1">
+      <widget class="QLineEdit" name="editHandName"/>
+     </item>
+     <item row="1" column="0">
+      <widget class="QLabel" name="labelHandName">
+       <property name="text">
+        <string>Hand Name</string>
+       </property>
+      </widget>
+     </item>
+    </layout>
+   </item>
+  </layout>
+ </widget>
+ <tabstops>
+  <tabstop>editHapticUnitName</tabstop>
+  <tabstop>buttonBox</tabstop>
+ </tabstops>
+ <resources/>
+ <connections>
+  <connection>
+   <sender>buttonBox</sender>
+   <signal>accepted()</signal>
+   <receiver>HapticUnitConfigDialog</receiver>
+   <slot>accept()</slot>
+   <hints>
+    <hint type="sourcelabel">
+     <x>248</x>
+     <y>254</y>
+    </hint>
+    <hint type="destinationlabel">
+     <x>157</x>
+     <y>274</y>
+    </hint>
+   </hints>
+  </connection>
+  <connection>
+   <sender>buttonBox</sender>
+   <signal>rejected()</signal>
+   <receiver>HapticUnitConfigDialog</receiver>
+   <slot>reject()</slot>
+   <hints>
+    <hint type="sourcelabel">
+     <x>316</x>
+     <y>260</y>
+    </hint>
+    <hint type="destinationlabel">
+     <x>286</x>
+     <y>274</y>
+    </hint>
+   </hints>
+  </connection>
+ </connections>
+</ui>
diff --git a/source/RobotAPI/gui_plugins/HapticUnitPlugin/HapticUnitGuiPlugin.cpp b/source/RobotAPI/gui_plugins/HapticUnitPlugin/HapticUnitGuiPlugin.cpp
new file mode 100644
index 000000000..c40d50f2f
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/HapticUnitPlugin/HapticUnitGuiPlugin.cpp
@@ -0,0 +1,177 @@
+#include "HapticUnitGuiPlugin.h"
+#include "HapticUnitConfigDialog.h"
+#include "ui_HapticUnitConfigDialog.h"
+
+#include <Core/core/system/ArmarXDataPath.h>
+#include <Core/observers/variant/SingleTypeVariantList.h>
+#include <Core/util/variants/eigen3/MatrixVariant.h>
+#include <Core/observers/variant/TimestampVariant.h>
+#include <IceUtil/Time.h>
+
+
+// Qt headers
+#include <Qt>
+#include <QtGlobal>
+#include <QtGui/QPushButton>
+#include <QtGui/QComboBox>
+
+using namespace armarx;
+
+
+HapticUnitGuiPlugin::HapticUnitGuiPlugin()
+{
+    addWidget<HapticUnitWidget>();
+}
+
+
+HapticUnitWidget::HapticUnitWidget()
+{
+    // init gui
+    ui.setupUi(getWidget());
+    //ui.stateOpen->setChecked(true);
+    HapticObserverProxyName = "HapticUnitObserver";
+
+    updateTimer = new QTimer(this);
+    layout = new QGridLayout(getWidget());
+
+
+
+
+}
+
+
+void HapticUnitWidget::onInitComponent()
+{
+    usingProxy(HapticObserverProxyName);
+    //usingTopic(handName + "State");
+    //ARMARX_WARNING << "Listening on Topic: " << handName + "State";
+}
+
+
+void HapticUnitWidget::onConnectComponent()
+{
+    HapticObserverProxy = getProxy<ObserverInterfacePrx>(HapticObserverProxyName);
+    connectSlots();
+    createMatrixWidgets();
+    updateTimer->start(25); // 50 Hz
+
+
+    /*SingleTypeVariantListPtr preshapeStrings = SingleTypeVariantListPtr::dynamicCast(HapticUnitProxy->getPreshapeNames());
+    QStringList list;
+    int preshapeCount = preshapeStrings->getSize();
+    for (int i = 0; i < preshapeCount; ++i)
+    {
+        std::string shape = ((preshapeStrings->getVariant(i))->get<std::string>());
+        list << QString::fromStdString(shape);
+    }
+    ui.comboPreshapes->addItems(list);*/
+}
+
+
+void HapticUnitWidget::onExitComponent()
+{
+    updateTimer->stop();
+}
+
+
+QPointer<QDialog> HapticUnitWidget::getConfigDialog(QWidget* parent)
+{
+    if(!dialog)
+    {
+        dialog = new HapticUnitConfigDialog(parent);
+    }
+    /*dialog->ui->editHapticUnitName->setText(QString::fromStdString(HapticUnitProxyName));
+    dialog->ui->editHandName->setText(QString::fromStdString(handName));*/
+    return qobject_cast<HapticUnitConfigDialog*>(dialog);
+}
+
+
+ void HapticUnitWidget::configured()
+ {
+     //HapticUnitProxyName = dialog->ui->editHapticUnitName->text().toStdString();
+     //handName = dialog->ui->editHandName->text().toStdString();
+ }
+
+ void HapticUnitWidget::updateData()
+ {
+     /*//::armarx::ChannelRegistryEntry channel = HapticObserverProxy->getAvailableChannels().at("A");
+     //float max = HapticObserverProxy->getDataField(new DataFieldIdentifier(HapticObserverProxyName, "A", "max"))->getFloat();
+     MatrixFloatPtr matrix1 = VariantPtr::dynamicCast(HapticObserverProxy->getDataField(new DataFieldIdentifier(HapticObserverProxyName, "A", "matrix")))->get<MatrixFloat>();
+     MatrixFloatPtr matrix2 = VariantPtr::dynamicCast(HapticObserverProxy->getDataField(new DataFieldIdentifier(HapticObserverProxyName, "B", "matrix")))->get<MatrixFloat>();
+
+     //::armarx::DataFieldRegistryEntry dataFieldMax = channel.dataFields.at("max");
+     //float max = dataFieldMax.value->getFloat();
+     //::armarx::DataFieldRegistryEntry dataFieldMatrix = channel.dataFields.at("matrix");
+
+     //MatrixFloatPtr matrix = VariantPtr::dynamicCast(dataFieldMatrix.value)->get<MatrixFloat>();
+
+     //ARMARX_LOG << max;
+     //ARMARX_LOG << matrix1->toEigen();
+     matrixDisplays.at(0)->setData(matrix1->toEigen().cast<double>());
+     matrixDisplays.at(0)->invokeUpdate();
+     matrixDisplays.at(1)->setData(matrix2->toEigen().cast<double>());
+     matrixDisplays.at(1)->invokeUpdate();*/
+
+     for(std::map<std::string,MatrixDisplayWidget*>::iterator it = matrixDisplays.begin(); it != matrixDisplays.end(); it++)
+     {
+         MatrixFloatPtr matrix = VariantPtr::dynamicCast(HapticObserverProxy->getDataField(new DataFieldIdentifier(HapticObserverProxyName, it->first, "matrix")))->get<MatrixFloat>();
+         std::string name = HapticObserverProxy->getDataField(new DataFieldIdentifier(HapticObserverProxyName, it->first, "name"))->getString();
+         float rate = HapticObserverProxy->getDataField(new DataFieldIdentifier(HapticObserverProxyName, it->first, "rate"))->getFloat();
+         TimestampVariantPtr timestamp = VariantPtr::dynamicCast(HapticObserverProxy->getDataField(new DataFieldIdentifier(HapticObserverProxyName, it->first, "timestamp")))->get<TimestampVariant>();
+         MatrixDisplayWidget* matrixDisplay = it->second;
+         matrixDisplay->setData(matrix->toEigen().cast<double>());
+         matrixDisplay->setInfoOverlay(QString::fromStdString(it->first) + ": " + QString::fromStdString(name) + " " + QString::fromStdString(timestamp->toTime().toDateTime()) + " " + QString::number(rate, 'g', 4) + " Frames/s");
+         matrixDisplay->invokeUpdate();
+     }
+
+ }
+
+
+void HapticUnitWidget::loadSettings(QSettings *settings)
+{
+    //HapticUnitProxyName = settings->value("HapticUnitProxyName", QString::fromStdString(HapticUnitProxyName)).toString().toStdString();
+    //handName = settings->value("handName", QString::fromStdString(handName)).toString().toStdString();
+}
+
+
+void HapticUnitWidget::saveSettings(QSettings *settings)
+{
+    //settings->setValue("HapticUnitProxyName", QString::fromStdString(HapticUnitProxyName));
+    //settings->setValue("handName", QString::fromStdString(handName));
+}
+
+
+void HapticUnitWidget::connectSlots()
+{
+    connect(this, SIGNAL(doUpdateDisplayWidgets()), SLOT(updateDisplayWidgets()), Qt::QueuedConnection);
+    connect(updateTimer, SIGNAL(timeout()), this, SLOT(updateData()));
+    /*connect(ui.buttonOpen, SIGNAL(clicked()), this, SLOT(openHand()));
+    connect(ui.buttonClose, SIGNAL(clicked()), this, SLOT(closeHand()));
+    connect(ui.buttonPreshape, SIGNAL(clicked()), this, SLOT(preshapeHand()));
+    connect(ui.comboPreshapes, SIGNAL(currentIndexChanged(const QString&)), this, SLOT(selectPreshape(const QString&)));*/
+}
+
+void HapticUnitWidget::createMatrixWidgets()
+{
+    ARMARX_LOG << "HapticUnitWidget::createMatrixWidgets()";
+    emit doUpdateDisplayWidgets();
+}
+
+void HapticUnitWidget::updateDisplayWidgets()
+{
+    int i = 0;
+    ChannelRegistry channels = HapticObserverProxy->getAvailableChannels();
+    for(ChannelRegistry::iterator it = channels.begin(); it != channels.end(); it++)
+    {
+        ARMARX_LOG << it->first;
+        MatrixDisplayWidget* matrixDisplay = new MatrixDisplayWidget();
+        matrixDisplay->setRange(0, 4095);
+        matrixDisplays[it->first] = matrixDisplay;
+        layout->addWidget(matrixDisplay, 0, i);
+        i++;
+    }
+}
+
+
+Q_EXPORT_PLUGIN2(armar3_gui_HapticUnitGuiPlugin, HapticUnitGuiPlugin)
+
diff --git a/source/RobotAPI/gui_plugins/HapticUnitPlugin/HapticUnitGuiPlugin.h b/source/RobotAPI/gui_plugins/HapticUnitPlugin/HapticUnitGuiPlugin.h
new file mode 100644
index 000000000..6defbcd7c
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/HapticUnitPlugin/HapticUnitGuiPlugin.h
@@ -0,0 +1,135 @@
+/*
+* This file is part of ArmarX.
+*
+* ArmarX is free software; you can redistribute it and/or modify
+* it under the terms of the GNU Lesser General Public License as
+* published by the Free Software Foundation; either version 2 of
+* the License, or (at your option) any later version.
+*
+* ArmarX is distributed in the hope that it will be useful, but
+* WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+* GNU Lesser General Public License for more details.
+*
+* You should have received a copy of the GNU General Public License
+* along with this program. If not, see <http://www.gnu.org/licenses/>.
+*
+* @package    ArmarX::Component::ObjectExaminerGuiPlugin
+* @author     Nikolaus Vahrenkamp ( vahrenkamp at kit dot edu)
+* @copyright  2012
+* @license    http://www.gnu.org/licenses/gpl.txt
+*             GNU General Public License
+
+*/
+
+#ifndef _ARMARXGUI_PLUGINS_HapticUnitWIDGET_H
+#define _ARMARXGUI_PLUGINS_HapticUnitWIDGET_H
+
+/* ArmarX headers */
+#include "ui_HapticUnitGuiPlugin.h"
+#include <Core/core/Component.h>
+#include <Gui/ArmarXGuiLib/ArmarXGuiPlugin.h>
+#include <Gui/ArmarXGuiLib/ArmarXComponentWidgetController.h>
+#include <Core/observers/Observer.h>
+
+/* Qt headers */
+#include <QtGui/QMainWindow>
+#include <QtCore/QTimer>
+
+#include <string>
+#include <QLayout>
+#include "MatrixDisplayWidget.h"
+
+
+namespace armarx
+{
+    class HapticUnitConfigDialog;
+
+    /**
+      \class HapticUnitGuiPlugin
+      \brief With this plugin the HapticUnit can be controlled.
+      \ingroup ArmarXGuiPlugins
+
+      \see HapticUnitWidget
+      */
+    class HapticUnitGuiPlugin :
+            public ArmarXGuiPlugin
+    {
+    public:
+        HapticUnitGuiPlugin();
+        QString getPluginName()
+        {
+            return "HapticUnitGuiPlugin";
+        }
+    };
+
+    /**
+      \class HapticUnitWidget
+      \brief With this widget the HapticUnit can be controlled.
+      \ingroup ArmarXGuiPlugins
+
+      \see HapticUnitGuiPlugin
+      */
+    class HapticUnitWidget :
+            public ArmarXComponentWidgetController
+    {
+        Q_OBJECT
+    public:
+        HapticUnitWidget();
+        ~HapticUnitWidget()
+        {}
+
+        // inherited from Component
+        virtual void onInitComponent();
+        virtual void onConnectComponent();
+        virtual void onExitComponent();
+
+
+        // inherited of ArmarXWidget
+        virtual QString getWidgetName() const
+        {
+            return "HapticUnitGUI";
+        }
+
+        QPointer<QDialog> getConfigDialog(QWidget* parent = 0);
+        virtual void loadSettings(QSettings * settings);
+        virtual void saveSettings(QSettings * settings);
+        void configured();
+
+    public slots:
+        void updateData();
+
+    signals:
+        void doUpdateDisplayWidgets();
+
+    private slots:
+        void updateDisplayWidgets();
+
+    protected:
+        void connectSlots();
+
+        Ui::HapticUnitGuiPlugin ui;
+
+    private:
+
+        void createMatrixWidgets();
+
+    private:
+
+        std::string HapticObserverProxyName;
+        ObserverInterfacePrx HapticObserverProxy;
+
+        QPointer<QWidget> __widget;
+        QPointer<HapticUnitConfigDialog> dialog;
+
+        QTimer* updateTimer;
+
+        QGridLayout* layout;
+
+        std::map<std::string, MatrixDisplayWidget*> matrixDisplays;
+
+    };
+    //typedef boost::shared_ptr<HapticUnitWidget> HapticUnitGuiPluginPtr;
+}
+
+#endif
diff --git a/source/RobotAPI/gui_plugins/HapticUnitPlugin/HapticUnitGuiPlugin.ui b/source/RobotAPI/gui_plugins/HapticUnitPlugin/HapticUnitGuiPlugin.ui
new file mode 100644
index 000000000..51d71fb84
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/HapticUnitPlugin/HapticUnitGuiPlugin.ui
@@ -0,0 +1,25 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>HapticUnitGuiPlugin</class>
+ <widget class="QWidget" name="HapticUnitGuiPlugin">
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>338</width>
+    <height>210</height>
+   </rect>
+  </property>
+  <property name="sizePolicy">
+   <sizepolicy hsizetype="Minimum" vsizetype="Minimum">
+    <horstretch>0</horstretch>
+    <verstretch>0</verstretch>
+   </sizepolicy>
+  </property>
+  <property name="windowTitle">
+   <string>Form</string>
+  </property>
+ </widget>
+ <resources/>
+ <connections/>
+</ui>
diff --git a/source/RobotAPI/gui_plugins/HapticUnitPlugin/MatrixDisplayWidget.cpp b/source/RobotAPI/gui_plugins/HapticUnitPlugin/MatrixDisplayWidget.cpp
new file mode 100644
index 000000000..102a023af
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/HapticUnitPlugin/MatrixDisplayWidget.cpp
@@ -0,0 +1,73 @@
+#include "MatrixDisplayWidget.h"
+#include "ui_MatrixDisplayWidget.h"
+
+#include <QPainter>
+#include <pthread.h>
+#include <iostream>
+
+using namespace std;
+using namespace armarx;
+
+MatrixDisplayWidget::MatrixDisplayWidget(QWidget *parent) :
+    QWidget(parent),
+    ui(new Ui::MatrixDisplayWidget)
+{
+    ui->setupUi(this);
+    this->min = 0;
+    this->max = 1;
+    this->data = MatrixXd(1, 1);
+    this->data(0, 0) = 0;
+    QColor c[] = {QColor::fromHsv(0, 0, 0), QColor::fromHsv(240, 255, 255), QColor::fromHsv(270, 255, 255), QColor::fromHsv(300, 255, 255),
+                  QColor::fromHsv(0, 255, 255), QColor::fromHsv(30, 255, 255), QColor::fromHsv(60, 255, 255)};
+    this->colors = std::valarray<QColor>(c, sizeof c / sizeof c[0]);
+
+    //connect(this, SIGNAL(updateData(MatrixXd)), SLOT(setData(MatrixXd)), Qt::QueuedConnection);
+    connect(this, SIGNAL(doUpdate()), SLOT(update()), Qt::QueuedConnection);
+}
+
+MatrixDisplayWidget::~MatrixDisplayWidget()
+{
+    delete ui;
+}
+
+void MatrixDisplayWidget::paintEvent(QPaintEvent *)
+{
+    mtx.lock();
+    MatrixXd data = this->data;
+
+    //cout << "[" << pthread_self() << "] MatrixDisplayWidget::paintEvent" << endl;
+
+    int pixelSize = std::min(width() / data.cols(), height() / data.rows());
+    int dx = (width() - pixelSize * data.cols()) / 2;
+    int dy = (height() - pixelSize * data.rows()) / 2;
+    QPainter painter(this);
+    painter.fillRect(rect(), QColor::fromRgb(0,0,0));
+    painter.setFont(QFont("Arial", 8));
+
+    for(int x = 0; x < data.cols(); x++)
+    {
+        for(int y = 0; y < data.rows(); y++)
+        {
+            QRect target = QRect(dx + x * pixelSize, dy + y * pixelSize, pixelSize, pixelSize);
+            painter.fillRect(target, getColor(data(y, x), min, max));
+            painter.drawText(target, Qt::AlignCenter, QString::number(data(y, x)));
+        }
+    }
+    painter.setFont(QFont("Arial", 12));
+    painter.drawText(rect(), Qt::AlignBottom | Qt::AlignRight, infoOverlay);
+
+    mtx.unlock();
+}
+
+QColor MatrixDisplayWidget::getColor(double value, double min, double max)
+{
+    value = (value - min) / (max - min) * (colors.size() - 1);
+    if(value < 0) return colors[0];
+    if(value >= colors.size() - 1) return colors[colors.size() - 1];
+    int i = (int)value;
+    double f2 = value - i;
+    double f1 = 1- f2;
+    QColor c1 = colors[i];
+    QColor c2 = colors[i + 1];
+    return QColor((int)(c1.red() * f1 + c2.red() * f2), (int)(c1.green() * f1 + c2.green() * f2), (int)(c1.blue() * f1 + c2.blue() * f2));
+}
diff --git a/source/RobotAPI/gui_plugins/HapticUnitPlugin/MatrixDisplayWidget.h b/source/RobotAPI/gui_plugins/HapticUnitPlugin/MatrixDisplayWidget.h
new file mode 100644
index 000000000..2978adac4
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/HapticUnitPlugin/MatrixDisplayWidget.h
@@ -0,0 +1,67 @@
+#ifndef MATRIXDISPLAYWIDGET_H
+#define MATRIXDISPLAYWIDGET_H
+
+#include <QWidget>
+#include <QMutex>
+#include <eigen3/Eigen/Dense>
+#include <valarray>
+
+using Eigen::MatrixXd;
+
+namespace Ui {
+class MatrixDisplayWidget;
+}
+
+namespace armarx
+{
+    class MatrixDisplayWidget : public QWidget
+    {
+        Q_OBJECT
+
+    signals:
+        void doUpdate();
+
+    public slots:
+        void setData(MatrixXd data)
+        {
+            mtx.lock();
+            this->data = data;
+            mtx.unlock();
+            //this->update();
+        }
+
+    public:
+        explicit MatrixDisplayWidget(QWidget *parent = 0);
+        ~MatrixDisplayWidget();
+        void paintEvent(QPaintEvent *);
+
+
+
+        void setRange(double min, double max)
+        {
+            this->min = min;
+            this->max = max;
+        }
+        QColor getColor(double value, double min, double max);
+
+        void invokeUpdate(){
+            emit doUpdate();
+        }
+        void setInfoOverlay(QString infoOverlay)
+        {
+            mtx.lock();
+            this->infoOverlay = infoOverlay;
+            mtx.unlock();
+        }
+
+    private:
+        Ui::MatrixDisplayWidget *ui;
+        MatrixXd data;
+        double min, max;
+        std::valarray<QColor> colors;
+        QMutex mtx;
+        QString infoOverlay;
+    };
+}
+
+#endif // MATRIXDISPLAYWIDGET_H
diff --git a/source/RobotAPI/gui_plugins/HapticUnitPlugin/MatrixDisplayWidget.ui b/source/RobotAPI/gui_plugins/HapticUnitPlugin/MatrixDisplayWidget.ui
new file mode 100644
index 000000000..2ccbb9a34
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/HapticUnitPlugin/MatrixDisplayWidget.ui
@@ -0,0 +1,19 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>MatrixDisplayWidget</class>
+ <widget class="QWidget" name="MatrixDisplayWidget">
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>372</width>
+    <height>318</height>
+   </rect>
+  </property>
+  <property name="windowTitle">
+   <string>Form</string>
+  </property>
+ </widget>
+ <resources/>
+ <connections/>
+</ui>
diff --git a/source/RobotAPI/gui_plugins/KinematicUnitPlugin/CMakeLists.txt b/source/RobotAPI/gui_plugins/KinematicUnitPlugin/CMakeLists.txt
new file mode 100644
index 000000000..827da5184
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/KinematicUnitPlugin/CMakeLists.txt
@@ -0,0 +1,46 @@
+armarx_set_target("KinematicUnitGuiPlugin")
+
+find_package(Qt4 COMPONENTS QtCore QtGui QtOpenGL QUIET)
+
+find_package(Eigen3 QUIET)
+
+# VirtualRobot (adds dependencies to COin3D and SoQt)
+find_package(Simox 2.1.5 QUIET)
+find_package(ArmarXGui QUIET)
+
+armarx_build_if(ArmarXGui_FOUND "ArmarXGui not available")
+
+armarx_build_if(QT_FOUND "Qt not available")
+armarx_build_if(QT_QTOPENGL_FOUND "QtOpenGL not available")
+armarx_build_if(Eigen3_FOUND "Eigen3 not available")
+armarx_build_if(Simox_FOUND "VirtualRobot not available")
+
+include(${QT_USE_FILE})
+
+include_directories(${Eigen3_INCLUDE_DIR})
+include_directories(${Simox_INCLUDE_DIRS})
+
+
+set(SOURCES KinematicUnitGuiPlugin.cpp
+     KinematicUnitConfigDialog.cpp)
+set(HEADERS KinematicUnitGuiPlugin.h
+     KinematicUnitConfigDialog.h)
+
+set(GUI_MOC_HDRS
+    KinematicUnitGuiPlugin.h
+    KinematicUnitConfigDialog.h
+)
+
+set(GUI_UIS
+    kinematicunitguiplugin.ui
+    KinematicUnitConfigDialog.ui
+)
+
+set(COMPONENT_LIBS RobotAPIUnits ${Simox_LIBRARIES})
+
+set(LIB_VERSION    0.1.0)
+set(LIB_SOVERSION  0)
+
+if (ArmarXGui_FOUND)
+	armarx_gui_library(KinematicUnitGuiPlugin "${SOURCES}" "${GUI_MOC_HDRS}" "${GUI_UIS}" "" "${COMPONENT_LIBS}" "${LIB_VERSION}" "${LIB_SOVERSION}")
+endif()
diff --git a/source/RobotAPI/gui_plugins/KinematicUnitPlugin/KinematicUnitConfigDialog.cpp b/source/RobotAPI/gui_plugins/KinematicUnitPlugin/KinematicUnitConfigDialog.cpp
new file mode 100644
index 000000000..34d5e2b48
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/KinematicUnitPlugin/KinematicUnitConfigDialog.cpp
@@ -0,0 +1,93 @@
+/*
+* This file is part of ArmarX.
+*
+* ArmarX is free software; you can redistribute it and/or modify
+* it under the terms of the GNU Lesser General Public License as
+* published by the Free Software Foundation; either version 2 of
+* the License, or (at your option) any later version.
+*
+* ArmarX is distributed in the hope that it will be useful, but
+* WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+* GNU Lesser General Public License for more details.
+*
+* You should have received a copy of the GNU General Public License
+* along with this program. If not, see <http://www.gnu.org/licenses/>.
+*
+* @package    ArmarX::
+* @author     Mirko Waechter ( mirko.waechter at kit dot edu)
+* @date       2012
+* @copyright  http://www.gnu.org/licenses/gpl.txt
+*             GNU General Public License
+*/
+
+#include "KinematicUnitConfigDialog.h"
+#include "ui_KinematicUnitConfigDialog.h"
+
+#include <QTimer>
+#include <QPushButton>
+
+
+// ArmarX
+#include <RobotAPI/interface/units/KinematicUnitInterface.h>
+
+#include <IceUtil/UUID.h>
+
+#include <Gui/ArmarXGuiLib/utility/IceProxyFinder.h>
+
+using namespace armarx;
+
+KinematicUnitConfigDialog::KinematicUnitConfigDialog(QWidget *parent) :
+    QDialog(parent),
+    ui(new Ui::KinematicUnitConfigDialog),
+    uuid(IceUtil::generateUUID())
+{
+    ui->setupUi(this);
+    fileDialog = new QFileDialog(parent);
+    fileDialog->setModal(true);
+    fileDialog->setFileMode(QFileDialog::ExistingFiles);
+    QStringList fileTypes;
+    fileTypes << tr("XML (*.xml)")
+        << tr("All Files (*.*)");
+    fileDialog->setNameFilters(fileTypes);
+    connect(ui->btnSelectModelFile, SIGNAL(clicked()), fileDialog, SLOT(show()));
+    connect(fileDialog, SIGNAL(accepted()), this, SLOT(modelFileSelected()));
+    ui->buttonBox->button( QDialogButtonBox::Ok )->setDefault(true);
+    proxyFinder = new IceProxyFinder<KinematicUnitInterfacePrx>(this);
+    proxyFinder->setSearchMask("*Unit");
+    ui->gridLayout->addWidget(proxyFinder, 2,1,1,2);
+
+}
+
+KinematicUnitConfigDialog::~KinematicUnitConfigDialog()
+{
+    delete ui;
+}
+
+void
+KinematicUnitConfigDialog::onInitComponent()
+{
+    proxyFinder->setIceManager(getIceManager());
+}
+
+void
+KinematicUnitConfigDialog::onConnectComponent()
+{
+
+}
+
+void KinematicUnitConfigDialog::onExitComponent()
+{
+    QObject::disconnect();
+
+}
+
+
+
+void KinematicUnitConfigDialog::modelFileSelected()
+{
+    ui->editRobotFilepath->setText(fileDialog->selectedFiles()[0]);
+}
+
+
+
diff --git a/source/RobotAPI/gui_plugins/KinematicUnitPlugin/KinematicUnitConfigDialog.h b/source/RobotAPI/gui_plugins/KinematicUnitPlugin/KinematicUnitConfigDialog.h
new file mode 100644
index 000000000..de40adddd
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/KinematicUnitPlugin/KinematicUnitConfigDialog.h
@@ -0,0 +1,72 @@
+/*
+* This file is part of ArmarX.
+*
+* ArmarX is free software; you can redistribute it and/or modify
+* it under the terms of the GNU Lesser General Public License as
+* published by the Free Software Foundation; either version 2 of
+* the License, or (at your option) any later version.
+*
+* ArmarX is distributed in the hope that it will be useful, but
+* WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+* GNU Lesser General Public License for more details.
+*
+* You should have received a copy of the GNU General Public License
+* along with this program. If not, see <http://www.gnu.org/licenses/>.
+*
+* @package    ArmarX::
+* @author     Mirko Waechter ( mirko.waechter at kit dot edu)
+* @date       2012
+* @copyright  http://www.gnu.org/licenses/gpl.txt
+*             GNU General Public License
+*/
+
+#ifndef KINEMATICUNITCONFIGDIALOG_H
+#define KINEMATICUNITCONFIGDIALOG_H
+
+#include <QDialog>
+#include <QFileDialog>
+
+#include <Core/core/services/tasks/RunningTask.h>
+#include <Core/core/IceManager.h>
+#include <Core/core/ManagedIceObject.h>
+#include <Gui/ArmarXGuiLib/utility/IceProxyFinder.h>
+
+namespace Ui {
+    class KinematicUnitConfigDialog;
+}
+
+namespace armarx{
+    class KinematicUnitConfigDialog :
+        public QDialog,
+        virtual public ManagedIceObject
+    {
+        Q_OBJECT
+
+    public:
+        explicit KinematicUnitConfigDialog(QWidget *parent = 0);
+        ~KinematicUnitConfigDialog();
+
+        // inherited from ManagedIceObject
+        std::string getDefaultName() const { return "KinematicUnitConfigDialog" + uuid;}
+        void onInitComponent();
+        void onConnectComponent();
+        void onExitComponent();
+
+        void updateKinematicUnitList();
+    signals:
+
+    public slots:
+        void modelFileSelected();
+    private:
+
+        IceManagerPtr iceManager;
+        IceProxyFinderBase* proxyFinder;
+        Ui::KinematicUnitConfigDialog *ui;
+        QFileDialog* fileDialog;
+        std::string uuid;
+        friend class KinematicUnitWidgetController;
+    };
+}
+
+#endif
diff --git a/source/RobotAPI/gui_plugins/KinematicUnitPlugin/KinematicUnitConfigDialog.ui b/source/RobotAPI/gui_plugins/KinematicUnitPlugin/KinematicUnitConfigDialog.ui
new file mode 100644
index 000000000..377f3b242
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/KinematicUnitPlugin/KinematicUnitConfigDialog.ui
@@ -0,0 +1,129 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>KinematicUnitConfigDialog</class>
+ <widget class="QDialog" name="KinematicUnitConfigDialog">
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>527</width>
+    <height>133</height>
+   </rect>
+  </property>
+  <property name="sizePolicy">
+   <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+    <horstretch>0</horstretch>
+    <verstretch>0</verstretch>
+   </sizepolicy>
+  </property>
+  <property name="windowTitle">
+   <string>Dialog</string>
+  </property>
+  <property name="toolTip">
+   <string/>
+  </property>
+  <layout class="QGridLayout" name="gridLayout_2">
+   <item row="2" column="0">
+    <widget class="QDialogButtonBox" name="buttonBox">
+     <property name="orientation">
+      <enum>Qt::Horizontal</enum>
+     </property>
+     <property name="standardButtons">
+      <set>QDialogButtonBox::Cancel|QDialogButtonBox::Ok</set>
+     </property>
+    </widget>
+   </item>
+   <item row="0" column="0">
+    <layout class="QGridLayout" name="gridLayout">
+     <item row="2" column="0">
+      <widget class="QLabel" name="labelKinematicUnitName">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="Minimum" vsizetype="Preferred">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="text">
+        <string>Kinematic unit name</string>
+       </property>
+      </widget>
+     </item>
+     <item row="1" column="1" colspan="2">
+      <widget class="QLineEdit" name="ediRobotNodeSetName"/>
+     </item>
+     <item row="0" column="2">
+      <widget class="QToolButton" name="btnSelectModelFile">
+       <property name="text">
+        <string>...</string>
+       </property>
+       <property name="icon">
+        <iconset resource="../../ArmarXGui/icons.qrc">
+         <normaloff>:/icons/document-open-folder.png</normaloff>:/icons/document-open-folder.png</iconset>
+       </property>
+      </widget>
+     </item>
+     <item row="0" column="1">
+      <widget class="QLineEdit" name="editRobotFilepath"/>
+     </item>
+     <item row="0" column="0">
+      <widget class="QLabel" name="labelRobotFilepath">
+       <property name="text">
+        <string>Robot model filepath</string>
+       </property>
+      </widget>
+     </item>
+     <item row="1" column="0">
+      <widget class="QLabel" name="labelRobotNodeSetName">
+       <property name="text">
+        <string>Robot nodeset name</string>
+       </property>
+      </widget>
+     </item>
+    </layout>
+   </item>
+  </layout>
+ </widget>
+ <tabstops>
+  <tabstop>editRobotFilepath</tabstop>
+  <tabstop>btnSelectModelFile</tabstop>
+  <tabstop>ediRobotNodeSetName</tabstop>
+  <tabstop>buttonBox</tabstop>
+ </tabstops>
+ <resources>
+  <include location="../../ArmarXGui/icons.qrc"/>
+ </resources>
+ <connections>
+  <connection>
+   <sender>buttonBox</sender>
+   <signal>accepted()</signal>
+   <receiver>KinematicUnitConfigDialog</receiver>
+   <slot>accept()</slot>
+   <hints>
+    <hint type="sourcelabel">
+     <x>248</x>
+     <y>254</y>
+    </hint>
+    <hint type="destinationlabel">
+     <x>157</x>
+     <y>274</y>
+    </hint>
+   </hints>
+  </connection>
+  <connection>
+   <sender>buttonBox</sender>
+   <signal>rejected()</signal>
+   <receiver>KinematicUnitConfigDialog</receiver>
+   <slot>reject()</slot>
+   <hints>
+    <hint type="sourcelabel">
+     <x>316</x>
+     <y>260</y>
+    </hint>
+    <hint type="destinationlabel">
+     <x>286</x>
+     <y>274</y>
+    </hint>
+   </hints>
+  </connection>
+ </connections>
+</ui>
diff --git a/source/RobotAPI/gui_plugins/KinematicUnitPlugin/KinematicUnitGuiPlugin.cpp b/source/RobotAPI/gui_plugins/KinematicUnitPlugin/KinematicUnitGuiPlugin.cpp
new file mode 100644
index 000000000..19e8bb04f
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/KinematicUnitPlugin/KinematicUnitGuiPlugin.cpp
@@ -0,0 +1,1019 @@
+#include "KinematicUnitGuiPlugin.h"
+#include "KinematicUnitConfigDialog.h"
+#include "ui_KinematicUnitConfigDialog.h"
+#include <Core/core/system/ArmarXDataPath.h>
+#include <Core/core/ArmarXObjectScheduler.h>
+
+// Qt headers
+#include <Qt>
+#include <QtGlobal>
+#include <QSpinBox>
+#include <QSlider>
+#include <QPushButton>
+#include <QStringList>
+//#include <QTableWidget>
+#include <QTableView>
+#include <QCheckBox>
+
+#include <Inventor/SoDB.h>
+#include <Inventor/Qt/SoQt.h>
+
+// System
+#include <stdio.h>
+#include <string>
+#include <string.h>
+#include <stdlib.h>
+#include <iostream>
+#include <math.h>
+
+#include <boost/filesystem.hpp>
+
+
+// VirtualRobot
+#include <VirtualRobot/XML/RobotIO.h>
+
+using namespace armarx;
+using namespace VirtualRobot;
+using namespace std;
+
+
+KinematicUnitGuiPlugin::KinematicUnitGuiPlugin()
+{
+    addWidget<KinematicUnitWidgetController>();
+}
+
+
+KinematicUnitWidgetController::KinematicUnitWidgetController() :
+    kinematicUnitNode(NULL),
+    selectedControlMode(ePositionControl)
+{
+    // init gui
+
+    ui.setupUi(getWidget());
+    ARMARX_INFO << " setup of ui finished" << flush;
+}
+
+
+void KinematicUnitWidgetController::onInitComponent()
+{
+//    if(kinematicUnitFile.empty())
+//    {
+//        KinematicUnitConfigDialog dialog;
+//        if(dialog.exec())
+//        {
+//            kinematicUnitFile = dialog.ui->editRobotFilepath->text().toStdString();
+//            robotNodeSetName = dialog.ui->ediRobotNodeSetName->text().toStdString();
+//            kinematicUnitName = dialog.ui->editKinematicUnitName->text().toStdString();
+//        }
+//        else {
+//            return;
+//        }
+//    }
+
+    dirty_squaresum_old.resize(5,0);
+    ARMARX_INFO << flush;
+    verbose = true;
+
+//    // parsing properties from ice config
+//    kinematicUnitFile = getProperty<std::string>("RobotFileName").getValue();
+//    robotNodeSetName = getProperty<std::string>("RobotNodeSetName").getValue();
+//    kinematicUnitName = getProperty<std::string>("KinematicUnitName").getValue();
+
+    ARMARX_INFO << "RobotFileName: " << kinematicUnitFile << flush;
+    ARMARX_INFO << "RobotNodeSetName: " << robotNodeSetName << flush;
+    ARMARX_INFO << "KinematicUnitName: " << kinematicUnitName << flush;
+
+    //   VirtualRobot::RobotPtr robot = VirtualRobot::RobotIO::loadRobot(robotFile, VirtualRobot::RobotIO::eStructure);
+
+    // init
+    robot = loadRobotFile(kinematicUnitFile);
+    if(!robot)
+    {
+        getObjectScheduler()->terminate();
+        if(getWidget()->parentWidget())
+            getWidget()->parentWidget()->close();
+        std::cout << "returning" << std::endl;
+        return;
+    }
+    kinematicUnitVisualization = getCoinVisualization(robot);
+    kinematicUnitNode = kinematicUnitVisualization->getCoinVisualization();
+    kinematicUnitNode->ref();
+
+    robotNodeSet = getRobotNodeSet(robot, robotNodeSetName);
+
+
+
+    string widgetLabel = "KinematicUnit: " + kinematicUnitName;
+    ui.labelKinematicUnitName->setText(QString(widgetLabel.c_str()));
+    initGUIComboBox(robotNodeSet); // init the pull down menu (QT: ComboBox)
+    initGUIJointListTable(robotNodeSet);
+
+    connect(this, SIGNAL(jointAnglesReported()), this, SLOT(updateJointAnglesTable()), Qt::QueuedConnection);
+    connect(this, SIGNAL(jointVelocitiesReported()), this, SLOT(updateJointVelocitiesTable()), Qt::QueuedConnection);
+    connect(this, SIGNAL(jointTorquesReported()), this, SLOT(updateJointTorquesTable()), Qt::QueuedConnection);
+    connect(this, SIGNAL(jointCurrentsReported()), this, SLOT(updateJointCurrentsTable()), Qt::QueuedConnection);
+    connect(this, SIGNAL(jointControlModesReported()), this, SLOT(updateControlModesTable()), Qt::QueuedConnection);
+    connect(this, SIGNAL(jointMotorTemperaturesReported()), this, SLOT(updateJointMotorTemperaturesTable()), Qt::QueuedConnection);
+    connect(this, SIGNAL(jointStatusesReported()), this, SLOT(updateJointStatusesTable()), Qt::QueuedConnection);
+
+    ui.radioButtonPositionControl->setChecked(true);
+
+    std::string kinematicUnitReporterName = robotNodeSetName + "State";
+    ARMARX_INFO << "topicname: " << kinematicUnitReporterName << flush;
+    usingTopic(kinematicUnitReporterName);
+
+    usingProxy(kinematicUnitName);
+}
+
+void KinematicUnitWidgetController::onConnectComponent()
+{
+    if(!robot)
+        return;
+    ARMARX_INFO << flush;
+
+    // subscribe topic in order to receive the kinematic unit reports
+    std::string kinematicUnitReporterName = robotNodeSetName + "State";
+
+    kinematicUnitListenerPrx = getTopic<KinematicUnitListenerPrx>(kinematicUnitReporterName);
+    ARMARX_INFO << "subscribing topic: " << kinematicUnitReporterName << flush;
+
+    // get proxy to send commands to the kinematic unit
+    std::string kinematicUnitInstructionChannel = kinematicUnitName;
+    // NOW: kinematicUnitInstructionChannel -> HeadKinematicUnit
+    kinematicUnitInterfacePrx = getProxy<KinematicUnitInterfacePrx>(kinematicUnitInstructionChannel);
+    ARMARX_INFO << "setting instruction channel to: " << kinematicUnitReporterName << flush; //HeadState //RobotState
+    connectSlots();
+}
+
+void KinematicUnitWidgetController::onExitComponent()
+{
+
+    if (kinematicUnitNode)
+        kinematicUnitNode->unref();
+}
+
+QPointer<QDialog> KinematicUnitWidgetController::getConfigDialog(QWidget* parent)
+{
+    if(!dialog)
+    {
+        dialog = new KinematicUnitConfigDialog(parent);
+        dialog->setName(dialog->getDefaultName());
+        boost::filesystem::path dir(KINEMATIC_UNIT_FILE_DEFAULT);
+
+        dialog->fileDialog->setDirectory(QString::fromStdString(dir.remove_filename().string()));
+        dialog->ui->editRobotFilepath->setText(QString::fromStdString(KINEMATIC_UNIT_FILE_DEFAULT));
+        dialog->ui->ediRobotNodeSetName->setText(KINEMATIC_UNIT_NAME_DEFAULT);
+
+    }
+    return qobject_cast<KinematicUnitConfigDialog*>(dialog);
+}
+
+
+
+ void KinematicUnitWidgetController::configured()
+ {
+     ARMARX_VERBOSE << "KinematicUnitWidget::configured()";
+     kinematicUnitFile = dialog->ui->editRobotFilepath->text().toStdString();
+     robotNodeSetName = dialog->ui->ediRobotNodeSetName->text().toStdString();
+     kinematicUnitName = dialog->proxyFinder->getSelectedProxyName().toStdString();
+ }
+
+
+void KinematicUnitWidgetController::loadSettings(QSettings *settings)
+{
+    kinematicUnitFile = settings->value("kinematicUnitFile", QString::fromStdString(KINEMATIC_UNIT_FILE_DEFAULT)).toString().toStdString();
+    ArmarXDataPath::getAbsolutePath(kinematicUnitFile, kinematicUnitFile);
+    kinematicUnitName = settings->value("kinematicUnitName", KINEMATIC_UNIT_NAME_DEFAULT).toString().toStdString();
+    robotNodeSetName = settings->value("robotNodeSetName", KINEMATIC_UNIT_NAME_DEFAULT).toString().toStdString();
+}
+
+void KinematicUnitWidgetController::saveSettings(QSettings *settings)
+{
+
+    settings->setValue("kinematicUnitName", QString::fromStdString(kinematicUnitName));
+    settings->setValue("robotNodeSetName", QString::fromStdString(robotNodeSetName));
+    settings->setValue("kinematicUnitFile", QString::fromStdString(ArmarXDataPath::getRelativeArmarXPath(kinematicUnitFile)));
+}
+
+
+
+void KinematicUnitWidgetController::updateGuiElements()
+{
+    // modelUpdateCB();
+}
+
+void KinematicUnitWidgetController::modelUpdateCB()
+{
+
+
+    /*
+    if (data->getDirtyFlag())
+    {
+        FloatVector angles;
+        FloatVector velocities;
+        Armar3ControlMode m;
+        Armar3ComponentState s;
+
+        if (data->getDirtyFlagAngles())
+        {
+            data->getDataAngles(angles);
+            reportKinematicUnitJointAnglesDegree(angles);
+        }
+        if (data->getDirtyFlagComponentState())
+        {
+            data->getDataComponentState(s);
+            reportKinematicUnitStateChanged(s);
+        }
+        if (data->getDirtyFlagControlMode())
+        {
+            data->getDataControlMode(m);if (!currentNode)
+                return;
+    float ticks = (float)(ui.horizontalSliderKinematicUnitPos->maximum() - ui.horizontalSliderKinematicUnitPos->minimum()+1);
+    float value = (float)ui.horizontalSliderKinematicUnitPos->value();
+    float perc = (value - (float)ui.horizontalSliderKinematicUnitPos->minimum()) / ticks;
+    float lo = currentNode->getJointLimitLo();
+    float hi = currentNode->getJointLimitHi();
+    float result = lo + (hi-lo)*perc;
+
+    if (KinematicUnitPrx)
+        KinematicUnitPrx->begin_setJoint(currentNodeType,result*180.0f/(float)M_PI);
+            reportKinematicUnitControlModeChanged(m);
+        }
+    }
+*/
+}
+
+SoNode *KinematicUnitWidgetController::getScene()
+{
+    if(kinematicUnitNode)
+        std::cout << "returning scene=" << kinematicUnitNode->getName() << std::endl;
+    return kinematicUnitNode;
+}
+
+
+
+void KinematicUnitWidgetController::connectSlots()
+{
+    ui.labelKinematicUnitState->setText(QString("KinematicUnitState: --"));
+
+    // setup kinematic unit slots
+    connect(ui.requestUnitCheckBox, SIGNAL(toggled(bool)), this, SLOT(kinematicUnitRequestChange()));
+
+    connect(ui.pushButtonKinematicUnitStart, SIGNAL(clicked()), this, SLOT(kinematicUnitStart()));
+    connect(ui.pushButtonKinematicUnitStop,  SIGNAL(clicked()), this, SLOT(kinematicUnitStop()));
+    connect(ui.pushButtonKinematicUnitInit,  SIGNAL(clicked()), this, SLOT(kinematicUnitInit()));
+    connect(ui.pushButtonKinematicUnitTest,  SIGNAL(clicked()), this, SLOT(kinematicUnitTest()));
+
+    connect(ui.pushButtonKinematicUnitPos1,  SIGNAL(clicked()), this, SLOT(kinematicUnitZeroPosition()));
+    connect(ui.pushButtonKinematicUnitPos2,  SIGNAL(clicked()), this, SLOT(kinematicUnitPos2()));
+
+
+    connect(ui.nodeListComboBox, SIGNAL(activated(int)), this, SLOT(selectJoint(int)));
+    connect(ui.horizontalSliderKinematicUnitPos, SIGNAL(valueChanged(int)), this, SLOT(sliderValueChanged(int)));
+
+    connect(ui.radioButtonPositionControl, SIGNAL(clicked(bool)), this, SLOT(setControlModePosition()));
+    connect(ui.radioButtonVelocityControl, SIGNAL(clicked(bool)), this, SLOT(setControlModeVelocity()));
+    connect(ui.radioButtonTorqueControl, SIGNAL(clicked(bool)), this, SLOT(setControlModeTorque()));
+
+    connect(this, SIGNAL(jointAnglesReported()), this, SLOT(updateJointAnglesTable()), Qt::QueuedConnection);
+    connect(this, SIGNAL(jointVelocitiesReported()), this, SLOT(updateJointVelocitiesTable()), Qt::QueuedConnection);
+    connect(this, SIGNAL(jointTorquesReported()), this, SLOT(updateJointTorquesTable()), Qt::QueuedConnection);
+    connect(this, SIGNAL(jointControlModesReported()), this, SLOT(updateControlModesTable()), Qt::QueuedConnection);
+    connect(this, SIGNAL(jointMotorTemperaturesReported()), this, SLOT(updateJointMotorTemperaturesTable()), Qt::QueuedConnection);
+}
+
+void KinematicUnitWidgetController::kinematicUnitRequestChange()
+{
+    ARMARX_INFO << "toggled" << flush;
+
+    if (!kinematicUnitInterfacePrx) return;
+
+    if ( ui.requestUnitCheckBox->checkState() == Qt::Checked )
+    {
+        ARMARX_INFO << "request" << flush;
+        kinematicUnitInterfacePrx->request();
+    }
+    else
+    {
+        ARMARX_INFO << "release" << flush;
+        kinematicUnitInterfacePrx->release();
+    }
+
+}
+
+void KinematicUnitWidgetController::kinematicUnitInit()
+{
+    if (kinematicUnitInterfacePrx)
+    {
+        if (kinematicUnitInterfacePrx->getExecutionState() == eUnitInitialized)
+        {
+            ui.labelKinematicUnitState->setText(QString("Is already Initialized"));
+        } else
+        {
+            kinematicUnitInterfacePrx->init();
+            ui.labelKinematicUnitState->setText(QString("Initialized"));
+        }
+    }
+
+    // initalliy set the default control mode
+    const ControlMode defaultControlMode  = ePositionControl;
+    std::vector< RobotNodePtr > rn = robotNodeSet->getAllRobotNodes();
+    for (unsigned int i=0;i<rn.size();i++)
+    {
+        reportedJointControlModes.insert(std::make_pair(rn[i]->getName(), defaultControlMode));
+    }
+        emit updateControlModesTable();
+}
+
+
+
+
+
+void KinematicUnitWidgetController::kinematicUnitStart()
+{
+    if (kinematicUnitInterfacePrx)
+    {
+        if (kinematicUnitInterfacePrx->getExecutionState() == eUnitStarted)
+        {
+            ui.labelKinematicUnitState->setText(QString("Has already started"));
+        } else
+        { 		kinematicUnitInterfacePrx->start();
+            ui.labelKinematicUnitState->setText(QString("Started"));
+        }
+    } else
+    {
+        ARMARX_INFO << "kinematicUnitInterfacePrx not found" << flush;
+    }
+}
+
+void KinematicUnitWidgetController::kinematicUnitStop()
+{
+
+    if (kinematicUnitInterfacePrx)
+    {
+        ARMARX_INFO << flush;
+
+        if (kinematicUnitInterfacePrx->getExecutionState() == eUnitStopped)
+        {
+
+            ui.labelKinematicUnitState->setText(QString("Is already stopped"));
+        } else
+        {
+
+            kinematicUnitInterfacePrx->stop();
+            ui.labelKinematicUnitState->setText(QString("Stopped"));
+        }
+    }
+}
+
+
+void KinematicUnitWidgetController::kinematicUnitTest()
+{
+//    std::vector< RobotNodePtr > rn = robotNodeSet->getAllRobotNodes();
+//    NameValueMap jointAngles;
+//    for (unsigned int i=0;i<rn.size();i++)
+//        jointAngles[rn[i]->getName()]=(float)2;
+
+//    kinematicUnitInterfacePrx->setJointAngles(jointAngles);
+//    // updateModel();
+}
+
+
+void KinematicUnitWidgetController::kinematicUnitZeroPosition()
+{
+    boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
+    std::vector< RobotNodePtr > rn = robotNodeSet->getAllRobotNodes();
+    NameValueMap jointAngles;
+    for (unsigned int i=0;i<rn.size();i++)
+        jointAngles[rn[i]->getName()]=(float)0;
+
+    kinematicUnitInterfacePrx->setJointAngles(jointAngles);
+}
+
+void KinematicUnitWidgetController::kinematicUnitPos2()
+{
+    boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
+    std::vector< RobotNodePtr > rn = robotNodeSet->getAllRobotNodes();
+    NameValueMap jointAngles;
+
+
+    for (unsigned int i=0;i<rn.size();i++)
+    {
+        VirtualRobot::RobotNodePtr      myNode;
+
+        myNode = robotNodeSet->getAllRobotNodes()[i];
+        //ARMARX_INFO << "Robot Node Name: "<< rn[i]->getName() << flush;
+        float lo = myNode->getJointLimitLo();
+        //ARMARX_INFO << "lo: "<< lo << flush;
+        float hi = myNode->getJointLimitHi();
+        //ARMARX_INFO << "hi: "<< hi << flush;
+        float result = lo + (hi-lo)*0.5;
+        //  result*=180.0f/(float)M_PI;
+        //ARMARX_INFO << "result: "<< result << flush;
+        jointAngles[rn[i]->getName()]=(float)result;
+    }
+    kinematicUnitInterfacePrx->setJointAngles(jointAngles);
+    //updateModel();
+}
+
+
+void KinematicUnitWidgetController::setControlModePosition()
+{
+    NameControlModeMap jointModes;
+    jointModes[currentNode->getName()] = ePositionControl;
+
+    ARMARX_INFO << "setting position control for current Node Name: " << currentNode->getName() << flush;
+
+    if (kinematicUnitInterfacePrx)
+        kinematicUnitInterfacePrx->switchControlMode(jointModes);
+
+    selectedControlMode = ePositionControl;
+}
+
+void KinematicUnitWidgetController::setControlModeVelocity()
+{
+    NameControlModeMap jointModes;
+    jointModes[currentNode->getName()] = eVelocityControl;
+
+    ARMARX_INFO << "setting velocity control for current Node Name: " << currentNode->getName() << flush;
+
+    if (kinematicUnitInterfacePrx)
+        kinematicUnitInterfacePrx->switchControlMode(jointModes);
+
+    selectedControlMode = eVelocityControl;
+}
+
+void KinematicUnitWidgetController::setControlModeTorque()
+{
+    NameControlModeMap jointModes;
+    jointModes[currentNode->getName()] = eTorqueControl;
+
+    ARMARX_INFO << "setting torque control for current Node Name: " << currentNode->getName() << flush;
+
+    if (kinematicUnitInterfacePrx)
+        kinematicUnitInterfacePrx->switchControlMode(jointModes);
+
+    selectedControlMode = eTorqueControl;
+}
+
+VirtualRobot::RobotPtr KinematicUnitWidgetController::loadRobotFile(std::string fileName)
+{
+    VirtualRobot::RobotPtr robot;
+
+    if (verbose)
+        ARMARX_INFO << "Loading KinematicUnit " << kinematicUnitName << " from " << kinematicUnitFile << " ..." << flush;
+
+    if (!ArmarXDataPath::getAbsolutePath(fileName,fileName))
+    {
+       ARMARX_INFO << "Could not find Robot XML file with name " << fileName << flush;
+    }
+    robot = RobotIO::loadRobot(fileName);
+    if (!robot)
+    {
+        ARMARX_INFO << "Could not find Robot XML file with name " << fileName << "(" << kinematicUnitName << ")" << flush;
+    }
+
+    return robot;
+}
+
+CoinVisualizationPtr KinematicUnitWidgetController::getCoinVisualization(VirtualRobot::RobotPtr robot)
+{
+    CoinVisualizationPtr coinVisualization;
+
+    if (robot != NULL)
+    {
+        ARMARX_INFO << "getting coin visualization" << flush;
+        coinVisualization = robot->getVisualization<CoinVisualization>();
+
+        if (!coinVisualization || !coinVisualization->getCoinVisualization())
+        {
+            ARMARX_INFO << "could not get coin visualization" << flush;
+        }
+    }
+
+    return coinVisualization;
+}
+
+VirtualRobot::RobotNodeSetPtr KinematicUnitWidgetController::getRobotNodeSet(VirtualRobot::RobotPtr robot, std::string nodeSetName)
+{
+    VirtualRobot::RobotNodeSetPtr nodeSetPtr;
+
+    if (robot)
+    {
+        nodeSetPtr = robot->getRobotNodeSet(nodeSetName);
+
+        if (!nodeSetPtr)
+        {
+            ARMARX_INFO << "RobotNodeSet with name " << nodeSetName << " is not defined" << flush;
+
+        }
+    }
+    return nodeSetPtr;
+}
+
+
+bool KinematicUnitWidgetController::initGUIComboBox(VirtualRobot::RobotNodeSetPtr robotNodeSet)
+{
+    ui.nodeListComboBox->clear();
+
+    if (robotNodeSet)
+    {
+        std::vector< RobotNodePtr > rn = robotNodeSet->getAllRobotNodes();
+        for (unsigned int i=0;i<rn.size();i++)
+        {
+            //            ARMARX_INFO << "adding item to joint combo box" << rn[i]->getName() << flush;
+            QString name(rn[i]->getName().c_str());
+            ui.nodeListComboBox->addItem(name);
+        }
+        selectJoint(0);
+        return true;
+    }
+    return false;
+}
+
+bool KinematicUnitWidgetController::initGUIJointListTable(VirtualRobot::RobotNodeSetPtr robotNodeSet)
+{
+    uint numberOfColumns = 12;
+
+    ui.tableJointList->clear();
+
+    if (robotNodeSet)
+    {
+        std::vector< RobotNodePtr > rn = robotNodeSet->getAllRobotNodes();
+
+        //set dimension of table
+        //ui.tableJointList->setColumnWidth(0,110);
+
+        //ui.tableJointList->horizontalHeader()->setResizeMode(QHeaderView::ResizeToContents);
+        ui.tableJointList->setRowCount(rn.size());
+        ui.tableJointList->setColumnCount(numberOfColumns);
+
+
+        //ui.tableJointList->setSizePolicy(QSizePolicy::Expanding,QSizePolicy::Expanding);
+
+        // set table header
+        QStringList s;
+        s << "Joint Name" << "Op" << "Er" << "En" << "Em" << "Control Mode" << "Angle [rad]"  << "Velocity [rad/s]" << "Torque [Nm]" << "Current [A]" << "Temperature [C]";
+        ui.tableJointList->setHorizontalHeaderLabels(s);
+
+
+        // fill in joint names
+        for (unsigned int i=0;i<rn.size();i++)
+        {
+            //         ARMARX_INFO << "adding item to joint table" << rn[i]->getName() << flush;
+            QString name(rn[i]->getName().c_str());
+
+            QTableWidgetItem *newItem = new QTableWidgetItem(name);
+            ui.tableJointList->setItem(i, 0, newItem);
+        }
+
+        // init missing table fields with default values
+        for (unsigned int i=0;i<rn.size();i++)
+        {
+            for (unsigned int j=1;j<numberOfColumns;j++)
+            {
+                QString state = "--";
+                QTableWidgetItem *newItem = new QTableWidgetItem(state);
+                ui.tableJointList->setItem(i, j, newItem);
+            }
+        }
+
+        return true;
+    }
+    return false;
+}
+
+
+void KinematicUnitWidgetController::selectJoint(int i)
+{
+    ARMARX_INFO << "select joint" << flush;
+
+    boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
+    if (!robotNodeSet || i<0 || i>=(int)robotNodeSet->getSize())
+        return;
+
+    currentNode = robotNodeSet->getAllRobotNodes()[i];
+
+    /*float lo = currentNode->getJointLimitLo();
+    float hi = currentNode->getJointLimitHi();
+    if (hi-lo <= 0.0f)
+        return;
+    float pos = currentNode->getJointValue();
+    float ticks = (float)(ui.horizontalSliderKinematicUnitPos->maximum() - ui.horizontalSliderKinematicUnitPos->minimum()+1);
+    float posT = (pos-lo) / (hi-lo) * ticks + (float)ui.horizontalSliderKinematicUnitPos->minimum();
+    ui.horizontalSliderKinematicUnitPos->setSliderPosition((int)posT);
+    //ui.lcdNumberKinematicUnitJointValue->display(pos*180.0f/(float)M_PI);
+    ui.lcdNumberKinematicUnitJointValue->display(posT);
+    */
+
+    ui.horizontalSliderKinematicUnitPos->setSliderPosition(50);
+}
+
+void KinematicUnitWidgetController::sliderValueChanged(int pos)
+{
+    boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
+    if (!currentNode)
+        return;
+
+    float ticks = (float)(ui.horizontalSliderKinematicUnitPos->maximum() - ui.horizontalSliderKinematicUnitPos->minimum()+1);
+    float value = (float)ui.horizontalSliderKinematicUnitPos->value();
+    float perc = (value - (float)ui.horizontalSliderKinematicUnitPos->minimum()) / ticks;
+
+//    NameControlModeMap::const_iterator it;
+//    it = reportedJointControlModes.find(currentNode->getName());
+//    const ControlMode currentControlMode = it->second;
+    const ControlMode currentControlMode = selectedControlMode;
+
+    if (currentControlMode == ePositionControl)
+    {
+        // TODO: Joint limits are not respected
+        //float lo = currentNode->getJointLimitLo();
+        //float hi = currentNode->getJointLimitHi();
+        //float result = lo + (hi-lo)*perc;
+
+        NameValueMap jointAngles;
+        jointAngles[currentNode->getName()] = (perc - 0.5) * 2 * M_PI;
+        if (kinematicUnitInterfacePrx)
+        {
+            kinematicUnitInterfacePrx->setJointAngles(jointAngles);
+            updateModel();
+        }
+    }
+    else if (currentControlMode == eVelocityControl)
+    {
+        NameValueMap jointVelocities;
+        jointVelocities[currentNode->getName()] = (perc - 0.5) * M_PI;
+        if (kinematicUnitInterfacePrx)
+        {
+            kinematicUnitInterfacePrx->setJointVelocities(jointVelocities);
+            updateModel();
+        }
+    }
+    else if(currentControlMode == eTorqueControl)
+    {
+        NameValueMap jointTorques;
+        jointTorques[currentNode->getName()] = (perc - 0.5) * 150;
+        if (kinematicUnitInterfacePrx)
+        {
+            kinematicUnitInterfacePrx->setJointTorques(jointTorques);
+            updateModel();
+        }
+    }
+    else
+    {
+        ARMARX_INFO << "current ControlModes unknown" << flush;
+    }
+}
+
+
+
+void KinematicUnitWidgetController::updateControlModesTable()
+{
+    if(!getWidget())
+        return;
+
+    boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
+    std::vector< RobotNodePtr > rn = robotNodeSet->getAllRobotNodes();
+    for (unsigned int i = 0; i < rn.size(); i++)
+    {
+        NameControlModeMap::const_iterator it;
+        it = reportedJointControlModes.find(rn[i]->getName());
+        ControlMode currentMode = it->second;
+
+        QString state;
+
+        switch (currentMode)
+        {
+            /*case eNoMode:
+                state = "None";
+                break;
+
+            case eUnknownMode:
+                state = "Unknown";
+                break;
+            */
+            case ePositionControl:
+                state = "Position";
+                break;
+
+            case eVelocityControl:
+                state = "Velocity";
+                break;
+
+            case eTorqueControl:
+                state = "Torque";
+                break;
+
+            default:
+                state = "<nyi>";
+                break;
+        }
+
+        QTableWidgetItem *newItem = new QTableWidgetItem(state);
+        ui.tableJointList->setItem(i, 5, newItem);
+    }
+}
+
+void KinematicUnitWidgetController::updateJointStatusesTable()
+{
+    if(!getWidget())
+        return;
+
+    boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
+    std::vector< RobotNodePtr > rn = robotNodeSet->getAllRobotNodes();
+    for (unsigned int i = 0; i < rn.size(); i++)
+    {
+        NameStatusMap::const_iterator it;
+        it = reportedJointStatuses.find(rn[i]->getName());
+        JointStatus currentStatus = it->second;
+
+        QString state = translateStatus(currentStatus.operation);
+        QTableWidgetItem *newItem = new QTableWidgetItem(state);
+        ui.tableJointList->setItem(i, 1, newItem);
+
+        state = translateStatus(currentStatus.error);
+        newItem = new QTableWidgetItem(state);
+        ui.tableJointList->setItem(i, 2, newItem);
+
+        state = currentStatus.enabled? "X" : "-";
+        newItem = new QTableWidgetItem(state);
+        ui.tableJointList->setItem(i, 3, newItem);
+
+        state = currentStatus.emergencyStop? "X" : "-";
+        newItem = new QTableWidgetItem(state);
+        ui.tableJointList->setItem(i, 4, newItem);
+    }
+}
+
+QString KinematicUnitWidgetController::translateStatus(OperationStatus status)
+{
+    switch(status)
+    {
+        case eOffline:
+            return "Off";
+
+        case eOnline:
+            return "On";
+
+        case eInitialized:
+            return "In";
+
+        default:
+            return "?";
+    }
+}
+
+QString KinematicUnitWidgetController::translateStatus(ErrorStatus status)
+{
+    switch(status)
+    {
+        case eOk:
+            return "Ok";
+
+        case eWarning:
+            return "Wr";
+
+        case eError:
+            return "Er";
+
+        default:
+            return "?";
+    }
+}
+
+void KinematicUnitWidgetController::updateJointAnglesTable()
+{
+    float dirty_squaresum = 0;
+
+    boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
+    std::vector< RobotNodePtr > rn = robotNodeSet->getAllRobotNodes();
+
+    FloatVector kinematicUnitAnglesCurrent; // obe line or in header
+    kinematicUnitAnglesCurrent = FloatVector(7, 0.0f); // fix here 7 ELemente ?!?!?
+
+    QTableWidgetItem* newItem;
+    for (unsigned int i = 0; i < rn.size(); i++)
+    {
+        NameValueMap::const_iterator it;
+        it = reportedJointAngles.find(rn[i]->getName());
+        if(it == reportedJointAngles.end())
+        {
+            continue;
+        }
+        const float currentValue = it->second;
+        dirty_squaresum += currentValue*currentValue;
+        const QString Text = QString::number(currentValue);
+
+        newItem = new QTableWidgetItem(Text);
+        ui.tableJointList->setItem(i, 6, newItem);
+    }
+
+    //update only if values changed
+    if ((fabs(dirty_squaresum_old[0] - dirty_squaresum)) > 0.0000005)
+    {
+        updateModel();
+        dirty_squaresum_old[0] = dirty_squaresum;
+//        ARMARX_INFO << "update model" << flush;
+    }
+}
+
+void KinematicUnitWidgetController::updateJointVelocitiesTable(){
+    if(!getWidget())
+        return;
+
+    float dirty_squaresum = 0;
+    boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
+    std::vector< RobotNodePtr > rn = robotNodeSet->getAllRobotNodes();
+    QTableWidgetItem* newItem;
+    for (unsigned int i = 0; i < rn.size(); i++)
+    {
+        NameValueMap::const_iterator it;
+        it = reportedJointVelocities.find(rn[i]->getName());
+        if(it == reportedJointVelocities.end())
+        {
+            continue;
+        }
+        const float currentValue = it->second;
+        dirty_squaresum += currentValue*currentValue;
+        const QString Text = QString::number(currentValue);
+        newItem = new QTableWidgetItem(Text);
+        ui.tableJointList->setItem(i, 7, newItem);
+    }
+    if ( (fabs(dirty_squaresum_old[1] - dirty_squaresum)) > 0.0000005)  {
+        updateModel();
+        dirty_squaresum_old[1] = dirty_squaresum;
+    }
+}
+
+void KinematicUnitWidgetController::updateJointTorquesTable()
+{
+    if(!getWidget())
+        return;
+
+    boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
+    std::vector< RobotNodePtr > rn = robotNodeSet->getAllRobotNodes();
+    QTableWidgetItem* newItem;
+    NameValueMap::const_iterator it;
+
+    for (unsigned int i = 0; i < rn.size(); i++)
+    {
+        it = reportedJointTorques.find(rn[i]->getName());
+        if(it == reportedJointTorques.end())
+        {
+            continue;
+        }
+
+        const float currentValue = it->second;
+        newItem = new QTableWidgetItem(QString::number(currentValue));
+        ui.tableJointList->setItem(i, 8, newItem);
+    }
+}
+
+void KinematicUnitWidgetController::updateJointCurrentsTable()
+{
+    if(!getWidget())
+        return;
+
+    boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
+    std::vector< RobotNodePtr > rn = robotNodeSet->getAllRobotNodes();
+    QTableWidgetItem* newItem;
+    NameValueMap::const_iterator it;
+
+    for (unsigned int i = 0; i < rn.size(); i++)
+    {
+        it = reportedJointCurrents.find(rn[i]->getName());
+        if(it == reportedJointCurrents.end())
+        {
+            continue;
+        }
+
+        const float currentValue = it->second;
+        newItem = new QTableWidgetItem(QString::number(currentValue));
+        ui.tableJointList->setItem(i, 9, newItem);
+    }
+}
+
+void KinematicUnitWidgetController::updateJointMotorTemperaturesTable()
+{
+    if(!getWidget())
+        return;
+
+    boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
+    std::vector< RobotNodePtr > rn = robotNodeSet->getAllRobotNodes();
+    QTableWidgetItem* newItem;
+    NameValueMap::const_iterator it;
+
+    for (unsigned int i = 0; i < rn.size(); i++)
+    {
+        it = reportedJointMotorTemperatures.find(rn[i]->getName());
+        if(it == reportedJointMotorTemperatures.end())
+        {
+            continue;
+        }
+
+        const float currentValue = it->second;
+        newItem = new QTableWidgetItem(QString::number(currentValue));
+        ui.tableJointList->setItem(i, 10, newItem);
+    }
+}
+
+void KinematicUnitWidgetController::reportJointAngles(const NameValueMap& jointAngles, bool aValueChanged, const Ice::Current& c)
+{
+    if(!aValueChanged && reportedJointAngles.size() > 0)
+        return;
+
+    boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
+    reportedJointAngles = jointAngles;
+    emit jointAnglesReported();
+}
+
+void KinematicUnitWidgetController::reportJointVelocities(const NameValueMap& jointVelocities, bool aValueChanged, const Ice::Current& c)
+{
+    if(!aValueChanged && reportedJointVelocities.size() > 0)
+        return;
+
+    boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
+    reportedJointVelocities = jointVelocities;
+    emit jointVelocitiesReported();
+}
+
+void KinematicUnitWidgetController::reportJointTorques(const NameValueMap& jointTorques, bool aValueChanged, const Ice::Current& c)
+{
+    if(!aValueChanged && reportedJointTorques.size() > 0)
+        return;
+
+    boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
+    reportedJointTorques = jointTorques;
+
+    emit jointTorquesReported();
+}
+
+void KinematicUnitWidgetController::reportControlModeChanged(const NameControlModeMap& jointModes, bool aValueChanged, const Ice::Current& c)
+{
+    if(!aValueChanged && reportedJointControlModes.size() > 0)
+        return;
+
+    boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
+    reportedJointControlModes = jointModes;
+
+    emit jointControlModesReported();
+}
+
+void KinematicUnitWidgetController::reportJointCurrents(const NameValueMap& jointCurrents, bool aValueChanged, const Ice::Current& c)
+{
+    if(!aValueChanged && reportedJointCurrents.size() > 0)
+        return;
+
+    boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
+    reportedJointCurrents = jointCurrents;
+
+    emit jointCurrentsReported();
+}
+
+void KinematicUnitWidgetController::reportJointMotorTemperatures(const NameValueMap& jointMotorTemperatures, bool aValueChanged,  const Ice::Current& c)
+{
+    if(!aValueChanged && reportedJointMotorTemperatures.size() > 0)
+        return;
+
+    boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
+    reportedJointMotorTemperatures = jointMotorTemperatures;
+
+    emit jointMotorTemperaturesReported();
+}
+
+void KinematicUnitWidgetController::reportJointStatuses(const NameStatusMap &jointStatuses, bool aValueChanged, const Ice::Current &)
+{
+    if(!aValueChanged && reportedJointStatuses.size() > 0)
+        return;
+
+    boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
+    reportedJointStatuses = jointStatuses;
+
+    emit jointStatusesReported();
+}
+
+
+void KinematicUnitWidgetController::updateModel()
+{
+//    ARMARX_INFO << "updateModel()" << flush;
+    boost::recursive_mutex::scoped_lock lock(mutexNodeSet);
+    std::vector< RobotNodePtr > rn2 = robotNodeSet->getAllRobotNodes();
+
+    std::vector< RobotNodePtr > usedNodes;
+    std::vector< float > jv;
+
+    for (unsigned int i = 0; i < rn2.size(); i++)
+    {
+        VirtualRobot::RobotNodePtr node = robot->getRobotNode(rn2[i]->getName());
+        NameValueMap::const_iterator it;
+        it = reportedJointAngles.find(node->getName());
+        if(it != reportedJointAngles.end())
+        {
+            usedNodes.push_back(node);
+            jv.push_back(it->second);
+        }
+    }
+    robot->setJointValues(usedNodes, jv);
+}
+
+Q_EXPORT_PLUGIN2(armar3_gui_KinematicUnitGuiPlugin, KinematicUnitGuiPlugin)
diff --git a/source/RobotAPI/gui_plugins/KinematicUnitPlugin/KinematicUnitGuiPlugin.h b/source/RobotAPI/gui_plugins/KinematicUnitPlugin/KinematicUnitGuiPlugin.h
new file mode 100644
index 000000000..951e5368d
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/KinematicUnitPlugin/KinematicUnitGuiPlugin.h
@@ -0,0 +1,227 @@
+/*
+* This file is part of ArmarX.
+*
+* ArmarX is free software; you can redistribute it and/or modify
+* it under the terms of the GNU Lesser General Public License as
+* published by the Free Software Foundation; either version 2 of
+* the License, or (at your option) any later version.
+*
+* ArmarX is distributed in the hope that it will be useful, but
+* WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+* GNU Lesser General Public License for more details.
+*
+* You should have received a copy of the GNU General Public License
+* along with this program. If not, see <http://www.gnu.org/licenses/>.
+*
+* @package    ArmarX::Component::KinematicUnitGuiPlugin
+* @author     Christian Boege <boege at kit dot edu>
+* @copyright  2011 Christian Böge
+* @license    http://www.gnu.org/licenses/gpl.txt
+*             GNU General Public License
+
+*/
+
+#ifndef ARMARX_COMPONENT_GUIHANDLERKINEMATICUNIT_GUI_H
+#define ARMARX_COMPONENT_GUIHANDLERKINEMATICUNIT_GUI_H
+
+/* ArmarX headers */
+#include "ui_kinematicunitguiplugin.h"
+#include <RobotAPI/interface/units/KinematicUnitInterface.h>
+#include <Core/core/Component.h>
+#include <Gui/ArmarXGuiLib/ArmarXGuiPlugin.h>
+#include <Gui/ArmarXGuiLib/ArmarXComponentWidgetController.h>
+
+/* Qt headers */
+#include <QtGui/QMainWindow>
+
+/* SoQt headers */
+#include <Inventor/nodes/SoNode.h>
+
+/* Boost headers */
+#include <boost/shared_ptr.hpp>
+#include <boost/cstdint.hpp>
+
+#include <Inventor/sensors/SoTimerSensor.h>
+#include <Inventor/nodes/SoEventCallback.h>
+#include <Inventor/nodes/SoSeparator.h>
+#include <Inventor/Qt/viewers/SoQtExaminerViewer.h>
+#include <Inventor/Qt/SoQt.h>
+
+/* VirtualRobot headers */
+#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/Nodes/RobotNode.h>
+#include <VirtualRobot/RobotNodeSet.h>
+
+#include <VirtualRobot/Visualization/VisualizationFactory.h>
+#include <VirtualRobot/Visualization/CoinVisualization/CoinVisualization.h>
+
+#define KINEMATIC_UNIT_FILE_DEFAULT armarx::ArmarXDataPath::getHomePath()+std::string("Armar4/data/Armar4/robotmodel/ArmarIV.xml")
+#define KINEMATIC_UNIT_NAME_DEFAULT "Robot"
+
+namespace armarx
+{
+    typedef boost::shared_ptr<VirtualRobot::CoinVisualization> CoinVisualizationPtr;
+
+    class KinematicUnitConfigDialog;
+
+    /**
+      \class KinematicUnitGuiPlugin
+      \brief This plugin provides a generic widget showing position and velocity of all joints. Optionally a 3d robot model can be visualized.
+      \ingroup ArmarXGuiPlugins
+
+      \see KinematicUnitWidget
+      */
+    class KinematicUnitGuiPlugin :
+            public ArmarXGuiPlugin
+    {
+    public:
+        KinematicUnitGuiPlugin();
+
+        QString getPluginName()
+        {
+            return "KinematicUnitGuiPlugin";
+        }
+    };
+
+    /**
+      \class KinematicUnitWidget
+      \ingroup ArmarXGuiPlugins
+      \see KinematicUnitGuiPlugin
+      */
+    class KinematicUnitWidgetController :
+            public ArmarXComponentWidgetController,
+            public KinematicUnitListener
+    {
+        Q_OBJECT
+    public:
+        KinematicUnitWidgetController();
+        virtual ~KinematicUnitWidgetController() {}
+
+        // inherited from Component
+        virtual void onInitComponent();
+        virtual void onConnectComponent();
+        virtual void onExitComponent();
+
+        // inherited of ArmarXWidget
+        virtual QString getWidgetName() const
+        {
+            return "KinematicUnitGUI";
+        }
+        QPointer<QDialog> getConfigDialog(QWidget* parent = 0);
+        virtual void loadSettings(QSettings * settings);
+        virtual void saveSettings(QSettings * settings);
+        void configured();
+
+        SoNode* getScene();
+
+        bool kinematicUnitSetupViewer();
+
+        void modelUpdateCB();
+
+        void updateGuiElements();
+
+    signals:
+
+        void jointAnglesReported();
+        void jointVelocitiesReported();
+        void jointControlModesReported();
+        void jointTorquesReported();
+        void jointCurrentsReported();
+        void jointMotorTemperaturesReported();
+        void jointStatusesReported();
+
+
+    public slots:
+
+        // KinematicUnit
+        void kinematicUnitRequestChange();
+        void kinematicUnitInit();
+        void kinematicUnitStart();
+        void kinematicUnitStop();
+        void kinematicUnitTest();
+        void kinematicUnitZeroPosition();
+        void kinematicUnitPos2();
+        void setControlModePosition();
+        void setControlModeVelocity();
+        void setControlModeTorque();
+        void selectJoint(int i);
+        void sliderValueChanged(int i);
+
+        void updateJointAnglesTable();
+        void updateJointVelocitiesTable();
+        void updateJointTorquesTable();
+        void updateJointCurrentsTable();
+        void updateJointMotorTemperaturesTable();
+        void updateJointStatusesTable();
+        void updateControlModesTable();
+        void updateKinematicUnitListInDialog() {}
+
+
+    protected:
+        void connectSlots();
+
+        QString translateStatus(OperationStatus status);
+        QString translateStatus(ErrorStatus status);
+
+        Ui::KinematicUnitGuiPlugin ui;
+
+        // ice proxies
+        KinematicUnitInterfacePrx kinematicUnitInterfacePrx;// send commands to kinematic unit
+        KinematicUnitListenerPrx kinematicUnitListenerPrx; // receive reports from kinematic unit
+
+        bool verbose;
+
+        std::string kinematicUnitFile;
+        std::string kinematicUnitFileDefault;
+        std::string kinematicUnitName;
+        std::string robotNodeSetName;
+
+        VirtualRobot::RobotPtr robot;
+        VirtualRobot::RobotNodeSetPtr robotNodeSet;
+        VirtualRobot::RobotNodePtr currentNode;
+
+        CoinVisualizationPtr kinematicUnitVisualization;
+        SoNode* kinematicUnitNode;
+
+        // interface implementation
+        void reportControlModeChanged(const NameControlModeMap& jointModes, bool aValueChanged, const Ice::Current& c);
+        void reportJointAngles(const NameValueMap& jointAngles, bool aValueChanged, const Ice::Current& c);
+        void reportJointVelocities(const NameValueMap& jointVelocities, bool aValueChanged, const Ice::Current& c);
+        void reportJointTorques(const NameValueMap& jointTorques, bool aValueChanged, const Ice::Current& c);
+        void reportJointCurrents(const NameValueMap& jointCurrents, bool aValueChanged, const Ice::Current& c);
+        void reportJointMotorTemperatures(const NameValueMap& jointMotorTemperatures, bool aValueChanged, const Ice::Current& c);
+        void reportJointStatuses(const NameStatusMap& jointStatuses, bool aValueChanged, const Ice::Current &);
+
+
+        void updateModel();
+
+    private:
+
+        boost::recursive_mutex mutexNodeSet;
+        // init stuff
+        VirtualRobot::RobotPtr loadRobotFile(std::string fileName);
+        CoinVisualizationPtr getCoinVisualization(VirtualRobot::RobotPtr robot);
+        VirtualRobot::RobotNodeSetPtr getRobotNodeSet(VirtualRobot::RobotPtr robot, std::string nodeSetName);
+        bool initGUIComboBox(VirtualRobot::RobotNodeSetPtr robotNodeSet);
+        bool initGUIJointListTable(VirtualRobot::RobotNodeSetPtr robotNodeSet);
+
+        NameValueMap reportedJointAngles;
+        NameValueMap reportedJointVelocities;
+        NameControlModeMap reportedJointControlModes;
+        NameValueMap reportedJointTorques;
+        NameValueMap reportedJointCurrents;
+        NameValueMap reportedJointMotorTemperatures;
+        NameStatusMap reportedJointStatuses;
+
+        std::vector<float> dirty_squaresum_old;
+
+        QPointer<QWidget> __widget;
+        QPointer<KinematicUnitConfigDialog> dialog;
+        ControlMode selectedControlMode;
+    };
+    typedef ::std::vector< ::Ice::Float> FloatVector;
+    typedef boost::shared_ptr<KinematicUnitWidgetController> KinematicUnitGuiPluginPtr;
+}
+
+#endif
diff --git a/source/RobotAPI/gui_plugins/KinematicUnitPlugin/kinematicunitguiplugin.ui b/source/RobotAPI/gui_plugins/KinematicUnitPlugin/kinematicunitguiplugin.ui
new file mode 100644
index 000000000..5db8f50eb
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/KinematicUnitPlugin/kinematicunitguiplugin.ui
@@ -0,0 +1,365 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>KinematicUnitGuiPlugin</class>
+ <widget class="QWidget" name="KinematicUnitGuiPlugin">
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>822</width>
+    <height>547</height>
+   </rect>
+  </property>
+  <property name="sizePolicy">
+   <sizepolicy hsizetype="Minimum" vsizetype="Minimum">
+    <horstretch>0</horstretch>
+    <verstretch>0</verstretch>
+   </sizepolicy>
+  </property>
+  <property name="minimumSize">
+   <size>
+    <width>0</width>
+    <height>300</height>
+   </size>
+  </property>
+  <property name="windowTitle">
+   <string>Form</string>
+  </property>
+  <layout class="QGridLayout" name="gridLayout_2">
+   <item row="0" column="0">
+    <layout class="QVBoxLayout" name="verticalLayout">
+     <property name="sizeConstraint">
+      <enum>QLayout::SetMaximumSize</enum>
+     </property>
+     <item>
+      <widget class="QLabel" name="labelKinematicUnitName">
+       <property name="font">
+        <font>
+         <family>AlArabiya</family>
+         <pointsize>14</pointsize>
+        </font>
+       </property>
+       <property name="text">
+        <string>KinematicUnit</string>
+       </property>
+      </widget>
+     </item>
+     <item>
+      <layout class="QGridLayout" name="gridLayout">
+       <item row="1" column="1">
+        <widget class="QPushButton" name="pushButtonKinematicUnitStart">
+         <property name="enabled">
+          <bool>true</bool>
+         </property>
+         <property name="text">
+          <string>Start</string>
+         </property>
+        </widget>
+       </item>
+       <item row="0" column="0">
+        <widget class="QCheckBox" name="requestUnitCheckBox">
+         <property name="text">
+          <string>request unit</string>
+         </property>
+        </widget>
+       </item>
+       <item row="1" column="0">
+        <widget class="QPushButton" name="pushButtonKinematicUnitInit">
+         <property name="enabled">
+          <bool>false</bool>
+         </property>
+         <property name="text">
+          <string>Init</string>
+         </property>
+        </widget>
+       </item>
+       <item row="4" column="0">
+        <widget class="QLabel" name="label">
+         <property name="text">
+          <string>Select Joint</string>
+         </property>
+        </widget>
+       </item>
+       <item row="5" column="0">
+        <widget class="QLabel" name="label_2">
+         <property name="text">
+          <string>Control Mode</string>
+         </property>
+        </widget>
+       </item>
+       <item row="6" column="0">
+        <widget class="QLCDNumber" name="lcdNumberKinematicUnitJointValue">
+         <property name="enabled">
+          <bool>true</bool>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>80</width>
+           <height>100</height>
+          </size>
+         </property>
+         <property name="toolTip">
+          <string>Value in percent between low and high limit of joint</string>
+         </property>
+         <property name="smallDecimalPoint">
+          <bool>false</bool>
+         </property>
+        </widget>
+       </item>
+       <item row="2" column="0">
+        <widget class="QPushButton" name="pushButtonKinematicUnitTest">
+         <property name="enabled">
+          <bool>true</bool>
+         </property>
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="text">
+          <string>Test</string>
+         </property>
+        </widget>
+       </item>
+       <item row="2" column="1">
+        <widget class="QPushButton" name="pushButtonKinematicUnitPos1">
+         <property name="enabled">
+          <bool>true</bool>
+         </property>
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="Expanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="text">
+          <string>ZeroPosition</string>
+         </property>
+        </widget>
+       </item>
+       <item row="2" column="2">
+        <widget class="QPushButton" name="pushButtonKinematicUnitPos2">
+         <property name="enabled">
+          <bool>true</bool>
+         </property>
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="Expanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="text">
+          <string>Position 50 %</string>
+         </property>
+        </widget>
+       </item>
+       <item row="4" column="1" colspan="2">
+        <widget class="QComboBox" name="nodeListComboBox">
+         <property name="enabled">
+          <bool>true</bool>
+         </property>
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="Expanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+        </widget>
+       </item>
+       <item row="0" column="1" colspan="2">
+        <widget class="QLabel" name="labelKinematicUnitState">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Preferred">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="text">
+          <string/>
+         </property>
+        </widget>
+       </item>
+       <item row="1" column="2">
+        <widget class="QPushButton" name="pushButtonKinematicUnitStop">
+         <property name="enabled">
+          <bool>true</bool>
+         </property>
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="text">
+          <string>Stop</string>
+         </property>
+        </widget>
+       </item>
+       <item row="5" column="1" colspan="2">
+        <layout class="QHBoxLayout" name="horizontalLayout">
+         <item>
+          <widget class="QRadioButton" name="radioButtonPositionControl">
+           <property name="enabled">
+            <bool>true</bool>
+           </property>
+           <property name="autoFillBackground">
+            <bool>false</bool>
+           </property>
+           <property name="text">
+            <string>Position Control</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QRadioButton" name="radioButtonVelocityControl">
+           <property name="enabled">
+            <bool>true</bool>
+           </property>
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="Minimum" vsizetype="Minimum">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="text">
+            <string>Velocity Control</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QRadioButton" name="radioButtonTorqueControl">
+           <property name="text">
+            <string>Torque Control</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <spacer name="horizontalSpacer">
+           <property name="orientation">
+            <enum>Qt::Horizontal</enum>
+           </property>
+           <property name="sizeHint" stdset="0">
+            <size>
+             <width>40</width>
+             <height>20</height>
+            </size>
+           </property>
+          </spacer>
+         </item>
+        </layout>
+       </item>
+       <item row="6" column="1" colspan="2">
+        <widget class="QSlider" name="horizontalSliderKinematicUnitPos">
+         <property name="enabled">
+          <bool>true</bool>
+         </property>
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+         <property name="tickPosition">
+          <enum>QSlider::TicksBelow</enum>
+         </property>
+         <property name="tickInterval">
+          <number>0</number>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item>
+      <widget class="QTableWidget" name="tableJointList">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="Expanding" vsizetype="Expanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="font">
+        <font>
+         <pointsize>8</pointsize>
+        </font>
+       </property>
+       <property name="alternatingRowColors">
+        <bool>true</bool>
+       </property>
+       <attribute name="verticalHeaderDefaultSectionSize">
+        <number>17</number>
+       </attribute>
+       <attribute name="verticalHeaderMinimumSectionSize">
+        <number>12</number>
+       </attribute>
+      </widget>
+     </item>
+    </layout>
+   </item>
+  </layout>
+ </widget>
+ <resources/>
+ <connections>
+  <connection>
+   <sender>pushButtonKinematicUnitInit</sender>
+   <signal>toggled(bool)</signal>
+   <receiver>pushButtonKinematicUnitStart</receiver>
+   <slot>setEnabled(bool)</slot>
+   <hints>
+    <hint type="sourcelabel">
+     <x>130</x>
+     <y>107</y>
+    </hint>
+    <hint type="destinationlabel">
+     <x>41</x>
+     <y>143</y>
+    </hint>
+   </hints>
+  </connection>
+  <connection>
+   <sender>pushButtonKinematicUnitStart</sender>
+   <signal>clicked(bool)</signal>
+   <receiver>pushButtonKinematicUnitStop</receiver>
+   <slot>setEnabled(bool)</slot>
+   <hints>
+    <hint type="sourcelabel">
+     <x>123</x>
+     <y>153</y>
+    </hint>
+    <hint type="destinationlabel">
+     <x>125</x>
+     <y>173</y>
+    </hint>
+   </hints>
+  </connection>
+  <connection>
+   <sender>horizontalSliderKinematicUnitPos</sender>
+   <signal>valueChanged(int)</signal>
+   <receiver>lcdNumberKinematicUnitJointValue</receiver>
+   <slot>display(int)</slot>
+   <hints>
+    <hint type="sourcelabel">
+     <x>190</x>
+     <y>268</y>
+    </hint>
+    <hint type="destinationlabel">
+     <x>88</x>
+     <y>266</y>
+    </hint>
+   </hints>
+  </connection>
+  <connection>
+   <sender>requestUnitCheckBox</sender>
+   <signal>clicked(bool)</signal>
+   <receiver>pushButtonKinematicUnitInit</receiver>
+   <slot>setEnabled(bool)</slot>
+   <hints>
+    <hint type="sourcelabel">
+     <x>81</x>
+     <y>81</y>
+    </hint>
+    <hint type="destinationlabel">
+     <x>80</x>
+     <y>104</y>
+    </hint>
+   </hints>
+  </connection>
+ </connections>
+</ui>
diff --git a/source/RobotAPI/gui_plugins/PlatformUnitPlugin/CMakeLists.txt b/source/RobotAPI/gui_plugins/PlatformUnitPlugin/CMakeLists.txt
new file mode 100644
index 000000000..6808b22ee
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/PlatformUnitPlugin/CMakeLists.txt
@@ -0,0 +1,39 @@
+armarx_set_target("PlatformUnitGuiPlugin")
+
+find_package(Qt4 COMPONENTS QtCore QtGui QUIET)
+armarx_build_if(QT_FOUND "Qt not available")
+
+find_package(Simox QUIET)
+find_package(ArmarXGui QUIET)
+
+armarx_build_if(ArmarXGui_FOUND "ArmarXGui not available")
+armarx_build_if(Simox_FOUND "Simox not available")
+
+
+include(${QT_USE_FILE})
+
+include(${ArmarXGui_CMAKE_DIR}/ArmarXGui.cmake)
+
+file(GLOB SOURCES PlatformUnitGuiPlugin.cpp
+     PlatformUnitConfigDialog.cpp)
+file(GLOB HEADERS PlatformUnitGuiPlugin.h
+     PlatformUnitConfigDialog.h)
+
+set(GUI_MOC_HDRS
+    PlatformUnitGuiPlugin.h
+    PlatformUnitConfigDialog.h
+)
+
+set(GUI_UIS
+    PlatformUnitGuiPlugin.ui
+    PlatformUnitConfigDialog.ui
+)
+
+set(COMPONENT_LIBS RobotAPIUnits ArmarXInterfaces ${Simox_LIBRARIES})
+
+set(LIB_VERSION    0.1.0)
+set(LIB_SOVERSION  0)
+
+if (ArmarXGui_FOUND)
+	armarx_gui_library(PlatformUnitGuiPlugin "${SOURCES}" "${GUI_MOC_HDRS}" "${GUI_UIS}" "" "${COMPONENT_LIBS}" "${LIB_VERSION}" "${LIB_SOVERSION}")
+endif()
diff --git a/source/RobotAPI/gui_plugins/PlatformUnitPlugin/PlatformUnitConfigDialog.cpp b/source/RobotAPI/gui_plugins/PlatformUnitPlugin/PlatformUnitConfigDialog.cpp
new file mode 100644
index 000000000..654b370d6
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/PlatformUnitPlugin/PlatformUnitConfigDialog.cpp
@@ -0,0 +1,38 @@
+/*
+* This file is part of ArmarX.
+*
+* ArmarX is free software; you can redistribute it and/or modify
+* it under the terms of the GNU Lesser General Public License as
+* published by the Free Software Foundation; either version 2 of
+* the License, or (at your option) any later version.
+*
+* ArmarX is distributed in the hope that it will be useful, but
+* WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+* GNU Lesser General Public License for more details.
+*
+* You should have received a copy of the GNU General Public License
+* along with this program. If not, see <http://www.gnu.org/licenses/>.
+*
+* @package    ArmarX::
+* @author     Nikolaus Vahrenkamp ( vahrenkamp at kit dot edu)
+* @date       2012
+* @copyright  http://www.gnu.org/licenses/gpl.txt
+*             GNU General Public License
+*/
+
+#include "PlatformUnitConfigDialog.h"
+#include "ui_PlatformUnitConfigDialog.h"
+
+armarx::PlatformUnitConfigDialog::PlatformUnitConfigDialog(QWidget *parent) :
+    QDialog(parent),
+    ui(new Ui::PlatformUnitConfigDialog)
+{
+    ui->setupUi(this);
+}
+
+armarx::PlatformUnitConfigDialog::~PlatformUnitConfigDialog()
+{
+    delete ui;
+}
+
diff --git a/source/RobotAPI/gui_plugins/PlatformUnitPlugin/PlatformUnitConfigDialog.h b/source/RobotAPI/gui_plugins/PlatformUnitPlugin/PlatformUnitConfigDialog.h
new file mode 100644
index 000000000..1283a5089
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/PlatformUnitPlugin/PlatformUnitConfigDialog.h
@@ -0,0 +1,51 @@
+/*
+* This file is part of ArmarX.
+*
+* ArmarX is free software; you can redistribute it and/or modify
+* it under the terms of the GNU Lesser General Public License as
+* published by the Free Software Foundation; either version 2 of
+* the License, or (at your option) any later version.
+*
+* ArmarX is distributed in the hope that it will be useful, but
+* WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+* GNU Lesser General Public License for more details.
+*
+* You should have received a copy of the GNU General Public License
+* along with this program. If not, see <http://www.gnu.org/licenses/>.
+*
+* @package    ArmarX::
+* @author     Nikolaus Vahrenkamp ( vahrenkamp at kit dot edu)
+* @date       2012
+* @copyright  http://www.gnu.org/licenses/gpl.txt
+*             GNU General Public License
+*/
+
+#ifndef _ARMARXGUI_PLUGINS_PLATFORMUNITCONFIGDIALOG_H
+#define _ARMARXGUI_PLUGINS_PLATFORMUNITCONFIGDIALOG_H
+
+#include <QDialog>
+
+namespace Ui {
+    class PlatformUnitConfigDialog;
+}
+
+namespace armarx
+{
+    class PlatformUnitConfigDialog :
+        public QDialog
+    {
+        Q_OBJECT
+
+    public:
+        explicit PlatformUnitConfigDialog(QWidget *parent = 0);
+        ~PlatformUnitConfigDialog();
+
+    private:
+        Ui::PlatformUnitConfigDialog *ui;
+
+        friend class PlatformUnitWidget;
+    };
+}
+
+#endif
diff --git a/source/RobotAPI/gui_plugins/PlatformUnitPlugin/PlatformUnitConfigDialog.ui b/source/RobotAPI/gui_plugins/PlatformUnitPlugin/PlatformUnitConfigDialog.ui
new file mode 100644
index 000000000..53b89acf0
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/PlatformUnitPlugin/PlatformUnitConfigDialog.ui
@@ -0,0 +1,92 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>PlatformUnitConfigDialog</class>
+ <widget class="QDialog" name="PlatformUnitConfigDialog">
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>527</width>
+    <height>113</height>
+   </rect>
+  </property>
+  <property name="windowTitle">
+   <string>Dialog</string>
+  </property>
+  <layout class="QGridLayout" name="gridLayout_2">
+   <item row="3" column="0">
+    <widget class="QDialogButtonBox" name="buttonBox">
+     <property name="orientation">
+      <enum>Qt::Horizontal</enum>
+     </property>
+     <property name="standardButtons">
+      <set>QDialogButtonBox::Cancel|QDialogButtonBox::Ok</set>
+     </property>
+    </widget>
+   </item>
+   <item row="0" column="0">
+    <layout class="QGridLayout" name="gridLayout">
+     <item row="0" column="1">
+      <widget class="QLineEdit" name="editPlatformUnitName"/>
+     </item>
+     <item row="0" column="0">
+      <widget class="QLabel" name="labelPlatformUnitName">
+       <property name="text">
+        <string>PlatformUnit</string>
+       </property>
+      </widget>
+     </item>
+     <item row="1" column="1">
+      <widget class="QLineEdit" name="editPlatformName"/>
+     </item>
+     <item row="1" column="0">
+      <widget class="QLabel" name="labelPlatformName">
+       <property name="text">
+        <string>Platform Name</string>
+       </property>
+      </widget>
+     </item>
+    </layout>
+   </item>
+  </layout>
+ </widget>
+ <tabstops>
+  <tabstop>editPlatformUnitName</tabstop>
+  <tabstop>buttonBox</tabstop>
+ </tabstops>
+ <resources/>
+ <connections>
+  <connection>
+   <sender>buttonBox</sender>
+   <signal>accepted()</signal>
+   <receiver>PlatformUnitConfigDialog</receiver>
+   <slot>accept()</slot>
+   <hints>
+    <hint type="sourcelabel">
+     <x>248</x>
+     <y>254</y>
+    </hint>
+    <hint type="destinationlabel">
+     <x>157</x>
+     <y>274</y>
+    </hint>
+   </hints>
+  </connection>
+  <connection>
+   <sender>buttonBox</sender>
+   <signal>rejected()</signal>
+   <receiver>PlatformUnitConfigDialog</receiver>
+   <slot>reject()</slot>
+   <hints>
+    <hint type="sourcelabel">
+     <x>316</x>
+     <y>260</y>
+    </hint>
+    <hint type="destinationlabel">
+     <x>286</x>
+     <y>274</y>
+    </hint>
+   </hints>
+  </connection>
+ </connections>
+</ui>
diff --git a/source/RobotAPI/gui_plugins/PlatformUnitPlugin/PlatformUnitGuiPlugin.cpp b/source/RobotAPI/gui_plugins/PlatformUnitPlugin/PlatformUnitGuiPlugin.cpp
new file mode 100644
index 000000000..fc01d3ee6
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/PlatformUnitPlugin/PlatformUnitGuiPlugin.cpp
@@ -0,0 +1,115 @@
+#include "PlatformUnitGuiPlugin.h"
+#include "PlatformUnitConfigDialog.h"
+#include "ui_PlatformUnitConfigDialog.h"
+#include <Core/core/system/ArmarXDataPath.h>
+
+// Qt headers
+#include <Qt>
+#include <QtGlobal>
+#include <QPushButton>
+#include <QLabel>
+#include <QLineEdit>
+
+using namespace armarx;
+
+
+PlatformUnitGuiPlugin::PlatformUnitGuiPlugin()
+{
+    addWidget<PlatformUnitWidget>();
+}
+
+
+PlatformUnitWidget::PlatformUnitWidget() :
+    platformUnitProxyName("PlatformUnitDynamicSimulation"),
+    platformName("Platform")
+{
+    // init gui
+    ui.setupUi(getWidget());
+}
+
+
+void PlatformUnitWidget::onInitComponent()
+{
+    usingProxy(platformUnitProxyName);
+    usingTopic(platformName + "State");
+    ARMARX_WARNING << "Listening on Topic: " << platformName + "State";
+}
+
+void PlatformUnitWidget::onConnectComponent()
+{
+    connectSlots();
+    platformUnitProxy = getProxy<PlatformUnitInterfacePrx>(platformUnitProxyName);
+}
+
+void PlatformUnitWidget::onExitComponent()
+{
+}
+
+QPointer<QDialog> PlatformUnitWidget::getConfigDialog(QWidget* parent)
+{
+    if(!dialog)
+    {
+        dialog = new PlatformUnitConfigDialog(parent);
+    }
+    dialog->ui->editPlatformUnitName->setText(QString::fromStdString(platformUnitProxyName));
+    dialog->ui->editPlatformName->setText(QString::fromStdString(platformName));
+    return qobject_cast<PlatformUnitConfigDialog*>(dialog);
+}
+
+ void PlatformUnitWidget::configured()
+ {
+     platformUnitProxyName = dialog->ui->editPlatformUnitName->text().toStdString();
+     platformName = dialog->ui->editPlatformName->text().toStdString();
+ }
+
+
+void PlatformUnitWidget::loadSettings(QSettings *settings)
+{
+    platformUnitProxyName = settings->value("platformUnitProxyName", QString::fromStdString(platformUnitProxyName)).toString().toStdString();
+    platformName = settings->value("platformName", QString::fromStdString(platformName)).toString().toStdString();
+}
+
+void PlatformUnitWidget::saveSettings(QSettings *settings)
+{
+    settings->setValue("platformUnitProxyName", QString::fromStdString(platformUnitProxyName));
+    settings->setValue("platformName", QString::fromStdString(platformName));
+}
+
+
+void PlatformUnitWidget::connectSlots()
+{
+    connect(ui.buttonMoveToPosition, SIGNAL(clicked()), this, SLOT(moveTo()));
+}
+
+void PlatformUnitWidget::moveTo()
+{
+    ARMARX_LOG << "Moving Platform";
+    ::Ice::Float positionX = ui.editTargetPositionX->text().toFloat();
+    ::Ice::Float positionY = ui.editTargetPositionY->text().toFloat();
+    ::Ice::Float rotation = ui.editTargetRotation->text().toFloat();
+    ::Ice::Float posAcc = 10.0f;
+    ::Ice::Float rotAcc = 0.1f;
+    platformUnitProxy->moveTo(positionX, positionY, rotation, posAcc, rotAcc);
+}
+
+void PlatformUnitWidget::reportPlatformPose(::Ice::Float currentPlatformPositionX, ::Ice::Float currentPlatformPositionY, ::Ice::Float currentPlatformRotation, const Ice::Current& c)
+{
+    ui.labelCurrentPositionX->setText(QString::number(currentPlatformPositionX));
+    ui.labelCurrentPositionY->setText(QString::number(currentPlatformPositionY));
+    ui.labelCurrentRotation->setText(QString::number(currentPlatformRotation));
+}
+
+void PlatformUnitWidget::reportNewTargetPose(::Ice::Float newPlatformPositionX, ::Ice::Float newPlatformPositionY, ::Ice::Float newPlatformRotation, const Ice::Current& c)
+{
+    ui.editTargetPositionX->setText(QString::number(newPlatformPositionX));
+    ui.editTargetPositionY->setText(QString::number(newPlatformPositionY));
+    ui.editTargetRotation->setText(QString::number(newPlatformRotation));
+}
+
+void PlatformUnitWidget::reportPlatformVelocity(::Ice::Float currentPlatformVelocityX, ::Ice::Float currentPlatformVelocityY, ::Ice::Float currentPlatformVelocityRotation, const Ice::Current& c)
+{
+
+}
+
+Q_EXPORT_PLUGIN2(armar3_gui_PlatformUnitGuiPlugin, PlatformUnitGuiPlugin)
+
diff --git a/source/RobotAPI/gui_plugins/PlatformUnitPlugin/PlatformUnitGuiPlugin.h b/source/RobotAPI/gui_plugins/PlatformUnitPlugin/PlatformUnitGuiPlugin.h
new file mode 100644
index 000000000..f791b42d1
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/PlatformUnitPlugin/PlatformUnitGuiPlugin.h
@@ -0,0 +1,123 @@
+/*
+* This file is part of ArmarX.
+*
+* ArmarX is free software; you can redistribute it and/or modify
+* it under the terms of the GNU Lesser General Public License as
+* published by the Free Software Foundation; either version 2 of
+* the License, or (at your option) any later version.
+*
+* ArmarX is distributed in the hope that it will be useful, but
+* WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+* GNU Lesser General Public License for more details.
+*
+* You should have received a copy of the GNU General Public License
+* along with this program. If not, see <http://www.gnu.org/licenses/>.
+*
+* @package    ArmarX::Component::ObjectExaminerGuiPlugin
+* @author     Nikolaus Vahrenkamp ( vahrenkamp at kit dot edu)
+* @copyright  2012
+* @license    http://www.gnu.org/licenses/gpl.txt
+*             GNU General Public License
+
+*/
+
+#ifndef _ARMARXGUI_PLUGINS_PLATFORMUNITWIDGET_H
+#define _ARMARXGUI_PLUGINS_PLATFORMUNITWIDGET_H
+
+/* ArmarX headers */
+#include "ui_PlatformUnitGuiPlugin.h"
+#include <Core/core/Component.h>
+#include <Gui/ArmarXGuiLib/ArmarXGuiPlugin.h>
+#include <Gui/ArmarXGuiLib/ArmarXComponentWidgetController.h>
+
+#include <RobotAPI/interface/units/PlatformUnitInterface.h>
+
+/* Qt headers */
+#include <QtGui/QMainWindow>
+
+#include <string>
+
+
+namespace armarx
+{
+    class PlatformUnitConfigDialog;
+
+    /**
+      \class PlatformUnitGuiPlugin
+      \brief With this plugin the PlatformUnit can be controlled.
+      \ingroup ArmarXGuiPlugins
+
+      \see PlatformUnitWidget
+      */
+    class PlatformUnitGuiPlugin :
+            public ArmarXGuiPlugin
+    {
+    public:
+        PlatformUnitGuiPlugin();
+        QString getPluginName()
+        {
+            return "PlatformUnitGuiPlugin";
+        }
+    };
+
+    /**
+      \class PlatformUnitWidget
+      \brief With this widget the PlatformUnit can be controlled.
+      \ingroup ArmarXGuiPlugins
+
+      \see PlatformUnitGuiPlugin
+      */
+    class PlatformUnitWidget :
+            public ArmarXComponentWidgetController,
+            public PlatformUnitListener
+    {
+        Q_OBJECT
+    public:
+        PlatformUnitWidget();
+        ~PlatformUnitWidget()
+        {}
+
+        // inherited from Component
+        virtual void onInitComponent();
+        virtual void onConnectComponent();
+        virtual void onExitComponent();
+
+        // slice interface implementation
+        void reportPlatformPose(::Ice::Float currentPlatformPositionX, ::Ice::Float currentPlatformPositionY, ::Ice::Float currentPlatformRotation, const Ice::Current& c = ::Ice::Current());
+        void reportNewTargetPose(::Ice::Float newPlatformPositionX, ::Ice::Float newPlatformPositionY, ::Ice::Float newPlatformRotation, const Ice::Current& c = ::Ice::Current());
+        void reportPlatformVelocity(::Ice::Float currentPlatformVelocityX, ::Ice::Float currentPlatformVelocityY, ::Ice::Float currentPlatformVelocityRotation, const Ice::Current& c = ::Ice::Current());
+
+        // inherited of ArmarXWidget
+        virtual QString getWidgetName() const
+        {
+            return "PlatformUnitGUI";
+        }
+
+        QPointer<QDialog> getConfigDialog(QWidget* parent = 0);
+        virtual void loadSettings(QSettings * settings);
+        virtual void saveSettings(QSettings * settings);
+        void configured();
+
+    public slots:
+
+        void moveTo();
+
+    protected:
+        void connectSlots();
+
+        Ui::PlatformUnitGuiPlugin ui;
+
+    private:
+        std::string platformUnitProxyName;
+        std::string platformName;
+
+        PlatformUnitInterfacePrx platformUnitProxy;
+
+        QPointer<QWidget> __widget;
+        QPointer<PlatformUnitConfigDialog> dialog;
+    };
+    typedef boost::shared_ptr<PlatformUnitWidget> PlatformUnitGuiPluginPtr;
+}
+
+#endif
diff --git a/source/RobotAPI/gui_plugins/PlatformUnitPlugin/PlatformUnitGuiPlugin.ui b/source/RobotAPI/gui_plugins/PlatformUnitPlugin/PlatformUnitGuiPlugin.ui
new file mode 100644
index 000000000..5a21e34a0
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/PlatformUnitPlugin/PlatformUnitGuiPlugin.ui
@@ -0,0 +1,115 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>PlatformUnitGuiPlugin</class>
+ <widget class="QWidget" name="PlatformUnitGuiPlugin">
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>360</width>
+    <height>190</height>
+   </rect>
+  </property>
+  <property name="sizePolicy">
+   <sizepolicy hsizetype="Minimum" vsizetype="Minimum">
+    <horstretch>0</horstretch>
+    <verstretch>0</verstretch>
+   </sizepolicy>
+  </property>
+  <property name="windowTitle">
+   <string>Form</string>
+  </property>
+  <widget class="QWidget" name="layoutWidget">
+   <property name="geometry">
+    <rect>
+     <x>9</x>
+     <y>9</y>
+     <width>341</width>
+     <height>171</height>
+    </rect>
+   </property>
+   <layout class="QGridLayout" name="gridLayout">
+    <item row="0" column="1">
+     <widget class="QLabel" name="labelCurrent">
+      <property name="text">
+       <string>Current Position</string>
+      </property>
+     </widget>
+    </item>
+    <item row="2" column="2">
+     <widget class="QLineEdit" name="editTargetPositionY"/>
+    </item>
+    <item row="1" column="0">
+     <widget class="QLabel" name="labelPositionX">
+      <property name="text">
+       <string>X Position</string>
+      </property>
+     </widget>
+    </item>
+    <item row="3" column="2">
+     <widget class="QLineEdit" name="editTargetRotation"/>
+    </item>
+    <item row="2" column="0">
+     <widget class="QLabel" name="labelPositionY">
+      <property name="text">
+       <string>Y Position</string>
+      </property>
+     </widget>
+    </item>
+    <item row="3" column="0">
+     <widget class="QLabel" name="labelRotation">
+      <property name="text">
+       <string>Rotation</string>
+      </property>
+     </widget>
+    </item>
+    <item row="0" column="2">
+     <widget class="QLabel" name="labelTarget">
+      <property name="text">
+       <string>Target Position</string>
+      </property>
+     </widget>
+    </item>
+    <item row="1" column="2">
+     <widget class="QLineEdit" name="editTargetPositionX"/>
+    </item>
+    <item row="2" column="1">
+     <widget class="QLabel" name="labelCurrentPositionY">
+      <property name="text">
+       <string>0</string>
+      </property>
+     </widget>
+    </item>
+    <item row="1" column="1">
+     <widget class="QLabel" name="labelCurrentPositionX">
+      <property name="text">
+       <string>0</string>
+      </property>
+     </widget>
+    </item>
+    <item row="3" column="1">
+     <widget class="QLabel" name="labelCurrentRotation">
+      <property name="text">
+       <string>0</string>
+      </property>
+     </widget>
+    </item>
+    <item row="4" column="2">
+     <widget class="QPushButton" name="buttonMoveToPosition">
+      <property name="text">
+       <string>Move To Position</string>
+      </property>
+     </widget>
+    </item>
+   </layout>
+  </widget>
+ </widget>
+ <tabstops>
+  <tabstop>editTargetPositionX</tabstop>
+  <tabstop>editTargetPositionY</tabstop>
+  <tabstop>editTargetRotation</tabstop>
+  <tabstop>buttonMoveToPosition</tabstop>
+ </tabstops>
+ <resources/>
+ <connections/>
+</ui>
diff --git a/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotter.cpp b/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotter.cpp
new file mode 100644
index 000000000..59b59d5c7
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotter.cpp
@@ -0,0 +1,387 @@
+/*
+* This file is part of ArmarX.
+*
+* ArmarX is free software; you can redistribute it and/or modify
+* it under the terms of the GNU Lesser General Public License as
+* published by the Free Software Foundation; either version 2 of
+* the License, or (at your option) any later version.
+*
+* ArmarX is distributed in the hope that it will be useful, but
+* WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+* GNU Lesser General Public License for more details.
+*
+* You should have received a copy of the GNU General Public License
+* along with this program. If not, see <http://www.gnu.org/licenses/>.
+*
+* @package    ArmarX::Gui
+* @author     Mirko Waechter ( mirko.waechter at kit dot edu)
+* @date       2012
+* @copyright  http://www.gnu.org/licenses/gpl.txt
+*             GNU General Public License
+*/
+
+#include "ArmarXPlotter.h"
+
+//QWT
+#include <qwt_plot.h>
+#include <qwt_plot_curve.h>
+#include <qwt_plot_panner.h>
+#include <qwt_plot_magnifier.h>
+#include <qwt_plot_canvas.h>
+#include <qwt_legend.h>
+#include <qwt_legend_item.h>
+#include <qwt_series_data.h>
+
+//QT
+#include <QTimer>
+#include <QTime>
+#include <QSettings>
+
+//STL
+#include <sstream>
+
+//ArmarX
+//#include <Core/observers/variant/Variant.h>
+#include <Core/observers/ObserverObjectFactories.h>
+#include <Core/observers/variant/DataFieldIdentifier.h>
+#include "ArmarXPlotterDialog.h"
+#include <Core/observers/exceptions/local/InvalidChannelException.h>
+
+#include <boost/date_time/posix_time/posix_time.hpp>
+
+#include <IceUtil/IceUtil.h>
+
+using namespace std;
+
+namespace armarx
+{
+
+    ArmarXPlotter::ArmarXPlotter() :
+        ArmarXComponentWidgetController(),
+        updateInterval(100),
+        shownInterval(60),
+        startUpTime(QDateTime::currentDateTime())
+
+
+    {
+        setTag("Plotter");
+        ui.setupUi(getWidget());
+        timer = new QTimer(getWidget());
+
+        ////////////////
+        //  Setup Plotter
+        ///////////////
+        // panning with the left mouse button
+        ( void ) new QwtPlotPanner( ui.qwtPlot->canvas() );
+
+        // zoom in/out with the wheel
+        QwtPlotMagnifier * magnifier = new QwtPlotMagnifier( ui.qwtPlot->canvas() );
+        magnifier->setAxisEnabled(QwtPlot::xBottom, false);
+
+        ui.qwtPlot->canvas()->setPaintAttribute(QwtPlotCanvas::BackingStore, false); //increases performance for incremental drawing
+
+        QwtLegend *legend = new QwtLegend;
+        legend->setItemMode( QwtLegend::CheckableItem );
+        ui.qwtPlot->insertLegend( legend, QwtPlot::BottomLegend );
+
+
+        ui.qwtPlot->setAxisTitle( QwtPlot::xBottom, "Time (in sec)");
+        //        ui.qwtPlot->setAutoReplot();
+
+        dialog = new ArmarXPlotterDialog(getWidget(), NULL);
+
+    }
+
+    ArmarXPlotter::~ArmarXPlotter()
+    {
+        //        if(dialog && this->getState() == eManagedIceObjectInitialized)
+        //            getArmarXManager()->removeObjectNonBlocking(dialog);
+        //        delete dialog;
+    }
+
+
+
+
+
+
+
+    void ArmarXPlotter::onInitComponent()
+    {
+    }
+
+    void ArmarXPlotter::onConnectComponent()
+    {
+        ARMARX_VERBOSE<< "ArmarXPlotter started" << flush;
+        dialog->setIceManager(getIceManager());
+
+        connect(dialog, SIGNAL(accepted()), this, SLOT(configDone()));
+        connect(ui.BTNEdit, SIGNAL(clicked()), this, SLOT(configDialog()));
+        connect(timer, SIGNAL(timeout()), this, SLOT(updateGraph()));
+        connect(ui.BTNPlotterStatus, SIGNAL(toggled(bool)), this, SLOT(plottingPaused(bool)));
+
+        connect(ui.BTNAutoScale, SIGNAL(toggled(bool)), this, SLOT(autoScale(bool)));
+        connect(  ui.qwtPlot, SIGNAL( legendChecked( QwtPlotItem *, bool ) ),
+                  SLOT( showCurve( QwtPlotItem *, bool ) ) );
+
+    }
+
+    void ArmarXPlotter::onCloseWidget(QCloseEvent *event)
+    {
+        ARMARX_VERBOSE << "closing" << flush;
+        timer->stop();
+    }
+
+    void ArmarXPlotter::ButtonAddSensorChannelClicked()
+    {
+    }
+
+    void ArmarXPlotter::configDialog()
+    {
+        if(!dialog)
+            return;
+        dialog->ui.spinBoxUpdateInterval->setValue(updateInterval);
+        dialog->ui.spinBoxShownInterval->setValue(shownInterval);
+        dialog->ui.listWidget->clear();
+        dialog->ui.listWidget->addItems(selectedChannels);
+        //        if(dialog->exec())
+        //            configDone();
+        dialog->setModal(true);
+        dialog->show();
+        //        dialog->raise();
+        //        dialog->activateWindow();
+        //        dialog->setParent(0);
+    }
+
+    void ArmarXPlotter::configDone()
+    {
+        ScopedLock lock(dataMutex);
+        updateInterval = dialog->ui.spinBoxUpdateInterval->value();
+        shownInterval = dialog->ui.spinBoxShownInterval->value();
+        selectedChannels = dialog->getSelectedChannels();
+
+        curves.clear();
+        ui.qwtPlot->detachItems();
+
+        applyCurves();
+    }
+
+
+
+    void ArmarXPlotter::updateGraph()
+    {
+        ScopedLock lock(dataMutex);
+        //get new data from observers for all selected channels and append them to the dataMap
+        QPointF p;
+        getData(selectedChannels, dataMap);
+        int size = shownInterval*1000/updateInterval;
+        GraphDataMap::iterator it = dataMap.begin();
+        boost::system_time curTime = boost::get_system_time();
+
+        for(; it != dataMap.end(); ++it)
+        {
+
+            QVector<QPointF> pointList;
+            pointList.clear();
+            std::vector<TimeData>& dataVec = it->second;
+            pointList.resize(min(size,(int)dataVec.size()));
+            try
+            {
+                for (unsigned int i = 0; i < dataVec.size(); ++i) {
+                    TimeData& data = dataVec[i];
+                    boost::posix_time::time_duration age = (data.time - curTime);
+                    if(age.total_milliseconds() <= shownInterval*1000)
+                    {
+                        VariantPtr var = VariantPtr::dynamicCast(data.data);
+                        if(var->getInitialized())
+                        {
+                            if((signed int)i < pointList.size())
+                            {
+                                if(var->getType() == VariantType::Float)
+                                    pointList[i].setY(var->getFloat());
+                                else if(var->getType() == VariantType::Int)
+                                    pointList[i].setY(var->getInt());
+                                else continue;
+                                pointList[i].setX(0.001f*age.total_milliseconds());
+                            }else
+                            {
+                                if(var->getType() == VariantType::Float)
+                                    p.setY(var->getFloat());
+                                else if(var->getType() == VariantType::Int)
+                                    p.setY(var->getInt());
+                                else continue;
+                                p.setX(0.001*age.total_milliseconds());
+                                pointList.push_back(p);
+                            }
+                        }
+                    }
+                }
+            }
+            catch(...)
+            {
+                handleExceptions();
+            }
+
+            QwtSeriesData<QPointF>* pointSeries = new  QwtPointSeriesData(pointList);
+            if(curves.find(it->first) != curves.end()){
+                QwtPlotCurve *curve = curves[it->first];
+                curve->setData(pointSeries);
+            }
+        }
+
+
+        ui.qwtPlot->setAxisScale( QwtPlot::xBottom, shownInterval*-1, 0.f);
+        if(ui.BTNAutoScale->isChecked())
+            ui.qwtPlot->setAxisAutoScale(QwtPlot::yLeft, true);
+        //        ui.qwtPlot->setAxisScale( QwtPlot::yLeft, -1, 1);
+
+        ui.qwtPlot->replot();
+    }
+
+    void ArmarXPlotter::showCurve( QwtPlotItem *item, bool on )
+    {
+        item->setVisible( on );
+
+        QwtLegendItem *legendItem =
+                qobject_cast<QwtLegendItem *>( ui.qwtPlot->legend()->find( item ) );
+
+        if ( legendItem )
+            legendItem->setChecked( on );
+
+        ui.qwtPlot->replot();
+    }
+
+    void ArmarXPlotter::autoScale(bool toggled)
+    {
+        ARMARX_VERBOSE << "clicked autoscale" << flush;
+
+        ui.qwtPlot->setAxisAutoScale(QwtPlot::yLeft, toggled);
+        ui.qwtPlot->replot();
+
+
+    }
+
+    void ArmarXPlotter::plottingPaused(bool toggled)
+    {
+        __plottingPaused = toggled;
+        if(__plottingPaused)
+            timer->stop();
+        else
+            timer->start();
+    }
+
+
+
+    void ArmarXPlotter::saveSettings(QSettings * settings)
+    {
+        ScopedLock lock(dataMutex);
+        settings->setValue("updateInterval", updateInterval);
+        settings->setValue("shownInterval", shownInterval);
+        settings->setValue("selectedChannels", selectedChannels);
+        settings->setValue("autoScaleActive", ui.BTNAutoScale->isChecked());
+    }
+
+    void ArmarXPlotter::loadSettings(QSettings * settings)
+    {
+        ScopedLock lock(dataMutex);
+        updateInterval = settings->value("updateInterval", 100).toInt();
+        shownInterval = settings->value("shownInterval", 60).toInt();
+        selectedChannels = settings->value("selectedChannels", QStringList()).toStringList();
+        ui.BTNAutoScale->setChecked(settings->value("autoScaleActive", true).toBool());
+        applyCurves();
+        ARMARX_VERBOSE << "Settings loaded" << flush;
+    }
+
+    void ArmarXPlotter::applyCurves()
+    {
+        for(int i = 0; i < selectedChannels.size(); i++){
+            ARMARX_VERBOSE << "Channel: " << selectedChannels.at(i).toStdString() << flush;
+            QwtPlotCurve* curve = new QwtPlotCurve(selectedChannels.at(i));
+
+            curve->setPen( QColor( Qt::GlobalColor((i+7)%15) ) );
+            curve->setStyle( QwtPlotCurve::Lines );
+
+            curve->attach(ui.qwtPlot);
+            showCurve(curve, true);
+            curves[selectedChannels.at(i).toStdString()]=curve;
+        }
+        ui.qwtPlot->replot();
+        timer->start(updateInterval);
+    }
+
+    void ArmarXPlotter::getData(const QStringList &channels, GraphDataMap &dataMaptoAppend)
+    {
+        map< std::string, DataFieldIdentifierBaseList > channelsSplittedByObserver;
+        foreach(QString channel, channels)
+        {
+            DataFieldIdentifierPtr identifier = new DataFieldIdentifier(channel.toStdString());
+            channelsSplittedByObserver[identifier->getObserverName()].push_back(identifier);
+//            ARMARX_INFO << identifier;
+        }
+
+        // first clear to old entries
+        GraphDataMap::iterator itmap = dataMaptoAppend.begin();
+        for(; itmap != dataMaptoAppend.end(); ++itmap)
+        {
+            std::vector<TimeData>& dataVec = itmap->second;
+            int thresholdIndex = -1;
+            for(unsigned int i=0; dataVec.size(); ++i)
+            {
+                // only delete if entries are older than 2*showninterval
+                // and delete then all entries that are older than showninterval.
+                // otherwise it would delete items on every call, which would be very slow
+
+
+                if((boost::get_system_time() - dataVec[i].time).total_milliseconds() > shownInterval*2*1000
+                        || (thresholdIndex != -1 && (boost::get_system_time() - dataVec[i].time ).total_milliseconds() > shownInterval*1000)
+                        )
+                {
+                    thresholdIndex = i;
+                }else
+                    break;
+            }
+            if(thresholdIndex!=-1)
+                dataVec.erase(dataVec.begin(), dataVec.begin()+std::min((int)dataVec.size(),thresholdIndex));
+        }
+        // now get new data
+        map<string, DataFieldIdentifierBaseList >::iterator it = channelsSplittedByObserver.begin();
+        try
+        {
+            for(; it != channelsSplittedByObserver.end(); ++it)
+            {
+                std::string observerName = it->first;
+
+                if(proxyMap.find(observerName) == proxyMap.end())
+                {
+                    proxyMap[observerName] = getProxy<ObserverInterfacePrx>(observerName);
+
+                }
+                //            QDateTime time(QDateTime::currentDateTime());
+                boost::system_time time = boost::get_system_time();
+                VariantBaseList variants = proxyMap[observerName]->getDataFields(it->second);
+//                ARMARX_IMPORTANT << "data from observer: " << observerName;
+                for(unsigned int i = 0; i < variants.size(); ++i)
+                {
+//                    ARMARX_IMPORTANT << "Variant: " << VariantPtr::dynamicCast(variants[i]);
+                    dataMaptoAppend[DataFieldIdentifierPtr::dynamicCast(it->second[i])->getIdentifierStr()].push_back(TimeData(time, VariantPtr::dynamicCast(variants[i])));
+                }
+
+            }
+        }
+        catch(Ice::NotRegisteredException &e){
+            ARMARX_WARNING << deactivateSpam(3) << "Caught Exception: " << e.what();
+        }
+        catch(exceptions::local::InvalidDataFieldException &e){
+            ARMARX_WARNING << deactivateSpam(5) << "Caught InvalidDataFieldException: " << e.what();
+        }
+        catch(exceptions::local::InvalidChannelException &e){
+            ARMARX_WARNING << deactivateSpam(5) << "Caught InvalidDataFieldException: " << e.what();
+        }
+        catch(...)
+        {
+            handleExceptions();
+        }
+    }
+
+
+}
diff --git a/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotter.h b/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotter.h
new file mode 100644
index 000000000..633ed6efc
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotter.h
@@ -0,0 +1,138 @@
+/*
+* This file is part of ArmarX.
+*
+* ArmarX is free software; you can redistribute it and/or modify
+* it under the terms of the GNU Lesser General Public License as
+* published by the Free Software Foundation; either version 2 of
+* the License, or (at your option) any later version.
+*
+* ArmarX is distributed in the hope that it will be useful, but
+* WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+* GNU Lesser General Public License for more details.
+*
+* You should have received a copy of the GNU General Public License
+* along with this program. If not, see <http://www.gnu.org/licenses/>.
+*
+* @package    ArmarX::Gui
+* @author     Mirko Waechter ( mirko.waechter at kit dot edu)
+* @date       2012
+* @copyright  http://www.gnu.org/licenses/gpl.txt
+*             GNU General Public License
+*/
+
+#ifndef ARMARXPLOTTER_H
+#define ARMARXPLOTTER_H
+
+#include "ui_ArmarXPlotter.h"
+
+// ArmarX
+#include <Core/core/Component.h>
+#include <Core/core/system/ImportExportComponent.h>
+#include <Core/core/system/AbstractFactoryMethod.h>
+#include <Core/interface/observers/ConditionHandlerInterface.h>
+#include <Core/observers/variant/DataFieldIdentifier.h>
+#include <Core/observers/variant/Variant.h>
+#include <Gui/ArmarXGuiLib/ArmarXComponentWidgetController.h>
+
+#include <Gui/gui_plugins/ObserverPropertiesPlugin/ObserverItemModel.h>
+
+// QT
+#include <QWidget>
+#include <QDialog>
+#include <QDateTime>
+
+
+//STL
+#include <vector>
+
+
+
+//forward declarations
+class QwtPlotCurve;
+
+namespace armarx
+{
+    struct TimeData{
+        TimeData(const boost::system_time &time, const VariantPtr &data): time(time), data(data){}
+
+        boost::system_time time;
+        VariantPtr data;
+    };
+
+    typedef std::map< std::string, ObserverInterfacePrx> ProxyMap;
+    typedef std::map< std::string, std::vector<TimeData> > GraphDataMap;
+
+    class ArmarXPlotterDialog;
+    /**
+      \class ArmarXPlotter
+      \ingroup ArmarXGuiPlugins
+      */
+    class ARMARXCOMPONENT_IMPORT_EXPORT
+    ArmarXPlotter:
+            public ArmarXComponentWidgetController
+    {
+        Q_OBJECT
+    public:
+
+
+        std::map<std::string, QwtPlotCurve *> curves;
+        Ui::ArmarXPlotter ui;
+        QPointer<ArmarXPlotterDialog> dialog;
+        QTimer * timer;
+        ConditionHandlerInterfacePrx handler;
+
+        // Configuration Parameters
+        int updateInterval;
+        int shownInterval;
+        QStringList selectedChannels;
+
+        explicit ArmarXPlotter();
+        ~ArmarXPlotter();
+        //inherited from ArmarXWidget
+        virtual QString getWidgetName() const { return "Plotter";}
+        void loadSettings(QSettings * settings);
+        void saveSettings(QSettings * settings);
+        //for AbstractFactoryMethod class
+
+
+        // inherited from Component
+        virtual void onInitComponent();
+        virtual void onConnectComponent();
+
+
+
+        /**
+        * emits the closeRequest signal
+        */
+        void onCloseWidget(QCloseEvent *event);
+    signals:
+
+    public slots:
+        void ButtonAddSensorChannelClicked();
+        void configDialog();
+        void updateGraph();
+        void showCurve(QwtPlotItem *item, bool on);
+        void autoScale(bool toggled);
+        void plottingPaused(bool toggled);
+        void configDone();
+
+
+    protected:
+        boost::shared_ptr<QSettings> settings;
+    private:
+        QDateTime startUpTime;
+        GraphDataMap dataMap;
+        std::map< std::string, ObserverInterfacePrx> proxyMap;
+        bool __plottingPaused;
+
+
+        void applyCurves();
+        void getData(const QStringList &channels, GraphDataMap &dataMaptoAppend);
+
+        Mutex dataMutex;
+    };
+
+}
+
+#endif
diff --git a/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotter.ui b/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotter.ui
new file mode 100644
index 000000000..dce7941c6
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotter.ui
@@ -0,0 +1,120 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>ArmarXPlotter</class>
+ <widget class="QWidget" name="ArmarXPlotter">
+  <property name="enabled">
+   <bool>true</bool>
+  </property>
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>400</width>
+    <height>400</height>
+   </rect>
+  </property>
+  <property name="sizePolicy">
+   <sizepolicy hsizetype="Expanding" vsizetype="Expanding">
+    <horstretch>0</horstretch>
+    <verstretch>0</verstretch>
+   </sizepolicy>
+  </property>
+  <property name="minimumSize">
+   <size>
+    <width>150</width>
+    <height>150</height>
+   </size>
+  </property>
+  <property name="windowTitle">
+   <string>ArmarX Plotter</string>
+  </property>
+  <layout class="QVBoxLayout" name="verticalLayout">
+   <property name="spacing">
+    <number>3</number>
+   </property>
+   <property name="margin">
+    <number>3</number>
+   </property>
+   <item>
+    <widget class="QwtPlot" name="qwtPlot"/>
+   </item>
+   <item>
+    <layout class="QHBoxLayout" name="horizontalLayout">
+     <property name="spacing">
+      <number>0</number>
+     </property>
+     <item>
+      <widget class="QToolButton" name="BTNEdit">
+       <property name="text">
+        <string>...</string>
+       </property>
+       <property name="icon">
+        <iconset resource="../../../ArmarXGui/icons.qrc">
+         <normaloff>:/icons/configure-3.png</normaloff>:/icons/configure-3.png</iconset>
+       </property>
+      </widget>
+     </item>
+     <item>
+      <widget class="QToolButton" name="BTNPlotterStatus">
+       <property name="text">
+        <string>...</string>
+       </property>
+       <property name="icon">
+        <iconset resource="../../../ArmarXGui/icons.qrc">
+         <normaloff>:/icons/media-playback-pause.ico</normaloff>:/icons/media-playback-pause.ico</iconset>
+       </property>
+       <property name="checkable">
+        <bool>true</bool>
+       </property>
+      </widget>
+     </item>
+     <item>
+      <widget class="QToolButton" name="BTNAutoScale">
+       <property name="toolTip">
+        <string>Automatic scaling of the graph</string>
+       </property>
+       <property name="text">
+        <string>Auto Scale</string>
+       </property>
+       <property name="icon">
+        <iconset resource="../../../ArmarXGui/icons.qrc">
+         <normaloff>:/icons/zoom-original-2.png</normaloff>:/icons/zoom-original-2.png</iconset>
+       </property>
+       <property name="checkable">
+        <bool>true</bool>
+       </property>
+       <property name="checked">
+        <bool>true</bool>
+       </property>
+      </widget>
+     </item>
+     <item>
+      <spacer name="horizontalSpacer">
+       <property name="orientation">
+        <enum>Qt::Horizontal</enum>
+       </property>
+       <property name="sizeHint" stdset="0">
+        <size>
+         <width>40</width>
+         <height>20</height>
+        </size>
+       </property>
+      </spacer>
+     </item>
+    </layout>
+   </item>
+  </layout>
+ </widget>
+ <customwidgets>
+  <customwidget>
+   <class>QwtPlot</class>
+   <extends>QFrame</extends>
+   <header>qwt_plot.h</header>
+   <container>1</container>
+  </customwidget>
+ </customwidgets>
+ <resources>
+  <include location="../../../ArmarXGui/icons.qrc"/>
+ </resources>
+ <connections/>
+</ui>
diff --git a/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotterDialog.cpp b/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotterDialog.cpp
new file mode 100644
index 000000000..2a88cb830
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotterDialog.cpp
@@ -0,0 +1,189 @@
+/*
+* This file is part of ArmarX.
+*
+* ArmarX is free software; you can redistribute it and/or modify
+* it under the terms of the GNU Lesser General Public License as
+* published by the Free Software Foundation; either version 2 of
+* the License, or (at your option) any later version.
+*
+* ArmarX is distributed in the hope that it will be useful, but
+* WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+* GNU Lesser General Public License for more details.
+*
+* You should have received a copy of the GNU General Public License
+* along with this program. If not, see <http://www.gnu.org/licenses/>.
+*
+* @package    ArmarX::Gui
+* @author     Mirko Waechter ( mirko.waechter at kit dot edu)
+* @date       2012
+* @copyright  http://www.gnu.org/licenses/gpl.txt
+*             GNU General Public License
+*/
+
+#include "ArmarXPlotterDialog.h"
+#include "ArmarXPlotter.h"
+#include <sstream>
+
+#include <IceUtil/UUID.h>
+
+
+
+using namespace armarx;
+using namespace std;
+
+
+ArmarXPlotterDialog::ArmarXPlotterDialog(QWidget *parent, IceManagerPtr iceManager) :
+    QDialog(parent),
+    uuid(IceUtil::generateUUID()),
+    iceManager(iceManager)
+{
+    ui.setupUi(this);
+    model = NULL;
+
+
+    connect(ui.BTNAddSelectedChannels, SIGNAL(clicked()), this, SLOT(ButtonAddSelectedChannelClicked()));
+    connect(ui.BTNRemoveSelected, SIGNAL(clicked()), this, SLOT(ButtonRemoveChannelClicked()));
+    connect(ui.treeViewObservers, SIGNAL(doubleClicked(QModelIndex)), this, SLOT(treeView_doubleClick(QModelIndex)));
+    connect(ui.listWidget, SIGNAL(doubleClicked(QModelIndex)), this, SLOT(ButtonRemoveChannelClicked(QModelIndex)));
+    connect(ui.btnRefresh, SIGNAL(clicked()), this, SLOT(updateObservers()));
+
+
+}
+
+ArmarXPlotterDialog::~ArmarXPlotterDialog()
+{
+//    ARMARX_INFO << "~ArmarXPlotterDialog" ;
+}
+
+void ArmarXPlotterDialog::setIceManager(IceManagerPtr iceManager)
+{
+    this->iceManager = iceManager;
+}
+
+
+
+//string ArmarXPlotterDialog::getDefaultName() const
+//{
+//    stringstream str;
+//    str << "ArmarXPlotterDialog" << uuid;
+//    return str.str();
+//}
+
+
+//void ArmarXPlotterDialog::onInitComponent()
+//{
+//    usingProxy("ConditionHandler");
+//}
+
+//void ArmarXPlotterDialog::onConnectComponent()
+//{
+//    // get proxy of conditionhandler
+//    handler = getProxy<ConditionHandlerInterfacePrx>("ConditionHandler");
+
+//    updateObservers();
+//}
+
+//void ArmarXPlotterDialog::onExitComponent()
+//{
+
+//}
+
+void ArmarXPlotterDialog::onCloseWidget(QCloseEvent *event)
+{
+
+}
+
+void ArmarXPlotterDialog::updateObservers()
+{
+    if(!model)
+    {
+        model = new ObserverItemModel(iceManager);
+        ui.treeViewObservers->setModel(model);
+
+    }
+
+        model->updateObservers();
+
+//    if(!iceManager)
+//        return;
+//    ObserverList observerList = iceManager->getIceGridSession()->getRegisteredObjectNames<ObserverInterfacePrx>("*Observer");
+//    ObserverList::iterator iter = observerList.begin();
+
+//    while(iter != observerList.end())
+//    {
+//        model->updateModel(*iter, iceManager->getProxy<ObserverInterfacePrx>(*iter)->getAvailableChannels(), StringConditionCheckMap());
+//        iter++;
+//    }
+}
+
+
+
+
+
+
+void ArmarXPlotterDialog::ButtonAddSelectedChannelClicked()
+{
+     QItemSelectionModel* selectionModel = ui.treeViewObservers->selectionModel();
+     for(int i = 0; i < selectionModel->selectedIndexes().size(); ++i)
+     {
+         QModelIndex index = selectionModel->selectedIndexes().at(i);
+         treeView_doubleClick(index);
+     }
+     ui.treeViewObservers->clearSelection();
+
+}
+
+void ArmarXPlotterDialog::ButtonRemoveChannelClicked()
+{
+    QList<QListWidgetItem*> selectedItems = ui.listWidget->selectedItems();
+    for(int i=0; i < selectedItems.size(); ++i)
+    {
+        delete selectedItems.at(i);
+    }
+}
+
+void ArmarXPlotterDialog::ButtonRemoveChannelClicked(QModelIndex index)
+{
+     delete ui.listWidget->item(index.row());
+}
+
+QStringList ArmarXPlotterDialog::getSelectedChannels()
+{
+    QStringList result;
+    QList <QListWidgetItem*> items = ui.listWidget->findItems(QString("*"), Qt::MatchWrap | Qt::MatchWildcard);
+    foreach(QListWidgetItem *item, items)
+      result.append(item->text());
+
+    return result;
+}
+
+void ArmarXPlotterDialog::treeView_selected(const QItemSelection& selected, const QItemSelection& deselected)
+{
+}
+
+void ArmarXPlotterDialog::treeView_doubleClick(const QModelIndex &index)
+{
+
+        QStandardItem* item = model->itemFromIndex(index);
+        QVariant id = item->data(OBSERVER_ITEM_ID);
+        switch(item->data(OBSERVER_ITEM_TYPE).toInt())
+        {
+        case eDataFieldItem:
+            if(ui.listWidget->findItems(id.toString(),Qt::MatchExactly).size() == 0)
+                ui.listWidget->addItem(id.toString());
+            break;
+
+        }
+}
+
+void ArmarXPlotterDialog::destroyed(QObject *)
+{
+    setParent(0);
+}
+
+void ArmarXPlotterDialog::showEvent(QShowEvent *)
+{
+    updateObservers();
+}
+
diff --git a/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotterDialog.h b/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotterDialog.h
new file mode 100644
index 000000000..d7fca1bd3
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotterDialog.h
@@ -0,0 +1,99 @@
+/*
+* This file is part of ArmarX.
+*
+* ArmarX is free software; you can redistribute it and/or modify
+* it under the terms of the GNU Lesser General Public License as
+* published by the Free Software Foundation; either version 2 of
+* the License, or (at your option) any later version.
+*
+* ArmarX is distributed in the hope that it will be useful, but
+* WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+* GNU Lesser General Public License for more details.
+*
+* You should have received a copy of the GNU General Public License
+* along with this program. If not, see <http://www.gnu.org/licenses/>.
+*
+* @package    ArmarX::Gui
+* @author     Mirko Waechter ( mirko.waechter at kit dot edu)
+* @date       2012
+* @copyright  http://www.gnu.org/licenses/gpl.txt
+*             GNU General Public License
+*/
+
+#ifndef ARMARXPLOTTERDIALOG_H
+#define ARMARXPLOTTERDIALOG_H
+
+
+// QT
+#include "ui_ArmarXPlotterDialog.h"
+#include <QDialog>
+#include <QComboBox>
+#include <QList>
+#include <QMenu>
+#include <QAction>
+#include <QItemSelectionModel>
+#include <QStandardItemModel>
+//STL
+#include <vector>
+
+//ArmarX
+#include <Core/core/IceManager.h>
+
+#include <Core/interface/observers/ConditionHandlerInterface.h>
+#include "../../ObserverPropertiesPlugin/ObserverItemModel.h"
+
+
+
+namespace armarx
+{
+    class ArmarXPlotter;
+    class ArmarXPlotterDialog:
+            public QDialog
+    {
+        Q_OBJECT
+        QStringList availableChannelsList;
+        ObserverItemModel *model;
+        std::string uuid;
+        IceManagerPtr iceManager;
+        int mdiId;
+
+
+    public:
+        ArmarXPlotterDialog(QWidget *parent, IceManagerPtr iceManager);
+        ~ArmarXPlotterDialog();
+        ConditionHandlerInterfacePrx handler;
+        struct ChannelWidgetsEntry{
+            QComboBox* comboBox;
+            QLabel *label;
+            QPushButton *deleteButton;
+        };
+
+        void setIceManager(IceManagerPtr iceManager);
+
+        Ui::ArmarXPlotterDialog ui;
+        std::vector< ChannelWidgetsEntry > sensorChannelList;
+        QStringList getSelectedChannels();
+
+
+//        // inherited from Component
+//        std::string getDefaultName() const;
+//        virtual void onInitComponent();
+//        virtual void onConnectComponent();
+//        void onExitComponent();
+        /**
+        * emits the closeRequest signal
+        */
+        void onCloseWidget(QCloseEvent *event);
+    public slots:
+        void ButtonAddSelectedChannelClicked();
+        void ButtonRemoveChannelClicked();
+        void ButtonRemoveChannelClicked(QModelIndex index);
+        void updateObservers();
+        void treeView_selected(const QItemSelection& selected, const QItemSelection& deselected);
+        void treeView_doubleClick(const QModelIndex &index);
+        void destroyed(QObject *);
+        void showEvent(QShowEvent *);
+    };
+}
+#endif // ARMARXPLOTTERDIALOG_H
diff --git a/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotterDialog.ui b/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotterDialog.ui
new file mode 100644
index 000000000..dd5c23165
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXPlotter/ArmarXPlotterDialog.ui
@@ -0,0 +1,260 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>ArmarXPlotterDialog</class>
+ <widget class="QDialog" name="ArmarXPlotterDialog">
+  <property name="windowModality">
+   <enum>Qt::ApplicationModal</enum>
+  </property>
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>586</width>
+    <height>599</height>
+   </rect>
+  </property>
+  <property name="windowTitle">
+   <string>ArmarX Plotter Config Dialog</string>
+  </property>
+  <property name="sizeGripEnabled">
+   <bool>true</bool>
+  </property>
+  <property name="modal">
+   <bool>true</bool>
+  </property>
+  <layout class="QVBoxLayout" name="verticalLayout">
+   <item>
+    <layout class="QGridLayout" name="gridLayout">
+     <item row="1" column="0">
+      <widget class="QLabel" name="LblUpdateInterval">
+       <property name="text">
+        <string>Update interval (in ms)</string>
+       </property>
+      </widget>
+     </item>
+     <item row="0" column="0">
+      <widget class="QLabel" name="LBLShownInterval">
+       <property name="text">
+        <string>Shown Interval (in s)</string>
+       </property>
+      </widget>
+     </item>
+     <item row="0" column="2">
+      <widget class="QSpinBox" name="spinBoxShownInterval">
+       <property name="minimum">
+        <number>1</number>
+       </property>
+       <property name="maximum">
+        <number>6000</number>
+       </property>
+       <property name="value">
+        <number>60</number>
+       </property>
+      </widget>
+     </item>
+     <item row="1" column="2">
+      <widget class="QSpinBox" name="spinBoxUpdateInterval">
+       <property name="buttonSymbols">
+        <enum>QAbstractSpinBox::UpDownArrows</enum>
+       </property>
+       <property name="minimum">
+        <number>0</number>
+       </property>
+       <property name="maximum">
+        <number>999999999</number>
+       </property>
+       <property name="singleStep">
+        <number>10</number>
+       </property>
+       <property name="value">
+        <number>100</number>
+       </property>
+      </widget>
+     </item>
+     <item row="0" column="1">
+      <spacer name="horizontalSpacer">
+       <property name="orientation">
+        <enum>Qt::Horizontal</enum>
+       </property>
+       <property name="sizeHint" stdset="0">
+        <size>
+         <width>40</width>
+         <height>20</height>
+        </size>
+       </property>
+      </spacer>
+     </item>
+    </layout>
+   </item>
+   <item>
+    <widget class="QGroupBox" name="groupBoxSensorChannels">
+     <property name="minimumSize">
+      <size>
+       <width>200</width>
+       <height>200</height>
+      </size>
+     </property>
+     <property name="title">
+      <string>Sensor Channels</string>
+     </property>
+     <layout class="QVBoxLayout" name="verticalLayout_3">
+      <item>
+       <widget class="QSplitter" name="splitter">
+        <property name="orientation">
+         <enum>Qt::Horizontal</enum>
+        </property>
+        <widget class="FilterableTreeView" name="treeViewObservers">
+         <property name="editTriggers">
+          <set>QAbstractItemView::NoEditTriggers</set>
+         </property>
+         <property name="selectionMode">
+          <enum>QAbstractItemView::ExtendedSelection</enum>
+         </property>
+         <property name="animated">
+          <bool>true</bool>
+         </property>
+         <property name="headerHidden">
+          <bool>true</bool>
+         </property>
+        </widget>
+        <widget class="QListWidget" name="listWidget">
+         <property name="editTriggers">
+          <set>QAbstractItemView::NoEditTriggers</set>
+         </property>
+         <property name="selectionMode">
+          <enum>QAbstractItemView::ExtendedSelection</enum>
+         </property>
+        </widget>
+       </widget>
+      </item>
+      <item>
+       <layout class="QHBoxLayout" name="horizontalLayout_2">
+        <item>
+         <widget class="QToolButton" name="BTNAddSelectedChannels">
+          <property name="sizePolicy">
+           <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
+            <horstretch>0</horstretch>
+            <verstretch>0</verstretch>
+           </sizepolicy>
+          </property>
+          <property name="toolTip">
+           <string>Add selected datafields</string>
+          </property>
+          <property name="text">
+           <string/>
+          </property>
+          <property name="icon">
+           <iconset resource="../../../ArmarXGui/icons.qrc">
+            <normaloff>:/icons/edit-add.ico</normaloff>:/icons/edit-add.ico</iconset>
+          </property>
+         </widget>
+        </item>
+        <item>
+         <widget class="QToolButton" name="btnRefresh">
+          <property name="toolTip">
+           <string>Refresh observerlist</string>
+          </property>
+          <property name="text">
+           <string>...</string>
+          </property>
+          <property name="icon">
+           <iconset resource="../../../ArmarXGui/icons.qrc">
+            <normaloff>:/icons/view-refresh-7.png</normaloff>:/icons/view-refresh-7.png</iconset>
+          </property>
+         </widget>
+        </item>
+        <item>
+         <spacer name="horizontalSpacer_2">
+          <property name="orientation">
+           <enum>Qt::Horizontal</enum>
+          </property>
+          <property name="sizeHint" stdset="0">
+           <size>
+            <width>40</width>
+            <height>20</height>
+           </size>
+          </property>
+         </spacer>
+        </item>
+        <item>
+         <widget class="QToolButton" name="BTNRemoveSelected">
+          <property name="sizePolicy">
+           <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
+            <horstretch>0</horstretch>
+            <verstretch>0</verstretch>
+           </sizepolicy>
+          </property>
+          <property name="toolTip">
+           <string>Remove selected datafields</string>
+          </property>
+          <property name="text">
+           <string/>
+          </property>
+          <property name="icon">
+           <iconset resource="../../../ArmarXGui/icons.qrc">
+            <normaloff>:/icons/dialog-cancel-5.svg</normaloff>:/icons/dialog-cancel-5.svg</iconset>
+          </property>
+         </widget>
+        </item>
+       </layout>
+      </item>
+     </layout>
+    </widget>
+   </item>
+   <item>
+    <widget class="QDialogButtonBox" name="buttonBox">
+     <property name="orientation">
+      <enum>Qt::Horizontal</enum>
+     </property>
+     <property name="standardButtons">
+      <set>QDialogButtonBox::Cancel|QDialogButtonBox::Ok</set>
+     </property>
+    </widget>
+   </item>
+  </layout>
+ </widget>
+ <customwidgets>
+  <customwidget>
+   <class>FilterableTreeView</class>
+   <extends>QTreeView</extends>
+   <header location="global">Gui/ArmarXGui/Widgets/FilterableTreeView.h</header>
+  </customwidget>
+ </customwidgets>
+ <resources>
+  <include location="../../../ArmarXGui/icons.qrc"/>
+ </resources>
+ <connections>
+  <connection>
+   <sender>buttonBox</sender>
+   <signal>accepted()</signal>
+   <receiver>ArmarXPlotterDialog</receiver>
+   <slot>accept()</slot>
+   <hints>
+    <hint type="sourcelabel">
+     <x>248</x>
+     <y>254</y>
+    </hint>
+    <hint type="destinationlabel">
+     <x>157</x>
+     <y>274</y>
+    </hint>
+   </hints>
+  </connection>
+  <connection>
+   <sender>buttonBox</sender>
+   <signal>rejected()</signal>
+   <receiver>ArmarXPlotterDialog</receiver>
+   <slot>reject()</slot>
+   <hints>
+    <hint type="sourcelabel">
+     <x>316</x>
+     <y>260</y>
+    </hint>
+    <hint type="destinationlabel">
+     <x>286</x>
+     <y>274</y>
+    </hint>
+   </hints>
+  </connection>
+ </connections>
+</ui>
diff --git a/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.cpp b/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.cpp
new file mode 100644
index 000000000..df6c4e205
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.cpp
@@ -0,0 +1,392 @@
+/*
+* This file is part of ArmarX.
+*
+* ArmarX is free software; you can redistribute it and/or modify
+* it under the terms of the GNU Lesser General Public License as
+* published by the Free Software Foundation; either version 2 of
+* the License, or (at your option) any later version.
+*
+* ArmarX is distributed in the hope that it will be useful, but
+* WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+* GNU Lesser General Public License for more details.
+*
+* You should have received a copy of the GNU General Public License
+* along with this program. If not, see <http://www.gnu.org/licenses/>.
+*
+* @package    ArmarX::
+* @author     Mirko Waechter ( mirko.waechter at kit dot edu)
+* @date       2012
+* @copyright  http://www.gnu.org/licenses/gpl.txt
+*             GNU General Public License
+*/
+
+#include "TCPMover.h"
+
+
+//VirtualRobot
+#include <VirtualRobot/XML/RobotIO.h>
+#include <VirtualRobot/LinkedCoordinate.h>
+#include <RobotAPI/libraries/robotstate/remote/ArmarPose.h>
+
+
+// C++ includes
+#include <sstream>
+
+// Qt includes
+#include <QScrollBar>
+#include <QLineEdit>
+#include <QDialogButtonBox>
+
+using namespace armarx;
+using namespace VirtualRobot;
+
+
+TCPMover::TCPMover() :
+    robotRequested(false)
+
+{
+
+//    handData[selectedTCP][0] = handData[selectedTCP][1] = handData[selectedTCP][2] = 0.0f;
+//    handData[selectedTCP][3] = handData[selectedTCP][4] = handData[selectedTCP][5] = 0.0f;
+    ui.setupUi(getWidget());
+    ui.gridLayout->setEnabled(false);
+    // SIGNALS AND SLOTS CONNECTIONS
+    connect(ui.cbselectedTCP, SIGNAL(currentIndexChanged(int)), this, SLOT(selectHand(int)));
+    connect(ui.BtnRequestControl, SIGNAL(clicked(bool)), this, SLOT(robotControl(bool)));
+    connect(ui.btnUp, SIGNAL(clicked()), this, SLOT(moveUp()));
+    connect(ui.btnDown, SIGNAL(clicked()), this, SLOT(moveDown()));
+    connect(ui.btnZUp, SIGNAL(clicked()), this, SLOT(moveZUp()));
+    connect(ui.btnZDown, SIGNAL(clicked()), this, SLOT(moveZDown()));
+    connect(ui.btnLeft, SIGNAL(clicked()), this, SLOT(moveRight()));
+    connect(ui.btnRight, SIGNAL(clicked()), this, SLOT(moveLeft()));
+    connect(ui.btnIncreaseAlpha, SIGNAL(clicked()), this, SLOT(increaseAlpha()));
+    connect(ui.btnDecreaseAlpha, SIGNAL(clicked()), this, SLOT(decreaseAlpha()));
+    connect(ui.btnIncreaseBeta, SIGNAL(clicked()), this, SLOT(increaseBeta()));
+    connect(ui.btnDecreaseBeta, SIGNAL(clicked()), this, SLOT(decreaseBeta()));
+    connect(ui.btnIncreaseGamma, SIGNAL(clicked()), this, SLOT(increaseGamma()));
+    connect(ui.btnDecreaseGamma, SIGNAL(clicked()), this, SLOT(decreaseGamma()));
+
+    connect(ui.btnRight, SIGNAL(clicked()), this, SLOT(moveLeft()));
+    connect(ui.btnStop, SIGNAL(clicked()), this, SLOT(stopMoving()));
+    connect(ui.btnResetJoinAngles, SIGNAL(clicked()), this, SLOT(reset()));
+
+}
+
+TCPMover::~TCPMover()
+{
+
+}
+
+
+
+void armarx::TCPMover::loadSettings(QSettings *settings)
+{
+    tcpMoverUnitName = settings->value("TCPControlUnitName", "TCPControlUnit").toString().toStdString();
+}
+
+void armarx::TCPMover::saveSettings(QSettings *settings)
+{
+    settings->setValue("TCPControlUnitName", tcpMoverUnitName.c_str());
+}
+
+QPointer<QDialog> TCPMover::getConfigDialog(QWidget *parent)
+{
+    if(!configDialog)
+        configDialog = new TCPMoverConfigDialog(parent);
+    return qobject_cast<TCPMoverConfigDialog*>(configDialog);
+}
+
+void TCPMover::configured()
+{
+    tcpMoverUnitName = qobject_cast<TCPMoverConfigDialog*>(getConfigDialog())->editTCPMoverUnitName->text().toStdString();
+}
+
+
+
+
+void armarx::TCPMover::onInitComponent()
+{
+//    kinematicUnitFile = getProperty<std::string>("RobotFileName", KINEMATIC_UNIT_FILE_DEFAULT).getValueOrDefault();
+//    kinematicUnitName = getProperty<std::string>("RobotNodeSetName",KINEMATIC_UNIT_NAME_DEFAULT).getValueOrDefault();
+
+//    // Load Robot
+//    ARMARX_VERBOSE << ": Loading KinematicUnit " << kinematicUnitName << " from '" << kinematicUnitFile << "' ..." << flush;
+//    robot = RobotIO::loadRobot(kinematicUnitFile);
+//    if (!robot)
+//    {
+//        ARMARX_ERROR << "Could not find Robot XML file with name '" << kinematicUnitFile << "'" << flush;
+//    }
+
+
+//    usingProxy(kinematicUnitName);
+    usingProxy(tcpMoverUnitName);
+    usingProxy("RobotStateComponent");
+
+}
+
+void armarx::TCPMover::onConnectComponent()
+{
+
+    tcpMoverUnitPrx = getProxy<TCPControlUnitInterfacePrx>(tcpMoverUnitName);
+    robotStateComponentPrx = getProxy<RobotStateComponentInterfacePrx>("RobotStateComponent");
+
+    robotPrx = robotStateComponentPrx->getSynchronizedRobot();
+    NameList nodeSets = robotPrx->getRobotNodeSets();
+    QStringList nodeSetsQStr;
+    for(unsigned int i=0; i < nodeSets.size(); i++)
+    {
+        if(!robotPrx->getRobotNodeSet(nodeSets.at(i))->tcpName.empty())
+        {
+            tcpData[nodeSets.at(i)].resize(6, 0.f);
+            nodeSetsQStr << QString::fromStdString(nodeSets.at(i));
+        }
+    }
+    QString selected = ui.cbselectedTCP->currentText();
+    ui.cbselectedTCP->clear();
+    ui.cbselectedTCP->addItems(nodeSetsQStr);
+    int index = ui.cbselectedTCP->findText(selected);
+    if(index != -1)
+        ui.cbselectedTCP->setCurrentIndex(index);
+    refFrame = robotStateComponentPrx->getSynchronizedRobot()->getRootNode()->getName();
+
+//    kinematicUnitPrx = getProxy<KinematicUnitInterfacePrx>(kinematicUnitName);
+
+//    tcpNodeSetName = "LARM";
+//    tcpNodeSet = robot->getRobotNodeSet(tcpNodeSetName);
+//    NameControlModeMap modeMap;
+//    for(unsigned int i = 0; i < tcpNodeSet->getSize(); i++)
+//    {
+//        modeMap[tcpNodeSet->getNode(i)->getName()] = eVelocityControl;
+//    }
+//    kinematicUnitPrx->switchControlMode(modeMap);
+//    ik = DifferentialIKPtr(new DifferentialIK(tcpNodeSet));
+    ui.gridLayout->setEnabled(false);
+}
+
+void TCPMover::onExitComponent()
+{
+
+//    if(robotRequested)
+//        kinematicUnitPrx->release();
+}
+
+void TCPMover::moveUp()
+{
+//    moveRelative(-1,0,0);
+    tcpData[selectedTCP][0]++;
+    execMove();
+}
+
+void TCPMover::moveDown()
+{
+//    moveRelative(1,0,0);
+    tcpData[selectedTCP][0]--;
+    execMove();
+}
+
+void TCPMover::moveZUp()
+{
+    tcpData[selectedTCP][2]++;
+    execMove();
+}
+
+void TCPMover::moveZDown()
+{
+    tcpData[selectedTCP][2]--;
+    execMove();
+}
+
+void TCPMover::moveLeft()
+{
+//    moveRelative(0,1,0);
+    tcpData[selectedTCP][1] ++;
+    execMove();
+
+}
+
+void TCPMover::moveRight()
+{
+    tcpData[selectedTCP][1] --;
+    execMove();
+
+    //    moveRelative(0,-1,0);
+}
+
+void TCPMover::increaseAlpha()
+{
+    tcpData[selectedTCP].at(3) += 2.f;
+    execMove();
+}
+
+void TCPMover::decreaseAlpha()
+{
+    tcpData[selectedTCP].at(3) -= 2.f;
+    execMove();
+}
+
+void TCPMover::increaseBeta()
+{
+    tcpData[selectedTCP].at(4) += 2.f;
+    execMove();
+}
+
+void TCPMover::decreaseBeta()
+{
+    tcpData[selectedTCP].at(4) -= 2.f;
+    execMove();
+}
+
+void TCPMover::increaseGamma()
+{
+    tcpData[selectedTCP].at(5) += 2.f;
+    execMove();
+}
+
+void TCPMover::decreaseGamma()
+{
+    tcpData[selectedTCP].at(5) -= 2.f;
+    execMove();
+}
+
+void TCPMover::stopMoving()
+{
+    tcpData[selectedTCP][0] = tcpData[selectedTCP][1] = tcpData[selectedTCP][2] = 0.0f;
+
+    execMove();
+}
+
+void TCPMover::reset()
+{
+     tcpData[selectedTCP][0] = tcpData[selectedTCP][1] = tcpData[selectedTCP][2] = 0.0f;
+     tcpData[selectedTCP].at(3) = tcpData[selectedTCP].at(4) = tcpData[selectedTCP].at(5) = 0.0f;
+     execMove();
+     tcpMoverUnitPrx->release();
+//     tcpMoverUnitPrx->resetArmToHomePosition(eLeftHand);
+
+}
+
+void TCPMover::robotControl(bool request)
+{
+    tcpMoverUnitPrx->request();
+//    try{
+//        if(request)
+//            kinematicUnitPrx->request();
+//        else
+//            kinematicUnitPrx->release();
+//    }catch(ResourceUnavailableException &e){
+//        ui.BtnRequestControl->setChecked(false);
+
+//    }catch(ResourceNotOwnedException &e){
+//        ui.BtnRequestControl->setChecked(true);
+//    }
+//    robotRequested = ui.BtnRequestControl->isChecked();
+
+}
+
+void TCPMover::selectHand(int index)
+{
+    selectedTCP = ui.cbselectedTCP->itemText(index).toStdString();    
+}
+
+void TCPMover::execMove()
+{
+    ARMARX_INFO << "Setting new velos and orientation";
+    ui.lblXValue->setText(QString::number(tcpData[selectedTCP][0]));
+    ui.lblYValue->setText(QString::number(tcpData[selectedTCP][1]));
+    ui.lblZValue->setText(QString::number(tcpData[selectedTCP][2]));
+    ui.lblAlphaValue->setText(QString::number(tcpData[selectedTCP].at(3)));
+    ui.lblBetaValue->setText(QString::number(tcpData[selectedTCP].at(4)));
+    ui.lblGammaValue->setText(QString::number(tcpData[selectedTCP].at(5)));
+
+    Eigen::Vector3f vec;
+    vec << tcpData[selectedTCP][0], tcpData[selectedTCP][1], tcpData[selectedTCP][2];
+    vec *= ui.sbFactor->value();
+    FramedVector3Ptr tcpVel = new FramedVector3(vec, refFrame);
+    Eigen::Vector3f vecOri;
+    vecOri << tcpData[selectedTCP].at(3)/180.f*3.145f, tcpData[selectedTCP].at(4)/180.f*3.145f, tcpData[selectedTCP].at(5)/180.f*3.145f;
+    vecOri *= ui.sbFactor->value();
+    FramedVector3Ptr tcpOri = new FramedVector3(vecOri, refFrame);
+
+    if(!ui.cbTranslation->isChecked() )
+        tcpVel = NULL;
+    if(!ui.cbOrientation->isChecked() )
+        tcpOri = NULL;
+    tcpMoverUnitPrx->begin_setTCPVelocity(selectedTCP,ui.edtTCPName->text().toStdString(), tcpVel,tcpOri);
+
+//    tcpMoverUnitPrx->setCartesianTCPVelocity(selectedTCP, handData[selectedTCP][0], handData[selectedTCP][1], handData[selectedTCP][2], ui.sbFactor->value());
+//    tcpMoverUnitPrx->setTCPOrientation(selectedTCP, handData[selectedTCP].at(3)/180.f*3.145f, handData[selectedTCP].at(4)/180.f*3.145f, handData[selectedTCP].at(5)/180.f*3.145f);
+}
+
+void TCPMover::moveRelative(float x, float y, float z)
+{
+//    RobotNodePtr tcpNode = tcpNodeSet->getTCP();
+//    // calculate cartesian error
+//    Eigen::Matrix4f newPosRelative;
+//    newPosRelative
+//            << 1, 0, 0, 10*ui.sbFactor->value(),
+//               0, 1, 0, 0,
+//               0, 0, 1, 0,
+//               0, 0, 0, 1;
+//    Eigen::VectorXf errorCartVec(3);
+//    errorCartVec << x*ui.sbFactor->value(),y*ui.sbFactor->value(),z*ui.sbFactor->value();
+////    errorCartVec.segment(0,3) = newPosRelative.block(0,3,3,1);
+
+
+
+
+//    Eigen::MatrixXf Ji = ik->getPseudoInverseJacobianMatrix(tcpNode, IKSolver::Position);
+//    // calculat joint error
+//    Eigen::VectorXf errorJoint(tcpNodeSet->getSize());
+//    errorJoint = Ji * errorCartVec;
+//    std::vector<float> angles = tcpNodeSet->getJointValues();
+//    std::vector<float> targetAngles(tcpNodeSet->getSize());
+//    NameValueMap targetAnglesMap;
+
+//    for(unsigned int i = 0; i < tcpNodeSet->getSize(); i++)
+//    {
+////        float newAngle = angles[i] + errorJoint(i);
+//        float newAngle = errorJoint(i);
+//        targetAngles[i] = newAngle;
+//        targetAnglesMap[tcpNodeSet->getNode(i)->getName()] = newAngle;
+//        //ARMARX_VERBOSE << tcpNodeSet->getNode(i)->getName() << ": " << newAngle;
+//    }
+//    tcpNodeSet->setJointValues(targetAngles);
+//    kinematicUnitPrx->setJointVelocities(targetAnglesMap);
+}
+
+
+void TCPMoverConfigDialog::setupUI(QWidget *parent)
+{
+    this->setWindowTitle("Enter name of TCPMoverUnit");
+
+    layout = new QGridLayout(parent);
+
+    label = new QLabel("TCPMoverUnit name:", parent);
+    layout->addWidget(label, 0,0);
+
+    editTCPMoverUnitName = new QLineEdit("TCPMoverUnit", parent);
+    layout->addWidget(editTCPMoverUnitName, 0, 1);
+
+    buttonBox = new QDialogButtonBox(parent);
+    buttonBox->setObjectName(QString::fromUtf8("buttonBox"));
+    buttonBox->setOrientation(Qt::Horizontal);
+    buttonBox->setStandardButtons(QDialogButtonBox::Cancel|QDialogButtonBox::Ok);
+
+    layout->addWidget(buttonBox, 1, 0, 1, 2);
+
+
+    QObject::connect(buttonBox, SIGNAL(accepted()), this, SLOT(accept()));
+    QObject::connect(buttonBox, SIGNAL(rejected()), this, SLOT(reject()));
+
+
+
+}
+
+
+TCPMoverConfigDialog::TCPMoverConfigDialog(QWidget *parent) :
+    QDialog(parent)
+{
+
+    setupUI(this);
+}
diff --git a/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.h b/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.h
new file mode 100644
index 000000000..d647ab82d
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.h
@@ -0,0 +1,137 @@
+/*
+* This file is part of ArmarX.
+*
+* ArmarX is free software; you can redistribute it and/or modify
+* it under the terms of the GNU Lesser General Public License as
+* published by the Free Software Foundation; either version 2 of
+* the License, or (at your option) any later version.
+*
+* ArmarX is distributed in the hope that it will be useful, but
+* WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+* GNU Lesser General Public License for more details.
+*
+* You should have received a copy of the GNU General Public License
+* along with this program. If not, see <http://www.gnu.org/licenses/>.
+*
+* @package    ArmarX::
+* @author     Mirko Waechter ( mirko.waechter at kit dot edu)
+* @date       2012
+* @copyright  http://www.gnu.org/licenses/gpl.txt
+*             GNU General Public License
+*/
+
+#ifndef ARMARXGUI_TCPMOVER_H
+#define ARMARXGUI_TCPMOVER_H
+
+/** ArmarX headers **/
+#include "ui_TCPMover.h"
+
+// ArmarX includes
+#include <RobotAPI/interface/units/TCPMoverUnitInterface.h>
+#include <RobotAPI/interface/units/TCPControlUnit.h>
+/** VirtualRobot headers **/
+#include <VirtualRobot/Robot.h>
+#include <VirtualRobot/Nodes/RobotNode.h>
+#include <VirtualRobot/RobotNodeSet.h>
+#include <VirtualRobot/IK/DifferentialIK.h>
+
+#include <Gui/ArmarXGuiLib/ArmarXComponentWidgetController.h>
+
+// Qt includes
+#include <QDialog>
+
+#define KINEMATIC_UNIT_FILE_DEFAULT armarx::ArmarXDataPath::getHomePath()+std::string("Armar4/ARMAR_IV_simox.xml")
+#define KINEMATIC_UNIT_NAME_DEFAULT "RobotKinematicUnit"
+
+
+class QDialogButtonBox;
+
+namespace armarx {
+
+    class TCPMoverConfigDialog : public QDialog
+    {
+        Q_OBJECT
+
+    public:
+        TCPMoverConfigDialog(QWidget *parent = 0);
+
+        friend class TCPMover;
+    protected:
+        QGridLayout *layout;
+        QLabel *label;
+        QLineEdit *editTCPMoverUnitName;
+        QDialogButtonBox *buttonBox;
+
+        void setupUI(QWidget *parent);
+    };
+
+
+
+    class TCPMover :
+            public ArmarXComponentWidgetController
+    {
+        Q_OBJECT
+
+    public:
+        TCPMover();
+        ~TCPMover();
+        //inherited from ArmarXMdiWidget
+        void loadSettings(QSettings * settings);
+        void saveSettings(QSettings * settings);
+        QString getWidgetName() const { return "TCPMover";}
+        QPointer<QDialog> getConfigDialog(QWidget *parent = 0);
+        void configured();
+
+        // inherited from Component
+        virtual void onInitComponent();
+        virtual void onConnectComponent();
+        virtual void onExitComponent();
+
+
+    public slots:
+        void moveUp();
+        void moveDown();
+        void moveZUp();
+        void moveZDown();
+        void moveLeft();
+        void moveRight();
+        void increaseAlpha();
+        void decreaseAlpha();
+        void increaseBeta();
+        void decreaseBeta();
+        void increaseGamma();
+        void decreaseGamma();
+        void stopMoving();
+        void reset();
+        void robotControl(bool request);
+        void selectHand(int index);
+    signals:
+
+    protected:
+        void execMove();
+
+        void moveRelative(float x, float y, float z);
+        std::map<std::string, std::vector<float> > tcpData;
+        std::string selectedTCP;
+        std::string refFrame;
+//        float velocities[2][3];
+//        float orientation[2][3];
+        NameValueMap velocityMap;
+        bool robotRequested;
+        VirtualRobot::RobotNodeSetPtr tcpNodeSet;
+        std::string tcpNodeSetName;
+        VirtualRobot::DifferentialIKPtr ik;
+        Ui::TCPMover ui;
+        std::string kinematicUnitName;
+        std::string kinematicUnitFile;
+        std::string tcpMoverUnitName;
+        VirtualRobot::RobotPtr robot;
+        TCPControlUnitInterfacePrx tcpMoverUnitPrx;
+        RobotStateComponentInterfacePrx robotStateComponentPrx;
+        SharedRobotInterfacePrx robotPrx;
+        QPointer<TCPMoverConfigDialog> configDialog;
+    };
+}
+
+#endif
diff --git a/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.ui b/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.ui
new file mode 100644
index 000000000..b44a4e31e
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/ArmarXTCPMover/TCPMover.ui
@@ -0,0 +1,525 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>TCPMover</class>
+ <widget class="QWidget" name="TCPMover">
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>260</width>
+    <height>196</height>
+   </rect>
+  </property>
+  <property name="minimumSize">
+   <size>
+    <width>100</width>
+    <height>100</height>
+   </size>
+  </property>
+  <property name="windowTitle">
+   <string>TCPMover</string>
+  </property>
+  <layout class="QGridLayout" name="gridLayout_2">
+   <property name="margin">
+    <number>3</number>
+   </property>
+   <property name="spacing">
+    <number>3</number>
+   </property>
+   <item row="1" column="0">
+    <widget class="QDoubleSpinBox" name="sbFactor">
+     <property name="sizePolicy">
+      <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
+       <horstretch>0</horstretch>
+       <verstretch>0</verstretch>
+      </sizepolicy>
+     </property>
+     <property name="maximum">
+      <double>999999.000000000000000</double>
+     </property>
+     <property name="value">
+      <double>10.000000000000000</double>
+     </property>
+    </widget>
+   </item>
+   <item row="0" column="0">
+    <layout class="QGridLayout" name="gridLayout">
+     <item row="4" column="1">
+      <widget class="QToolButton" name="btnUp">
+       <property name="toolTip">
+        <string>Move Up</string>
+       </property>
+       <property name="text">
+        <string>...</string>
+       </property>
+       <property name="iconSize">
+        <size>
+         <width>24</width>
+         <height>24</height>
+        </size>
+       </property>
+       <property name="arrowType">
+        <enum>Qt::UpArrow</enum>
+       </property>
+      </widget>
+     </item>
+     <item row="6" column="6">
+      <widget class="QToolButton" name="btnDecreaseGamma">
+       <property name="text">
+        <string>...</string>
+       </property>
+       <property name="iconSize">
+        <size>
+         <width>24</width>
+         <height>24</height>
+        </size>
+       </property>
+       <property name="arrowType">
+        <enum>Qt::DownArrow</enum>
+       </property>
+      </widget>
+     </item>
+     <item row="3" column="3" colspan="4">
+      <widget class="QCheckBox" name="cbOrientation">
+       <property name="text">
+        <string>Orientation</string>
+       </property>
+      </widget>
+     </item>
+     <item row="1" column="3" colspan="4">
+      <widget class="QComboBox" name="cbselectedTCP">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="currentIndex">
+        <number>-1</number>
+       </property>
+      </widget>
+     </item>
+     <item row="6" column="5">
+      <widget class="QToolButton" name="btnDecreaseBeta">
+       <property name="text">
+        <string>...</string>
+       </property>
+       <property name="iconSize">
+        <size>
+         <width>24</width>
+         <height>24</height>
+        </size>
+       </property>
+       <property name="arrowType">
+        <enum>Qt::DownArrow</enum>
+       </property>
+      </widget>
+     </item>
+     <item row="7" column="4">
+      <widget class="QLabel" name="lblAlphaValue">
+       <property name="text">
+        <string/>
+       </property>
+      </widget>
+     </item>
+     <item row="7" column="1">
+      <widget class="QLabel" name="lblXValue">
+       <property name="text">
+        <string/>
+       </property>
+      </widget>
+     </item>
+     <item row="7" column="3">
+      <widget class="QLabel" name="lblZValue">
+       <property name="text">
+        <string/>
+       </property>
+      </widget>
+     </item>
+     <item row="5" column="2">
+      <widget class="QLabel" name="label_3">
+       <property name="text">
+        <string>Y</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="5" column="6">
+      <widget class="QLabel" name="label_6">
+       <property name="text">
+        <string>G</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="7" column="5">
+      <widget class="QLabel" name="lblBetaValue">
+       <property name="text">
+        <string/>
+       </property>
+      </widget>
+     </item>
+     <item row="6" column="0">
+      <widget class="QToolButton" name="btnResetJoinAngles">
+       <property name="toolTip">
+        <string>Reset Both Arms to Home Position</string>
+       </property>
+       <property name="text">
+        <string>...</string>
+       </property>
+       <property name="icon">
+        <iconset resource="../../../ArmarXGui/icons.qrc">
+         <normaloff>:/icons/dialog-close.ico</normaloff>:/icons/dialog-close.ico</iconset>
+       </property>
+       <property name="iconSize">
+        <size>
+         <width>24</width>
+         <height>24</height>
+        </size>
+       </property>
+      </widget>
+     </item>
+     <item row="4" column="3">
+      <widget class="QToolButton" name="btnZUp">
+       <property name="text">
+        <string>...</string>
+       </property>
+       <property name="iconSize">
+        <size>
+         <width>24</width>
+         <height>24</height>
+        </size>
+       </property>
+       <property name="arrowType">
+        <enum>Qt::UpArrow</enum>
+       </property>
+      </widget>
+     </item>
+     <item row="7" column="6">
+      <widget class="QLabel" name="lblGammaValue">
+       <property name="text">
+        <string/>
+       </property>
+      </widget>
+     </item>
+     <item row="4" column="0">
+      <widget class="QToolButton" name="BtnRequestControl">
+       <property name="toolTip">
+        <string>Request Control over Kinematic Unit</string>
+       </property>
+       <property name="text">
+        <string>...</string>
+       </property>
+       <property name="icon">
+        <iconset resource="../../../ArmarXGui/icons.qrc">
+         <normaloff>:/icons/games.ico</normaloff>:/icons/games.ico</iconset>
+       </property>
+       <property name="iconSize">
+        <size>
+         <width>24</width>
+         <height>24</height>
+        </size>
+       </property>
+       <property name="checkable">
+        <bool>true</bool>
+       </property>
+      </widget>
+     </item>
+     <item row="6" column="4">
+      <widget class="QToolButton" name="btnDecreaseAlpha">
+       <property name="text">
+        <string>...</string>
+       </property>
+       <property name="iconSize">
+        <size>
+         <width>24</width>
+         <height>24</height>
+        </size>
+       </property>
+       <property name="arrowType">
+        <enum>Qt::DownArrow</enum>
+       </property>
+      </widget>
+     </item>
+     <item row="6" column="2">
+      <widget class="QToolButton" name="btnLeft">
+       <property name="toolTip">
+        <string>Move Left</string>
+       </property>
+       <property name="text">
+        <string>...</string>
+       </property>
+       <property name="iconSize">
+        <size>
+         <width>24</width>
+         <height>24</height>
+        </size>
+       </property>
+       <property name="arrowType">
+        <enum>Qt::DownArrow</enum>
+       </property>
+      </widget>
+     </item>
+     <item row="4" column="2">
+      <widget class="QToolButton" name="btnRight">
+       <property name="toolTip">
+        <string>Move Right</string>
+       </property>
+       <property name="text">
+        <string>...</string>
+       </property>
+       <property name="iconSize">
+        <size>
+         <width>24</width>
+         <height>24</height>
+        </size>
+       </property>
+       <property name="arrowType">
+        <enum>Qt::UpArrow</enum>
+       </property>
+      </widget>
+     </item>
+     <item row="5" column="5">
+      <widget class="QLabel" name="label_5">
+       <property name="text">
+        <string>B</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="5" column="4">
+      <widget class="QLabel" name="label_4">
+       <property name="text">
+        <string>A</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="5" column="3">
+      <widget class="QLabel" name="label">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="Minimum" vsizetype="Preferred">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="layoutDirection">
+        <enum>Qt::LeftToRight</enum>
+       </property>
+       <property name="text">
+        <string>Z</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="6" column="3">
+      <widget class="QToolButton" name="btnZDown">
+       <property name="text">
+        <string>...</string>
+       </property>
+       <property name="iconSize">
+        <size>
+         <width>24</width>
+         <height>24</height>
+        </size>
+       </property>
+       <property name="arrowType">
+        <enum>Qt::DownArrow</enum>
+       </property>
+      </widget>
+     </item>
+     <item row="5" column="1">
+      <widget class="QLabel" name="label_2">
+       <property name="text">
+        <string>X</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="7" column="2">
+      <widget class="QLabel" name="lblYValue">
+       <property name="text">
+        <string/>
+       </property>
+      </widget>
+     </item>
+     <item row="6" column="1">
+      <widget class="QToolButton" name="btnDown">
+       <property name="toolTip">
+        <string>Move Down</string>
+       </property>
+       <property name="text">
+        <string>...</string>
+       </property>
+       <property name="iconSize">
+        <size>
+         <width>24</width>
+         <height>24</height>
+        </size>
+       </property>
+       <property name="toolButtonStyle">
+        <enum>Qt::ToolButtonIconOnly</enum>
+       </property>
+       <property name="autoRaise">
+        <bool>false</bool>
+       </property>
+       <property name="arrowType">
+        <enum>Qt::DownArrow</enum>
+       </property>
+      </widget>
+     </item>
+     <item row="4" column="5">
+      <widget class="QToolButton" name="btnIncreaseBeta">
+       <property name="text">
+        <string>...</string>
+       </property>
+       <property name="iconSize">
+        <size>
+         <width>24</width>
+         <height>24</height>
+        </size>
+       </property>
+       <property name="arrowType">
+        <enum>Qt::UpArrow</enum>
+       </property>
+      </widget>
+     </item>
+     <item row="1" column="0" colspan="3">
+      <widget class="QLabel" name="lblHand">
+       <property name="text">
+        <string>Robot Node set</string>
+       </property>
+      </widget>
+     </item>
+     <item row="4" column="6">
+      <widget class="QToolButton" name="btnIncreaseGamma">
+       <property name="text">
+        <string>...</string>
+       </property>
+       <property name="iconSize">
+        <size>
+         <width>24</width>
+         <height>24</height>
+        </size>
+       </property>
+       <property name="arrowType">
+        <enum>Qt::UpArrow</enum>
+       </property>
+      </widget>
+     </item>
+     <item row="5" column="0">
+      <widget class="QToolButton" name="btnStop">
+       <property name="toolTip">
+        <string>Stop Motion</string>
+       </property>
+       <property name="text">
+        <string>...</string>
+       </property>
+       <property name="icon">
+        <iconset>
+         <normaloff>:/icons/edit-delete.ico</normaloff>:/icons/edit-delete.ico</iconset>
+       </property>
+       <property name="iconSize">
+        <size>
+         <width>24</width>
+         <height>24</height>
+        </size>
+       </property>
+      </widget>
+     </item>
+     <item row="4" column="4">
+      <widget class="QToolButton" name="btnIncreaseAlpha">
+       <property name="text">
+        <string>...</string>
+       </property>
+       <property name="iconSize">
+        <size>
+         <width>24</width>
+         <height>24</height>
+        </size>
+       </property>
+       <property name="arrowType">
+        <enum>Qt::UpArrow</enum>
+       </property>
+      </widget>
+     </item>
+     <item row="3" column="0" colspan="3">
+      <widget class="QCheckBox" name="cbTranslation">
+       <property name="text">
+        <string> Translation</string>
+       </property>
+       <property name="checked">
+        <bool>true</bool>
+       </property>
+      </widget>
+     </item>
+     <item row="2" column="0" colspan="3">
+      <widget class="QLabel" name="label_7">
+       <property name="text">
+        <string>TCP Name</string>
+       </property>
+      </widget>
+     </item>
+     <item row="2" column="3" colspan="4">
+      <widget class="QLineEdit" name="edtTCPName"/>
+     </item>
+    </layout>
+   </item>
+   <item row="0" column="1">
+    <spacer name="horizontalSpacer">
+     <property name="orientation">
+      <enum>Qt::Horizontal</enum>
+     </property>
+     <property name="sizeType">
+      <enum>QSizePolicy::Expanding</enum>
+     </property>
+     <property name="sizeHint" stdset="0">
+      <size>
+       <width>5</width>
+       <height>1</height>
+      </size>
+     </property>
+    </spacer>
+   </item>
+   <item row="2" column="0">
+    <spacer name="verticalSpacer">
+     <property name="orientation">
+      <enum>Qt::Vertical</enum>
+     </property>
+     <property name="sizeHint" stdset="0">
+      <size>
+       <width>1</width>
+       <height>1</height>
+      </size>
+     </property>
+    </spacer>
+   </item>
+  </layout>
+  <action name="actionSaveAs">
+   <property name="text">
+    <string>Save As..</string>
+   </property>
+  </action>
+  <action name="actionSave">
+   <property name="text">
+    <string>Save</string>
+   </property>
+  </action>
+ </widget>
+ <resources>
+  <include location="../../../ArmarXGui/icons.qrc"/>
+ </resources>
+ <connections/>
+</ui>
diff --git a/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/CMakeLists.txt b/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/CMakeLists.txt
new file mode 100644
index 000000000..2c9a66d30
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/CMakeLists.txt
@@ -0,0 +1,69 @@
+armarx_set_target("SensorActorWidgetsGuiPlugin")
+
+
+find_package(Qt4 COMPONENTS QtCore QtGui)
+find_package(qwt QUIET)
+
+find_package(Eigen3 QUIET)
+# VirtualRobot
+find_package(Simox QUIET)
+find_package(ArmarXGui QUIET)
+
+armarx_build_if(ArmarXGui_FOUND "ArmarXGui not available")
+
+armarx_build_if(QT_FOUND "Qt not available")
+armarx_build_if(QT_QTOPENGL_FOUND "QtOpenGL not available")
+armarx_build_if(qwt_FOUND "Qwt not available")
+armarx_build_if(Eigen3_FOUND "Eigen3 not available")
+armarx_build_if(Simox_FOUND "VirtualRobot not available")
+
+include(${QT_USE_FILE})
+
+include(${ArmarXGui_CMAKE_DIR}/ArmarXGui.cmake)
+
+if (qwt_FOUND AND Eigen3_FOUND AND Simox_FOUND AND RobotAPI_FOUND)
+    include_directories(${qwt_INCLUDE_DIR}
+        ${Eigen3_INCLUDE_DIR}
+        ${Simox_INCLUDE_DIRS}
+        ${RobotAPI_INCLUDE_DIRS})
+endif()
+
+set(SOURCES
+    SensorActorWidgetsPlugin.cpp
+    ArmarXPlotter/ArmarXPlotter.cpp
+    ArmarXPlotter/ArmarXPlotterDialog.cpp
+
+    ArmarXTCPMover/TCPMover.cpp
+)
+
+set(HEADERS
+    SensorActorWidgetsPlugin.h
+    ArmarXPlotter/ArmarXPlotter.h
+    ArmarXPlotter/ArmarXPlotterDialog.h
+
+    ArmarXTCPMover/TCPMover.h
+)
+
+set(GUI_MOC_HDRS
+    ArmarXPlotter/ArmarXPlotter.h
+    ArmarXPlotter/ArmarXPlotterDialog.h
+
+    ArmarXTCPMover/TCPMover.h
+)
+
+set(GUI_UIS
+    ArmarXPlotter/ArmarXPlotter.ui
+    ArmarXPlotter/ArmarXPlotterDialog.ui
+
+    ArmarXTCPMover/TCPMover.ui
+)
+
+
+set(COMPONENT_LIBS RobotAPIUnits ArmarXCoreObservers ObserverPropertiesGuiPlugin RobotAPIInterfaces ${qwt_LIBRARIES} ${Simox_LIBRARIES} ${QT_LIBRARIES})
+
+set(LIB_VERSION    0.1.0)
+set(LIB_SOVERSION  0)
+
+if (ArmarXGui_FOUND)
+	armarx_gui_library(SensorActorWidgetsGuiPlugin "${SOURCES}" "${GUI_MOC_HDRS}" "${GUI_UIS}" "" "${COMPONENT_LIBS}" "${LIB_VERSION}" "${LIB_SOVERSION}")
+endif()
diff --git a/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/SensorActorWidgetsPlugin.cpp b/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/SensorActorWidgetsPlugin.cpp
new file mode 100644
index 000000000..ba223fa22
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/SensorActorWidgetsPlugin.cpp
@@ -0,0 +1,39 @@
+/*
+* This file is part of ArmarX.
+*
+* ArmarX is free software; you can redistribute it and/or modify
+* it under the terms of the GNU Lesser General Public License as
+* published by the Free Software Foundation; either version 2 of
+* the License, or (at your option) any later version.
+*
+* ArmarX is distributed in the hope that it will be useful, but
+* WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+* GNU Lesser General Public License for more details.
+*
+* You should have received a copy of the GNU General Public License
+* along with this program. If not, see <http://www.gnu.org/licenses/>.
+*
+* @package    ArmarX::Gui::SensorActorWidgetsPlugin
+* @author     ( at kit dot edu)
+* @date       
+* @copyright  http://www.gnu.org/licenses/gpl.txt
+*             GNU General Public License
+*/
+
+#include "SensorActorWidgetsPlugin.h"
+
+//ArmarX
+#include "ArmarXPlotter/ArmarXPlotter.h"
+#include "ArmarXTCPMover/TCPMover.h"
+
+namespace armarx
+{
+
+    MdiPlugin::MdiPlugin(){
+        addWidget<TCPMover>();
+        addWidget<ArmarXPlotter>();
+    }
+	
+    Q_EXPORT_PLUGIN2(armarX_gui_MdiPlugin, MdiPlugin)
+}
diff --git a/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/SensorActorWidgetsPlugin.h b/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/SensorActorWidgetsPlugin.h
new file mode 100644
index 000000000..0ab65e97a
--- /dev/null
+++ b/source/RobotAPI/gui_plugins/SensorActorWidgetsPlugin/SensorActorWidgetsPlugin.h
@@ -0,0 +1,49 @@
+/*
+* This file is part of ArmarX.
+*
+* ArmarX is free software; you can redistribute it and/or modify
+* it under the terms of the GNU Lesser General Public License as
+* published by the Free Software Foundation; either version 2 of
+* the License, or (at your option) any later version.
+*
+* ArmarX is distributed in the hope that it will be useful, but
+* WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+* GNU Lesser General Public License for more details.
+*
+* You should have received a copy of the GNU General Public License
+* along with this program. If not, see <http://www.gnu.org/licenses/>.
+*
+* @package    ArmarX::Gui::SensorActorWidgetsPlugin
+* @author     ( at kit dot edu)
+* @date       
+* @copyright  http://www.gnu.org/licenses/gpl.txt
+*             GNU General Public License
+*/
+
+#ifndef ARMARX_COMPONENT_MDIGUIPLUGIN_H
+#define ARMARX_COMPONENT_MDIGUIPLUGIN_H
+
+
+//ArmarX
+#include <Core/core/system/ImportExportComponent.h>
+
+#include <Gui/ArmarXGuiLib/ArmarXGuiPlugin.h>
+
+namespace armarx
+{
+    /**
+     * @brief The MdiPlugin class
+     *
+     *
+     */
+    class ARMARXCOMPONENT_IMPORT_EXPORT MdiPlugin :
+            public ArmarXGuiPlugin
+    {
+    public:
+        MdiPlugin();
+    };
+
+}
+
+#endif
-- 
GitLab