diff --git a/CMakeLists.txt b/CMakeLists.txt
index 67263b55543410733f37cf50e1940297b7b58808..af848c21dc30833af6f7c67fa0550be098b064eb 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -32,13 +32,12 @@ INCLUDE(cmake/test.cmake)
 
 SET(PROJECT_NAME gepetto-viewer-corba)
 SET(PROJECT_DESCRIPTION "Corba server for gepetto-viewer")
-SET(PROJECT_URL "")
+SET(PROJECT_URL "https://github.com/Gepetto/gepetto-viewer-corba")
 
 SET(CLIENT_ONLY FALSE CACHE BOOL "Set to true to install the client only")
 SET(USE_QT4 TRUE CACHE BOOL "Use Qt4 instead of Qt5")
 
 SET(${PROJECT_NAME}_HEADERS
-  include/gepetto/viewer/corba/windows-manager.hh
   include/gepetto/viewer/corba/server.hh
   include/gepetto/viewer/corba/client.hh
   include/gepetto/viewer/corba/fwd.hh
@@ -70,7 +69,7 @@ IF(NOT CLIENT_ONLY)
   ADD_REQUIRED_DEPENDENCY("gepetto-viewer")
   ADD_REQUIRED_DEPENDENCY("urdfdom")
 
-  SET(BOOST_COMPONENTS system thread regex)
+  SET(BOOST_COMPONENTS system regex)
   SEARCH_FOR_BOOST ()
   FINDPYTHON()
 
@@ -136,7 +135,6 @@ IF(NOT CLIENT_ONLY)
   ENDIF(GEPETTO_GUI_HAS_PYTHONQT)
   SET (${PROJECT_NAME}_HEADERS_NO_MOC
     ${CMAKE_SOURCE_DIR}/include/gepetto/gui/fwd.hh
-    ${CMAKE_SOURCE_DIR}/include/gepetto/gui/meta.hh
     ${CMAKE_SOURCE_DIR}/include/gepetto/gui/settings.hh
     ${CMAKE_SOURCE_DIR}/include/gepetto/gui/color-map.hh
     ${CMAKE_BINARY_DIR}/include/gepetto/gui/config-dep.hh
diff --git a/include/gepetto/gui/mainwindow.hh b/include/gepetto/gui/mainwindow.hh
index 618f6d4b56a57e3403e7b938be50bb4b4915339e..26e5ce248ad0927ffcfd3acce20516970dc6eba4 100644
--- a/include/gepetto/gui/mainwindow.hh
+++ b/include/gepetto/gui/mainwindow.hh
@@ -109,9 +109,6 @@ namespace gepetto {
 
 signals:
         void sendToBackground (WorkItem* item);
-        /// You should not need to call this function.
-        /// Use MainWindow::createView(const std::string&)
-        void createViewOnMainThread(const std::string& name);
         /// Triggered when an OSGWidget is created.
         void viewCreated (OSGWidget* widget);
         void refresh ();
@@ -268,7 +265,6 @@ signals:
 
         ActionSearchBar* actionSearchBar_;
 
-        QMutex delayedCreateView_;
         QStringList robotNames_;
         QStringList lastBodiesInCollision_;
 
diff --git a/include/gepetto/gui/meta.hh b/include/gepetto/gui/meta.hh
deleted file mode 100644
index b014a41e286106673451de6bc905084d1ef415e9..0000000000000000000000000000000000000000
--- a/include/gepetto/gui/meta.hh
+++ /dev/null
@@ -1,57 +0,0 @@
-// Copyright (c) 2015-2018, LAAS-CNRS
-// Authors: Joseph Mirabel (joseph.mirabel@laas.fr)
-//
-// This file is part of gepetto-viewer-corba.
-// gepetto-viewer-corba 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
-// 3 of the License, or (at your option) any later version.
-//
-// gepetto-viewer-corba 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
-// General Lesser Public License for more details. You should have
-// received a copy of the GNU Lesser General Public License along with
-// gepetto-viewer-corba. If not, see <http://www.gnu.org/licenses/>.
-
-#ifndef GEPETTO_GUI_META_HH
-#define GEPETTO_GUI_META_HH
-
-#include <QString>
-
-namespace gepetto {
-  namespace gui {
-    template <typename T> struct convertTo {
-      static inline       T& from (      T& t) { return t; }
-      static inline const T& from (const T& t) { return t; }
-    };
-    template <> struct convertTo<std::string> {
-      static inline std::string from (const QString& in) { return in.toStdString(); };
-    };
-
-    template <typename T> struct Traits;
-
-    template <> struct Traits <CORBA::String_var> {
-      typedef CORBA::String_var type;
-      static inline type from (const QString& s) { return (const char*)s.toLocal8Bit().data(); }
-      static inline type from (const std::string& s) { return s.c_str(); }
-    };
-
-    template <> struct Traits <QString> {
-      typedef CORBA::String_var CORBA_t;
-      static inline CORBA_t to_corba (const QString& s) { return (const char*)s.toLocal8Bit().data(); }
-    };
-
-
-    template <typename In, typename Out, std::size_t Size>
-    inline void convertSequence (const In* in, Out (&out)[Size]) {
-      for (size_t i = 0; i < Size; ++i) out[i] = (Out)in[i];
-    }
-    template <typename In, typename Out>
-    inline void convertSequence (const In* in, Out* out, const std::size_t& s) {
-      for (size_t i = 0; i < s; ++i) out[i] = (Out)in[i];
-    }
-  }
-}
-
-#endif // GEPETTO_GUI_META_HH
diff --git a/include/gepetto/gui/osgwidget.hh b/include/gepetto/gui/osgwidget.hh
index 6583b465ee82447c527735bc00e3530207f7e51e..ebdbbca5fea2a6e7ce04976afc7a666d93463972 100644
--- a/include/gepetto/gui/osgwidget.hh
+++ b/include/gepetto/gui/osgwidget.hh
@@ -35,6 +35,9 @@ class QTextBrowser;
 
 namespace gepetto {
   namespace gui {
+    typedef graphics::WindowManagerPtr_t WindowManagerPtr_t;
+    typedef WindowsManager::WindowID WindowID;
+
     /// Widget that displays scenes.
     class OSGWidget : public QWidget
     {
@@ -48,9 +51,9 @@ namespace gepetto {
 
         virtual ~OSGWidget();
 
-        WindowsManager::WindowID windowID () const;
+        WindowID windowID () const;
 
-        graphics::WindowManagerPtr_t window () const;
+        WindowManagerPtr_t window () const;
 
         WindowsManagerPtr_t osg () const;
 
@@ -62,6 +65,10 @@ namespace gepetto {
 
         void toggleCapture (bool active);
 
+        void captureFrame (const std::string& filename);
+        bool startCapture (const std::string& filename, const std::string& extension);
+        bool stopCapture ();
+
       protected:
         virtual void paintEvent(QPaintEvent* event);
 
diff --git a/include/gepetto/gui/windows-manager.hh b/include/gepetto/gui/windows-manager.hh
index 0870fb5f3417c915a9235a4e9a64340f7cfd0e25..1b3eaf62729c3acd0edd9666cc912beae9adcb00 100644
--- a/include/gepetto/gui/windows-manager.hh
+++ b/include/gepetto/gui/windows-manager.hh
@@ -18,25 +18,14 @@
 #define GEPETTO_GUI_WINDOWSMANAGER_HH
 
 #include <gepetto/gui/fwd.hh>
-#include <gepetto/viewer/corba/windows-manager.hh>
+#include <gepetto/viewer/windows-manager.h>
 
-#include <gepetto/gui/meta.hh>
 #include <QColor>
 #include <QObject>
 #include <QVector3D>
 
 namespace gepetto {
   namespace gui {
-    template <> struct convertTo<graphics::WindowsManager::Color_t> {
-      typedef graphics::WindowsManager::Color_t T;
-      typedef typename T::value_type v_t;
-      static inline T from (const QColor& in) {
-        T v((v_t)in.redF(), (v_t)in.greenF(), (v_t)in.blueF(), (v_t)in.alphaF());
-        // in.getRgbF(&v[0],&v[1],&v[2],&v[3]);
-        return v;
-      }
-    };
-
     class WindowsManager : public QObject, public graphics::WindowsManager
     {
       Q_OBJECT
@@ -50,6 +39,7 @@ namespace gepetto {
 
         WindowID createWindow(const std::string& windowName);
         WindowID createWindow(const std::string& windowName,
+                              OSGWidget* widget,
                               osgViewer::Viewer* viewer,
                               osg::GraphicsContext *gc);
 
@@ -59,6 +49,11 @@ namespace gepetto {
 
         BodyTreeItems_t bodyTreeItems (const std::string& name) const;
 
+        void captureFrame (const WindowID windowId, const std::string& filename);
+        bool startCapture (const WindowID windowId, const std::string& filename,
+            const std::string& extension);
+        bool stopCapture (const WindowID windowId);
+
         public slots:
           int createWindow(QString windowName);
       protected:
@@ -78,6 +73,8 @@ namespace gepetto {
                          const NodePtr_t&   node,     const BodyTreeItems_t& groups,
                          bool isGroup);
         void deleteBodyItem(const std::string& nodeName);
+
+        std::vector<OSGWidget*> widgets_;
     };
   } // namespace gui
 } // namespace gepetto
diff --git a/include/gepetto/viewer/corba/se3.hh b/include/gepetto/viewer/corba/se3.hh
deleted file mode 100644
index 41019809e748e3c3c01d8ac12f52a62330d6432f..0000000000000000000000000000000000000000
--- a/include/gepetto/viewer/corba/se3.hh
+++ /dev/null
@@ -1,146 +0,0 @@
-// Copyright (c) 2015-2018, LAAS-CNRS
-// Authors: Joseph Mirabel (joseph.mirabel@laas.fr)
-//
-// This file is part of gepetto-viewer-corba.
-// gepetto-viewer-corba 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
-// 3 of the License, or (at your option) any later version.
-//
-// gepetto-viewer-corba 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
-// General Lesser Public License for more details. You should have
-// received a copy of the GNU Lesser General Public License along with
-// gepetto-viewer-corba. If not, see <http://www.gnu.org/licenses/>.
-
-#ifndef __se3_se3_hpp__
-#define __se3_se3_hpp__
-#include <Eigen/Geometry>
-
-namespace se3
-{
-/* Type returned by the "se3Action" and "se3ActionInverse" functions. */
-namespace internal
-{
-template<typename D>
-struct ActionReturn { typedef D Type; };
-}
-/** The rigid transform aMb can be seen in two ways:
-*
-* - given a point p expressed in frame B by its coordinate vector Bp, aMb
-* computes its coordinates in frame A by Ap = aMb Bp.
-* - aMb displaces a solid S centered at frame A into the solid centered in
-* B. In particular, the origin of A is displaced at the origin of B: $^aM_b
-* ^aA = ^aB$.
-* The rigid displacement is stored as a rotation matrix and translation vector by:
-* aMb (x) = aRb*x + aAB
-* where aAB is the vector from origin A to origin B expressed in coordinates A.
-*/
-template<typename _Scalar, int _Options>
-class SE3Tpl
-{
-public:
-typedef _Scalar Scalar;
-enum { Options = _Options };
-typedef Eigen::Matrix<Scalar,3,1,Options> Vector3;
-typedef Eigen::Matrix<Scalar,4,1,Options> Vector4;
-typedef Eigen::Matrix<Scalar,3,3,Options> Matrix3;
-typedef Eigen::Matrix<Scalar,6,1,Options> Vector6;
-typedef Eigen::Matrix<Scalar,4,4,Options> Matrix4;
-typedef Eigen::Matrix<Scalar,6,6,Options> Matrix6;
-typedef Eigen::Quaternion<Scalar,Options> Quaternion;
-//typedef MotionTpl<Scalar,Options> Motion;
-//typedef ForceTpl<Scalar,Options> Force;
-//typedef ActionTpl<Scalar,Options> Action;
-enum { LINEAR = 0, ANGULAR = 3 };
-public:
-// Constructors
-SE3Tpl() : rot(), trans() {}
-template<typename M3,typename v3>
-SE3Tpl(const Eigen::MatrixBase<M3> & R, const Eigen::MatrixBase<v3> & p)
-: rot(R), trans(p) {}
-SE3Tpl(int) : rot(Matrix3::Identity()), trans(Vector3::Zero()) {}
-template<typename S2, int O2>
-SE3Tpl( const SE3Tpl<S2,O2> clone )
-: rot(clone.rotation()),trans(clone.translation()) {}
-template<typename S2, int O2>
-SE3Tpl & operator= (const SE3Tpl<S2,O2> & other)
-{
-rot = other.rotation ();
-trans = other.translation ();
-return *this;
-}
-const Matrix3 & rotation() const { return rot; }
-const Vector3 & translation() const { return trans; }
-Matrix3 & rotation() { return rot; }
-Vector3 & translation() { return trans; }
-void rotation(const Matrix3 & R) { rot=R; }
-void translation(const Vector3 & p) { trans=p; }
-static SE3Tpl Identity()
-{
-return SE3Tpl(1);
-}
-static SE3Tpl Random()
-{
-Eigen::Quaternion<Scalar,Options> q(Vector4::Random());
-q.normalize();
-return SE3Tpl(q.matrix(),Vector3::Random());
-}
-Eigen::Matrix<Scalar,4,4,Options> toHomogeneousMatrix() const
-{
-Eigen::Matrix<Scalar,4,4,Options> M;
-M.template block<3,3>(0,0) = rot;
-M.template block<3,1>(0,3) = trans;
-M.template block<1,3>(3,0).setZero();
-M(3,3) = 1;
-return M;
-}
-/// Vb.toVector() = bXa.toMatrix() * Va.toVector()
-Matrix6 toActionMatrix() const
-{
-Matrix6 M;
-M.template block<3,3>(ANGULAR,ANGULAR)
-= M.template block<3,3>(LINEAR,LINEAR) = rot;
-M.template block<3,3>(ANGULAR,LINEAR).setZero();
-M.template block<3,3>(LINEAR,ANGULAR)
-= skew(trans) * M.template block<3,3>(ANGULAR,ANGULAR);
-return M;
-}
-/// aXb = bXa.inverse()
-SE3Tpl inverse() const
-{
-return SE3Tpl(rot.transpose(), -rot.transpose()*trans);
-}
-void disp(std::ostream & os) const
-{
-os << " R =\n" << rot << std::endl
-<< " p =\n" << trans.transpose() << std::endl;
-}
-/* --- GROUP ACTIONS ON M6, F6 and I6 --- */
-/// ay = aXb.act(by)
-template<typename D> typename internal::ActionReturn<D>::Type act (const D & d) const
-{ return d.se3Action(*this); }
-/// by = aXb.actInv(ay)
-template<typename D> typename internal::ActionReturn<D>::Type actInv(const D & d) const
-{ return d.se3ActionInverse(*this); }
-Vector3 act (const Vector3& p) const { return (rot*p+trans).eval(); }
-Vector3 actInv(const Vector3& p) const { return (rot.transpose()*(p-trans)).eval(); }
-SE3Tpl act (const SE3Tpl& m2) const { return SE3Tpl( rot*m2.rot,trans+rot*m2.trans);}
-SE3Tpl actInv (const SE3Tpl& m2) const { return SE3Tpl( rot.transpose()*m2.rot,
-rot.transpose()*(m2.trans-trans));}
-/* --- OPERATORS -------------------------------------------------------- */
-operator Matrix4() const { return toHomogeneousMatrix(); }
-operator Matrix6() const { return toActionMatrix(); }
-SE3Tpl operator*(const SE3Tpl & m2) const { return this->act(m2); }
-friend std::ostream & operator << (std::ostream & os,const SE3Tpl & X)
-{ X.disp(os); return os; }
-public:
-private:
-Matrix3 rot;
-Vector3 trans;
-};
-typedef SE3Tpl<float,0> SE3;
-} // namespace se3
-#endif // ifndef __se3_se3_hpp__
-
diff --git a/include/gepetto/viewer/corba/server.hh b/include/gepetto/viewer/corba/server.hh
index faec5e4f6f74cf9c75de256f976b7cdda0913240..c82ca7d24963b1682f82fb4b9ac402a4941da79c 100644
--- a/include/gepetto/viewer/corba/server.hh
+++ b/include/gepetto/viewer/corba/server.hh
@@ -12,14 +12,14 @@
 # define SCENEVIEWER_CORBASERVER_SERVER_HH
 
 #include "gepetto/viewer/corba/fwd.hh"
-#include <gepetto/viewer/corba/windows-manager.hh>
+#include <gepetto/gui/windows-manager.hh>
 
 namespace graphics
 {
   namespace corbaServer
   {
-    using graphics::WindowsManager;
-    using graphics::WindowsManagerPtr_t;
+    using gepetto::gui::WindowsManager;
+    using gepetto::gui::WindowsManagerPtr_t;
 
     /// Implementation of Hpp module Corba server.
 
diff --git a/include/gepetto/viewer/corba/windows-manager.hh b/include/gepetto/viewer/corba/windows-manager.hh
deleted file mode 100644
index 09fb091f5cd2228b899c69e31fc0c8c85a42d755..0000000000000000000000000000000000000000
--- a/include/gepetto/viewer/corba/windows-manager.hh
+++ /dev/null
@@ -1,286 +0,0 @@
-// Copyright (c) 2014, LAAS-CNRS
-// Authors: Joseph Mirabel (joseph.mirabel@laas.fr)
-//
-// This file is part of gepetto-viewer.
-// gepetto-viewer 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
-// 3 of the License, or (at your option) any later version.
-//
-// gepetto-viewer 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
-// General Lesser Public License for more details.  You should have
-// received a copy of the GNU Lesser General Public License along with
-// gepetto-viewer. If not, see <http://www.gnu.org/licenses/>.
-
-#ifndef SCENEVIEWER_WINDOWMANAGERS_HH
-#define SCENEVIEWER_WINDOWMANAGERS_HH
-
-#include <gepetto/viewer/window-manager.h>
-#include <gepetto/viewer/roadmap-viewer.h>
-#include <gepetto/viewer/transform-writer.h>
-#include "gepetto/viewer/corba/graphical-interface.hh"
-#include <boost/thread/mutex.hpp>
-
-namespace graphics {
-
-    struct Configuration {
-        osgVector3 position;
-        osgQuat quat;
-        Configuration() {}
-        /// \param XYZW when false, the 4 last parameters are a quaternion (w,x,y,z)
-        ///             otherwise, a quaternion (x,y,z,w)
-        explicit Configuration(const float* a, bool XYZW)
-          : position(a[0],a[1],a[2])
-          , quat(a[(XYZW ? 3 : 4)],
-                 a[(XYZW ? 4 : 5)],
-                 a[(XYZW ? 5 : 6)],
-                 a[(XYZW ? 6 : 3)]) {}
-        Configuration(const osgVector3& p, const osgQuat& q) : position(p), quat(q) {}
-    };
-    struct NodeConfiguration : Configuration {
-        NodePtr_t node;
-    };
-
-    struct BlenderFrameCapture {
-      typedef std::vector<NodePtr_t> Nodes_t;
-      osg::ref_ptr < TransformWriterVisitor > writer_visitor_;
-      Nodes_t nodes_;
-      BlenderFrameCapture ()
-        : writer_visitor_ (new TransformWriterVisitor (
-              new YamlTransformWriter ("gepetto_viewer.yaml")))
-        , nodes_ ()
-      {}
-      void captureFrame () {
-        using std::invalid_argument;
-        if (!writer_visitor_)
-          throw invalid_argument ("Capture writer not defined");
-        if (nodes_.empty()) throw invalid_argument ("No node to capture");
-        writer_visitor_->captureFrame (nodes_.begin(), nodes_.end());
-      }
-    };
-
-    DEF_CLASS_SMART_PTR(WindowsManager)
-
-    class WindowsManager
-    {
-        public:
-            // Typedef for position and color values.
-            typedef osg::Vec3f::value_type value_type;
-            typedef osgVector4 Color_t;
-            typedef ::osg::Vec3ArrayRefPtr Vec3ArrayPtr_t;
-            typedef unsigned int WindowID;
-
-            typedef std::map <std::string, WindowID> WindowIDMap_t;
-            WindowIDMap_t windowIDmap_;
-
-        private:
-            typedef std::vector <WindowManagerPtr_t> WindowManagerVector_t;
-            typedef std::vector<NodeConfiguration> NodeConfigurations_t;
-            WindowManagerVector_t windowManagers_;
-            std::map<std::string, NodePtr_t> nodes_;
-            std::map<std::string, GroupNodePtr_t> groupNodes_;
-            std::map<std::string, RoadmapViewerPtr_t> roadmapNodes_;
-            boost::mutex osgFrameMtx_, configListMtx_;
-            int rate_;
-            NodeConfigurations_t newNodeConfigurations_;
-            BlenderFrameCapture blenderCapture_;
-            bool autoCaptureTransform_;
-
-            static osgVector4 getColor(const std::string& colorName);
-            static std::string parentName(const std::string& name);
-            static VisibilityMode getVisibility(const std::string& visibilityName);
-            static WireFrameMode getWire(const std::string& wireName);
-            static LightingMode getLight(const std::string& lightName);
-            NodePtr_t find (const std::string name, GroupNodePtr_t group = GroupNodePtr_t());
-            void initParent(NodePtr_t node, GroupNodePtr_t parent);
-            void threadRefreshing(WindowManagerPtr_t window);
-            bool loadUDRF(const std::string& urdfName, const std::string& urdfPath,
-                bool visual, bool linkFrame);
-
-        protected:
-            /**
-              \brief Default constructor
-              */
-            WindowsManager ();
-            WindowID addWindow (std::string winName, WindowManagerPtr_t newWindow);
-
-            template <typename NodeContainer_t>
-              std::size_t getNodes
-              (const gepetto::corbaserver::Names_t& name, NodeContainer_t& nodes);
-            template <typename Iterator, typename NodeContainer_t> 
-              std::size_t getNodes
-              (const Iterator& begin, const Iterator& end, NodeContainer_t& nodes);
-
-            /// Warning, the mutex should be locked before and unlocked after this opertations.
-            void addNode (const std::string& nodeName, NodePtr_t node, bool guessParent = false);
-            virtual void addNode (const std::string& nodeName, NodePtr_t node, GroupNodePtr_t parent);
-            void addGroup(const std::string& groupName, GroupNodePtr_t group, bool guessParent = false);
-            virtual void addGroup(const std::string& groupName, GroupNodePtr_t group, GroupNodePtr_t parent);
-
-        public:
-            static WindowsManagerPtr_t create ();
-
-            virtual ~WindowsManager () {};
-
-            virtual std::vector<std::string> getNodeList();
-            virtual std::vector<std::string> getGroupNodeList(const std::string& group);
-            virtual std::vector<std::string> getSceneList();
-            virtual std::vector<std::string> getWindowList();
-
-            /// Return the mutex to be locked before refreshing
-            boost::mutex& osgFrameMutex () {
-              return osgFrameMtx_;
-            }
-
-            virtual bool setRate(const int& rate);
-            virtual void refresh();
-
-            virtual WindowID createWindow(const std::string& windowName);
-            virtual WindowID getWindowID (const std::string& windowName);
-
-            virtual void createScene(const std::string& sceneName);
-            virtual void createSceneWithFloor(const std::string& sceneName);
-            virtual bool addSceneToWindow(const std::string& sceneName, const WindowID windowId);
-
-            virtual bool attachCameraToNode(const std::string& nodeName, const WindowID windowId);
-            virtual bool detachCamera(const WindowID windowId);
-
-            virtual bool nodeExists (const std::string& name);
-
-            virtual bool addFloor(const std::string& floorName);
-
-            virtual bool addBox(const std::string& boxName, const float& boxSize1, const float& boxSize2, const float& boxSize3, const Color_t& color);
-
-            virtual bool addCapsule(const std::string& capsuleName, float radius, float height, const Color_t& color);
-
-            virtual  bool addArrow (const std::string& arrowName,const float radius, const float length,  const Color_t& color);
-
-            virtual bool addRod (const std::string& rodName, const Color_t& color,const float radius,const float length, short maxCapsule);
-
-            virtual bool resizeCapsule(const std::string& capsuleName, float newHeight) throw (std::exception);
-            virtual bool resizeArrow(const std::string& arrowName ,float newRadius, float newLength) throw(std::exception);
-
-            virtual bool addMesh(const std::string& meshName, const std::string& meshPath);
-
-            virtual bool addCone(const std::string& coneName, float radius, float height, const Color_t& color);
-
-            virtual bool addCylinder(const std::string& cylinderName, float radius, float height, const Color_t& color);
-
-            virtual bool addSphere(const std::string& sphereName, float radius, const Color_t& color);
-
-            virtual bool addLight(const std::string& lightName, const WindowID wid, float radius, const Color_t& color);
-
-            virtual bool addLine(const std::string& lineName, const osgVector3& pos1, const osgVector3& pos2, const Color_t& color);
-            virtual bool setLineStartPoint(const std::string& lineName, const osgVector3& pos1);
-            virtual bool setLineEndPoint(const std::string& lineName, const osgVector3& pos2);
-            virtual bool setLineExtremalPoints(const std::string& lineName, const osgVector3& pos1, const osgVector3& pos2);
-
-            virtual bool addCurve(const std::string& curveName, const Vec3ArrayPtr_t& pos, const Color_t& color);
-      
-            virtual bool setCurvePoints(const std::string& curveName, const Vec3ArrayPtr_t& pos);
-
-            /// \param mode See LeafNodeLine::setMode for possible values
-            virtual bool setCurveMode (const std::string& curveName, const GLenum mode);
-            virtual bool setCurvePointsSubset (const std::string& curveName, const int first, const std::size_t count);
-            virtual bool setCurveLineWidth (const std::string& curveName, const float& width);
-
-            virtual bool addSquareFace(const std::string& faceName, const osgVector3& pos1, const osgVector3& pos2, const osgVector3& pos3, const osgVector3& pos4, const Color_t& color);
-            virtual bool setTexture (const std::string& nodeName, const std::string& filename);
-            virtual bool addTriangleFace(const std::string& faceName, const osgVector3& pos1, const osgVector3& pos2, const osgVector3& pos3, const Color_t& color);
-            virtual bool addXYZaxis (const std::string& nodeName, const Color_t& color, float radius, float sizeAxis);
-
-            virtual bool createRoadmap(const std::string& name,const Color_t& colorNode, float radius, float sizeAxis, const Color_t& colorEdge);
-
-            virtual bool addEdgeToRoadmap(const std::string& nameRoadmap, const osgVector3& posFrom, const osgVector3& posTo);
-
-            virtual bool addNodeToRoadmap(const std::string& nameRoadmap, const Configuration& configuration);
-
-            virtual bool addURDF(const std::string& urdfName, const std::string& urdfPath);
-            /// \deprecated Argument urdfPackagePathCorba is ignored.
-            virtual bool addURDF(const std::string& urdfName, const std::string& urdfPath, const std::string& urdfPackagePath);
-
-            virtual bool addUrdfCollision (const std::string& urdfName,
-                    const std::string& urdfPath) ;
-            /// \deprecated Argument urdfPackagePathCorba is ignored.
-            virtual bool addUrdfCollision (const std::string& urdfName,
-                    const std::string& urdfPath,
-                    const std::string& urdfPackagePath) ;
-
-            virtual void addUrdfObjects (const std::string& urdfName,
-                    const std::string& urdfPath,
-                    bool visual) ;
-            /// \deprecated Argument urdfPackagePathCorba is ignored.
-            virtual void addUrdfObjects (const std::string& urdfName,
-                    const std::string& urdfPath,
-                    const std::string& urdfPackagePath,
-                    bool visual) ;
-
-            virtual bool createGroup(const std::string& groupName);
-            virtual bool addToGroup(const std::string& nodeName, const std::string& groupName);
-            virtual bool removeFromGroup (const std::string& nodeName, const std::string& groupName);
-            virtual bool deleteNode (const std::string& nodeName, bool all);
-
-            virtual bool applyConfiguration(const std::string& nodeName, const Configuration& configuration);
-            virtual bool applyConfigurations(const std::vector<std::string>& nodeName, const std::vector<Configuration>& configuration);
-
-            virtual bool addLandmark(const std::string& nodeName, float size);
-            virtual bool deleteLandmark(const std::string& nodeName);
-
-            virtual Configuration getStaticTransform (const std::string& nodeName) const;
-            virtual bool setStaticTransform (const std::string& nodeName, const Configuration& transform);
-
-            virtual bool setVisibility(const std::string& nodeName, const std::string& visibilityMode);
-            virtual bool setScale(const std::string& nodeName, const osgVector3& scale);
-            virtual bool setScale(const std::string& nodeName, const float& scale);
-            virtual bool setScale(const std::string& nodeName, const int& scalePercentage);
-            virtual bool setColor(const std::string& nodeName, const Color_t& color);
-            virtual bool setWireFrameMode(const std::string& nodeName, const std::string& wireFrameMode);
-            virtual bool setLightingMode(const std::string& nodeName, const std::string& lightingMode);
-            virtual bool setHighlight(const std::string& nodeName, int state);
-            virtual bool setAlpha(const std::string& nodeName, const float& alpha);
-            virtual bool setAlpha(const std::string& nodeName, const int& alphaPercentage);
-
-            virtual void captureFrame (const WindowID windowId, const std::string& filename);
-            virtual bool startCapture (const WindowID windowId, const std::string& filename,
-                    const std::string& extension);
-            virtual bool stopCapture (const WindowID windowId);
-            virtual bool setCaptureTransform (const std::string& filename, const std::vector<std::string>& nodename);
-            virtual void captureTransformOnRefresh (bool autoCapture);
-            virtual void captureTransform ();
-            virtual bool writeBlenderScript (const std::string& filename, const std::vector<std::string>& nodename);
-            virtual bool writeNodeFile (const std::string& nodename, const std::string& filename);
-            virtual bool writeWindowFile (const WindowID windowId, const std::string& filename);
-            virtual bool setBackgroundColor1(const WindowID windowId,const Color_t& color);
-            virtual bool setBackgroundColor2(const WindowID windowId,const Color_t& color);
-            virtual Configuration getCameraTransform(const WindowID windowId);
-            virtual bool setCameraTransform(const WindowID windowId, const Configuration &configuration);
-
-            virtual std::vector<std::string> getPropertyNames(const std::string& nodeName) const;
-            virtual std::vector<std::string> getPropertyTypes(const std::string& nodeName) const;
-
-            template <typename Property_t> Property_t getProperty (const std::string& nodeName, const std::string& propName) const;
-            template <typename Property_t> void setProperty (const std::string& nodeName, const std::string& propName, const Property_t& value) const;
-
-            virtual std::string getStringProperty(const std::string& nodeName, const std::string& propName) const;
-            virtual void setStringProperty(const std::string& nodeName, const std::string& propName, const std::string& value) const;
-            virtual osgVector3 getVector3Property(const std::string& nodeName, const std::string& propName) const;
-            virtual void setVector3Property(const std::string& nodeName, const std::string& propName, const osgVector3& value) const;
-            virtual osgVector4 getColorProperty(const std::string& nodeName, const std::string& propName) const;
-            virtual void setColorProperty(const std::string& nodeName, const std::string& propName, const osgVector4& value) const;
-            virtual float getFloatProperty(const std::string& nodeName, const std::string& propName) const;
-            virtual void setFloatProperty(const std::string& nodeName, const std::string& propName, const float& value) const;
-            virtual bool getBoolProperty(const std::string& nodeName, const std::string& propName) const;
-            virtual void setBoolProperty(const std::string& nodeName, const std::string& propName, const bool& value) const;
-            virtual int getIntProperty(const std::string& nodeName, const std::string& propName) const;
-            virtual void setIntProperty(const std::string& nodeName, const std::string& propName, const int& value) const;
-
-            WindowManagerPtr_t getWindowManager (const WindowID wid, bool throwIfDoesntExist = false) const;
-            GroupNodePtr_t getGroup (const std::string groupName, bool throwIfDoesntExist = false) const;
-            NodePtr_t getNode (const std::string& nodeName, bool throwIfDoesntExist = false) const;
-            Configuration getNodeGlobalTransform(const std::string nodeName) const;
-    };
-} /* namespace graphics */
-
-#endif /* SCENEVIEWER_WINDOWMANAGERS_HH */
diff --git a/plugins/pyqcustomplot/CMakeLists.txt b/plugins/pyqcustomplot/CMakeLists.txt
index a751a24b5d3891b12cb6b5795133f7619f8912fc..2238f6192df0f81dca83046d89ad1e4a5683495a 100644
--- a/plugins/pyqcustomplot/CMakeLists.txt
+++ b/plugins/pyqcustomplot/CMakeLists.txt
@@ -22,7 +22,7 @@ ELSE()
   SET(QT4 "")
 ENDIF()
 
-INCLUDE_DIRECTORIES("${PYTHON_INCLUDE_DIR}" "${PYTHONQT_INCLUDE_DIR}")
+INCLUDE_DIRECTORIES(SYSTEM "${PYTHON_INCLUDE_DIR}" "${PYTHONQT_INCLUDE_DIR}")
 ADD_DEFINITIONS(-DQCUSTOMPLOT_COMPILE_LIBRARY)
 
 GEPETTO_GUI_PLUGIN(pyqcustomplot
@@ -47,3 +47,7 @@ GEPETTO_GUI_PLUGIN(pyqcustomplot
   PKG_CONFIG_DEPENDENCIES
   omniORB4
   )
+
+SET_SOURCE_FILES_PROPERTIES(qcustomplot.cpp
+  PROPERTIES
+  COMPILE_FLAGS "-Wno-conversion")
diff --git a/plugins/pyqgv/CMakeLists.txt b/plugins/pyqgv/CMakeLists.txt
index 50d1a6391a5ddc08bbab0ba96be8723e5da98c2a..dc3aae7786f6b00872c970144ebe476aba733465 100644
--- a/plugins/pyqgv/CMakeLists.txt
+++ b/plugins/pyqgv/CMakeLists.txt
@@ -22,7 +22,7 @@ ELSE()
   SET(QT4 "")
 ENDIF()
 
-INCLUDE_DIRECTORIES("${PYTHON_INCLUDE_DIR}" "${PYTHONQT_INCLUDE_DIR}")
+INCLUDE_DIRECTORIES(SYSTEM "${PYTHON_INCLUDE_DIR}" "${PYTHONQT_INCLUDE_DIR}")
 
 GEPETTO_GUI_PLUGIN(pyqgv
   INSIDE_GEPETTO_VIEWER_CORBA
diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt
index fa2f47f58a566e5852619a8f16e58b50915fd5d8..f808b2bf4f0643a45372aefde2377895494d1dd1 100644
--- a/src/CMakeLists.txt
+++ b/src/CMakeLists.txt
@@ -56,7 +56,6 @@ IF(NOT CLIENT_ONLY)
     SHARED
     graphical-interface.impl.cpp
     graphical-interface.impl.hh
-    windows-manager.cpp
     server.cc
     client.cc
     server-private.cc
@@ -64,6 +63,11 @@ IF(NOT CLIENT_ONLY)
     ${CMAKE_CURRENT_BINARY_DIR}/gepetto/viewer/corba/graphical-interface.hh
     ${CMAKE_CURRENT_BINARY_DIR}/gepetto/viewer/corba/graphical-interfaceSK.cc
   )
+  # Removes 5 warnings about anonymous variadic macros that were added from
+  # c++ 11.
+  SET_SOURCE_FILES_PROPERTIES(graphical-interface.impl.cpp
+    PROPERTIES
+    COMPILE_FLAGS "-Wno-variadic-macros")
 
   ADD_DEPENDENCIES (${LIBRARY_NAME} generate_idl_cpp)
   ADD_DEPENDENCIES (${LIBRARY_NAME} generate_idl_python)
diff --git a/src/client-cpp.cc b/src/client-cpp.cc
deleted file mode 100644
index 721c8232ab32c7872c82681d9f734790a16692a6..0000000000000000000000000000000000000000
--- a/src/client-cpp.cc
+++ /dev/null
@@ -1,230 +0,0 @@
-//
-//  client-cpp.cc
-//  C++ CORBA client interface for SceneViewer.
-//
-//  Created by Mathieu Geisert in December 2014.
-//  Copyright (c) 2014 LAAS-CNRS. All rights reserved.
-//
-
-#include <gepetto/viewer/corba/client.hh>
-
-namespace graphics { 
-namespace corbaServer {
-
-void ClientCpp::se3ToCorba(CORBA::Float* corbaPosition, const se3::SE3& se3position)
-{
-    Eigen::Quaternion<value_type> q(se3position.rotation());
-    corbaPosition[0] = se3position.translation()(0);
-    corbaPosition[1] = se3position.translation()(1);
-    corbaPosition[2] = se3position.translation()(2);    
-    corbaPosition[3] = q.w();
-    corbaPosition[4] = q.x();
-    corbaPosition[5] = q.y();
-    corbaPosition[6] = q.z();        
-}
-
-ClientCpp::ClientCpp()
-{
-    int    argc=0;       // Dummy variables to support following call.
-    char** argv=0;
-    orb_ = CORBA::ORB_init(argc, argv);
-
-    // Get a reference to the Naming Service
-    CORBA::Object_var rootContextObj = 
-        orb_->resolve_initial_references("NameService");
-    CosNaming::NamingContext_var nc =
-	CosNaming::NamingContext::_narrow(rootContextObj.in());
-
-    CosNaming::Name name;
-    name.length(2);
-    name[0].id = (const char *) "gepetto";
-    name[0].kind = (const char *) "viewer";
-    name[1].id = (const char *) "corbaserver";
-    name[1].kind = (const char *) "gui";
-    // Invoke the root context to retrieve the object reference
-    CORBA::Object_var managerObj = nc->resolve(name);
-    // Narrow the previous object to obtain the correct type
-    manager_ =
-      gepetto::corbaserver::GraphicalInterface::_narrow(managerObj.in());
-}
-
-ClientCpp::~ClientCpp()
-{
-    //manager_->shutdown();
-    if (!CORBA::is_nil(orb_)) {
-	try {
-	    orb_->destroy();
-	    std::cout << "Ending CORBA..." << std::endl;
-	} catch(const CORBA::Exception& e) {
-	    std::cout << "orb->destroy failed" << std::endl;
-	}
-    }
-}
-
-void ClientCpp::getNodeList()
-{
-   manager_->getNodeList();
-}
-
-
-void ClientCpp::getWindowList()
-{
-   manager_->getWindowList();
-}
-
-bool ClientCpp::setRate(int  rate)
-{
-   return manager_->setRate(rate);
-}
-
-void ClientCpp::refresh()
-{
-    manager_->refresh();
-}
-
-ClientCpp::WindowID ClientCpp::createWindow(const char* windowName)
-{
-    return manager_->createWindow(windowName);
-}
-
-
-    //void ClientCpp::createWindow(const char* name, CORBA::ULong x, CORBA::ULong y, CORBA::ULong width, CORBA::ULong height) ;
-
-void ClientCpp::createScene(const char* sceneName)
-{
-  manager_->createScene(sceneName);
-}
-
-void ClientCpp::createSceneWithFloor(const char* sceneName)
-{
-  manager_->createSceneWithFloor(sceneName);
-}
-
-bool ClientCpp::addSceneToWindow(const char* sceneName, const ClientCpp::WindowID windowId)
-{
-   return  manager_->addSceneToWindow(sceneName, windowId);
-}
-
-/*bool ClientCpp::addBox(const char* boxName, float boxSize1, float boxSize2, float boxSize3)
-{
-    return manager_->addBox(boxName, boxSize1, boxSize2, boxSize3);
-}*/
-
-bool ClientCpp::addBox(const char* boxName, const float boxSize1, const float boxSize2, const float boxSize3, const value_type* color)
-{
-    return manager_->addBox(boxName, boxSize1, boxSize2, boxSize3, color);
-}
-
-/*bool ClientCpp::addCapsule(const char* capsuleName, float radius, float height)
-{
-    return manager_->addCapsule(capsuleName, radius, height);
-}*/
-
-bool ClientCpp::addCapsule(const char* capsuleName, const float radius, const float height, const value_type* color)
-{
-    return manager_->addCapsule(capsuleName, radius, height, color);
-}
-
-bool ClientCpp::addMesh(const char* meshName, const char* meshPath)
-{
-    return manager_->addMesh(meshName, meshPath);
-}
-
-/*bool ClientCpp::addCone(const char* coneName, float radius, float height)
-{
-    return manager_->addCone(coneName, radius, height);
-}*/
-
-bool ClientCpp::addCone(const char* coneName, const float radius, const float height, const value_type* color)
-{
-    return manager_->addCone(coneName, radius, height, color);
-}
-
-/*bool ClientCpp::addCylinder(const char* cylinderName, float radius, float height)
-{
-    return manager_->addCylinder(cylinderName, radius, height);
-}*/
-
-bool ClientCpp::addCylinder(const char* cylinderName, const float radius, const float height, const value_type* color)
-{
-    return manager_->addCylinder(cylinderName, radius, height, color);
-}
-
-/*bool ClientCpp::addSphere(const char* sphereName, float radius)
-{
-    return manager_->addSphere(sphereName, radius);
-}*/
-
-bool ClientCpp::addSphere(const char* sphereName, const float radius, const value_type* color)
-{
-    return manager_->addSphere(sphereName, radius, color);
-}
-
-bool ClientCpp::addLine(const char* lineName, const value_type* pos1, const value_type* pos2, const value_type* color)
-{
-    return manager_->addLine(lineName, pos1, pos2, color);
-}
-
-bool ClientCpp::addTriangleFace(const char* faceName, const value_type* pos1, const value_type* pos2, const value_type* pos3, const value_type* color)
-{
-    return manager_->addTriangleFace(faceName, pos1, pos2, pos3, color);
-}
-
-bool ClientCpp::addSquareFace(const char* faceName, const value_type* pos1, const value_type* pos2, const value_type* pos3, const value_type* pos4, const value_type* color)
-{
-    return manager_->addSquareFace(faceName, pos1, pos2, pos3, pos4, color);
-}
-
-bool ClientCpp::addURDF(const char* urdfName, const char* urdfPath, const char* urdfPackagePath)
-{
-    return manager_->addURDF(urdfName, urdfPath, urdfPackagePath);
-}
-
-bool ClientCpp::createGroup(const char* groupName)
-{
-    return manager_->createGroup(groupName);
-}
-
-bool ClientCpp::addToGroup(const char* nodeName, const char* groupName)
-{
-    return manager_->addToGroup(nodeName, groupName);
-}
-
-bool ClientCpp::applyConfiguration(const char* nodeName, const se3::SE3& se3position)
-{
-    CORBA::Float corbaPosition[7];
-    ClientCpp::se3ToCorba(corbaPosition, se3position);
-    return manager_->applyConfiguration(nodeName, corbaPosition);
-}
-
-bool ClientCpp::setVisibility(const char* nodeName, const char* visibilityMode)
-{
-    return manager_->setVisibility(nodeName, visibilityMode);
-}
-
-bool ClientCpp::setWireFrameMode(const char* nodeName, const char* wireFrameMode)
-{
-    return manager_->setWireFrameMode(nodeName, wireFrameMode);
-}
-bool ClientCpp::setLightingMode(const char* nodeName, const char* lightingMode)
-{
-    return manager_->setLightingMode(nodeName, lightingMode);
-}
-
-bool ClientCpp::startCapture (const WindowID windowId, const char* filename, const char* extension)
-{
-  return manager_->startCapture (windowId, filename, extension);
-}
-
-bool ClientCpp::stopCapture (const WindowID windowId)
-{
-  return manager_->stopCapture (windowId);
-}
-
-bool ClientCpp::writeNodeFile (const WindowID windowId, const char* filename)
-{
-  return manager_->writeWindowFile (windowId, filename);
-}
-
-} // end of namespace corbaserver
-} // end of namespace graphics
diff --git a/src/graphical-interface.impl.cpp b/src/graphical-interface.impl.cpp
index 4cfa29e163418f02bda716e88b232e449b97dfc4..4850aea3e3e9ce31796e655ab3171c7aeb62c6d7 100644
--- a/src/graphical-interface.impl.cpp
+++ b/src/graphical-interface.impl.cpp
@@ -25,7 +25,7 @@ namespace graphics {
 
         template <typename Input, typename Output>
           void to (const Input& in, Output& out, const int size) {
-            for (CORBA::ULong i = 0; i < size; ++i)
+            for (CORBA::ULong i = 0; i < (CORBA::ULong)size; ++i)
               out[i] = in[i];
           }
 
diff --git a/src/graphical-interface.impl.hh b/src/graphical-interface.impl.hh
index 76f94a6631f96b76fdd64a8e06293cb9023d0b82..7b6e6b518f1940b400fbe65b115a41fb977b51be 100644
--- a/src/graphical-interface.impl.hh
+++ b/src/graphical-interface.impl.hh
@@ -24,14 +24,14 @@ struct NodeConfiguration {
     osgQuat quat;
 };
 
-using graphics::WindowsManagerPtr_t;
+using gepetto::gui::WindowsManagerPtr_t;
 class GraphicalInterface :
     public virtual POA_gepetto::corbaserver::GraphicalInterface
 {
 private:
     WindowsManagerPtr_t windowsManager_;
     typedef gepetto::Error Error;
-    typedef graphics::WindowsManager::value_type value_type;
+    typedef gepetto::gui::WindowsManager::value_type value_type;
     typedef gepetto::corbaserver::Transform_slice Transform_slice;
 
 public:
diff --git a/src/gui/CMakeLists.txt b/src/gui/CMakeLists.txt
index 88e08c754aa41131878a404b726f70b0430547d8..b9b15ae2f69665f1efdee148924d1be422831d16 100644
--- a/src/gui/CMakeLists.txt
+++ b/src/gui/CMakeLists.txt
@@ -18,8 +18,6 @@
 # <http://www.gnu.org/licenses/>.
 
 # Configure the project
-INCLUDE_DIRECTORIES(${CMAKE_BINARY_DIR}/src)
-
 SET (${PROJECT_NAME}_SOURCES
   ${CMAKE_BINARY_DIR}/src/gui/main.cc
   settings.cc
@@ -43,7 +41,7 @@ SET (${PROJECT_NAME}_SOURCES
   )
 
 IF(GEPETTO_GUI_HAS_PYTHONQT)
-  INCLUDE_DIRECTORIES("${PYTHON_INCLUDE_DIR}" "${PYTHONQT_INCLUDE_DIR}")
+  INCLUDE_DIRECTORIES(SYSTEM "${PYTHON_INCLUDE_DIR}" "${PYTHONQT_INCLUDE_DIR}")
   SET (${PROJECT_NAME}_SOURCES
     ${${PROJECT_NAME}_SOURCES}
     pythonwidget.cc)
diff --git a/src/gui/bodytreewidget.cc b/src/gui/bodytreewidget.cc
index 785f4f18d27093fd677684ebb1d5e3ac968a9cc8..4358f3aec434d21ac076d989e344935c0cbf430a 100644
--- a/src/gui/bodytreewidget.cc
+++ b/src/gui/bodytreewidget.cc
@@ -20,12 +20,10 @@
 #include <gepetto/gui/mainwindow.hh>
 #include <gepetto/gui/windows-manager.hh>
 #include <gepetto/gui/osgwidget.hh>
-#include <gepetto/gui/meta.hh>
 #include <gepetto/gui/selection-event.hh>
 #include <gepetto/gui/node-action.hh>
 
 #include <QSignalMapper>
-#include <QColorDialog>
 #include <QHBoxLayout>
 #include <QApplication>
 
diff --git a/src/gui/main.cc.in b/src/gui/main.cc.in
index 2dd85cfc208ddef9b2721d1b2f131619238a9a84..5e9d589a0cf863d9f9db07d9b271c63a8e45c64a 100644
--- a/src/gui/main.cc.in
+++ b/src/gui/main.cc.in
@@ -24,7 +24,7 @@ Q_DECLARE_METATYPE(QItemSelection)
 void setupApplication ()
 {
   QCoreApplication::setOrganizationName("gepetto-gui");
-  QCoreApplication::setOrganizationDomain("https://github.com/humanoid-path-planner/gepetto-viewer-corba");
+  QCoreApplication::setOrganizationDomain("@PROJECT_URL@");
   QCoreApplication::setApplicationName("gepetto-gui");
   QCoreApplication::setApplicationVersion("@PROJECT_VERSION@");
   
diff --git a/src/gui/mainwindow.cc b/src/gui/mainwindow.cc
index 145248f9d5ff8941d8f5801ad9be6f5b0e05bf82..c2fe6f2b7645e9f2c2ccb9101e53266fd5327459 100644
--- a/src/gui/mainwindow.cc
+++ b/src/gui/mainwindow.cc
@@ -21,6 +21,8 @@
 #include <QScrollBar>
 #include <QMessageBox>
 
+#include <osg/Version>
+
 #include <gepetto/viewer/corba/server.hh>
 
 #include "gepetto/gui/windows-manager.hh"
@@ -34,7 +36,6 @@
 #include "gepetto/gui/action-search-bar.hh"
 #include "gepetto/gui/node-action.hh"
 
-#include <gepetto/gui/meta.hh>
 #include <gepetto/gui/config-dep.hh>
 
 #if GEPETTO_GUI_HAS_PYTHONQT
@@ -75,8 +76,6 @@ namespace gepetto {
       osg()->createScene("hpp-gui");
 
       // Setup the main OSG widget
-      connect (this, SIGNAL (createViewOnMainThread(std::string)), SLOT (createView(std::string)));
-
       connect (ui_->actionRefresh, SIGNAL (triggered()), SLOT (requestRefresh()));
 
       connect (&backgroundQueue_, SIGNAL (done(int)), this, SLOT (handleWorkerDone(int)));
@@ -226,23 +225,18 @@ namespace gepetto {
     OSGWidget *MainWindow::createView(const std::string& name)
     {
       if (thread() != QThread::currentThread()) {
-        delayedCreateView_.lock();
-        emit createViewOnMainThread(name);
-        delayedCreateView_.lock();
-        delayedCreateView_.unlock();
-        return osgWindows_.last();
-      } else {
-        OSGWidget* osgWidget = new OSGWidget (osgViewerManagers_, name, this, 0
+        qDebug() << "createView must be called from the main thread.";
+        throw std::runtime_error("Cannot create a new window.");
+      }
+      OSGWidget* osgWidget = new OSGWidget (osgViewerManagers_, name, this, 0
 #if (QT_VERSION >= QT_VERSION_CHECK(5,0,0))
-            , osgViewer::Viewer::SingleThreaded
+          , osgViewer::Viewer::SingleThreaded
 #endif
-            );
-        osgWidget->setObjectName(name.c_str());
-        addOSGWidget (osgWidget);
-        emit viewCreated(osgWidget);
-        delayedCreateView_.unlock();
-        return osgWidget;
-      }
+          );
+      osgWidget->setObjectName(name.c_str());
+      addOSGWidget (osgWidget);
+      emit viewCreated(osgWidget);
+      return osgWidget;
     }
 
     void MainWindow::requestRefresh()
@@ -364,10 +358,20 @@ namespace gepetto {
       }
     }
 
+#define _to_str_(a) #a
+#define _to_str(a) _to_str_(a)
+#define _osg_version_str _to_str(OPENSCENEGRAPH_MAJOR_VERSION)"."_to_str(OPENSCENEGRAPH_MINOR_VERSION)"."_to_str(OPENSCENEGRAPH_PATCH_VERSION)
+
     void MainWindow::about()
     {
       QString devString;
       devString = trUtf8("<p>Version %1. For more information visit <a href=\"%2\">%2</a></p>"
+          "<p><ul>"
+          "<li>Compiled with Qt %4, run with Qt %5</li>"
+          "<li>Compiled with OpenSceneGraph version " _osg_version_str "</li>, run with version %6"
+          "<li></li>"
+          "<li></li>"
+          "</ul></p>"
           "<p><small>Copyright (c) 2015-2016 CNRS<br/>By Joseph Mirabel and others.</small></p>"
           "<p><small>"
           "%3 is free software: you can redistribute it and/or modify it under the "
@@ -384,11 +388,18 @@ namespace gepetto {
           )
         .arg(QApplication::applicationVersion())
         .arg(QApplication::organizationDomain())
-        .arg(QApplication::applicationName());
+        .arg(QApplication::applicationName())
+        .arg(QT_VERSION_STR)
+        .arg(qVersion())
+        .arg(osgGetVersion())
+        ;
 
       QMessageBox::about(this, QApplication::applicationName(), devString);
     }
 
+#undef _to_str
+#undef _osg_version_str
+
     void MainWindow::activateCollision(bool activate)
     {
       if (activate) {
diff --git a/src/gui/osgwidget.cc b/src/gui/osgwidget.cc
index 13c41312b3ebbfd376762171c4cc2ac2a8fb151e..5215f32af83b455953e73b62c30f028ab95515e8 100644
--- a/src/gui/osgwidget.cc
+++ b/src/gui/osgwidget.cc
@@ -116,7 +116,7 @@ namespace gepetto {
       viewer_->addEventHandler(new osgViewer::HelpHandler);
       viewer_->addEventHandler(pickHandler_);
 
-      wid_ = wm->createWindow (name, viewer_, graphicsWindow_.get());
+      wid_ = wm->createWindow (name, this, viewer_, graphicsWindow_.get());
       wm_ = wsm_->getWindowManager (wid_);
 
       viewer_->setThreadingModel(threadingModel);
@@ -151,9 +151,8 @@ namespace gepetto {
 
     void OSGWidget::paintEvent(QPaintEvent*)
     {
-      wsm_->osgFrameMutex().lock();
+      graphics::ScopedLock lock(wsm_->osgFrameMutex());
       viewer_->frame();
-      wsm_->osgFrameMutex().unlock();
     }
 
     graphics::WindowsManager::WindowID OSGWidget::windowID() const
@@ -220,6 +219,27 @@ namespace gepetto {
       }
     }
 
+    void OSGWidget::captureFrame (const std::string& filename)
+    {
+      graphics::ScopedLock lock(wsm_->osgFrameMutex());
+      wm_->captureFrame (filename);
+    }
+
+    bool OSGWidget::startCapture (const std::string& filename,
+        const std::string& extension)
+    {
+      graphics::ScopedLock lock(wsm_->osgFrameMutex());
+      wm_->startCapture (filename, extension);
+      return true;
+    }
+
+    bool OSGWidget::stopCapture ()
+    {
+      graphics::ScopedLock lock(wsm_->osgFrameMutex());
+      wm_->stopCapture ();
+      return true;
+    }
+
     void OSGWidget::readyReadProcessOutput()
     {
       pOutput_->append(process_->readAll());
diff --git a/src/gui/selection-event.cc b/src/gui/selection-event.cc
index 23c3ab69a528211549106434a4cf10efaf078b3a..130e4cca2084ad7eef68cc809944e9388436bb30 100644
--- a/src/gui/selection-event.cc
+++ b/src/gui/selection-event.cc
@@ -30,9 +30,9 @@ namespace gepetto {
         out.setZ(in[2]);
       }
       void toQVector3(const osg::Vec3d& in, QVector3D& out) {
-        out.setX(in[0]);
-        out.setY(in[1]);
-        out.setZ(in[2]);
+        out.setX((float)in[0]);
+        out.setY((float)in[1]);
+        out.setZ((float)in[2]);
       }
     }
 
diff --git a/src/gui/tree-item.cc b/src/gui/tree-item.cc
index 6ee5be5044f08b13531c73ac14e7f89192b604cf..18b683d1307524abde85a74ca693f1bf4b296746 100644
--- a/src/gui/tree-item.cc
+++ b/src/gui/tree-item.cc
@@ -28,6 +28,8 @@
 #include <gepetto/gui/bodytreewidget.hh>
 
 namespace gepetto {
+  using graphics::ScopedLock;
+
   namespace gui {
     QWidget* boolPropertyEditor (BodyTreeItem* bti, const graphics::PropertyPtr_t prop)
     {
@@ -177,7 +179,7 @@ namespace gepetto {
         QVariant nameVariant = sender->property("propertyName");
         if (nameVariant.isValid()) {
           std::string name = nameVariant.toString().toStdString();
-          boost::mutex::scoped_lock lock (MainWindow::instance()->osg()->osgFrameMutex());
+          ScopedLock lock (MainWindow::instance()->osg()->osgFrameMutex());
           node_->setProperty<T>(name, value);
         } else {
           qDebug() << "Sender has no property propertyName" << sender;
diff --git a/src/gui/windows-manager.cc b/src/gui/windows-manager.cc
index 83a2d91922730eb89c2306537a1876b80be69167..e60f1f3922acd9b4ffca878b6e3cec1d1dc08f61 100644
--- a/src/gui/windows-manager.cc
+++ b/src/gui/windows-manager.cc
@@ -38,15 +38,24 @@ namespace gepetto {
 
     WindowsManager::WindowID WindowsManager::createWindow(const std::string& windowName)
     {
-      return MainWindow::instance()->createView(windowName)->windowID();
+      MainWindow* main = MainWindow::instance();
+      OSGWidget* widget;
+      QMetaObject::invokeMethod (main, "createView",
+          Qt::BlockingQueuedConnection,
+          Q_RETURN_ARG (OSGWidget*, widget),
+          Q_ARG (std::string, windowName));
+      return widget->windowID();
     }
 
     WindowsManager::WindowID WindowsManager::createWindow(const std::string& windowName,
+                                                          gepetto::gui::OSGWidget* widget,
                                                           osgViewer::Viewer *viewer,
                                                           osg::GraphicsContext *gc)
     {
       graphics::WindowManagerPtr_t newWindow = graphics::WindowManager::create (viewer, gc);
       WindowID windowId = addWindow (windowName, newWindow);
+      assert (windowId == widgets_.size());
+      widgets_.push_back(widget);
       return windowId;
     }
 
@@ -100,7 +109,7 @@ namespace gepetto {
         bool isGroup = true;
         try {
             getGroup(nodeName, true);
-        } catch (const gepetto::Error& exc) {
+        } catch (const std::invalid_argument& exc) {
             isGroup = false;
         }
         assert(node);
@@ -169,7 +178,7 @@ namespace gepetto {
         } else {
           parent->takeRow(bti->row());
         }
-        delete bti;
+        bti->deleteLater();
         _nodes->second.first[i] = NULL;
       }
       nodeItemMap_.erase(_nodes);
@@ -186,5 +195,42 @@ namespace gepetto {
       }
       return false;
     }
+
+    void WindowsManager::captureFrame (const WindowID wid, const std::string& filename)
+    {
+      WindowManagerPtr_t wm = getWindowManager(wid, true);
+      OSGWidget* widget = widgets_[wid];
+      assert(widget->windowID()==wid);
+      QMetaObject::invokeMethod (widget, "captureFrame",
+            Qt::BlockingQueuedConnection,
+            Q_ARG (std::string, filename));
+    }
+
+    bool WindowsManager::startCapture (const WindowID wid, const std::string& filename,
+            const std::string& extension)
+    {
+      WindowManagerPtr_t wm = getWindowManager(wid, true);
+      OSGWidget* widget = widgets_[wid];
+      assert(widget->windowID()==wid);
+      bool res;
+      QMetaObject::invokeMethod (widget, "startCapture",
+          Qt::BlockingQueuedConnection,
+          Q_RETURN_ARG (bool, res),
+          Q_ARG (std::string, filename),
+          Q_ARG (std::string, extension));
+      return res;
+    }
+
+    bool WindowsManager::stopCapture (const WindowID wid)
+    {
+      WindowManagerPtr_t wm = getWindowManager(wid, true);
+      OSGWidget* widget = widgets_[wid];
+      assert(widget->windowID()==wid);
+      bool res;
+      QMetaObject::invokeMethod (widget, "stopCapture",
+          Qt::BlockingQueuedConnection,
+          Q_RETURN_ARG (bool, res));
+      return res;
+    }
   } // namespace gui
 } // namespace gepetto
diff --git a/src/test-client-cpp.cc b/src/test-client-cpp.cc
deleted file mode 100644
index 78ec8bf299e1cd8620d81a7628e9a4c04ab6bea2..0000000000000000000000000000000000000000
--- a/src/test-client-cpp.cc
+++ /dev/null
@@ -1,71 +0,0 @@
-//
-//  test-client-cpp.cc
-//  Test SceneViewer with C++ CORBA client interface.
-//
-//  Created by Mathieu Geisert in December 2014.
-//  Copyright (c) 2014 LAAS-CNRS. All rights reserved.
-//
-
-#include <gepetto/viewer/corba/client.hh>
-
-void se3ToCorba(CORBA::Float* corbaPosition, const se3::SE3& se3position)
-{
-    Eigen::Quaternion<float> q(se3position.rotation());
-    corbaPosition[0] = se3position.translation()(0);
-    corbaPosition[1] = se3position.translation()(1);
-    corbaPosition[2] = se3position.translation()(2);
-    corbaPosition[3] = q.w();
-    corbaPosition[4] = q.x();
-    corbaPosition[5] = q.y();
-    corbaPosition[6] = q.z();
-}
-
-int main(int, const char **)
-{
-    using namespace graphics;
-    using namespace corbaServer;
-    using namespace std;
-
-    Client client (0, NULL);
-    client.connect ();
-
-    se3::SE3 position1 = se3::SE3::Random();
-    se3::SE3 position2 = se3::SE3::Random();
-    se3::SE3 position3 = se3::SE3::Random();
-    se3::SE3 position4 = se3::SE3::Random();
-    se3::SE3 position5 = se3::SE3::Random();
-    CORBA::Float pos[7];
-
-    Client::WindowID windowId = client.gui()->createWindow("window1");
-    client.gui()->createScene("scene1");
-    client.gui()->addSceneToWindow("scene1",windowId);
-    client.gui()->addURDF("scene1/hrp2", "/local/mgeisert/devel/src/hrp2/hrp2_14_description/urdf/hrp2_14_capsule.urdf", "/local/mgeisert/devel/src/hrp2/");
-
-    sleep(5);
-
-    //vector<float> tri01 (3);
-
-    float pos1[3]= {1.,0.,0.};
-    float pos2[3] = {0.,1.,0.};
-    float pos3[3]= {0.,1.,1.};
-    float color[4] = {1.,1.,1.,1.};
-    client.gui()->addTriangleFace("scene1/triangle", pos1, pos2, pos3, color);
-
-    sleep(15);
-
-
-    se3ToCorba (pos, position1);
-    client.gui()->applyConfiguration("scene1/hrp2/RLEG_LINK0", pos);
-    se3ToCorba (pos, position2);
-    client.gui()->applyConfiguration("scene1/hrp2/RLEG_LINK1", pos);
-    se3ToCorba (pos, position3);
-    client.gui()->applyConfiguration("scene1/hrp2/LLEG_LINK1", pos);
-    se3ToCorba (pos, position4);
-    client.gui()->applyConfiguration("scene1/hrp2/LLEG_LINK2", pos);
-    se3ToCorba (pos, position5);
-    client.gui()->applyConfiguration("scene1/hrp2/BODY", pos);
-
-    client.gui()->refresh();
-
-    return 0;
-}
diff --git a/src/windows-manager.cpp b/src/windows-manager.cpp
deleted file mode 100644
index 8ec5df35c46322565bba7b805b4180d2acbc4bd8..0000000000000000000000000000000000000000
--- a/src/windows-manager.cpp
+++ /dev/null
@@ -1,1322 +0,0 @@
-// Copyright (c) 2015, Joseph Mirabel
-// Authors: Joseph Mirabel (joseph.mirabel@laas.fr)
-//
-// This file is part of gepetto-viewer.
-// gepetto-viewer 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
-// 3 of the License, or (at your option) any later version.
-//
-// gepetto-viewer 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
-// General Lesser Public License for more details.  You should have
-// received a copy of the GNU Lesser General Public License along with
-// gepetto-viewer. If not, see <http://www.gnu.org/licenses/>.
-
-#include "gepetto/viewer/corba/windows-manager.hh"
-
-#include <sys/types.h>
-#include <sys/stat.h>
-#include <unistd.h>
-
-#include <algorithm>
-
-#include <boost/thread.hpp>
-
-#include <osgDB/WriteFile>
-
-#include <gepetto/viewer/window-manager.h>
-#include <gepetto/viewer/node.h>
-#include <gepetto/viewer/group-node.h>
-#include <gepetto/viewer/leaf-node-box.h>
-#include <gepetto/viewer/leaf-node-capsule.h>
-#include <gepetto/viewer/leaf-node-cone.h>
-#include <gepetto/viewer/leaf-node-cylinder.h>
-#include <gepetto/viewer/leaf-node-line.h>
-#include <gepetto/viewer/leaf-node-face.h>
-#include <gepetto/viewer/leaf-node-sphere.h>
-#include <gepetto/viewer/leaf-node-arrow.h>
-#include <gepetto/viewer/leaf-node-light.h>
-#include <gepetto/viewer/leaf-node-xyzaxis.h>
-#include <gepetto/viewer/node-rod.h>
-#include <gepetto/viewer/roadmap-viewer.h>
-#include <gepetto/viewer/macros.h>
-#include <gepetto/viewer/config-osg.h>
-#include <gepetto/viewer/leaf-node-ground.h>
-#include <gepetto/viewer/leaf-node-collada.h>
-#include <gepetto/viewer/urdf-parser.h>
-#include <gepetto/viewer/blender-geom-writer.h>
-
-#include "gepetto/viewer/corba/graphical-interface.hh"
-
-#define RETURN_FALSE_IF_NODE_EXISTS(name)                                      \
-  if (nodeExists(name)) {                                                      \
-    std::cerr << "Node \"" << name << "\" already exists." << std::endl;       \
-    return false;                                                              \
-  }
-
-#define RETURN_FALSE_IF_NODE_DOES_NOT_EXIST(name)                              \
-  if (!nodeExists(name)) {                                                     \
-    std::cerr << "Node \"" << name << "\" does not exist." << std::endl;       \
-    return false;                                                              \
-  }
-
-#define THROW_IF_NODE_EXISTS(name)                                             \
-  if (nodeExists(name)) {                                                      \
-    std::ostringstream oss;                                                    \
-    oss << "Node \"" << name << "\" already exists.";                          \
-    throw gepetto::Error (oss.str ().c_str ());				       \
-  }
-
-#define THROW_IF_NODE_DOES_NOT_EXIST(name)                                     \
-  if (!nodeExists(name)) {                                                     \
-    std::ostringstream oss;                                                    \
-    oss << "Node \"" << name << "\" does not exist.";                          \
-    throw gepetto::Error (oss.str ().c_str ());				       \
-  }
-
-#define FIND_NODE_OF_TYPE_OR_THROW(NodeType, varname, nodename)                \
-  NodeType##Ptr_t varname (dynamic_pointer_cast <NodeType>                     \
-      (getNode(nodename, true)));                                              \
-  if (!varname) {                                                              \
-    std::ostringstream oss;                                                    \
-    oss << "Node \"" << nodename << "\" is not of type " #NodeType;             \
-    throw gepetto::Error (oss.str ().c_str ());				       \
-  }
-
-namespace graphics {
-    namespace {
-      typedef std::map<std::string, NodePtr_t>::iterator          NodeMapIt;
-      typedef std::map<std::string, NodePtr_t>::const_iterator    NodeMapConstIt;
-
-      typedef std::map<std::string, GroupNodePtr_t>::iterator          GroupNodeMapIt;
-      typedef std::map<std::string, GroupNodePtr_t>::const_iterator    GroupNodeMapConstIt;
-
-      typedef boost::mutex::scoped_lock scoped_lock;
-
-      struct ApplyConfigurationFunctor {
-        void operator() (const NodeConfiguration& nc) const
-        {
-            nc.node->applyConfiguration ( nc.position, nc.quat);
-        }
-      };
-    }
-
-    WindowsManager::WindowsManager () :
-        windowManagers_ (), nodes_ (), groupNodes_ (),roadmapNodes_(),
-        osgFrameMtx_ (), configListMtx_ (), rate_ (20), newNodeConfigurations_ (),
-        autoCaptureTransform_ (false)
-    {}
-
-    WindowsManager::WindowID WindowsManager::addWindow (std::string winName,
-            WindowManagerPtr_t newWindow)
-    {
-      WindowID windowId = (WindowID) windowManagers_.size ();
-        windowIDmap_ [winName] = windowId;
-        windowManagers_.push_back (newWindow);
-        return windowId;
-    }
-
-    WindowsManagerPtr_t WindowsManager::create ()
-    {
-      WindowsManagerPtr_t shPtr (new WindowsManager());
-      return shPtr;
-    }
-
-    osgVector4 WindowsManager::getColor (const std::string& colorName)
-    {
-        if (colorName == "blue")
-            return osgVector4 (0.f, 0.f, 1.f, 1.f);
-        else if (colorName == "green")
-            return osgVector4 (0.f, 1.f, 0.f, 1.f);
-        else if (colorName == "red")
-            return osgVector4 (1.f, 0.f, 0.f, 1.f);
-        else if (colorName == "white")
-            return osgVector4 (1.f, 1.f, 1.f, 1.f);
-        else
-            return osgVector4 (0.f, 0.f, 0.f, 1.f);
-    }
-
-    VisibilityMode WindowsManager::getVisibility (const std::string& vName)
-    {
-        if (vName == "OFF")
-            return VISIBILITY_OFF;
-        else if (vName == "ALWAYS_ON_TOP")
-            return ALWAYS_ON_TOP;
-        else if (vName == "ON")
-            return VISIBILITY_ON;
-        else {
-            std::cout << "Visibility mode not known, visibility mode can be"
-                " \"ON\",\"OFF\" or \"ALWAYS_ON_TOP\"." << std::endl;
-            std::cout << "Visibility mode set to default = \"ON\"." << std::endl;
-            return VISIBILITY_ON;
-        }
-    }
-
-    WireFrameMode WindowsManager::getWire (const std::string& wireName)
-    {
-        if (wireName == "WIREFRAME")
-            return WIREFRAME;
-        else if (wireName == "FILL_AND_WIREFRAME")
-            return FILL_AND_WIREFRAME;
-        else if (wireName == "FILL")
-            return FILL;
-        else {
-            std::cout << "Wire mode not known, wire mode can be \"FILL\","
-                "\"WIREFRAME\" or \"FILL_AND_WIREFRAME\"." << std::endl;
-            std::cout << "Wire mode set to default = \"FILL\"." << std::endl;
-            return FILL;
-        }
-    }
-
-    LightingMode WindowsManager::getLight (const std::string& lightName)
-    {
-        if (lightName == "OFF")
-            return LIGHT_INFLUENCE_OFF;
-        else if (lightName == "ON")
-            return LIGHT_INFLUENCE_ON;
-        else {
-            std::cout << "Lighting mode not known, lighting mode can be "
-                "\"ON\" or \"OFF\"." << std::endl;
-            std::cout << "Lighting mode set to default = \"ON\"." << std::endl;
-            return LIGHT_INFLUENCE_ON;
-        }
-    }
-
-    std::string WindowsManager::parentName (const std::string& name)
-    {
-        std::string::size_type slash = name.find_last_of ('/');
-        if (slash == std::string::npos) return "";
-        else return name.substr(0, slash);
-    }
-
-    NodePtr_t WindowsManager::find (const std::string name, GroupNodePtr_t)
-    {
-      NodeMapIt it = nodes_.find (name);
-      if (it == nodes_.end ()) {
-        std::string::size_type slash = name.find_first_of ('/');
-        if (slash == std::string::npos)
-          return NodePtr_t ();
-        GroupNodeMapIt itg = groupNodes_.find (name.substr (0, slash));
-        if (itg == groupNodes_.end ())
-          return NodePtr_t ();
-        return find (name.substr (slash + 1), itg->second);
-      }
-      return it->second;
-    }
-
-    bool WindowsManager::nodeExists (const std::string& name)
-    {
-      NodeMapConstIt it = nodes_.find (name);
-      return (it != nodes_.end ());
-    }
-
-    NodePtr_t WindowsManager::getNode (const std::string& name,
-        bool throwIfDoesntExist) const
-    {
-      NodeMapConstIt it = nodes_.find (name);
-      if (it == nodes_.end ()) {
-        if (throwIfDoesntExist) {
-          std::ostringstream oss;
-          oss << "No node with name \"" << name << "\".";
-          throw gepetto::Error (oss.str ().c_str ());
-        } else
-          return NodePtr_t();
-      }
-      return it->second;
-    }
-
-    template <typename NodeContainer_t> std::size_t WindowsManager::getNodes
-      (const gepetto::corbaserver::Names_t& names, NodeContainer_t& nodes)
-    {
-      const std::size_t l = nodes.size();
-      for (CORBA::ULong i = 0; i < names.length(); ++i) {
-        std::string name (names[i]);
-        NodePtr_t n = getNode (name);
-        if (n) nodes.push_back (n);
-        else std::cout << "Node \"" << name << "\" doesn't exist." << std::endl;
-      }
-      return nodes.size() - l;
-    }
-
-    template <typename Iterator, typename NodeContainer_t>
-      std::size_t WindowsManager::getNodes
-      (const Iterator& begin, const Iterator& end, NodeContainer_t& nodes)
-    {
-      const std::size_t l = nodes.size();
-      for (Iterator it = begin; it != end; ++it) {
-        std::string name (*it);
-        NodePtr_t n = getNode (name);
-        if (n) nodes.push_back (n);
-        else std::cout << "Node \"" << name << "\" doesn't exist." << std::endl;
-      }
-      return nodes.size() - l;
-    }
-
-    void WindowsManager::initParent (NodePtr_t node, GroupNodePtr_t parent)
-    {
-      if (parent && !parent->hasChild(node)) parent->addChild (node);
-    }
-
-    void WindowsManager::addNode (const std::string& nodeName, NodePtr_t node,
-        bool guessParent)
-    {
-      GroupNodePtr_t parent;
-      if (guessParent) parent = getGroup(parentName(nodeName));
-      addNode(nodeName, node, parent);
-    }
-
-    void WindowsManager::addNode (const std::string& nodeName, NodePtr_t node,
-        GroupNodePtr_t parent)
-    {
-      initParent (node, parent);
-      nodes_[nodeName] = node;
-    }
-
-    void WindowsManager::addGroup (const std::string& groupName,
-            GroupNodePtr_t group,
-            bool guessParent)
-    {
-      GroupNodePtr_t parent;
-      if (guessParent) parent = getGroup(parentName(groupName));
-      addGroup (groupName, group, parent);
-    }
-
-    void WindowsManager::addGroup(const std::string& groupName,
-        GroupNodePtr_t group, GroupNodePtr_t parent)
-    {
-      initParent (group, parent);
-      nodes_[groupName] = group;
-      groupNodes_[groupName] = group;
-    }
-
-    void WindowsManager::threadRefreshing (WindowManagerPtr_t window)
-    {
-        while (!window->done ())
-        {
-            osgFrameMutex().lock ();
-            window->frame ();
-            osgFrameMutex().unlock ();
-            boost::this_thread::sleep (boost::posix_time::milliseconds (rate_));
-        }
-    }
-
-    //Public functions
-
-    bool WindowsManager::setRate (const int& rate)
-    {
-        if (rate <= 0) {
-            std::cout << "You should specify a positive rate" << std::endl;
-            return false;
-        }
-        else {
-            rate_ = rate;
-            return true;
-        }
-    }
-
-    WindowsManager::WindowID WindowsManager::createWindow (const std::string& wn)
-    {
-        WindowManagerPtr_t newWindow = WindowManager::create ();
-        WindowID windowId = addWindow (wn, newWindow);
-        boost::thread refreshThread (boost::bind
-                (&WindowsManager::threadRefreshing,
-                 this, newWindow));
-        return windowId;
-    }
-
-    WindowsManager::WindowID WindowsManager::getWindowID (const std::string& wn)
-    {
-        WindowIDMap_t::iterator it = windowIDmap_.find (wn);
-        if (it == windowIDmap_.end ())
-            throw gepetto::Error ("There is no windows with that name");
-        return it->second;
-    }
-
-    void WindowsManager::refresh ()
-    {
-        configListMtx_.lock ();
-        osgFrameMutex().lock ();
-        //refresh scene with the new configuration
-        std::for_each(newNodeConfigurations_.begin(),
-            newNodeConfigurations_.end(),
-            ApplyConfigurationFunctor());
-        osgFrameMutex().unlock ();
-        newNodeConfigurations_.clear ();
-        configListMtx_.unlock ();
-        if (autoCaptureTransform_) captureTransform ();
-    }
-
-    void WindowsManager::createScene (const std::string& sceneName)
-    {
-      createGroup(sceneName);
-    }
-
-    void WindowsManager::createSceneWithFloor (const std::string& sceneName)
-    {
-        createScene(sceneName);
-        addFloor((sceneName + "/floor").c_str());
-    }
-
-    bool WindowsManager::addSceneToWindow (const std::string& sceneName,
-            WindowID windowId)
-    {
-        GroupNodePtr_t group = getGroup(sceneName, true);
-        if (windowId < windowManagers_.size ()) {
-            scoped_lock lock(osgFrameMutex());
-            windowManagers_[windowId]->addNode (group);
-            return true;
-        }
-        else {
-            std::cout << "Window ID " << windowId
-                << " doesn't exist." << std::endl;
-            return false;
-        }
-    }
-
-     bool WindowsManager::attachCameraToNode(const std::string& nodeName, const WindowID windowId)
-     {
-        NodePtr_t node = getNode(nodeName, true);
-        if (windowId > windowManagers_.size()) {
-    	  std::cout << "Window ID" << windowId << "doesn't exist." << std::endl;
-  	  return false;
-        }
-  	scoped_lock lock(osgFrameMutex());
-	windowManagers_[windowId]->attachCameraToNode(node);
-	return true;
-     }
-
-     bool WindowsManager::detachCamera(const WindowID windowId)
-     {
-        if (windowId > windowManagers_.size()) {
-    	  std::cout << "Window ID " << windowId << " doesn't exist."
-  		    << std::endl;
-  	  return false;
-        }
-  	scoped_lock lock(osgFrameMutex());
-	windowManagers_[windowId]->detachCamera();
-	return true;
-     }
-
-    bool WindowsManager::addFloor(const std::string& floorName)
-    {
-        RETURN_FALSE_IF_NODE_EXISTS(floorName);
-        LeafNodeGroundPtr_t floor = LeafNodeGround::create (floorName);
-        scoped_lock lock(osgFrameMutex());
-        addNode (floorName, floor, true);
-        return true;
-    }
-
-    bool WindowsManager::addBox (const std::string& boxName,
-            const float& boxSize1,
-            const float& boxSize2,
-            const float& boxSize3,
-            const Color_t& color)
-    {
-        RETURN_FALSE_IF_NODE_EXISTS(boxName);
-
-        LeafNodeBoxPtr_t box = LeafNodeBox::create
-          (boxName, osgVector3 (boxSize1, boxSize2, boxSize3), color);
-        scoped_lock lock(osgFrameMutex());
-        addNode (boxName, box, true);
-        return true;
-    }
-
-    bool WindowsManager::addCapsule (const std::string& capsuleName,
-            const float radius,
-            const float height,
-            const Color_t& color)
-    {
-        RETURN_FALSE_IF_NODE_EXISTS(capsuleName);
-
-        LeafNodeCapsulePtr_t capsule = LeafNodeCapsule::create (capsuleName, radius, height, color);
-        scoped_lock lock(osgFrameMutex());
-        addNode (capsuleName, capsule, true);
-        return true;
-    }
-
-    bool WindowsManager::addArrow (const std::string& arrowName,
-            const float radius,
-            const float length,
-            const Color_t& color)
-    {
-        RETURN_FALSE_IF_NODE_EXISTS(arrowName);
-
-        LeafNodeArrowPtr_t arrow = LeafNodeArrow::create (arrowName, color, radius, length);
-        scoped_lock lock(osgFrameMutex());
-        addNode (arrowName, arrow, true);
-        return true;
-    }
-
-    bool WindowsManager::addRod (const std::string& rodName,
-            const Color_t& color,
-            const float radius,
-            const float length,
-            short maxCapsule)
-    {
-      RETURN_FALSE_IF_NODE_EXISTS(rodName);
-
-      NodeRodPtr_t rod = NodeRod::create(rodName,color,radius,length,maxCapsule);
-      scoped_lock lock(osgFrameMutex());
-      addNode (rodName, rod, true);
-      for(size_t i = 0 ; i < (size_t) maxCapsule ; i++)
-        addNode(rod->getCapsuleName(i),rod->getCapsule(i), false);
-      return true;
-    }
-
-    bool WindowsManager::resizeCapsule(const std::string& capsuleName, float newHeight)
-      throw(std::exception)
-    {
-        FIND_NODE_OF_TYPE_OR_THROW (LeafNodeCapsule, cap, capsuleName);
-        scoped_lock lock(osgFrameMutex());
-        cap->resize(newHeight);
-        return true;
-    }
-
-    bool WindowsManager::resizeArrow(const std::string& arrowName ,float newRadius, float newLength)
-      throw(std::exception)
-    {
-        FIND_NODE_OF_TYPE_OR_THROW (LeafNodeArrow, arrow, arrowName);
-        scoped_lock lock(osgFrameMutex());
-        arrow->resize(newRadius,newLength);
-        return true;
-    }
-
-    bool WindowsManager::addMesh (const std::string& meshName,
-            const std::string& meshPath)
-    {
-        RETURN_FALSE_IF_NODE_EXISTS(meshName);
-        LeafNodeColladaPtr_t mesh;
-        try {
-          mesh = LeafNodeCollada::create (meshName, meshPath);
-        } catch (const std::exception& exc) {
-          std::cout << exc.what() << std::endl;
-          return false;
-        }
-        scoped_lock lock(osgFrameMutex());
-        addNode (meshName, mesh, true);
-        return true;
-    }
-
-    bool WindowsManager::addCone (const std::string& coneName,
-            const float radius, const float height,
-            const Color_t&)
-    {
-        RETURN_FALSE_IF_NODE_EXISTS(coneName);
-
-        LeafNodeConePtr_t cone = LeafNodeCone::create
-          (coneName, radius, height);
-        scoped_lock lock(osgFrameMutex());
-        addNode (coneName, cone, true);
-        return true;
-    }
-
-    bool WindowsManager::addCylinder (const std::string& cylinderName,
-            const float radius,
-            const float height,
-            const Color_t& color)
-    {
-        RETURN_FALSE_IF_NODE_EXISTS(cylinderName);
-
-        LeafNodeCylinderPtr_t cylinder = LeafNodeCylinder::create
-          (cylinderName, radius, height, color);
-        scoped_lock lock(osgFrameMutex());
-        addNode (cylinderName, cylinder, true);
-        return true;
-    }
-
-    bool WindowsManager::addSphere (const std::string& sphereName,
-            const float radius,
-            const Color_t& color)
-    {
-        RETURN_FALSE_IF_NODE_EXISTS(sphereName);
-
-        LeafNodeSpherePtr_t sphere = LeafNodeSphere::create
-          (sphereName, radius, color);
-        scoped_lock lock(osgFrameMutex());
-        addNode (sphereName, sphere, true);
-        return true;
-    }
-
-    bool WindowsManager::addLight (const std::string& lightName,
-            const WindowID wid,
-            const float radius,
-            const Color_t& color)
-    {
-        RETURN_FALSE_IF_NODE_EXISTS(lightName);
-
-        WindowManagerPtr_t wm = getWindowManager(wid, true);
-        LeafNodeLightPtr_t light = LeafNodeLight::create
-          (lightName, radius, color);
-        scoped_lock lock(osgFrameMutex());
-        addNode (lightName, light, true);
-        light->setRoot (wm->getScene ());
-        return true;
-    }
-
-    bool WindowsManager::addLine (const std::string& lineName,
-            const osgVector3& pos1,
-            const osgVector3& pos2,
-            const Color_t& color)
-    {
-        RETURN_FALSE_IF_NODE_EXISTS(lineName);
-
-        LeafNodeLinePtr_t line = LeafNodeLine::create (lineName, pos1, pos2, color);
-        scoped_lock lock(osgFrameMutex());
-        addNode (lineName, line, true);
-        return true;
-    }
-
-  bool WindowsManager::setLineStartPoint(const std::string& lineName,
-                                            const osgVector3& pos1)
-  {
-    FIND_NODE_OF_TYPE_OR_THROW (LeafNodeLine, line, lineName);
-    scoped_lock lock(osgFrameMutex());
-    line->setStartPoint(pos1);
-    return true;
-  }
-
-  bool WindowsManager::setLineEndPoint(const std::string& lineName,
-                                            const osgVector3& pos2)
-  {
-    FIND_NODE_OF_TYPE_OR_THROW (LeafNodeLine, line, lineName);
-    scoped_lock lock(osgFrameMutex());
-    line->setEndPoint(pos2);
-    return true;
-  }
-
-  bool WindowsManager::setLineExtremalPoints(const std::string& lineName,
-                                             const osgVector3& pos1,
-                                             const osgVector3& pos2)
-  {
-    FIND_NODE_OF_TYPE_OR_THROW (LeafNodeLine, line, lineName);
-    scoped_lock lock(osgFrameMutex());
-    line->setStartPoint(pos1);
-    line->setEndPoint(pos2);
-    return true;
-  }
-
-    bool WindowsManager::addCurve (const std::string& curveName,
-            const Vec3ArrayPtr_t& pos,
-            const Color_t& color)
-    {
-      RETURN_FALSE_IF_NODE_EXISTS(curveName);
-      if (pos->size () < 2) {
-        throw std::invalid_argument ("Need at least two points");
-      }
-      LeafNodeLinePtr_t curve = LeafNodeLine::create (curveName, pos, color);
-      curve->setMode (GL_LINE_STRIP);
-      scoped_lock lock(osgFrameMutex());
-      addNode (curveName, curve, true);
-      return true;
-    }
-
-  bool WindowsManager::setCurvePoints (const std::string& curveName,
-                                       const Vec3ArrayPtr_t& pos)
-  {
-    FIND_NODE_OF_TYPE_OR_THROW (LeafNodeLine, curve, curveName);
-    if (pos->size () < 2) {
-        throw std::invalid_argument ("Need at least two points");
-    }
-    scoped_lock lock(osgFrameMutex());
-    curve->setPoints(pos);
-    return true;
-  }
-
-    bool WindowsManager::setCurveMode (const std::string& curveName, const GLenum mode)
-    {
-        FIND_NODE_OF_TYPE_OR_THROW (LeafNodeLine, curve, curveName);
-        scoped_lock lock(osgFrameMutex());
-        curve->setMode (mode);
-        return true;
-    }
-
-    bool WindowsManager::setCurvePointsSubset (const std::string& curveName,
-        const int first, const std::size_t count)
-    {
-        FIND_NODE_OF_TYPE_OR_THROW (LeafNodeLine, curve, curveName);
-        scoped_lock lock(osgFrameMutex());
-        curve->setPointsSubset (first, count);
-        return true;
-    }
-
-    bool WindowsManager::setCurveLineWidth (const std::string& curveName, const float& width)
-    {
-        FIND_NODE_OF_TYPE_OR_THROW (LeafNodeLine, curve, curveName);
-        scoped_lock lock(osgFrameMutex());
-        curve->setLineWidth (width);
-        return true;
-    }
-
-    bool WindowsManager::addTriangleFace (const std::string& faceName,
-            const osgVector3& pos1,
-            const osgVector3& pos2,
-            const osgVector3& pos3,
-            const Color_t& color)
-    {
-      RETURN_FALSE_IF_NODE_EXISTS (faceName);
-
-      LeafNodeFacePtr_t face = LeafNodeFace::create (faceName, pos1, pos2, pos3, color);
-      scoped_lock lock(osgFrameMutex());
-      addNode (faceName, face, true);
-      return true;
-    }
-
-    bool WindowsManager::addSquareFace (const std::string& faceName,
-            const osgVector3& pos1,
-            const osgVector3& pos2,
-            const osgVector3& pos3,
-            const osgVector3& pos4,
-            const Color_t& color)
-    {
-      RETURN_FALSE_IF_NODE_EXISTS(faceName);
-
-      LeafNodeFacePtr_t face = LeafNodeFace::create
-        (faceName, pos1, pos2, pos3, pos4, color);
-      scoped_lock lock(osgFrameMutex());
-      addNode (faceName, face, true);
-      return true;
-    }
-
-  bool WindowsManager::setTexture (const std::string& nodeName,
-				   const std::string& filename)
-  {
-    FIND_NODE_OF_TYPE_OR_THROW (LeafNodeFace, faceNode, nodeName);
-
-    if (faceNode->nbVertices () != 4) {
-      std::ostringstream oss;
-      oss << "Face should have 4 vertices to apply texture. "
-	  << nodeName << " has " << faceNode->nbVertices () << ".";
-      throw std::runtime_error (oss.str ());
-    }
-    faceNode->setTexture (filename);
-    return true;
-  }
-
-    bool WindowsManager::addXYZaxis (const std::string& nodeName,const Color_t& color, float radius, float sizeAxis)
-    {
-      RETURN_FALSE_IF_NODE_EXISTS (nodeName);
-
-      LeafNodeXYZAxisPtr_t axis = LeafNodeXYZAxis::create
-        (nodeName,color,radius,sizeAxis);
-      scoped_lock lock(osgFrameMutex());
-      addNode (nodeName, axis, true);
-      return true;
-    }
-
-    bool WindowsManager::createRoadmap(const std::string& roadmapName,const Color_t& colorNode, float radius, float sizeAxis, const Color_t& colorEdge)
-    {
-      RETURN_FALSE_IF_NODE_EXISTS(roadmapName);
-
-      RoadmapViewerPtr_t rm = RoadmapViewer::create(roadmapName,colorNode,radius,sizeAxis,colorEdge);
-      scoped_lock lock(osgFrameMutex());
-      addNode (roadmapName, rm, true);
-      roadmapNodes_[roadmapName]=rm;
-      return true;
-    }
-
-    bool WindowsManager::addEdgeToRoadmap(const std::string& nameRoadmap, const osgVector3& posFrom, const osgVector3& posTo)
-    {
-        if (roadmapNodes_.find (nameRoadmap) == roadmapNodes_.end ()) {
-            //no node named nodeName
-            std::cout << "No roadmap named \"" << nameRoadmap << "\"" << std::endl;
-            return false;
-        }
-        else {
-            RoadmapViewerPtr_t rm_ptr = roadmapNodes_[nameRoadmap];
-          //  scoped_lock lock(osgFrameMutex()); mtx is now locked only when required in addEdge
-            rm_ptr->addEdge(posFrom,posTo,osgFrameMutex());
-            return true;
-        }
-    }
-
-    bool WindowsManager::addNodeToRoadmap(const std::string& nameRoadmap, const Configuration& conf)
-    {
-        if (roadmapNodes_.find (nameRoadmap) == roadmapNodes_.end ()) {
-            //no node named nodeName
-            std::cout << "No roadmap named \"" << nameRoadmap << "\"" << std::endl;
-            return false;
-        }
-        else {
-            RoadmapViewerPtr_t rm_ptr = roadmapNodes_[nameRoadmap];
-           // scoped_lock lock(osgFrameMutex());
-            rm_ptr->addNode(conf.position,conf.quat,osgFrameMutex());
-            return true;
-        }
-    }
-
-    std::vector<std::string> WindowsManager::getNodeList ()
-    {
-        std::vector<std::string> l;
-        for (NodeMapIt it=nodes_.begin (); it!=nodes_.end (); ++it) {
-            l.push_back (it->first);
-        }
-        return l;
-    }
-
-    std::vector<std::string> WindowsManager::getGroupNodeList (const std::string& group)
-    {
-        std::vector<std::string> l;
-        GroupNodePtr_t g (getGroup(group));
-        if(!g)
-            std::cout << "Unexisting group: " << group << std::endl;
-        else
-        {
-            std::cout << "List of Nodes in group :" << group << std::endl;
-            l.reserve(g->getNumOfChildren());
-            for(std::size_t i = 0; i < g->getNumOfChildren(); ++i)
-            {
-                NodePtr_t node = g->getChild(i);
-                l.push_back(node->getID());
-                std::cout << '\t' << node->getID() << std::endl;
-            }
-        }
-        return l;
-    }
-
-    std::vector<std::string> WindowsManager::getSceneList ()
-    {
-        std::vector<std::string> l;
-        l.reserve(groupNodes_.size());
-        std::cout << "List of GroupNodes :" << std::endl;
-        for (GroupNodeMapConstIt it =
-                groupNodes_.begin (); it!=groupNodes_.end (); ++it) {
-            std::cout << "   " << it->first << std::endl;
-            l.push_back (it->first);
-        }
-        return l;
-    }
-
-    std::vector<std::string> WindowsManager::getWindowList ()
-    {
-        std::vector<std::string> l;
-        l.reserve(windowIDmap_.size());
-        for (WindowIDMap_t::const_iterator it = windowIDmap_.begin ();
-                it!=windowIDmap_.end (); ++it) {
-            l.push_back (it->first);
-        }
-        return l;
-    }
-
-    bool WindowsManager::createGroup (const std::string& groupName)
-    {
-      RETURN_FALSE_IF_NODE_EXISTS(groupName);
-
-      GroupNodePtr_t groupNode = GroupNode::create (groupName);
-      scoped_lock lock(osgFrameMutex());
-      addGroup (groupName, groupNode, true);
-      return true;
-    }
-
-    bool WindowsManager::addURDF (const std::string& urdfName,
-            const std::string& urdfPath)
-    {
-      return loadUDRF(urdfName, urdfPath, true, true);
-    }
-
-    bool WindowsManager::addURDF (const std::string& urdfName,
-            const std::string& urdfPath,
-            const std::string& /*urdfPackagePath*/)
-    {
-      return addURDF(urdfName, urdfPath);
-    }
-
-    bool WindowsManager::addUrdfCollision (const std::string& urdfName,
-            const std::string& urdfPath)
-    {
-      return loadUDRF(urdfName, urdfPath, false, true);
-    }
-
-    bool WindowsManager::addUrdfCollision (const std::string& urdfName,
-            const std::string& urdfPath, const std::string& /*urdfPackagePath*/)
-    {
-      return addUrdfCollision (urdfName, urdfPath);
-    }
-
-    void WindowsManager::addUrdfObjects (const std::string& urdfName,
-            const std::string& urdfPath,
-            bool visual)
-    {
-      loadUDRF(urdfName, urdfPath, visual, false);
-    }
-
-    void WindowsManager::addUrdfObjects (const std::string& urdfName,
-            const std::string& urdfPath,
-            const std::string& /*urdfPackagePath*/,
-            bool visual)
-    {
-      return addUrdfObjects (urdfName, urdfPath, visual);
-    }
-
-    bool WindowsManager::loadUDRF(const std::string& urdfName,
-        const std::string& urdfPath, bool visual, bool linkFrame)
-    {
-      RETURN_FALSE_IF_NODE_EXISTS(urdfName);
-
-      GroupNodePtr_t urdf =
-        urdfParser::parse (urdfName, urdfPath, visual, linkFrame);
-      scoped_lock lock(osgFrameMutex());
-      addGroup (urdfName, urdf, true);
-      NodePtr_t link;
-      for (std::size_t i=0; i< urdf->getNumOfChildren (); i++) {
-        link = urdf->getChild (i);
-        GroupNodePtr_t groupNode (dynamic_pointer_cast
-            <GroupNode> (link));
-        if (groupNode) {
-          addGroup(link->getID(), groupNode, urdf);
-          for (std::size_t j=0; j < groupNode->getNumOfChildren (); ++j) {
-            NodePtr_t object (groupNode->getChild (j));
-            addNode(object->getID (), object, groupNode);
-          }
-        } else {
-          addNode(link->getID(), link, urdf);
-        }
-      }
-      return true;
-    }
-
-    bool WindowsManager::addToGroup (const std::string& nodeName,
-            const std::string& groupName)
-    {
-        NodePtr_t node = getNode(nodeName, true);
-        GroupNodePtr_t group = getGroup(groupName, true);
-
-        if (group->hasChild(node)) return false;
-
-        scoped_lock lock(osgFrameMutex());// if addChild is called in the same time as osg::frame(), gepetto-viewer crash
-        groupNodes_[groupName]->addChild (nodes_[nodeName]);
-        return true;
-    }
-
-    bool WindowsManager::removeFromGroup (const std::string& nodeName,
-            const std::string& groupName)
-    {
-        if (nodes_.find (nodeName) == nodes_.end () ||
-                groupNodes_.find (groupName) == groupNodes_.end ()) {
-            std::cout << "Node name \"" << nodeName << "\" and/or groupNode \""
-                << groupName << "\" doesn't exist." << std::endl;
-            return false;
-        }
-        else {
-            scoped_lock lock(osgFrameMutex());
-            groupNodes_[groupName]->removeChild(nodes_[nodeName]);
-            return true;
-        }
-    }
-
-    bool WindowsManager::deleteNode (const std::string& nodeName, bool all)
-    {
-        NodePtr_t n = getNode (nodeName);
-        if (!n) return false;
-        else {
-            /// Check if it is a group
-            GroupNodeMapIt it = groupNodes_.find(nodeName);
-            if (it != groupNodes_.end ()) {
-              if (all) {
-                std::vector <std::string> names(it->second->getNumOfChildren ());
-                for (std::size_t i = 0; i < names.size(); ++i)
-                  names[i] = it->second->getChild (i)->getID();
-                osgFrameMutex().lock ();
-                it->second->removeAllChildren ();
-                osgFrameMutex().unlock ();
-                for (std::size_t i = 0; i < names.size(); ++i)
-                  deleteNode (names[i], all);
-              }
-              osgFrameMutex().lock ();
-              groupNodes_.erase (nodeName);
-              osgFrameMutex().unlock ();
-            }
-            GroupNodeMapConstIt itg;
-            osgFrameMutex().lock ();
-            for (itg = groupNodes_.begin (); itg != groupNodes_.end(); ++itg) {
-              if (itg->second && itg->second->hasChild (n))
-                itg->second->removeChild(n);
-            }
-            nodes_.erase (nodeName);
-            osgFrameMutex().unlock ();
-            return true;
-        }
-    }
-
-    bool WindowsManager::applyConfiguration (const std::string& nodeName,
-            const Configuration& configuration)
-    {
-        NodePtr_t updatedNode = getNode (nodeName, false);
-        if (!updatedNode) return false;
-
-        NodeConfiguration newNodeConfiguration;
-        newNodeConfiguration.node = updatedNode;
-        newNodeConfiguration.position = configuration.position;
-        newNodeConfiguration.quat = configuration.quat;
-
-        configListMtx_.lock();
-        newNodeConfigurations_.push_back (newNodeConfiguration);
-        configListMtx_.unlock();
-        return true;
-    }
-
-    bool WindowsManager::applyConfigurations (const std::vector<std::string>& nodeNames,
-            const std::vector<Configuration>& configurations)
-    {
-        if (nodeNames.size() != configurations.size())
-          throw std::invalid_argument ("Number of node names and configurations must be equal.");
-
-        newNodeConfigurations_.reserve (
-            newNodeConfigurations_.capacity() + nodeNames.size());
-
-        bool success = true;
-        scoped_lock lock(configListMtx_);
-        for (std::size_t i = 0; i < nodeNames.size(); ++i) {
-          NodePtr_t updatedNode = getNode (nodeNames[i], false);
-          if (!updatedNode) {
-            success = false;
-            continue;
-          }
-
-          NodeConfiguration newNodeConfiguration;
-          newNodeConfiguration.node = updatedNode;
-          newNodeConfiguration.position = configurations[i].position;
-          newNodeConfiguration.quat = configurations[i].quat;
-
-          newNodeConfigurations_.push_back (newNodeConfiguration);
-        }
-
-        return success;
-    }
-
-    bool WindowsManager::addLandmark (const std::string& nodeName,
-            float size)
-    {
-        THROW_IF_NODE_DOES_NOT_EXIST(nodeName);
-	scoped_lock lock(osgFrameMutex());
-        nodes_[nodeName]->addLandmark (size);
-        return true;
-    }
-
-    bool WindowsManager::deleteLandmark (const std::string& nodeName)
-    {
-        THROW_IF_NODE_DOES_NOT_EXIST(nodeName);
-	scoped_lock lock(osgFrameMutex());
-        nodes_[nodeName]->deleteLandmark ();
-        return true;
-    }
-
-    Configuration WindowsManager::getStaticTransform (const std::string& nodeName) const
-    {
-        NodePtr_t node = getNode(nodeName, true);
-        return Configuration(node->getStaticPosition (),
-                             node->getStaticRotation ());
-    }
-
-  bool WindowsManager::setStaticTransform (const std::string& nodeName,
-      const Configuration& transform)
-  {
-    RETURN_FALSE_IF_NODE_DOES_NOT_EXIST(nodeName);
-    scoped_lock lock(osgFrameMutex());
-    nodes_[nodeName]->setStaticTransform(transform.position,transform.quat);
-    return true;
-  }
-
-    bool WindowsManager::setVisibility (const std::string& nodeName,
-            const std::string& visibilityMode)
-    {
-        RETURN_FALSE_IF_NODE_DOES_NOT_EXIST(nodeName);
-        VisibilityMode visibility =  getVisibility (visibilityMode);
-	scoped_lock lock(osgFrameMutex());
-        nodes_[nodeName]->setVisibilityMode (visibility);
-        return true;
-    }
-
-    bool WindowsManager::setScale(const std::string& nodeName, const osgVector3& scale)
-    {
-        THROW_IF_NODE_DOES_NOT_EXIST(nodeName);
-        scoped_lock lock(osgFrameMutex());
-        nodes_[nodeName]->setScale(scale);
-        return true;
-    }
-
-    bool WindowsManager::setScale(const std::string& nodeName, const float& scale)
-    {
-      return setScale(nodeName, osgVector3(scale, scale, scale));
-    }
-
-    bool WindowsManager::setScale(const std::string& nodeName, const int& scalePercentage)
-    {
-      return setScale (nodeName, (value_type)scalePercentage / 100);
-    }
-
-    bool WindowsManager::setAlpha(const std::string& nodeName, const float& alpha)
-    {
-        RETURN_FALSE_IF_NODE_DOES_NOT_EXIST(nodeName);
-  	scoped_lock lock(osgFrameMutex());
-        nodes_[nodeName]->setAlpha (alpha);
-        return true;
-    }
-
-    bool WindowsManager::setAlpha(const std::string& nodeName, const int& alphaPercentage)
-    {
-      return setAlpha (nodeName, (float)alphaPercentage / 100);
-    }
-
-    bool WindowsManager::setColor(const std::string& nodeName, const Color_t& color)
-    {
-        RETURN_FALSE_IF_NODE_DOES_NOT_EXIST(nodeName);
-        osgVector4 vecColor(color[0],color[1],color[2],color[3]);
-        scoped_lock lock(osgFrameMutex());
-        nodes_[nodeName]->setColor (vecColor);
-        return true;
-    }
-
-    bool WindowsManager::setWireFrameMode (const std::string& nodeName,
-            const std::string& wireFrameMode)
-    {
-        RETURN_FALSE_IF_NODE_DOES_NOT_EXIST(nodeName);
-        WireFrameMode wire = getWire (wireFrameMode);
-	scoped_lock lock(osgFrameMutex());
-        nodes_[nodeName]->setWireFrameMode (wire);
-	return true;
-    }
-
-    bool WindowsManager::setLightingMode (const std::string& nodeName,
-            const std::string& lightingMode)
-    {
-        RETURN_FALSE_IF_NODE_DOES_NOT_EXIST(nodeName);
-        LightingMode light = getLight (lightingMode);
-	scoped_lock lock(osgFrameMutex());
-        nodes_[nodeName]->setLightingMode (light);
-        return true;
-    }
-
-    bool WindowsManager::setHighlight (const std::string& nodeName,
-            int state)
-    {
-        RETURN_FALSE_IF_NODE_DOES_NOT_EXIST(nodeName);
-	scoped_lock lock(osgFrameMutex());
-        nodes_[nodeName]->setHighlightState (state);
-        return true;
-    }
-
-    void WindowsManager::captureFrame (const WindowID wid, const std::string& filename)
-    {
-      WindowManagerPtr_t wm = getWindowManager(wid, true);
-      scoped_lock lock(osgFrameMutex());
-      wm->captureFrame (filename);
-    }
-
-    bool WindowsManager::startCapture (const WindowID windowId, const std::string& filename,
-            const std::string& extension)
-    {
-        WindowManagerPtr_t wm = getWindowManager(windowId, true);
-        scoped_lock lock(osgFrameMutex());
-        wm->startCapture (filename, extension);
-        return true;
-    }
-
-    bool WindowsManager::stopCapture (const WindowID windowId)
-    {
-        WindowManagerPtr_t wm = getWindowManager(windowId, true);
-        scoped_lock lock(osgFrameMutex());
-        wm->stopCapture ();
-        return true;
-    }
-
-    bool WindowsManager::setCaptureTransform (const std::string& filename,
-        const std::vector<std::string>& nodeNames)
-    {
-        blenderCapture_.nodes_.clear ();
-        std::size_t nb = getNodes (nodeNames.begin(), nodeNames.end(),
-            blenderCapture_.nodes_);
-        blenderCapture_.writer_visitor_->writer_ =
-          new YamlTransformWriter (filename);
-        return nb == nodeNames.size();
-    }
-
-    void WindowsManager::captureTransformOnRefresh (bool autoCapture)
-    {
-      autoCaptureTransform_ = autoCapture;
-    }
-
-    void WindowsManager::captureTransform ()
-    {
-        osgFrameMutex().lock ();
-        blenderCapture_.captureFrame ();
-        osgFrameMutex().unlock ();
-    }
-
-    bool WindowsManager::writeBlenderScript (const std::string& filename,
-        const std::vector<std::string>& nodeNames)
-    {
-      std::vector<NodePtr_t> nodes;
-      std::size_t nb = getNodes (nodeNames.begin(), nodeNames.end(), nodes);
-      if (nb != nodeNames.size())
-        throw std::invalid_argument ("Could not find one of the nodes");
-      BlenderGeomWriterVisitor visitor (filename);
-      for (std::size_t i = 0; i < nodes.size(); ++i)
-        nodes[i]->accept(visitor);
-      return true;
-    }
-
-    bool WindowsManager::writeNodeFile (const std::string& nodeName,
-        const std::string& filename)
-    {
-        RETURN_FALSE_IF_NODE_DOES_NOT_EXIST(nodeName);
-        scoped_lock lock(osgFrameMutex());
-        osg::ref_ptr <osgDB::Options> os = new osgDB::Options;
-        os->setOptionString ("NoExtras");
-        bool ret = osgDB::writeNodeFile (*nodes_[nodeName]->asGroup (),
-            std::string (filename), os.get());
-        return ret;
-    }
-
-    bool WindowsManager::writeWindowFile (const WindowID windowId,
-        const std::string& filename)
-    {
-        if (windowId < windowManagers_.size ()) {
-            scoped_lock lock(osgFrameMutex());
-            bool ret = windowManagers_[windowId]->writeNodeFile (std::string (filename));
-            return ret;
-        }
-        else {
-            std::cout << "Window ID " << windowId
-                << " doesn't exist." << std::endl;
-            return false;
-        }
-    }
-
-    WindowManagerPtr_t WindowsManager::getWindowManager (const WindowID wid,
-        bool throwIfDoesntExist) const
-    {
-      if (wid < windowManagers_.size ()) {
-        return windowManagers_[wid];
-      }
-      else {
-        std::ostringstream oss;
-        oss << "Window ID " << wid << " doesn't exist.";
-        if (throwIfDoesntExist)
-          throw std::invalid_argument (oss.str ());
-        std::cout << oss.str () << std::endl;
-        return WindowManagerPtr_t ();
-      }
-    }
-
-    GroupNodePtr_t WindowsManager::getGroup (const std::string groupName,
-        bool throwIfDoesntExist) const
-    {
-      GroupNodeMapConstIt it = groupNodes_.find (groupName);
-        if (it == groupNodes_.end ()) {
-          if (throwIfDoesntExist) {
-            std::ostringstream oss;
-            oss << "No group with name \"" << groupName << "\".";
-            throw gepetto::Error (oss.str ().c_str ());
-          } else
-            return GroupNodePtr_t ();
-        }
-        return it->second;
-    }
-
-    Configuration WindowsManager::getNodeGlobalTransform(const std::string nodeName) const
-    {
-        NodePtr_t node = getNode(nodeName, true);
-        std::pair<osgVector3, osgQuat> posQuat = node->getGlobalTransform();
-        return Configuration(posQuat.first, posQuat.second);
-    }
-
-    bool WindowsManager::setBackgroundColor1(const WindowID windowId,const Color_t& color)
-    {
-      WindowManagerPtr_t wm = getWindowManager(windowId, true);
-      scoped_lock lock(osgFrameMutex());
-      wm->setBackgroundColor1(color);
-      return true;
-    }
-
-  bool WindowsManager::setBackgroundColor2(const WindowID windowId,const Color_t& color)
-  {
-    WindowManagerPtr_t wm = getWindowManager(windowId, true);
-    scoped_lock lock(osgFrameMutex());
-    wm->setBackgroundColor2(color);
-    return true;
-  }
-
-  Configuration WindowsManager::getCameraTransform(const WindowID windowId){
-    osg::Quat rot;
-    osg::Vec3d pos;
-    WindowManagerPtr_t wm = getWindowManager(windowId, true);
-    scoped_lock lock(osgFrameMutex());
-    wm->getCameraTransform(pos,rot);
-    return Configuration(pos,rot);
-  }
-
-  bool WindowsManager::setCameraTransform(const WindowID windowId,const Configuration& configuration){
-    WindowManagerPtr_t wm = getWindowManager(windowId, true);
-    scoped_lock lock(osgFrameMutex());
-    wm->setCameraTransform(configuration.position,configuration.quat);
-    return true;
-  }
-
-  std::vector<std::string> WindowsManager::getPropertyNames(const std::string& nodeName) const
-  {
-    NodePtr_t node = getNode(nodeName, true);
-    const PropertyMap_t map = node->properties();
-    std::vector<std::string> names;
-    names.reserve(map.size());
-    for (PropertyMap_t::const_iterator _prop = map.begin(); _prop != map.end(); ++_prop)
-      names.push_back(_prop->first);
-    return names;
-  }
-
-  std::vector<std::string> WindowsManager::getPropertyTypes(const std::string& nodeName) const
-  {
-    NodePtr_t node = getNode(nodeName, true);
-    const PropertyMap_t map = node->properties();
-    std::vector<std::string> types;
-    types.reserve(map.size());
-    for (PropertyMap_t::const_iterator _prop = map.begin(); _prop != map.end(); ++_prop)
-      types.push_back(_prop->second->type());
-    return types;
-  }
-
-  template <typename Property_t>
-  Property_t WindowsManager::getProperty(const std::string& nodeName, const std::string& propName) const
-  {
-    NodePtr_t node = getNode(nodeName, true);
-    Property_t value;
-    if (!node->getProperty<Property_t>(propName, value)) {
-      throw std::invalid_argument ("Could not get the property");
-    }
-    return value;
-  }
-
-  template <typename Property_t>
-  void WindowsManager::setProperty(const std::string& nodeName, const std::string& propName, const Property_t& value) const
-  {
-    NodePtr_t node = getNode(nodeName, true);
-    if (!node->setProperty<Property_t>(propName, value)) {
-      throw std::invalid_argument ("Could not set the property");
-    }
-  }
-
-#define DEFINE_WINDOWS_MANAGER_GET_SET_PROPERTY_FOR_TYPE(Type,Name) \
-  Type WindowsManager::get ## Name ## Property(const std::string& nodeName, const std::string& propName) const \
-  { return getProperty<Type>(nodeName, propName); } \
-  void WindowsManager::set ## Name ## Property(const std::string& nodeName, const std::string& propName, const Type& value) const \
-  { setProperty<Type>(nodeName, propName, value); }
-
-#define INSTANCIATE_WINDOWS_MANAGER_GET_SET_PROPERTY_FOR_TYPE(Type) \
-  template Type WindowsManager::getProperty<Type>(const std::string&, const std::string&) const; \
-  template void WindowsManager::setProperty<Type>(const std::string&, const std::string&, const Type&) const
-
-  INSTANCIATE_WINDOWS_MANAGER_GET_SET_PROPERTY_FOR_TYPE(std::string);
-  INSTANCIATE_WINDOWS_MANAGER_GET_SET_PROPERTY_FOR_TYPE(osgVector3);
-  INSTANCIATE_WINDOWS_MANAGER_GET_SET_PROPERTY_FOR_TYPE(osgVector4);
-  INSTANCIATE_WINDOWS_MANAGER_GET_SET_PROPERTY_FOR_TYPE(float);
-  INSTANCIATE_WINDOWS_MANAGER_GET_SET_PROPERTY_FOR_TYPE(bool);
-  INSTANCIATE_WINDOWS_MANAGER_GET_SET_PROPERTY_FOR_TYPE(int);
-
-  DEFINE_WINDOWS_MANAGER_GET_SET_PROPERTY_FOR_TYPE(std::string, String)
-  DEFINE_WINDOWS_MANAGER_GET_SET_PROPERTY_FOR_TYPE(osgVector3, Vector3)
-  DEFINE_WINDOWS_MANAGER_GET_SET_PROPERTY_FOR_TYPE(osgVector4, Color)
-  DEFINE_WINDOWS_MANAGER_GET_SET_PROPERTY_FOR_TYPE(float, Float)
-  DEFINE_WINDOWS_MANAGER_GET_SET_PROPERTY_FOR_TYPE(bool, Bool)
-  DEFINE_WINDOWS_MANAGER_GET_SET_PROPERTY_FOR_TYPE(int, Int)
-} // namespace graphics