diff --git a/cmake b/cmake
index 9e21ae2222fdb51dccd1320bb7208f73259b0c73..c333a88decb3e4c0a86947bc6c7f072dc5c5df20 160000
--- a/cmake
+++ b/cmake
@@ -1 +1 @@
-Subproject commit 9e21ae2222fdb51dccd1320bb7208f73259b0c73
+Subproject commit c333a88decb3e4c0a86947bc6c7f072dc5c5df20
diff --git a/include/sot/core/binary-int-to-uint.hh b/include/sot/core/binary-int-to-uint.hh
index e61879f1c0f933e47c837cf0247c185631d5dc06..a073117f0524517b1c4d9c9dfe5f43e75c44e436 100644
--- a/include/sot/core/binary-int-to-uint.hh
+++ b/include/sot/core/binary-int-to-uint.hh
@@ -35,17 +35,16 @@
 
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
 
-class SOTBINARYINTTOUINT_EXPORT BinaryIntToUint : public dg::Entity {
+class SOTBINARYINTTOUINT_EXPORT BinaryIntToUint : public dynamicgraph::Entity {
 public:
   static const std::string CLASS_NAME;
   virtual const std::string &getClassName(void) const { return CLASS_NAME; }
 
   /* --- SIGNALS ------------------------------------------------------------ */
 public:
-  dg::SignalPtr<int, int> binaryIntSIN;
-  dg::SignalTimeDependent<unsigned, int> binaryUintSOUT;
+  dynamicgraph::SignalPtr<int, int> binaryIntSIN;
+  dynamicgraph::SignalTimeDependent<unsigned, int> binaryUintSOUT;
 
 public:
   BinaryIntToUint(const std::string &name);
diff --git a/include/sot/core/clamp-workspace.hh b/include/sot/core/clamp-workspace.hh
index d82905ed65127f324fe128c09fb4585c9e3f390c..7b53a11d710756d8a284b50670c38311d2235283 100644
--- a/include/sot/core/clamp-workspace.hh
+++ b/include/sot/core/clamp-workspace.hh
@@ -15,7 +15,6 @@
 
 /* Matrix */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
 
 /* SOT */
 #include <dynamic-graph/all-signals.h>
@@ -39,24 +38,23 @@ namespace dg = dynamicgraph;
 
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
 
 /* --------------------------------------------------------------------- */
 /* --- CLASS ----------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-class SOTCLAMPWORKSPACE_EXPORT ClampWorkspace : public dg::Entity {
+class SOTCLAMPWORKSPACE_EXPORT ClampWorkspace : public dynamicgraph::Entity {
 public:
   static const std::string CLASS_NAME;
   virtual const std::string &getClassName(void) const { return CLASS_NAME; }
 
   /* --- SIGNALS ------------------------------------------------------------ */
 public:
-  dg::SignalPtr<MatrixHomogeneous, int> positionrefSIN;
-  dg::SignalPtr<MatrixHomogeneous, int> positionSIN;
-  dg::SignalTimeDependent<dg::Matrix, int> alphaSOUT;
-  dg::SignalTimeDependent<dg::Matrix, int> alphabarSOUT;
-  dg::SignalTimeDependent<MatrixHomogeneous, int> handrefSOUT;
+  dynamicgraph::SignalPtr<MatrixHomogeneous, int> positionrefSIN;
+  dynamicgraph::SignalPtr<MatrixHomogeneous, int> positionSIN;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Matrix, int> alphaSOUT;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Matrix, int> alphabarSOUT;
+  dynamicgraph::SignalTimeDependent<MatrixHomogeneous, int> handrefSOUT;
 
 public:
   ClampWorkspace(const std::string &name);
@@ -64,8 +62,8 @@ public:
 
   void update(int time);
 
-  virtual dg::Matrix &computeOutput(dg::Matrix &res, int time);
-  virtual dg::Matrix &computeOutputBar(dg::Matrix &res, int time);
+  virtual dynamicgraph::Matrix &computeOutput(dynamicgraph::Matrix &res, int time);
+  virtual dynamicgraph::Matrix &computeOutputBar(dynamicgraph::Matrix &res, int time);
   virtual MatrixHomogeneous &computeRef(MatrixHomogeneous &res, int time);
 
   virtual void display(std::ostream &) const;
@@ -73,10 +71,10 @@ public:
 private:
   int timeUpdate;
 
-  dg::Matrix alpha;
-  dg::Matrix alphabar;
+  dynamicgraph::Matrix alpha;
+  dynamicgraph::Matrix alphabar;
   MatrixHomogeneous prefMp;
-  dg::Vector pd;
+  dynamicgraph::Vector pd;
   MatrixRotation Rd;
   MatrixHomogeneous handref;
 
diff --git a/include/sot/core/com-freezer.hh b/include/sot/core/com-freezer.hh
index 6e4a7aee48d7530e11f83f644861f4df91c15dc2..4621f6e25d94e0c13e447d30363ca7cb99f01447 100644
--- a/include/sot/core/com-freezer.hh
+++ b/include/sot/core/com-freezer.hh
@@ -16,7 +16,6 @@
 
 /* Matrix */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
 
 /* SOT */
 #include <dynamic-graph/all-signals.h>
@@ -39,19 +38,17 @@ namespace dg = dynamicgraph;
 namespace dynamicgraph {
 namespace sot {
 
-namespace dg = dynamicgraph;
-
 /* --------------------------------------------------------------------- */
 /* --- CLASS ----------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-class SOTCOMFREEZER_EXPORT CoMFreezer : public dg::Entity {
+class SOTCOMFREEZER_EXPORT CoMFreezer : public dynamicgraph::Entity {
 public:
   static const std::string CLASS_NAME;
   virtual const std::string &getClassName() const { return CLASS_NAME; }
 
 private:
-  dg::Vector m_lastCoM;
+  dynamicgraph::Vector m_lastCoM;
   bool m_previousPGInProcess;
   int m_lastStopTime;
 
@@ -60,12 +57,12 @@ public: /* --- CONSTRUCTION --- */
   virtual ~CoMFreezer(void);
 
 public: /* --- SIGNAL --- */
-  dg::SignalPtr<dg::Vector, int> CoMRefSIN;
-  dg::SignalPtr<unsigned, int> PGInProcessSIN;
-  dg::SignalTimeDependent<dg::Vector, int> freezedCoMSOUT;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> CoMRefSIN;
+  dynamicgraph::SignalPtr<unsigned, int> PGInProcessSIN;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> freezedCoMSOUT;
 
 public: /* --- FUNCTION --- */
-  dg::Vector &computeFreezedCoM(dg::Vector &freezedCoM, const int &time);
+  dynamicgraph::Vector &computeFreezedCoM(dynamicgraph::Vector &freezedCoM, const int &time);
 
 public: /* --- PARAMS --- */
   virtual void display(std::ostream &os) const;
diff --git a/include/sot/core/control-gr.hh b/include/sot/core/control-gr.hh
index 0ba768e9206a2c9086479f24e4465a91d1f16f3c..c0ac928f600e21942f7c012d44745d78d59fa7da 100644
--- a/include/sot/core/control-gr.hh
+++ b/include/sot/core/control-gr.hh
@@ -16,7 +16,6 @@
 
 /* Matrix */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
 
 /* SOT */
 #include <dynamic-graph/entity.h>
@@ -40,7 +39,6 @@ namespace dg = dynamicgraph;
 namespace dynamicgraph {
 namespace sot {
 
-namespace dg = dynamicgraph;
 
 /* --------------------------------------------------------------------- */
 /* --- CLASS ----------------------------------------------------------- */
@@ -70,14 +68,14 @@ protected:
   double _dimension;
 
 public: /* --- SIGNALS --- */
-  SignalPtr<dg::Matrix, int> matrixASIN;
-  SignalPtr<dg::Vector, int> accelerationSIN;
-  SignalPtr<dg::Vector, int> gravitySIN;
-  SignalTimeDependent<dg::Vector, int> controlSOUT;
+  SignalPtr<dynamicgraph::Matrix, int> matrixASIN;
+  SignalPtr<dynamicgraph::Vector, int> accelerationSIN;
+  SignalPtr<dynamicgraph::Vector, int> gravitySIN;
+  SignalTimeDependent<dynamicgraph::Vector, int> controlSOUT;
 
 protected:
   double &setsize(int dimension);
-  dg::Vector &computeControl(dg::Vector &tau, int t);
+  dynamicgraph::Vector &computeControl(dynamicgraph::Vector &tau, int t);
 };
 
 } // namespace sot
diff --git a/include/sot/core/control-pd.hh b/include/sot/core/control-pd.hh
index a9bc35762a1c207b29f827e0af5e54f901fb7f3b..293300f518fda79ecf836607e51685283cc736c3 100644
--- a/include/sot/core/control-pd.hh
+++ b/include/sot/core/control-pd.hh
@@ -16,7 +16,6 @@
 
 /* Matrix */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
 
 /* SOT */
 #include <dynamic-graph/entity.h>
@@ -67,22 +66,22 @@ protected:
   double TimeStep;
 
 public: /* --- SIGNALS --- */
-  SignalPtr<dg::Vector, int> KpSIN;
-  SignalPtr<dg::Vector, int> KdSIN;
-  SignalPtr<dg::Vector, int> positionSIN;
-  SignalPtr<dg::Vector, int> desiredpositionSIN;
-  SignalPtr<dg::Vector, int> velocitySIN;
-  SignalPtr<dg::Vector, int> desiredvelocitySIN;
-  SignalTimeDependent<dg::Vector, int> controlSOUT;
-  SignalTimeDependent<dg::Vector, int> positionErrorSOUT;
-  SignalTimeDependent<dg::Vector, int> velocityErrorSOUT;
+  SignalPtr<dynamicgraph::Vector, int> KpSIN;
+  SignalPtr<dynamicgraph::Vector, int> KdSIN;
+  SignalPtr<dynamicgraph::Vector, int> positionSIN;
+  SignalPtr<dynamicgraph::Vector, int> desiredpositionSIN;
+  SignalPtr<dynamicgraph::Vector, int> velocitySIN;
+  SignalPtr<dynamicgraph::Vector, int> desiredvelocitySIN;
+  SignalTimeDependent<dynamicgraph::Vector, int> controlSOUT;
+  SignalTimeDependent<dynamicgraph::Vector, int> positionErrorSOUT;
+  SignalTimeDependent<dynamicgraph::Vector, int> velocityErrorSOUT;
 
 protected:
-  dg::Vector &computeControl(dg::Vector &tau, int t);
-  dg::Vector position_error_;
-  dg::Vector velocity_error_;
-  dg::Vector &getPositionError(dg::Vector &position_error, int t);
-  dg::Vector &getVelocityError(dg::Vector &velocity_error, int t);
+  dynamicgraph::Vector &computeControl(dynamicgraph::Vector &tau, int t);
+  dynamicgraph::Vector position_error_;
+  dynamicgraph::Vector velocity_error_;
+  dynamicgraph::Vector &getPositionError(dynamicgraph::Vector &position_error, int t);
+  dynamicgraph::Vector &getVelocityError(dynamicgraph::Vector &velocity_error, int t);
 };
 
 } // namespace sot
diff --git a/include/sot/core/derivator-impl.hh b/include/sot/core/derivator-impl.hh
index 616b4cd7441a2a4b1ea32565ac4c63f1b88b8c4a..ba354eefa08681fbb13c8c1220a0a49ed162012a 100644
--- a/include/sot/core/derivator-impl.hh
+++ b/include/sot/core/derivator-impl.hh
@@ -33,7 +33,6 @@
 
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
 
 #ifdef WIN32
 #define DECLARE_SPECIFICATION(className, sotSigType)                           \
@@ -47,8 +46,8 @@ namespace dg = dynamicgraph;
 #endif
 
 DECLARE_SPECIFICATION(DerivatorDouble, double)
-DECLARE_SPECIFICATION(DerivatorVector, dg::Vector)
-DECLARE_SPECIFICATION(DerivatorMatrix, dg::Matrix)
+DECLARE_SPECIFICATION(DerivatorVector, dynamicgraph::Vector)
+DECLARE_SPECIFICATION(DerivatorMatrix, dynamicgraph::Matrix)
 DECLARE_SPECIFICATION(DerivatorVectorQuaternion, VectorQuaternion)
 } /* namespace sot */
 } /* namespace dynamicgraph */
diff --git a/include/sot/core/derivator.hh b/include/sot/core/derivator.hh
index 883c141a1daefd5d3e3b839198c10091e452c86e..82a7413ad017022e87fd81bd36bad0a335ca977b 100644
--- a/include/sot/core/derivator.hh
+++ b/include/sot/core/derivator.hh
@@ -29,13 +29,12 @@
 
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
 
 /* --------------------------------------------------------------------- */
 /* --- CLASS ----------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-template <class T> class Derivator : public dg::Entity {
+template <class T> class Derivator : public dynamicgraph::Entity {
   DYNAMIC_GRAPH_ENTITY_DECL();
 
 protected:
@@ -48,7 +47,7 @@ public: /* --- CONSTRUCTION --- */
   static std::string getTypeName(void) { return "Unknown"; }
 
   Derivator(const std::string &name)
-      : dg::Entity(name), memory(), initialized(false),
+      : dynamicgraph::Entity(name), memory(), initialized(false),
         timestep(TIMESTEP_DEFAULT),
         SIN(NULL, "sotDerivator<" + getTypeName() + ">(" + name + ")::input(" +
                       getTypeName() + ")::sin"),
@@ -65,9 +64,9 @@ public: /* --- CONSTRUCTION --- */
   virtual ~Derivator(void){};
 
 public: /* --- SIGNAL --- */
-  dg::SignalPtr<T, int> SIN;
-  dg::SignalTimeDependent<T, int> SOUT;
-  dg::Signal<double, int> timestepSIN;
+  dynamicgraph::SignalPtr<T, int> SIN;
+  dynamicgraph::SignalTimeDependent<T, int> SOUT;
+  dynamicgraph::Signal<double, int> timestepSIN;
 
 protected:
   T &computeDerivation(T &res, int time) {
diff --git a/include/sot/core/device.hh b/include/sot/core/device.hh
index 4ff081192d7db3052f8f1bd071fe68aa00d7867e..9cb5c266cf3e8938791d36476bdb975063785c53 100644
--- a/include/sot/core/device.hh
+++ b/include/sot/core/device.hh
@@ -17,7 +17,7 @@
 
 /* -- MaaL --- */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
+
 /* SOT */
 #include "sot/core/api.hh"
 #include "sot/core/periodic-call.hh"
@@ -55,10 +55,10 @@ public:
   };
 
 protected:
-  dg::Vector state_;
-  dg::Vector velocity_;
+  dynamicgraph::Vector state_;
+  dynamicgraph::Vector velocity_;
   bool sanityCheck_;
-  dg::Vector vel_control_;
+  dynamicgraph::Vector vel_control_;
   ControlInput controlInputType_;
   bool withForceSignals[4];
   PeriodicCall periodicCallBefore_;
@@ -81,9 +81,9 @@ public:
   virtual ~Device();
 
   virtual void setStateSize(const unsigned int &size);
-  virtual void setState(const dg::Vector &st);
+  virtual void setState(const dynamicgraph::Vector &st);
   void setVelocitySize(const unsigned int &size);
-  virtual void setVelocity(const dg::Vector &vel);
+  virtual void setVelocity(const dynamicgraph::Vector &vel);
   virtual void setSecondOrderIntegration();
   virtual void setNoIntegration();
   virtual void setControlInputType(const std::string &cit);
@@ -107,20 +107,20 @@ public: /* --- DISPLAY --- */
   }
 
 public: /* --- SIGNALS --- */
-  dynamicgraph::SignalPtr<dg::Vector, int> controlSIN;
-  dynamicgraph::SignalPtr<dg::Vector, int> attitudeSIN;
-  dynamicgraph::SignalPtr<dg::Vector, int> zmpSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> controlSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> attitudeSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> zmpSIN;
 
   /// \name Device current state.
   /// \{
-  dynamicgraph::Signal<dg::Vector, int> stateSOUT;
-  dynamicgraph::Signal<dg::Vector, int> velocitySOUT;
+  dynamicgraph::Signal<dynamicgraph::Vector, int> stateSOUT;
+  dynamicgraph::Signal<dynamicgraph::Vector, int> velocitySOUT;
   dynamicgraph::Signal<MatrixRotation, int> attitudeSOUT;
   /*! \brief The current state of the robot from the command viewpoint. */
-  dynamicgraph::Signal<dg::Vector, int> motorcontrolSOUT;
-  dynamicgraph::Signal<dg::Vector, int> previousControlSOUT;
+  dynamicgraph::Signal<dynamicgraph::Vector, int> motorcontrolSOUT;
+  dynamicgraph::Signal<dynamicgraph::Vector, int> previousControlSOUT;
   /*! \brief The ZMP reference send by the previous controller. */
-  dynamicgraph::Signal<dg::Vector, int> ZMPPreviousControllerSOUT;
+  dynamicgraph::Signal<dynamicgraph::Vector, int> ZMPPreviousControllerSOUT;
   /// \}
 
   /// \name Real robot current state
@@ -129,19 +129,19 @@ public: /* --- SIGNALS --- */
   /// does *not* match the state control input signal.
   /// \{
   /// Motor positions
-  dynamicgraph::Signal<dg::Vector, int> robotState_;
+  dynamicgraph::Signal<dynamicgraph::Vector, int> robotState_;
   /// Motor velocities
-  dynamicgraph::Signal<dg::Vector, int> robotVelocity_;
+  dynamicgraph::Signal<dynamicgraph::Vector, int> robotVelocity_;
   /// The force torque sensors
-  dynamicgraph::Signal<dg::Vector, int> *forcesSOUT[4];
+  dynamicgraph::Signal<dynamicgraph::Vector, int> *forcesSOUT[4];
   /// Motor torques
   /// \todo why pseudo ?
-  dynamicgraph::Signal<dg::Vector, int> pseudoTorqueSOUT;
+  dynamicgraph::Signal<dynamicgraph::Vector, int> pseudoTorqueSOUT;
   /// \}
 
 protected:
   /// Compute roll pitch yaw angles of freeflyer joint.
-  void integrateRollPitchYaw(dg::Vector &state, const dg::Vector &control,
+  void integrateRollPitchYaw(dynamicgraph::Vector &state, const dynamicgraph::Vector &control,
                              double dt);
   /// Store Position of free flyer joint
   MatrixHomogeneous ffPose_;
@@ -164,13 +164,13 @@ protected:
   const MatrixHomogeneous &freeFlyerPose() const;
 
 public:
-  virtual void setRoot(const dg::Matrix &root);
+  virtual void setRoot(const dynamicgraph::Matrix &root);
 
   virtual void setRoot(const MatrixHomogeneous &worldMwaist);
 
 private:
   // Intermediate variable to avoid dynamic allocation
-  dg::Vector forceZero6;
+  dynamicgraph::Vector forceZero6;
 };
 } // namespace sot
 } // namespace dynamicgraph
diff --git a/include/sot/core/exp-moving-avg.hh b/include/sot/core/exp-moving-avg.hh
index 6857cc119a56efd7e56bb0de912421ebbb09c95f..2ed1d42528e874041412611f85588a624a042660 100644
--- a/include/sot/core/exp-moving-avg.hh
+++ b/include/sot/core/exp-moving-avg.hh
@@ -18,7 +18,6 @@
 #include <dynamic-graph/signal-time-dependent.h>
 #include <sot/core/config.hh>
 
-namespace dg = ::dynamicgraph;
 
 namespace dynamicgraph {
 namespace sot {
@@ -35,9 +34,9 @@ class SOT_CORE_DLLAPI ExpMovingAvg : public Entity {
   DYNAMIC_GRAPH_ENTITY_DECL();
 
 public:
-  SignalPtr<dg::Vector, int> updateSIN;
+  SignalPtr<dynamicgraph::Vector, int> updateSIN;
   SignalTimeDependent<int, int> refresherSINTERN;
-  SignalTimeDependent<dg::Vector, int> averageSOUT;
+  SignalTimeDependent<dynamicgraph::Vector, int> averageSOUT;
 
 public:
   ExpMovingAvg(const std::string &n);
@@ -46,9 +45,9 @@ public:
   void setAlpha(const double &alpha_);
 
 protected:
-  dg::Vector &update(dg::Vector &res, const int &inTime);
+  dynamicgraph::Vector &update(dynamicgraph::Vector &res, const int &inTime);
 
-  dg::Vector average;
+  dynamicgraph::Vector average;
 
   double alpha;
   bool init;
diff --git a/include/sot/core/feature-1d.hh b/include/sot/core/feature-1d.hh
index 9eef46551dfa06695e31e916bf8dddd485106ab5..23705f190b10a3b82e8ab91b9c126f4db273b89f 100644
--- a/include/sot/core/feature-1d.hh
+++ b/include/sot/core/feature-1d.hh
@@ -38,7 +38,6 @@
 
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
 /*!
   \class Feature1D
   \brief Simple test: the task is defined to be e_2 = .5 . e'.e, with
@@ -65,10 +64,10 @@ public:
     @{
    */
   /*! \brief Input for the error. */
-  dg::SignalPtr<dg::Vector, int> errorSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> errorSIN;
 
   /*! \brief Input for the Jacobian. */
-  dg::SignalPtr<dg::Matrix, int> jacobianSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Matrix, int> jacobianSIN;
 
   /*! @} */
 
@@ -99,10 +98,10 @@ public:
 
   /*! \brief Compute the error between the desired value and the value itself.
    */
-  virtual dg::Vector &computeError(dg::Vector &res, int time);
+  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time);
 
   /*! \brief Compute the Jacobian of the value according to the robot state.. */
-  virtual dg::Matrix &computeJacobian(dg::Matrix &res, int time);
+  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time);
 
   /*! @} */
 
diff --git a/include/sot/core/feature-joint-limits.hh b/include/sot/core/feature-joint-limits.hh
index fbb67c1a5d1e9b41b5d04ff064b80cedd4276cce..8a11cb1ed320d842ed797dafab4c4c3b5e4db1e2 100644
--- a/include/sot/core/feature-joint-limits.hh
+++ b/include/sot/core/feature-joint-limits.hh
@@ -38,7 +38,6 @@
 
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
 
 /*!
   \class FeatureJointLimits
@@ -62,10 +61,10 @@ protected:
 
   /* --- SIGNALS ------------------------------------------------------------ */
 public:
-  dg::SignalPtr<dg::Vector, int> jointSIN;
-  dg::SignalPtr<dg::Vector, int> upperJlSIN;
-  dg::SignalPtr<dg::Vector, int> lowerJlSIN;
-  dg::SignalTimeDependent<dg::Vector, int> widthJlSINTERN;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> jointSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> upperJlSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> lowerJlSIN;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> widthJlSINTERN;
 
   using FeatureAbstract::selectionSIN;
 
@@ -84,9 +83,9 @@ public:
 
   virtual unsigned int &getDimension(unsigned int &dim, int time);
 
-  virtual dg::Vector &computeError(dg::Vector &res, int time);
-  virtual dg::Matrix &computeJacobian(dg::Matrix &res, int time);
-  dg::Vector &computeWidthJl(dg::Vector &res, const int &time);
+  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time);
+  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time);
+  dynamicgraph::Vector &computeWidthJl(dynamicgraph::Vector &res, const int &time);
 
   /** Static Feature selection. */
   inline static Flags selectActuated(void);
diff --git a/include/sot/core/feature-line-distance.hh b/include/sot/core/feature-line-distance.hh
index 37034c4a528eb9b2534f5068794ee791cc5ea6c4..c618cd9e9d0de169d46f5fb26aef3507fb7ae150 100644
--- a/include/sot/core/feature-line-distance.hh
+++ b/include/sot/core/feature-line-distance.hh
@@ -38,7 +38,6 @@
 
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
 
 /*!
   \class FeatureLineDistance
@@ -54,11 +53,11 @@ public:
 protected:
   /* --- SIGNALS ------------------------------------------------------------ */
 public:
-  dg::SignalPtr<MatrixHomogeneous, int> positionSIN;
-  dg::SignalPtr<dg::Matrix, int> articularJacobianSIN;
-  dg::SignalPtr<dg::Vector, int> positionRefSIN;
-  dg::SignalPtr<dg::Vector, int> vectorSIN;
-  dg::SignalTimeDependent<dg::Vector, int> lineSOUT;
+  dynamicgraph::SignalPtr<MatrixHomogeneous, int> positionSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Matrix, int> articularJacobianSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> positionRefSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> vectorSIN;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> lineSOUT;
 
   using FeatureAbstract::errorSOUT;
   using FeatureAbstract::jacobianSOUT;
@@ -76,9 +75,9 @@ public:
 
   virtual unsigned int &getDimension(unsigned int &dim, int time);
 
-  virtual dg::Vector &computeError(dg::Vector &res, int time);
-  virtual dg::Matrix &computeJacobian(dg::Matrix &res, int time);
-  dg::Vector &computeLineCoordinates(dg::Vector &cood, int time);
+  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time);
+  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time);
+  dynamicgraph::Vector &computeLineCoordinates(dynamicgraph::Vector &cood, int time);
 
   virtual void display(std::ostream &os) const;
 };
diff --git a/include/sot/core/feature-point6d-relative.hh b/include/sot/core/feature-point6d-relative.hh
index 9cf4afa83217379284c89a39db10ac00458c07e6..e1d0730705e536e71a3d74dbfe17605ec9866b2b 100644
--- a/include/sot/core/feature-point6d-relative.hh
+++ b/include/sot/core/feature-point6d-relative.hh
@@ -40,7 +40,6 @@
 
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
 
 /*!
   \class FeaturePoint6dRelative
@@ -56,23 +55,23 @@ public:
   virtual const std::string &getClassName(void) const { return CLASS_NAME; }
 
 protected:
-  dg::Matrix L;
+  dynamicgraph::Matrix L;
 
   /* --- SIGNALS ------------------------------------------------------------ */
 public:
-  dg::SignalPtr<MatrixHomogeneous, int> positionReferenceSIN;
-  dg::SignalPtr<dg::Matrix, int> articularJacobianReferenceSIN;
+  dynamicgraph::SignalPtr<MatrixHomogeneous, int> positionReferenceSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Matrix, int> articularJacobianReferenceSIN;
 
-  /*! dg::Signals related to the computation of the derivative of
+  /*! dynamicgraph::Signals related to the computation of the derivative of
     the error
   @{ */
 
-  /*! dg::Signals giving the derivative of the input signals.
+  /*! dynamicgraph::Signals giving the derivative of the input signals.
     @{*/
   /*! Derivative of the relative position. */
-  dg::SignalPtr<MatrixHomogeneous, int> dotpositionSIN;
+  dynamicgraph::SignalPtr<MatrixHomogeneous, int> dotpositionSIN;
   /*! Derivative of the reference position. */
-  dg::SignalPtr<MatrixHomogeneous, int> dotpositionReferenceSIN;
+  dynamicgraph::SignalPtr<MatrixHomogeneous, int> dotpositionReferenceSIN;
   /*! @} */
 
   using FeaturePoint6d::getReference;
@@ -81,9 +80,9 @@ public:
   FeaturePoint6dRelative(const std::string &name);
   virtual ~FeaturePoint6dRelative(void) {}
 
-  virtual dg::Vector &computeError(dg::Vector &res, int time);
-  virtual dg::Vector &computeErrorDot(dg::Vector &res, int time);
-  virtual dg::Matrix &computeJacobian(dg::Matrix &res, int time);
+  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time);
+  virtual dynamicgraph::Vector &computeErrorDot(dynamicgraph::Vector &res, int time);
+  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time);
 
   virtual void display(std::ostream &os) const;
 
diff --git a/include/sot/core/feature-point6d.hh b/include/sot/core/feature-point6d.hh
index 97b39443e6200ef8797dd26d41255d00a02d0224..e2624f0712e26558451cbadfd1368097ac5ac8d2 100644
--- a/include/sot/core/feature-point6d.hh
+++ b/include/sot/core/feature-point6d.hh
@@ -40,7 +40,6 @@
 
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
 
 /*!
   \class FeaturePoint6d
@@ -71,9 +70,9 @@ private:
 
   /* --- SIGNALS ------------------------------------------------------------ */
 public:
-  dg::SignalPtr<MatrixHomogeneous, int> positionSIN;
-  dg::SignalPtr<dg::Vector, int> velocitySIN;
-  dg::SignalPtr<dg::Matrix, int> articularJacobianSIN;
+  dynamicgraph::SignalPtr<MatrixHomogeneous, int> positionSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> velocitySIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Matrix, int> articularJacobianSIN;
 
   using FeatureAbstract::errorSOUT;
   using FeatureAbstract::jacobianSOUT;
@@ -90,9 +89,9 @@ public:
 
   virtual unsigned int &getDimension(unsigned int &dim, int time);
 
-  virtual dg::Vector &computeError(dg::Vector &res, int time);
-  virtual dg::Vector &computeErrordot(dg::Vector &res, int time);
-  virtual dg::Matrix &computeJacobian(dg::Matrix &res, int time);
+  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time);
+  virtual dynamicgraph::Vector &computeErrordot(dynamicgraph::Vector &res, int time);
+  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time);
 
   /** Static Feature selection. */
   inline static Flags selectX(void) { return FLAG_LINE_1; }
diff --git a/include/sot/core/feature-pose.hh b/include/sot/core/feature-pose.hh
index 6ca40ac71d5fe621344667b354be28613a03afe4..a55d842083d067abf2febb0593260e483011cf1a 100644
--- a/include/sot/core/feature-pose.hh
+++ b/include/sot/core/feature-pose.hh
@@ -24,7 +24,6 @@
 
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
 
 /// Enum used to specify what difference operation is used in FeaturePose.
 enum Representation_t { SE3Representation, R3xSO3Representation };
@@ -71,23 +70,23 @@ public:
     @{
   */
   /// Input pose of <em>Joint A</em> wrt to world frame.
-  dg::SignalPtr<MatrixHomogeneous, int> oMja;
+  dynamicgraph::SignalPtr<MatrixHomogeneous, int> oMja;
   /// Input pose of <em>Frame A</em> wrt to <em>Joint A</em>.
-  dg::SignalPtr<MatrixHomogeneous, int> jaMfa;
+  dynamicgraph::SignalPtr<MatrixHomogeneous, int> jaMfa;
   /// Input pose of <em>Joint B</em> wrt to world frame.
-  dg::SignalPtr<MatrixHomogeneous, int> oMjb;
+  dynamicgraph::SignalPtr<MatrixHomogeneous, int> oMjb;
   /// Input pose of <em>Frame B</em> wrt to <em>Joint B</em>.
-  dg::SignalPtr<MatrixHomogeneous, int> jbMfb;
+  dynamicgraph::SignalPtr<MatrixHomogeneous, int> jbMfb;
   /// Jacobian of the input <em>Joint A</em>, expressed in <em>Joint A</em>
-  dg::SignalPtr<Matrix, int> jaJja;
+  dynamicgraph::SignalPtr<Matrix, int> jaJja;
   /// Jacobian of the input <em>Joint B</em>, expressed in <em>Joint B</em>
-  dg::SignalPtr<Matrix, int> jbJjb;
+  dynamicgraph::SignalPtr<Matrix, int> jbJjb;
 
   /// The desired pose of <em>Frame B</em> wrt to <em>Frame A</em>.
-  dg::SignalPtr<MatrixHomogeneous, int> faMfbDes;
+  dynamicgraph::SignalPtr<MatrixHomogeneous, int> faMfbDes;
   /// The desired velocity of <em>Frame B</em> wrt to <em>Frame A</em>. The
   /// value is expressed in <em>Frame A</em>.
-  dg::SignalPtr<Vector, int> faNufafbDes;
+  dynamicgraph::SignalPtr<Vector, int> faNufafbDes;
   /*! @} */
 
   /*! \name Output signals
@@ -121,21 +120,21 @@ public:
   virtual unsigned int &getDimension(unsigned int &dim, int time);
 
   /// Computes \f$ {}^oM^{-1}_{fa} {}^oM_{fb} \ominus {}^{fa}M^*_{fb} \f$
-  virtual dg::Vector &computeError(dg::Vector &res, int time);
+  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time);
   /// Computes \f$ \frac{\partial\ominus}{\partial b} X {}^{fa}\nu^*_{fafb} \f$.
   /// There are two different cases, depending on the representation:
   /// - R3xSO3Representation: \f$ X = \left( \begin{array}{cc} I_3 & [
   /// {}^{fa}t_{fb} ] \\ 0_3 & {{}^{fa}R^*_{fb}}^T \end{array} \right) \f$
   /// - SE3Representation: \f$ X = {{}^{fa}X^*_{fb}}^{-1} \f$ (see
   /// pinocchio::SE3Base<Scalar,Options>::toActionMatrix)
-  virtual dg::Vector &computeErrorDot(dg::Vector &res, int time);
+  virtual dynamicgraph::Vector &computeErrorDot(dynamicgraph::Vector &res, int time);
   /// Computes \f$ \frac{\partial\ominus}{\partial b} Y \left( {{}^{fb}X_{jb}}
   /// {}^{jb}J_{jb} - {{}^{fb}X_{ja}} {}^{ja}J_{ja} \right) \f$. There are two
   /// different cases, depending on the representation:
   /// - R3xSO3Representation: \f$ Y = \left( \begin{array}{cc} {{}^{fa}R_{fb}} &
   /// 0_3 \\ 0_3 & I_3 \end{array} \right) \f$
   /// - SE3Representation: \f$ Y = I_6 \f$
-  virtual dg::Matrix &computeJacobian(dg::Matrix &res, int time);
+  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time);
 
   /** Static Feature selection. */
   inline static Flags selectX(void) { return FLAG_LINE_1; }
diff --git a/include/sot/core/feature-task.hh b/include/sot/core/feature-task.hh
index 66df85ac334dcd504c1010b08e98cdebef37a68d..d1f33f40a0d66c73cb94d601f33bb3cdde3e69f8 100644
--- a/include/sot/core/feature-task.hh
+++ b/include/sot/core/feature-task.hh
@@ -39,7 +39,7 @@
 
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
+
 
 class SOTFEATURETASK_EXPORT FeatureTask : public FeatureGeneric {
 
diff --git a/include/sot/core/feature-vector3.hh b/include/sot/core/feature-vector3.hh
index d5d42ebaed3b5e960dfa70f95036d6bb2f298bc3..43402f531c45b40728577d106fe6b25db108d579 100644
--- a/include/sot/core/feature-vector3.hh
+++ b/include/sot/core/feature-vector3.hh
@@ -39,7 +39,6 @@
 
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
 
 /*!
   \class FeatureVector3
@@ -56,10 +55,10 @@ public:
 protected:
   /* --- SIGNALS ------------------------------------------------------------ */
 public:
-  dg::SignalPtr<dg::Vector, int> vectorSIN;
-  dg::SignalPtr<MatrixHomogeneous, int> positionSIN;
-  dg::SignalPtr<dg::Matrix, int> articularJacobianSIN;
-  dg::SignalPtr<dg::Vector, int> positionRefSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> vectorSIN;
+  dynamicgraph::SignalPtr<MatrixHomogeneous, int> positionSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Matrix, int> articularJacobianSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> positionRefSIN;
 
   using FeatureAbstract::errorSOUT;
   using FeatureAbstract::jacobianSOUT;
@@ -71,8 +70,8 @@ public:
 
   virtual unsigned int &getDimension(unsigned int &dim, int time);
 
-  virtual dg::Vector &computeError(dg::Vector &res, int time);
-  virtual dg::Matrix &computeJacobian(dg::Matrix &res, int time);
+  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time);
+  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time);
 
   virtual void display(std::ostream &os) const;
 };
diff --git a/include/sot/core/feature-visual-point.hh b/include/sot/core/feature-visual-point.hh
index 7bebd3d2e4ef96536d51a9d1a9e0a4e8b2e8aa6e..ffdc37c5f6041608957d9bf2b23fe42883c95b55 100644
--- a/include/sot/core/feature-visual-point.hh
+++ b/include/sot/core/feature-visual-point.hh
@@ -38,7 +38,6 @@
 
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
 
 /*!
   \class FeatureVisualPoint
@@ -53,15 +52,15 @@ public:
   virtual const std::string &getClassName(void) const { return CLASS_NAME; }
 
 protected:
-  dg::Matrix L;
+  dynamicgraph::Matrix L;
 
   /* --- SIGNALS ------------------------------------------------------------ */
 public:
-  dg::SignalPtr<dg::Vector, int> xySIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> xySIN;
   /** FeatureVisualPoint depth (required to compute the interaction matrix)
    * default Z = 1m. */
-  dg::SignalPtr<double, int> ZSIN;
-  dg::SignalPtr<dg::Matrix, int> articularJacobianSIN;
+  dynamicgraph::SignalPtr<double, int> ZSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Matrix, int> articularJacobianSIN;
 
   using FeatureAbstract::errorSOUT;
   using FeatureAbstract::jacobianSOUT;
@@ -75,8 +74,8 @@ public:
 
   virtual unsigned int &getDimension(unsigned int &dim, int time);
 
-  virtual dg::Vector &computeError(dg::Vector &res, int time);
-  virtual dg::Matrix &computeJacobian(dg::Matrix &res, int time);
+  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time);
+  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time);
 
   /** Static Feature selection. */
   inline static Flags selectX(void) { return FLAG_LINE_1; }
diff --git a/include/sot/core/fir-filter.hh b/include/sot/core/fir-filter.hh
index b543dbdd807a15db5c78c4a71423424404a36bfe..3e563b36e747aa8e4833f5c3b2e865d1bcb84e87 100644
--- a/include/sot/core/fir-filter.hh
+++ b/include/sot/core/fir-filter.hh
@@ -21,7 +21,6 @@
 #include <dynamic-graph/command-setter.h>
 #include <dynamic-graph/entity.h>
 
-namespace dg = dynamicgraph;
 
 namespace dynamicgraph {
 namespace sot {
diff --git a/include/sot/core/gain-adaptive.hh b/include/sot/core/gain-adaptive.hh
index ffc643284d1c7f3476380e78de589a7f69ef7855..7482962de6ebfa4bda314817136ba27aac45f5d4 100644
--- a/include/sot/core/gain-adaptive.hh
+++ b/include/sot/core/gain-adaptive.hh
@@ -16,7 +16,6 @@
 
 /* Matrix */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
 
 /* SOT */
 #include <dynamic-graph/all-signals.h>
@@ -42,7 +41,6 @@ namespace dg = dynamicgraph;
 
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
 
 /** Exponentially decreasing gain.
  * It follows the law \f[ g(e) = a \exp (-b ||e||) + c \f].
@@ -52,7 +50,7 @@ namespace dg = dynamicgraph;
  * - \f$ b = 0   \f$,
  * - \f$ c = 0.1 \f$.
  */
-class SOTGAINADAPTATIVE_EXPORT GainAdaptive : public dg::Entity {
+class SOTGAINADAPTATIVE_EXPORT GainAdaptive : public dynamicgraph::Entity {
 
 public: /* --- CONSTANTS --- */
   /* Default values. */
@@ -119,8 +117,8 @@ public: /* --- INIT --- */
   void forceConstant(void);
 
 public: /* --- SIGNALS --- */
-  dg::SignalPtr<dg::Vector, int> errorSIN;
-  dg::SignalTimeDependent<double, int> gainSOUT;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> errorSIN;
+  dynamicgraph::SignalTimeDependent<double, int> gainSOUT;
 
 protected:
   double &computeGain(double &res, int t);
diff --git a/include/sot/core/gain-hyperbolic.hh b/include/sot/core/gain-hyperbolic.hh
index 3694eaef8f9b414759996c5468c2c323a4228290..abba25c40fe452c950620074070203937c214269 100644
--- a/include/sot/core/gain-hyperbolic.hh
+++ b/include/sot/core/gain-hyperbolic.hh
@@ -16,7 +16,6 @@
 
 /* Matrix */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
 
 /* SOT */
 #include <dynamic-graph/all-signals.h>
@@ -42,7 +41,6 @@ namespace dg = dynamicgraph;
 
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
 
 /** \brief Hyperbolic gain.
  * It follows the law \f[ g(e) = a \frac{\tanh(-b(||e|| - d)) + 1}{2} + c \f]
@@ -52,7 +50,7 @@ namespace dg = dynamicgraph;
  * - \f$ c = 0.1 \f$,
  * - \f$ d = 0   \f$.
  */
-class SOTGAINHYPERBOLIC_EXPORT GainHyperbolic : public dg::Entity {
+class SOTGAINHYPERBOLIC_EXPORT GainHyperbolic : public dynamicgraph::Entity {
 
 public: /* --- CONSTANTS --- */
   /* Default values. */
@@ -94,8 +92,8 @@ public: /* --- INIT --- */
   void forceConstant(void);
 
 public: /* --- SIGNALS --- */
-  dg::SignalPtr<dg::Vector, int> errorSIN;
-  dg::SignalTimeDependent<double, int> gainSOUT;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> errorSIN;
+  dynamicgraph::SignalTimeDependent<double, int> gainSOUT;
 
 protected:
   double &computeGain(double &res, int t);
diff --git a/include/sot/core/gradient-ascent.hh b/include/sot/core/gradient-ascent.hh
index fba98c76d83f2cde41cc52a4ab9bfb867d9ab5fe..8eff01ba5acaf21bbeeb901ee479077695520e02 100644
--- a/include/sot/core/gradient-ascent.hh
+++ b/include/sot/core/gradient-ascent.hh
@@ -18,7 +18,6 @@
 #include <dynamic-graph/signal-time-dependent.h>
 #include <sot/core/config.hh>
 
-namespace dg = ::dynamicgraph;
 
 namespace dynamicgraph {
 namespace sot {
@@ -35,19 +34,19 @@ class SOT_CORE_DLLAPI GradientAscent : public Entity {
   DYNAMIC_GRAPH_ENTITY_DECL();
 
 public:
-  SignalPtr<dg::Vector, int> gradientSIN;
+  SignalPtr<dynamicgraph::Vector, int> gradientSIN;
   SignalPtr<double, int> learningRateSIN;
   SignalTimeDependent<int, int> refresherSINTERN;
-  SignalTimeDependent<dg::Vector, int> valueSOUT;
+  SignalTimeDependent<dynamicgraph::Vector, int> valueSOUT;
 
 public:
   GradientAscent(const std::string &n);
   virtual ~GradientAscent(void);
 
 protected:
-  dg::Vector &update(dg::Vector &res, const int &inTime);
+  dynamicgraph::Vector &update(dynamicgraph::Vector &res, const int &inTime);
 
-  dg::Vector value;
+  dynamicgraph::Vector value;
 
   double alpha;
   bool init;
diff --git a/include/sot/core/gripper-control.hh b/include/sot/core/gripper-control.hh
index 36739641563b257924e921f1dcad466a9427110b..61189295a809e6c0b7f2fe19f1b292ee44cc6b60 100644
--- a/include/sot/core/gripper-control.hh
+++ b/include/sot/core/gripper-control.hh
@@ -16,7 +16,6 @@
 
 /* Matrix */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
 
 /* SOT */
 #include <dynamic-graph/all-signals.h>
@@ -47,7 +46,6 @@ namespace dg = dynamicgraph;
 namespace dynamicgraph {
 namespace sot {
 
-namespace dg = dynamicgraph;
 
 /*! \brief The goal of this entity is to ensure that the maximal torque will not
  * be exceeded during a grasping task.
@@ -60,7 +58,7 @@ protected:
   double offset;
   static const double OFFSET_DEFAULT;
   //! \brief The multiplication
-  dg::Vector factor;
+  dynamicgraph::Vector factor;
 
 public:
   GripperControl(void);
@@ -68,30 +66,30 @@ public:
   //! \brief Computes the
   // if the torque limit is reached, the normalized position is reduced by
   // (offset)
-  void computeIncrement(const dg::Vector &torques,
-                        const dg::Vector &torqueLimits,
-                        const dg::Vector &currentNormVel);
+  void computeIncrement(const dynamicgraph::Vector &torques,
+                        const dynamicgraph::Vector &torqueLimits,
+                        const dynamicgraph::Vector &currentNormVel);
 
   //! \brief
-  dg::Vector &computeDesiredPosition(const dg::Vector &currentPos,
-                                     const dg::Vector &desiredPos,
-                                     const dg::Vector &torques,
-                                     const dg::Vector &torqueLimits,
-                                     dg::Vector &referencePos);
+  dynamicgraph::Vector &computeDesiredPosition(const dynamicgraph::Vector &currentPos,
+                                     const dynamicgraph::Vector &desiredPos,
+                                     const dynamicgraph::Vector &torques,
+                                     const dynamicgraph::Vector &torqueLimits,
+                                     dynamicgraph::Vector &referencePos);
 
   /*! \brief select only some of the values of the vector fullsize,
    *   based on the Flags vector.
    */
 
-  static dg::Vector &selector(const dg::Vector &fullsize, const Flags &selec,
-                              dg::Vector &desPos);
+  static dynamicgraph::Vector &selector(const dynamicgraph::Vector &fullsize, const Flags &selec,
+                              dynamicgraph::Vector &desPos);
 };
 
 /* --------------------------------------------------------------------- */
 /* --- PLUGIN ---------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-class SOTGRIPPERCONTROL_EXPORT GripperControlPlugin : public dg::Entity,
+class SOTGRIPPERCONTROL_EXPORT GripperControlPlugin : public dynamicgraph::Entity,
                                                       public GripperControl {
   DYNAMIC_GRAPH_ENTITY_DECL();
 
@@ -107,22 +105,22 @@ public: /* --- CONSTRUCTION --- */
 
 public: /* --- SIGNAL --- */
   /* --- INPUTS --- */
-  dg::SignalPtr<dg::Vector, int> positionSIN;
-  dg::SignalPtr<dg::Vector, int> positionDesSIN;
-  dg::SignalPtr<dg::Vector, int> torqueSIN;
-  dg::SignalPtr<dg::Vector, int> torqueLimitSIN;
-  dg::SignalPtr<Flags, int> selectionSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> positionSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> positionDesSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> torqueSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> torqueLimitSIN;
+  dynamicgraph::SignalPtr<Flags, int> selectionSIN;
 
   /* --- INTERMEDIARY --- */
-  dg::SignalPtr<dg::Vector, int> positionFullSizeSIN;
-  dg::SignalTimeDependent<dg::Vector, int> positionReduceSOUT;
-  dg::SignalPtr<dg::Vector, int> torqueFullSizeSIN;
-  dg::SignalTimeDependent<dg::Vector, int> torqueReduceSOUT;
-  dg::SignalPtr<dg::Vector, int> torqueLimitFullSizeSIN;
-  dg::SignalTimeDependent<dg::Vector, int> torqueLimitReduceSOUT;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> positionFullSizeSIN;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> positionReduceSOUT;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> torqueFullSizeSIN;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> torqueReduceSOUT;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> torqueLimitFullSizeSIN;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> torqueLimitReduceSOUT;
 
   /* --- OUTPUTS --- */
-  dg::SignalTimeDependent<dg::Vector, int> desiredPositionSOUT;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> desiredPositionSOUT;
 
 public: /* --- COMMANDLINE --- */
   void initCommands();
diff --git a/include/sot/core/integrator-abstract-impl.hh b/include/sot/core/integrator-abstract-impl.hh
index 2f4b15bbd582de9196643ba6b2df12a21196b426..25df9ee43fef2e0347b7392612fab7d5b7a22dbb 100644
--- a/include/sot/core/integrator-abstract-impl.hh
+++ b/include/sot/core/integrator-abstract-impl.hh
@@ -46,7 +46,7 @@
 namespace dynamicgraph {
 namespace sot {
 DECLARE_SPECIFICATION(IntegratorAbstractDouble, double, double)
-DECLARE_SPECIFICATION(IntegratorAbstractVector, dg::Vector, dg::Matrix)
+DECLARE_SPECIFICATION(IntegratorAbstractVector, dynamicgraph::Vector, dynamicgraph::Matrix)
 } // namespace sot
 } // namespace dynamicgraph
 #endif // #ifndef  __SOT_MAILBOX_HH
diff --git a/include/sot/core/integrator-abstract.hh b/include/sot/core/integrator-abstract.hh
index b62a63211cb57fe14ac118fc6a4ae777975a9f99..9dc9e35c13e576715305e158f6b98072896c7d22 100644
--- a/include/sot/core/integrator-abstract.hh
+++ b/include/sot/core/integrator-abstract.hh
@@ -34,7 +34,6 @@
 
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
 
 /*! \brief integrates an ODE. If Y is the output and X the input, the
  * following equation is integrated:
@@ -43,20 +42,20 @@ namespace dg = dynamicgraph;
  * function between X and Y, while the b_i are those of the numerator.
  */
 template <class sigT, class coefT>
-class IntegratorAbstract : public dg::Entity {
+class IntegratorAbstract : public dynamicgraph::Entity {
 public:
   IntegratorAbstract(const std::string &name)
-      : dg::Entity(name),
+      : dynamicgraph::Entity(name),
         SIN(NULL, "sotIntegratorAbstract(" + name + ")::input(vector)::sin"),
         SOUT(boost::bind(&IntegratorAbstract<sigT, coefT>::integrate, this, _1,
                          _2),
              SIN, "sotIntegratorAbstract(" + name + ")::output(vector)::sout") {
     signalRegistration(SIN << SOUT);
 
-    using namespace dg::command;
+    using namespace dynamicgraph::command;
 
     const std::string typeName =
-        Value::typeName(dg::command::ValueHelper<coefT>::TypeID);
+        Value::typeName(dynamicgraph::command::ValueHelper<coefT>::TypeID);
 
     addCommand(
         "pushNumCoef",
@@ -92,9 +91,9 @@ public:
   void popDenomCoef() { denominator.pop_back(); }
 
 public:
-  dg::SignalPtr<sigT, int> SIN;
+  dynamicgraph::SignalPtr<sigT, int> SIN;
 
-  dg::SignalTimeDependent<sigT, int> SOUT;
+  dynamicgraph::SignalTimeDependent<sigT, int> SOUT;
 
 protected:
   std::vector<coefT> numerator;
diff --git a/include/sot/core/integrator-euler.hh b/include/sot/core/integrator-euler.hh
index 97458eaa6a6c52a943d404fb10e7302cb13f5fe6..e808c9b3123c4ad5880641c3e7afcd4552bb1b63 100644
--- a/include/sot/core/integrator-euler.hh
+++ b/include/sot/core/integrator-euler.hh
@@ -25,7 +25,6 @@
 
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
 
 namespace internal {
 template <class coefT> bool integratorEulerCoeffIsIdentity(const coefT c) {
@@ -70,7 +69,7 @@ public:
                            ")::output(vector)::derivativesout") {
     this->signalRegistration(derivativeSOUT);
 
-    using namespace dg::command;
+    using namespace dynamicgraph::command;
 
     setSamplingPeriod(0.005);
 
@@ -97,7 +96,7 @@ protected:
   std::vector<sigT> inputMemory;
   std::vector<sigT> outputMemory;
 
-  dg::SignalTimeDependent<sigT, int> derivativeSOUT;
+  dynamicgraph::SignalTimeDependent<sigT, int> derivativeSOUT;
 
   double dt;
   double invdt;
@@ -152,7 +151,7 @@ public:
 
   sigT &derivative(sigT &res, int time) {
     if (outputMemory.size() < 2)
-      throw dg::ExceptionSignal(dg::ExceptionSignal::GENERIC,
+      throw dynamicgraph::ExceptionSignal(dynamicgraph::ExceptionSignal::GENERIC,
                                 "Integrator does not compute the derivative.");
 
     SOUT.recompute(time);
@@ -184,8 +183,8 @@ public:
 
     // Check that denominator.back is the identity
     if (!internal::integratorEulerCoeffIsIdentity(denominator.back()))
-      throw dg::ExceptionSignal(
-          dg::ExceptionSignal::GENERIC,
+      throw dynamicgraph::ExceptionSignal(
+          dynamicgraph::ExceptionSignal::GENERIC,
           "The coefficient of the highest order derivative of denominator "
           "should be 1 (the last pushDenomCoef should be the identity).");
   }
diff --git a/include/sot/core/joint-limitator.hh b/include/sot/core/joint-limitator.hh
index af4d2617c26e273a0b670d9a63a147863c5e0cdc..e3cce324402049073f8c808d3b4d97531ca93d5a 100644
--- a/include/sot/core/joint-limitator.hh
+++ b/include/sot/core/joint-limitator.hh
@@ -11,7 +11,6 @@
 #define SOT_FEATURE_JOINTLIMITS_HH
 // Matrix
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
 
 // SOT
 #include <dynamic-graph/all-signals.h>
@@ -30,32 +29,31 @@ namespace dg = dynamicgraph;
 
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
 
 /// \brief Filter control vector to avoid exceeding joint maximum values.
 ///
 /// This must be plugged between the entity producing the command
 /// (i.e. usually the sot) and the entity executing it (the device).
-class SOTJOINTLIMITATOR_EXPORT JointLimitator : public dg::Entity {
+class SOTJOINTLIMITATOR_EXPORT JointLimitator : public dynamicgraph::Entity {
   DYNAMIC_GRAPH_ENTITY_DECL();
 
 public:
   JointLimitator(const std::string &name);
   virtual ~JointLimitator() {}
 
-  virtual dg::Vector &computeControl(dg::Vector &res, int time);
-  dg::Vector &computeWidthJl(dg::Vector &res, const int &time);
+  virtual dynamicgraph::Vector &computeControl(dynamicgraph::Vector &res, int time);
+  dynamicgraph::Vector &computeWidthJl(dynamicgraph::Vector &res, const int &time);
 
   virtual void display(std::ostream &os) const;
 
   /// \name Signals
   /// \{
-  dg::SignalPtr<dg::Vector, int> jointSIN;
-  dg::SignalPtr<dg::Vector, int> upperJlSIN;
-  dg::SignalPtr<dg::Vector, int> lowerJlSIN;
-  dg::SignalPtr<dg::Vector, int> controlSIN;
-  dg::SignalTimeDependent<dg::Vector, int> controlSOUT;
-  dg::SignalTimeDependent<dg::Vector, int> widthJlSINTERN;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> jointSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> upperJlSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> lowerJlSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> controlSIN;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> controlSOUT;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> widthJlSINTERN;
   /// \}
 };
 } // end of namespace sot.
diff --git a/include/sot/core/joint-trajectory-entity.hh b/include/sot/core/joint-trajectory-entity.hh
index e435e495ef9bcb005dd4360725dd24377a1bbfb7..91a7aa75555d5e48599c50c439cb68727b642662 100644
--- a/include/sot/core/joint-trajectory-entity.hh
+++ b/include/sot/core/joint-trajectory-entity.hh
@@ -15,7 +15,7 @@
 
 // Maal
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
+
 // SOT
 #include <dynamic-graph/all-signals.h>
 #include <dynamic-graph/entity.h>
@@ -57,13 +57,13 @@ public:
   void loadFile(const std::string &name);
 
   /// \brief Return the next pose for the legs.
-  dg::Vector &getNextPosition(dg::Vector &pos, const int &time);
+  dynamicgraph::Vector &getNextPosition(dynamicgraph::Vector &pos, const int &time);
 
   /// \brief Return the next com.
-  dg::Vector &getNextCoM(dg::Vector &com, const int &time);
+  dynamicgraph::Vector &getNextCoM(dynamicgraph::Vector &com, const int &time);
 
   /// \brief Return the next cop.
-  dg::Vector &getNextCoP(dg::Vector &cop, const int &time);
+  dynamicgraph::Vector &getNextCoP(dynamicgraph::Vector &cop, const int &time);
 
   /// \brief Return the next waist.
   sot::MatrixHomogeneous &getNextWaist(sot::MatrixHomogeneous &waist,
@@ -74,7 +74,7 @@ public:
 
   /// \brief Convert a xyztheta vector into an homogeneous matrix
   sot::MatrixHomogeneous
-  XYZThetaToMatrixHomogeneous(const dg::Vector &xyztheta);
+  XYZThetaToMatrixHomogeneous(const dynamicgraph::Vector &xyztheta);
 
   /// \brief Perform one update of the signals.
   int &OneStepOfUpdate(int &dummy, const int &time);
@@ -102,13 +102,13 @@ public:
   SignalTimeDependent<Dummy, int> OneStepOfUpdateS;
 
   /// \brief Publish pose for each evaluation of the graph.
-  dynamicgraph::SignalTimeDependent<dg::Vector, int> positionSOUT;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> positionSOUT;
 
   /// \brief Publish com for each evaluation of the graph.
-  dynamicgraph::SignalTimeDependent<dg::Vector, int> comSOUT;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> comSOUT;
 
   /// \brief Publish zmp for each evaluation of the graph.
-  dynamicgraph::SignalTimeDependent<dg::Vector, int> zmpSOUT;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> zmpSOUT;
 
   /// \brief Publish waist for each evaluation of the graph.
   dynamicgraph::SignalTimeDependent<sot::MatrixHomogeneous, int> waistSOUT;
@@ -128,13 +128,13 @@ protected:
   timestamp traj_timestamp_;
 
   /// \brief Store the pos;
-  dg::Vector pose_;
+  dynamicgraph::Vector pose_;
 
   /// \brief Store the center of mass.
-  dg::Vector com_;
+  dynamicgraph::Vector com_;
 
   /// \brief Store the center of pressure ZMP.
-  dg::Vector cop_;
+  dynamicgraph::Vector cop_;
 
   /// \brief Store the waist position.
   sot::MatrixHomogeneous waist_;
diff --git a/include/sot/core/mailbox.hh b/include/sot/core/mailbox.hh
index d28b4b2b860c3857c8e6353554a31409039d6c98..0aab925afb83ab1108ba251ac4b4224ba60ad5b5 100644
--- a/include/sot/core/mailbox.hh
+++ b/include/sot/core/mailbox.hh
@@ -31,9 +31,8 @@
 namespace dynamicgraph {
 namespace sot {
 
-namespace dg = dynamicgraph;
 
-template <class Object> class Mailbox : public dg::Entity {
+template <class Object> class Mailbox : public dynamicgraph::Entity {
 public:
   static const std::string CLASS_NAME;
   virtual const std::string &getClassName(void) const { return CLASS_NAME; }
@@ -63,9 +62,9 @@ protected:
   bool update;
 
 public: /* --- SIGNALS --- */
-  dg::SignalTimeDependent<struct sotTimestampedObject, int> SOUT;
-  dg::SignalTimeDependent<Object, int> objSOUT;
-  dg::SignalTimeDependent<struct timeval, int> timeSOUT;
+  dynamicgraph::SignalTimeDependent<struct sotTimestampedObject, int> SOUT;
+  dynamicgraph::SignalTimeDependent<Object, int> objSOUT;
+  dynamicgraph::SignalTimeDependent<struct timeval, int> timeSOUT;
 };
 
 } /* namespace sot */
diff --git a/include/sot/core/mailbox.hxx b/include/sot/core/mailbox.hxx
index 747575852e5fa45b25e16b0b3dd1024291b15fcd..a34b4b77df295900598ec5f43d362a9911de6368 100644
--- a/include/sot/core/mailbox.hxx
+++ b/include/sot/core/mailbox.hxx
@@ -15,8 +15,6 @@
 namespace dynamicgraph {
 namespace sot {
 
-namespace dg = dynamicgraph;
-
 /* -------------------------------------------------------------------------- */
 /* --- CONSTRUCTION --------------------------------------------------------- */
 /* -------------------------------------------------------------------------- */
diff --git a/include/sot/core/matrix-constant.hh b/include/sot/core/matrix-constant.hh
index 29ba4eaabe4c19804e9674d919f1f5e812358c87..f8fc26be371b5e715ba6783baa58c154848ea3f4 100644
--- a/include/sot/core/matrix-constant.hh
+++ b/include/sot/core/matrix-constant.hh
@@ -12,7 +12,6 @@
 
 /* Matrix */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
 
 /* --------------------------------------------------------------------- */
 /* --- MATRIX ---------------------------------------------------------- */
@@ -36,14 +35,14 @@ public:
   int rows, cols;
   double color;
 
-  void setValue(const dg::Matrix &inValue);
+  void setValue(const dynamicgraph::Matrix &inValue);
 
 public:
   MatrixConstant(const std::string &name);
 
   virtual ~MatrixConstant(void) {}
 
-  SignalTimeDependent<dg::Matrix, int> SOUT;
+  SignalTimeDependent<dynamicgraph::Matrix, int> SOUT;
 };
 
 } // namespace sot
diff --git a/include/sot/core/memory-task-sot.hh b/include/sot/core/memory-task-sot.hh
index f88b5a39a397b5e6bae29095932479d7e66c4fe4..3fcb0f22e0caba799f86104a36328bb764cc1b0e 100644
--- a/include/sot/core/memory-task-sot.hh
+++ b/include/sot/core/memory-task-sot.hh
@@ -20,7 +20,6 @@
 
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
 
 class SOT_CORE_EXPORT MemoryTaskSOT : public TaskAbstract::MemoryTaskAbstract {
 public: //   protected:
@@ -30,10 +29,10 @@ public: //   protected:
       KernelConst_t;
 
   /* Internal memory to reduce the dynamic allocation at task resolution. */
-  dg::Vector err, tmpTask, tmpVar, tmpControl;
-  dg::Matrix Jt; //( nJ,mJ );
+  dynamicgraph::Vector err, tmpTask, tmpVar, tmpControl;
+  dynamicgraph::Matrix Jt; //( nJ,mJ );
 
-  dg::Matrix JK; //(nJ,mJ);
+  dynamicgraph::Matrix JK; //(nJ,mJ);
 
   SVD_t svd;
   Kernel_t kernel;
diff --git a/include/sot/core/motion-period.hh b/include/sot/core/motion-period.hh
index b2fc894dee87adea329e8dbb982a47ad27c8e9e8..25ff16cd28870ba2257293b20d832ebed3877e1c 100644
--- a/include/sot/core/motion-period.hh
+++ b/include/sot/core/motion-period.hh
@@ -16,7 +16,6 @@
 
 /* Matrix */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
 
 /* SOT */
 #include <dynamic-graph/all-signals.h>
@@ -47,9 +46,8 @@ namespace dg = dynamicgraph;
 namespace dynamicgraph {
 namespace sot {
 
-namespace dg = dynamicgraph;
 
-class SOTMOTIONPERIOD_EXPORT MotionPeriod : public dg::Entity {
+class SOTMOTIONPERIOD_EXPORT MotionPeriod : public dynamicgraph::Entity {
 
 public:
   static const std::string CLASS_NAME;
@@ -73,13 +71,13 @@ protected:
 
   /* --- SIGNALS ------------------------------------------------------------ */
 public:
-  dg::SignalTimeDependent<dg::Vector, int> motionSOUT;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> motionSOUT;
 
 public:
   MotionPeriod(const std::string &name);
   virtual ~MotionPeriod(void) {}
 
-  dg::Vector &computeMotion(dg::Vector &res, const int &time);
+  dynamicgraph::Vector &computeMotion(dynamicgraph::Vector &res, const int &time);
 
   virtual void display(std::ostream &os) const;
 };
diff --git a/include/sot/core/neck-limitation.hh b/include/sot/core/neck-limitation.hh
index 0a3b80eb1edf8476bb7ab485edd87682dfdedafe..23c593229a97469297b11a6768b86762ec98d6fd 100644
--- a/include/sot/core/neck-limitation.hh
+++ b/include/sot/core/neck-limitation.hh
@@ -16,7 +16,6 @@
 
 /* Matrix */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
 
 /* SOT */
 #include <dynamic-graph/all-signals.h>
@@ -49,9 +48,8 @@ namespace dg = dynamicgraph;
 namespace dynamicgraph {
 namespace sot {
 
-namespace dg = dynamicgraph;
 
-class NeckLimitation_EXPORT NeckLimitation : public dg::Entity {
+class NeckLimitation_EXPORT NeckLimitation : public dynamicgraph::Entity {
 public:
   static const std::string CLASS_NAME;
   virtual const std::string &getClassName(void) const { return CLASS_NAME; }
@@ -74,11 +72,11 @@ public: /* --- CONSTRUCTION --- */
   virtual ~NeckLimitation(void);
 
 public: /* --- SIGNAL --- */
-  dg::SignalPtr<dg::Vector, int> jointSIN;
-  dg::SignalTimeDependent<dg::Vector, int> jointSOUT;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> jointSIN;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> jointSOUT;
 
 public: /* --- FUNCTIONS --- */
-  dg::Vector &computeJointLimitation(dg::Vector &jointLimited,
+  dynamicgraph::Vector &computeJointLimitation(dynamicgraph::Vector &jointLimited,
                                      const int &timeSpec);
 
 public: /* --- PARAMS --- */
diff --git a/include/sot/core/op-point-modifier.hh b/include/sot/core/op-point-modifier.hh
index 4b442acf6536ed32c4598539e96fd418ce9ee5a9..809c0dfd3378deec5fd1be8f6a434f6a4ec51be8 100644
--- a/include/sot/core/op-point-modifier.hh
+++ b/include/sot/core/op-point-modifier.hh
@@ -17,7 +17,6 @@
 
 /* Matrix */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
 
 /* --------------------------------------------------------------------- */
 /* --- API ------------------------------------------------------------- */
@@ -39,7 +38,6 @@ namespace dg = dynamicgraph;
 
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
 
 ///
 /// \brief Compute position and jacobian of a local frame attached to a joint.
@@ -47,23 +45,23 @@ namespace dg = dynamicgraph;
 /// The position of the local frame in the frame of the joint is represented by
 /// transformation.
 ///
-class SOTOPPOINTMODIFIER_EXPORT OpPointModifier : public dg::Entity {
+class SOTOPPOINTMODIFIER_EXPORT OpPointModifier : public dynamicgraph::Entity {
 public:
   static const std::string CLASS_NAME;
   virtual const std::string &getClassName(void) const { return CLASS_NAME; }
 
 public:
-  dg::SignalPtr<dg::Matrix, int> jacobianSIN;
-  dg::SignalPtr<MatrixHomogeneous, int> positionSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Matrix, int> jacobianSIN;
+  dynamicgraph::SignalPtr<MatrixHomogeneous, int> positionSIN;
 
-  dg::SignalTimeDependent<dg::Matrix, int> jacobianSOUT;
-  dg::SignalTimeDependent<MatrixHomogeneous, int> positionSOUT;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Matrix, int> jacobianSOUT;
+  dynamicgraph::SignalTimeDependent<MatrixHomogeneous, int> positionSOUT;
 
 public:
   OpPointModifier(const std::string &name);
   virtual ~OpPointModifier(void) {}
 
-  dg::Matrix &jacobianSOUT_function(dg::Matrix &res, const int &time);
+  dynamicgraph::Matrix &jacobianSOUT_function(dynamicgraph::Matrix &res, const int &time);
   MatrixHomogeneous &positionSOUT_function(MatrixHomogeneous &res,
                                            const int &time);
   void setTransformation(const Eigen::Matrix4d &tr);
diff --git a/include/sot/core/reader.hh b/include/sot/core/reader.hh
index 36f2c4d5a7515013fdff77c229293c5e77be9214..7c216aea5ddb33278313be31687101de8559f02d 100644
--- a/include/sot/core/reader.hh
+++ b/include/sot/core/reader.hh
@@ -16,7 +16,7 @@
 
 /* Matrix */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
+
 
 /* STD */
 #include <boost/function.hpp>
@@ -61,8 +61,8 @@ class SOTREADER_EXPORT sotReader : public Entity {
 
 public:
   SignalPtr<Flags, int> selectionSIN;
-  SignalTimeDependent<dg::Vector, int> vectorSOUT;
-  SignalTimeDependent<dg::Matrix, int> matrixSOUT;
+  SignalTimeDependent<dynamicgraph::Vector, int> vectorSOUT;
+  SignalTimeDependent<dynamicgraph::Matrix, int> matrixSOUT;
 
 public:
   sotReader(const std::string n);
@@ -80,8 +80,8 @@ protected:
 
   int rows, cols;
 
-  dg::Vector &getNextData(dg::Vector &res, const unsigned int time);
-  dg::Matrix &getNextMatrix(dg::Matrix &res, const unsigned int time);
+  dynamicgraph::Vector &getNextData(dynamicgraph::Vector &res, const unsigned int time);
+  dynamicgraph::Matrix &getNextMatrix(dynamicgraph::Matrix &res, const unsigned int time);
   void resize(const int &nbRow, const int &nbCol);
 
 public:
diff --git a/include/sot/core/robot-simu.hh b/include/sot/core/robot-simu.hh
index e37c838267ec89273581a98ee29af5858d83c556..50d232d0dbf18964947f25434f664cd20597c7ae 100644
--- a/include/sot/core/robot-simu.hh
+++ b/include/sot/core/robot-simu.hh
@@ -17,7 +17,7 @@
 
 /* -- MaaL --- */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
+
 /* SOT */
 #include "sot/core/api.hh"
 #include "sot/core/device.hh"
diff --git a/include/sot/core/robot-utils.hh b/include/sot/core/robot-utils.hh
index a6da9a110e911ed446804ed04a2e08287665ebea..6ddaafba9f1fd93a9c215879d89af5444026a986 100644
--- a/include/sot/core/robot-utils.hh
+++ b/include/sot/core/robot-utils.hh
@@ -18,8 +18,6 @@
 #include <map>
 #include <sot/core/matrix-geometry.hh>
 
-namespace dg = ::dynamicgraph;
-using namespace dg;
 
 namespace dynamicgraph {
 namespace sot {
@@ -57,8 +55,8 @@ struct SOT_CORE_EXPORT ForceUtil {
 
   void set_name_to_force_id(const std::string &name, const Index &force_id);
 
-  void set_force_id_to_limits(const Index &force_id, const dg::Vector &lf,
-                              const dg::Vector &uf);
+  void set_force_id_to_limits(const Index &force_id, const dynamicgraph::Vector &lf,
+                              const dynamicgraph::Vector &uf);
 
   void create_force_id_to_name_map();
 
@@ -169,7 +167,7 @@ public:
 
   /// Set the map between urdf index and sot index
   void set_urdf_to_sot(const std::vector<Index> &urdf_to_sot);
-  void set_urdf_to_sot(const dg::Vector &urdf_to_sot);
+  void set_urdf_to_sot(const dynamicgraph::Vector &urdf_to_sot);
 
   /// Set the limits (lq,uq) for joint idx
   void set_joint_limits_for_id(const Index &idx, const double &lq,
diff --git a/include/sot/core/seq-play.hh b/include/sot/core/seq-play.hh
index dd791ac735cb7da18938f73838091d1fe3a04aac..6be8ca4e30324d8fe714cde0df4eb8adfcc245bd 100644
--- a/include/sot/core/seq-play.hh
+++ b/include/sot/core/seq-play.hh
@@ -16,7 +16,7 @@
 
 /* -- MaaL --- */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
+
 /* SOT */
 #include <dynamic-graph/all-signals.h>
 #include <dynamic-graph/entity.h>
@@ -50,7 +50,7 @@ public:
   virtual const std::string &getClassName(void) const { return CLASS_NAME; }
 
 protected:
-  typedef std::list<dg::Vector> StateList;
+  typedef std::list<dynamicgraph::Vector> StateList;
   StateList stateList;
   StateList::iterator currPos;
   unsigned int currRank;
@@ -64,7 +64,7 @@ public:
 
   void loadFile(const std::string &name);
 
-  dg::Vector &getNextPosition(dg::Vector &pos, const int &time);
+  dynamicgraph::Vector &getNextPosition(dynamicgraph::Vector &pos, const int &time);
 
 public: /* --- DISPLAY --- */
   virtual void display(std::ostream &os) const;
@@ -75,10 +75,8 @@ public: /* --- DISPLAY --- */
   }
 
 public: /* --- SIGNALS --- */
-  // dynamicgraph::SignalPtr<dg::Vector,int> positionSIN;
-  // dynamicgraph::SignalTimeDependant<dg::Vector,int> velocitySOUT;
   dynamicgraph::SignalTimeDependent<int, int> refresherSINTERN;
-  dynamicgraph::SignalTimeDependent<dg::Vector, int> positionSOUT;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> positionSOUT;
 };
 
 } /* namespace sot */
diff --git a/include/sot/core/seqplay.hh b/include/sot/core/seqplay.hh
index dd791ac735cb7da18938f73838091d1fe3a04aac..6be8ca4e30324d8fe714cde0df4eb8adfcc245bd 100644
--- a/include/sot/core/seqplay.hh
+++ b/include/sot/core/seqplay.hh
@@ -16,7 +16,7 @@
 
 /* -- MaaL --- */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
+
 /* SOT */
 #include <dynamic-graph/all-signals.h>
 #include <dynamic-graph/entity.h>
@@ -50,7 +50,7 @@ public:
   virtual const std::string &getClassName(void) const { return CLASS_NAME; }
 
 protected:
-  typedef std::list<dg::Vector> StateList;
+  typedef std::list<dynamicgraph::Vector> StateList;
   StateList stateList;
   StateList::iterator currPos;
   unsigned int currRank;
@@ -64,7 +64,7 @@ public:
 
   void loadFile(const std::string &name);
 
-  dg::Vector &getNextPosition(dg::Vector &pos, const int &time);
+  dynamicgraph::Vector &getNextPosition(dynamicgraph::Vector &pos, const int &time);
 
 public: /* --- DISPLAY --- */
   virtual void display(std::ostream &os) const;
@@ -75,10 +75,8 @@ public: /* --- DISPLAY --- */
   }
 
 public: /* --- SIGNALS --- */
-  // dynamicgraph::SignalPtr<dg::Vector,int> positionSIN;
-  // dynamicgraph::SignalTimeDependant<dg::Vector,int> velocitySOUT;
   dynamicgraph::SignalTimeDependent<int, int> refresherSINTERN;
-  dynamicgraph::SignalTimeDependent<dg::Vector, int> positionSOUT;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> positionSOUT;
 };
 
 } /* namespace sot */
diff --git a/include/sot/core/sequencer.hh b/include/sot/core/sequencer.hh
index 0c0584b88e63edf3ed34438fe8e932bd100d818e..0a57cc3cd3b32adaf9a7a7ec9802d1fd1257a0a7 100644
--- a/include/sot/core/sequencer.hh
+++ b/include/sot/core/sequencer.hh
@@ -16,7 +16,6 @@
 
 /* Matrix */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
 
 /* SOT */
 #include <dynamic-graph/all-signals.h>
diff --git a/include/sot/core/smooth-reach.hh b/include/sot/core/smooth-reach.hh
index 1240e5b9dd303156b70a5f65e18b49db58cee65d..5848bb190396726d9b5eb9b70325bd85890dc1ed 100644
--- a/include/sot/core/smooth-reach.hh
+++ b/include/sot/core/smooth-reach.hh
@@ -16,7 +16,6 @@
 
 /* Matrix */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
 
 /* SOT */
 #include <dynamic-graph/all-signals.h>
@@ -39,19 +38,18 @@ namespace dg = dynamicgraph;
 namespace dynamicgraph {
 namespace sot {
 
-namespace dg = dynamicgraph;
 
 /* --------------------------------------------------------------------- */
 /* --- CLASS ----------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-class SOTSMOOTHREACH_EXPORT SmoothReach : public dg::Entity {
+class SOTSMOOTHREACH_EXPORT SmoothReach : public dynamicgraph::Entity {
 public:
   static const std::string CLASS_NAME;
   virtual const std::string &getClassName() const { return CLASS_NAME; }
 
 private:
-  dg::Vector start, goal;
+  dynamicgraph::Vector start, goal;
   int startTime, lengthTime;
   bool isStarted, isParam;
   int smoothMode;
@@ -64,15 +62,14 @@ public: /* --- CONSTRUCTION --- */
   virtual ~SmoothReach(void){};
 
 public: /* --- SIGNAL --- */
-  dg::SignalPtr<dg::Vector, int> startSIN;
-  dg::SignalTimeDependent<dg::Vector, int> goalSOUT;
-  // dg::SignalTimeDependent<double, int> percentSOUT;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> startSIN;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> goalSOUT;
 
 public: /* --- FUNCTION --- */
-  dg::Vector &goalSOUT_function(dg::Vector &goal, const int &time);
+  dynamicgraph::Vector &goalSOUT_function(dynamicgraph::Vector &goal, const int &time);
 
-  void set(const dg::Vector &goal, const int &length);
-  const dg::Vector &getGoal(void);
+  void set(const dynamicgraph::Vector &goal, const int &length);
+  const dynamicgraph::Vector &getGoal(void);
   const int &getLength(void);
   const int &getStart(void);
 
diff --git a/include/sot/core/sot.hh b/include/sot/core/sot.hh
index 54ab52eef4c4e40e876b7913461e50f0ba39ec31..0675735714fe93e40139305a053746d17e81144b 100644
--- a/include/sot/core/sot.hh
+++ b/include/sot/core/sot.hh
@@ -16,7 +16,6 @@
 
 /* Matrix */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
 
 /* Classes standards. */
 #include <list> /* Classe std::list   */
@@ -159,7 +158,7 @@ public: /* --- CONTROL --- */
   */
 
   /*! \brief Compute the control law. */
-  virtual dg::Vector &computeControlLaw(dg::Vector &control, const int &time);
+  virtual dynamicgraph::Vector &computeControlLaw(dynamicgraph::Vector &control, const int &time);
 
   /*! @} */
 
@@ -181,18 +180,18 @@ public: /* --- SIGNALS --- */
    * the recurence of the SOT (e.g. velocity coming from the other
    * OpenHRP plugins).
    */
-  SignalPtr<dg::Vector, int> q0SIN;
+  SignalPtr<dynamicgraph::Vector, int> q0SIN;
   /*! \brief A matrix K whose columns are a base of the desired velocity.
    * In other words, \f$ \dot{q} = K * u \f$ where \f$ u \f$ is the free
    * parameter to be computed.
    * \note K should be an orthonormal matrix.
    */
-  SignalPtr<dg::Matrix, int> proj0SIN;
+  SignalPtr<dynamicgraph::Matrix, int> proj0SIN;
   /*! \brief This signal allow to change the threshold for the
     damped pseudo-inverse on-line */
   SignalPtr<double, int> inversionThresholdSIN;
   /*! \brief Allow to get the result of the computed control law. */
-  SignalTimeDependent<dg::Vector, int> controlSOUT;
+  SignalTimeDependent<dynamicgraph::Vector, int> controlSOUT;
   /*! @} */
 
   /*! \brief This method write the priority between tasks in the output stream
diff --git a/include/sot/core/task-abstract.hh b/include/sot/core/task-abstract.hh
index cb9fe4dd530568eba58f7d36f4b8ff7dc8bd4534..248f1ec5c024b9cd09ad1a872c33290ce55d14aa 100644
--- a/include/sot/core/task-abstract.hh
+++ b/include/sot/core/task-abstract.hh
@@ -17,7 +17,6 @@
 /* Matrix */
 #include <Eigen/SVD>
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
 
 /* STD */
 #include <string>
@@ -46,7 +45,7 @@ namespace sot {
 /// TaskAbstract. The value and Jacobian of a Task are computed from the
 /// features that are stored in the task.
 
-class SOT_CORE_EXPORT TaskAbstract : public dg::Entity {
+class SOT_CORE_EXPORT TaskAbstract : public dynamicgraph::Entity {
 public:
   /* Use a derivative of this class to store computational memory. */
   class MemoryTaskAbstract {
@@ -76,8 +75,8 @@ public:
   TaskAbstract(const std::string &n);
 
 public: /* --- SIGNALS --- */
-  dg::SignalTimeDependent<VectorMultiBound, int> taskSOUT;
-  dg::SignalTimeDependent<dg::Matrix, int> jacobianSOUT;
+  dynamicgraph::SignalTimeDependent<VectorMultiBound, int> taskSOUT;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Matrix, int> jacobianSOUT;
 };
 
 } /* namespace sot */
diff --git a/include/sot/core/task-conti.hh b/include/sot/core/task-conti.hh
index 01b71002a90d6efa07ab51b814ce522b5d7e1f79..4098ea32596af2b3f785ee7f3aef2d3fd968e519 100644
--- a/include/sot/core/task-conti.hh
+++ b/include/sot/core/task-conti.hh
@@ -16,7 +16,6 @@
 
 /* Matrix */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
 
 /* STD */
 #include <string>
@@ -48,7 +47,6 @@ namespace dg = dynamicgraph;
 
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
 
 class SOTTASKCONTI_EXPORT TaskConti : public Task {
 protected:
@@ -56,7 +54,7 @@ protected:
 
   int timeRef;
   double mu;
-  dg::Vector q0;
+  dynamicgraph::Vector q0;
 
 public:
   static const std::string CLASS_NAME;
@@ -74,7 +72,7 @@ public:
 
   /* --- SIGNALS ------------------------------------------------------------ */
 public:
-  dg::SignalPtr<dg::Vector, int> controlPrevSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> controlPrevSIN;
 
   /* --- DISPLAY ------------------------------------------------------------ */
   void display(std::ostream &os) const;
diff --git a/include/sot/core/task-pd.hh b/include/sot/core/task-pd.hh
index 2778afb40c9eee6dcf17e9b8f66f82b8989cf820..8c674924c384e5aa86f9851a6426a6ee033c0793 100644
--- a/include/sot/core/task-pd.hh
+++ b/include/sot/core/task-pd.hh
@@ -37,27 +37,26 @@
 
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
 
 class SOTTASKPD_EXPORT TaskPD : public Task {
 public:
   static const std::string CLASS_NAME;
   virtual const std::string &getClassName(void) const { return CLASS_NAME; }
 
-  dg::Vector previousError;
+  dynamicgraph::Vector previousError;
   double beta;
 
 public:
   TaskPD(const std::string &n);
 
   /* --- COMPUTATION --- */
-  dg::Vector &computeErrorDot(dg::Vector &error, int time);
+  dynamicgraph::Vector &computeErrorDot(dynamicgraph::Vector &error, int time);
   VectorMultiBound &computeTaskModif(VectorMultiBound &error, int time);
 
   /* --- SIGNALS ------------------------------------------------------------ */
 public:
-  dg::SignalTimeDependent<dg::Vector, int> errorDotSOUT;
-  dg::SignalPtr<dg::Vector, int> errorDotSIN;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> errorDotSOUT;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> errorDotSIN;
 
   /* --- PARAMS --- */
   void initCommand(void);
diff --git a/include/sot/core/task-unilateral.hh b/include/sot/core/task-unilateral.hh
index 071669d6b5529cfa2bfaa4389a2dc7879adf153e..3a704a524f03c8e49bcd9fc61fd6cb65712857e4 100644
--- a/include/sot/core/task-unilateral.hh
+++ b/include/sot/core/task-unilateral.hh
@@ -16,7 +16,6 @@
 
 /* Matrix */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
 
 /* STD */
 #include <string>
@@ -48,7 +47,6 @@ namespace dg = dynamicgraph;
 
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
 
 class SOTTASKUNILATERAL_EXPORT TaskUnilateral : public Task {
 protected:
@@ -66,10 +64,10 @@ public:
 
   /* --- SIGNALS ------------------------------------------------------------ */
 public:
-  dg::SignalPtr<dg::Vector, int> positionSIN;
-  dg::SignalPtr<dg::Vector, int> referenceInfSIN;
-  dg::SignalPtr<dg::Vector, int> referenceSupSIN;
-  dg::SignalPtr<double, int> dtSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> positionSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> referenceInfSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> referenceSupSIN;
+  dynamicgraph::SignalPtr<double, int> dtSIN;
 
   /* --- DISPLAY ------------------------------------------------------------ */
   void display(std::ostream &os) const;
diff --git a/include/sot/core/task.hh b/include/sot/core/task.hh
index 24e6e1a7897c0d6f327fcab02cb62136df31ce00..7417a0342be22b0656b9daa1a7aaafde19d2bfe2 100644
--- a/include/sot/core/task.hh
+++ b/include/sot/core/task.hh
@@ -16,7 +16,6 @@
 
 /* Matrix */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
 
 /* STD */
 #include <string>
@@ -70,7 +69,6 @@ namespace dg = dynamicgraph;
 
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
 
 class SOTTASK_EXPORT Task : public TaskAbstract {
 public:
@@ -99,19 +97,19 @@ public:
   bool getWithDerivative(void);
 
   /* --- COMPUTATION --- */
-  dg::Vector &computeError(dg::Vector &error, int time);
+  dynamicgraph::Vector &computeError(dynamicgraph::Vector &error, int time);
   VectorMultiBound &computeTaskExponentialDecrease(VectorMultiBound &errorRef,
                                                    int time);
-  dg::Matrix &computeJacobian(dg::Matrix &J, int time);
-  dg::Vector &computeErrorTimeDerivative(dg::Vector &res, int time);
+  dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &J, int time);
+  dynamicgraph::Vector &computeErrorTimeDerivative(dynamicgraph::Vector &res, int time);
 
   /* --- SIGNALS ------------------------------------------------------------ */
 public:
-  dg::SignalPtr<double, int> controlGainSIN;
-  dg::SignalPtr<double, int> dampingGainSINOUT;
-  dg::SignalPtr<Flags, int> controlSelectionSIN;
-  dg::SignalTimeDependent<dg::Vector, int> errorSOUT;
-  dg::SignalTimeDependent<dg::Vector, int> errorTimeDerivativeSOUT;
+  dynamicgraph::SignalPtr<double, int> controlGainSIN;
+  dynamicgraph::SignalPtr<double, int> dampingGainSINOUT;
+  dynamicgraph::SignalPtr<Flags, int> controlSelectionSIN;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> errorSOUT;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> errorTimeDerivativeSOUT;
 
   /* --- DISPLAY ------------------------------------------------------------ */
   void display(std::ostream &os) const;
diff --git a/include/sot/core/time-stamp.hh b/include/sot/core/time-stamp.hh
index 6c1a9d03b2ed49043a2f199ab236ebe514811e59..93b3d9918fd21dfff98aee577289f36d8433f4f6 100644
--- a/include/sot/core/time-stamp.hh
+++ b/include/sot/core/time-stamp.hh
@@ -16,7 +16,6 @@
 
 /* Matrix */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
 
 /* Classes standards. */
 #ifndef WIN32
@@ -50,9 +49,8 @@ namespace dg = dynamicgraph;
 
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
 
-class TimeStamp_EXPORT TimeStamp : public dg::Entity {
+class TimeStamp_EXPORT TimeStamp : public dynamicgraph::Entity {
 public:
   static const std::string CLASS_NAME;
   virtual const std::string &getClassName(void) const { return CLASS_NAME; }
@@ -72,17 +70,17 @@ public: /* --- DISPLAY --- */
 public: /* --- SIGNALS --- */
   /* These signals can be called several time per period, given
    * each time a different results. Useful for chronos. */
-  dg::Signal<dg::Vector, int> timeSOUT;
-  dg::Signal<double, int> timeDoubleSOUT;
+  dynamicgraph::Signal<dynamicgraph::Vector, int> timeSOUT;
+  dynamicgraph::Signal<double, int> timeDoubleSOUT;
 
   /* These signals can be called several time per period, but give
    * always the same results different results. Useful for synchro. */
-  dg::SignalTimeDependent<dg::Vector, int> timeOnceSOUT;
-  dg::SignalTimeDependent<double, int> timeOnceDoubleSOUT;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> timeOnceSOUT;
+  dynamicgraph::SignalTimeDependent<double, int> timeOnceDoubleSOUT;
 
 protected: /* --- SIGNAL FUNCTIONS --- */
-  dg::Vector &getTimeStamp(dg::Vector &res, const int &time);
-  double &getTimeStampDouble(const dg::Vector &vect, double &res);
+  dynamicgraph::Vector &getTimeStamp(dynamicgraph::Vector &res, const int &time);
+  double &getTimeStampDouble(const dynamicgraph::Vector &vect, double &res);
 };
 
 } /* namespace sot */
diff --git a/include/sot/core/timer.hh b/include/sot/core/timer.hh
index 7651c81af722d05bd5873f3f19774dfc4629ff8a..0913968ebbfed26222972d36ecce812c607e7416 100644
--- a/include/sot/core/timer.hh
+++ b/include/sot/core/timer.hh
@@ -47,9 +47,8 @@
 /* --------------------------------------------------------------------- */
 /* --- CLASS ----------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
-namespace dg = dynamicgraph;
 
-template <class T> class Timer_EXPORT Timer : public dg::Entity {
+template <class T> class Timer_EXPORT Timer : public dynamicgraph::Entity {
 public:
   static const std::string CLASS_NAME;
   virtual const std::string &getClassName(void) const { return CLASS_NAME; }
@@ -72,13 +71,13 @@ public: /* --- DISPLAY --- */
   }
 
 public: /* --- SIGNALS --- */
-  dg::SignalPtr<T, int> sigSIN;
-  dg::SignalTimeDependent<T, int> sigSOUT;
-  dg::SignalTimeDependent<T, int> sigClockSOUT;
-  dg::Signal<double, int> timerSOUT;
+  dynamicgraph::SignalPtr<T, int> sigSIN;
+  dynamicgraph::SignalTimeDependent<T, int> sigSOUT;
+  dynamicgraph::SignalTimeDependent<T, int> sigClockSOUT;
+  dynamicgraph::Signal<double, int> timerSOUT;
 
 protected: /* --- SIGNAL FUNCTIONS --- */
-  void plug(dg::Signal<T, int> &sig) {
+  void plug(dynamicgraph::Signal<T, int> &sig) {
     sigSIN = &sig;
     dt = 0.;
   }
diff --git a/include/sot/core/trajectory.hh b/include/sot/core/trajectory.hh
index 7c25d02f7c4fbe2a717ceed031a91d0d0f468a2c..b6957f8e17c2dc95f7fa11c7d223acf9fcf6ae03 100644
--- a/include/sot/core/trajectory.hh
+++ b/include/sot/core/trajectory.hh
@@ -17,8 +17,6 @@
 #include <boost/assign/list_of.hpp>
 #include <boost/regex.hpp>
 
-namespace dg = dynamicgraph;
-namespace ba = boost::assign;
 
 namespace dynamicgraph {
 namespace sot {
@@ -124,7 +122,7 @@ public:
 
   void display(std::ostream &os) const {
     boost::array<std::string, 4> names =
-        ba::list_of("Positions")("Velocities")("Accelerations")("Effort");
+        boost::assign::list_of("Positions")("Velocities")("Accelerations")("Effort");
 
     const std::vector<double> *points = 0;
 
diff --git a/include/sot/core/vector-constant.hh b/include/sot/core/vector-constant.hh
index ba197a9b3b262c73b604f8bfd104f819bde3ab10..245c00e5ec2796167768a9b53ff6a7061d3dc1d8 100644
--- a/include/sot/core/vector-constant.hh
+++ b/include/sot/core/vector-constant.hh
@@ -16,7 +16,6 @@
 
 /* Matrix */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
 
 /* --------------------------------------------------------------------- */
 /* --- VECTOR ---------------------------------------------------------- */
@@ -42,10 +41,10 @@ public:
 
   virtual ~VectorConstant(void) {}
 
-  SignalTimeDependent<dg::Vector, int> SOUT;
+  SignalTimeDependent<dynamicgraph::Vector, int> SOUT;
 
   /// \brief Set value of vector (and therefore of output signal)
-  void setValue(const dg::Vector &inValue);
+  void setValue(const dynamicgraph::Vector &inValue);
 };
 
 } // namespace sot
diff --git a/include/sot/core/vector-to-rotation.hh b/include/sot/core/vector-to-rotation.hh
index 53e79bf5476f9d3464ecd3c9e5570b8a4aad3ab2..9a4bb2aeb5ef73d9c9f5fb2933240f02ff3174df 100644
--- a/include/sot/core/vector-to-rotation.hh
+++ b/include/sot/core/vector-to-rotation.hh
@@ -16,7 +16,6 @@
 
 /* Matrix */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
 
 /* STD */
 #include <vector>
@@ -40,9 +39,8 @@ namespace dg = dynamicgraph;
 /* --------------------------------------------------------------------- */
 namespace dynamicgraph {
 namespace sot {
-namespace dg = dynamicgraph;
 
-class SOTVECTORTOROTATION_EXPORT VectorToRotation : public dg::Entity {
+class SOTVECTORTOROTATION_EXPORT VectorToRotation : public dynamicgraph::Entity {
   static const std::string CLASS_NAME;
   virtual const std::string &getClassName(void) const { return CLASS_NAME; }
 
@@ -56,10 +54,10 @@ public:
 
   virtual ~VectorToRotation(void) {}
 
-  dg::SignalPtr<dg::Vector, int> SIN;
-  dg::SignalTimeDependent<MatrixRotation, int> SOUT;
+  dynamicgraph::SignalPtr<dynamicgraph::Vector, int> SIN;
+  dynamicgraph::SignalTimeDependent<MatrixRotation, int> SOUT;
 
-  MatrixRotation &computeRotation(const dg::Vector &angles,
+  MatrixRotation &computeRotation(const dynamicgraph::Vector &angles,
                                   MatrixRotation &res);
 };
 
diff --git a/include/sot/core/visual-point-projecter.hh b/include/sot/core/visual-point-projecter.hh
index 186aa2035fa2000b53f684f6f3c12239c6e030ac..98659a7361a08aebb3df271c48534527a91f4002 100644
--- a/include/sot/core/visual-point-projecter.hh
+++ b/include/sot/core/visual-point-projecter.hh
@@ -25,7 +25,7 @@
 
 /* Matrix */
 #include <dynamic-graph/linear-algebra.h>
-namespace dg = dynamicgraph;
+
 #include <sot/core/matrix-geometry.hh>
 
 /* SOT */
@@ -52,12 +52,12 @@ public: /* --- ENTITY INHERITANCE --- */
   virtual const std::string &getClassName(void) const { return CLASS_NAME; }
 
 public: /* --- SIGNALS --- */
-  DECLARE_SIGNAL_IN(point3D, dg::Vector);
+  DECLARE_SIGNAL_IN(point3D, dynamicgraph::Vector);
   DECLARE_SIGNAL_IN(transfo, MatrixHomogeneous);
 
-  DECLARE_SIGNAL_OUT(point3Dgaze, dg::Vector);
+  DECLARE_SIGNAL_OUT(point3Dgaze, dynamicgraph::Vector);
   DECLARE_SIGNAL_OUT(depth, double);
-  DECLARE_SIGNAL_OUT(point2D, dg::Vector);
+  DECLARE_SIGNAL_OUT(point2D, dynamicgraph::Vector);
 
 }; // class VisualPointProjecter
 
diff --git a/src/feature/feature-point6d-relative.cpp b/src/feature/feature-point6d-relative.cpp
index e6ab8179b68db5f777de84e18c555be201bfae4b..950eb7bc2db30a125cabcec06d5cba0b1115fe72 100644
--- a/src/feature/feature-point6d-relative.cpp
+++ b/src/feature/feature-point6d-relative.cpp
@@ -23,6 +23,7 @@
 using namespace std;
 using namespace dynamicgraph::sot;
 using namespace dynamicgraph;
+namespace dg = dynamicgraph;
 
 #include <sot/core/factory.hh>
 DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(FeaturePoint6dRelative,
diff --git a/src/tools/parameter-server.cpp b/src/tools/parameter-server.cpp
index 11fed8d809a073af9e03c50dd0f37d59ea3291d1..4370130899aee0f9212a6de28c4dec41a41306b4 100644
--- a/src/tools/parameter-server.cpp
+++ b/src/tools/parameter-server.cpp
@@ -249,7 +249,7 @@ void ParameterServer::setForceNameToForceId(const std::string &forceName,
                                                   static_cast<Index>(forceId));
 }
 
-void ParameterServer::setJoints(const dg::Vector &urdf_to_sot) {
+void ParameterServer::setJoints(const dynamicgraph::Vector &urdf_to_sot) {
   if (!m_initSucceeded) {
     SEND_WARNING_STREAM_MSG("Cannot set mapping to sot before initialization!");
     return;
diff --git a/src/tools/sequencer.cpp b/src/tools/sequencer.cpp
index 2cd18134ae2d6ea1378b245da41cd331023d18ff..ececc599e5b8aba6365786d1d8dbdecd9c2a6379 100644
--- a/src/tools/sequencer.cpp
+++ b/src/tools/sequencer.cpp
@@ -59,7 +59,7 @@ public:
       cmdArgs >> taskname;
       sotDEBUG(15) << "Add task " << taskname << std::endl;
       taskPtr = dynamic_cast<TaskAbstract *>(
-          &dg::PoolStorage::getInstance()->getEntity(taskname));
+          &dynamicgraph::PoolStorage::getInstance()->getEntity(taskname));
     }
   }
   virtual void display(std::ostream &os) const {
diff --git a/tests/tools/test_device.cpp b/tests/tools/test_device.cpp
index ebe3437a6f8623a4885ded823c8b94277079701d..a2edb35b1691b368d8df6cf5f6f23246565b0619 100644
--- a/tests/tools/test_device.cpp
+++ b/tests/tools/test_device.cpp
@@ -25,6 +25,7 @@ using namespace std;
 
 using namespace dynamicgraph;
 using namespace dynamicgraph::sot;
+namespace dg = dynamicgraph;
 
 class TestDevice : public dg::sot::Device {
 public:
diff --git a/tests/tools/test_robot_utils.cpp b/tests/tools/test_robot_utils.cpp
index 6f1955101861ecd4fceca7d4e5fcd2cce760f0b8..47169e8fb07d4b21fa376f7e40aff2b2d790b366 100644
--- a/tests/tools/test_robot_utils.cpp
+++ b/tests/tools/test_robot_utils.cpp
@@ -56,7 +56,7 @@ int main(void) {
 
   /*Test set urdf_to_sot */
 
-  dg::Vector urdf_to_sot(3);
+  dynamicgraph::Vector urdf_to_sot(3);
   urdf_to_sot << 0, 2, 1;
   robot_util->set_urdf_to_sot(urdf_to_sot);
   if (urdf_to_sot == robot_util->m_dgv_urdf_to_sot) {
@@ -65,10 +65,10 @@ int main(void) {
     std::cout << "ERROR: urdf_to_sot does not work !" << std::endl;
   }
   /*Test joints_urdf_to_sot and joints_sot_to_urdf */
-  dg::Vector q_urdf(3);
+  dynamicgraph::Vector q_urdf(3);
   q_urdf << 10, 20, 30;
-  dg::Vector q_sot(3);
-  dg::Vector q_test_urdf(3);
+  dynamicgraph::Vector q_sot(3);
+  dynamicgraph::Vector q_test_urdf(3);
   robot_util->joints_urdf_to_sot(q_urdf, q_sot);
   robot_util->joints_sot_to_urdf(q_sot, q_test_urdf);
   if (q_urdf == q_test_urdf) {
@@ -81,23 +81,23 @@ int main(void) {
   }
 
   /*Test velocity_sot_to_urdf and velocity_urdf_to_sot */
-  dg::Vector q2_urdf(10);
-  dg::Vector v_urdf(9);
-  dg::Vector v_sot(9);
+  dynamicgraph::Vector q2_urdf(10);
+  dynamicgraph::Vector v_urdf(9);
+  dynamicgraph::Vector v_sot(9);
   robot_util->velocity_urdf_to_sot(q2_urdf, v_urdf, v_sot);
   robot_util->velocity_sot_to_urdf(q2_urdf, v_sot, v_urdf);
   std::cout << "velocity_sot_to_urdf and velocity_urdf_to_sot work !"
             << std::endl;
 
   /*Test base_urdf_to_sot and base_sot_to_urdf */
-  dg::Vector base_q_urdf(7);
-  dg::Vector base_q_sot(6);
+  dynamicgraph::Vector base_q_urdf(7);
+  dynamicgraph::Vector base_q_sot(6);
   robot_util->base_urdf_to_sot(base_q_urdf, base_q_sot);
   robot_util->base_sot_to_urdf(base_q_sot, base_q_urdf);
   std::cout << "base_urdf_to_sot and base_sot_to_urdf work !" << std::endl;
 
   /*Test config_urdf_to_sot and config_sot_to_urdf */
-  dg::Vector q2_sot(9);
+  dynamicgraph::Vector q2_sot(9);
   robot_util->config_urdf_to_sot(q2_urdf, q2_sot);
   robot_util->config_sot_to_urdf(q2_sot, q2_urdf);
   std::cout << "config_urdf_to_sot and config_sot_to_urdf work !" << std::endl;
@@ -116,9 +116,9 @@ int main(void) {
   robot_util->m_force_util.set_name_to_force_id(lh, 2);
   robot_util->m_force_util.set_name_to_force_id(rh, 3);
 
-  dg::Vector lf_lim(6);
+  dynamicgraph::Vector lf_lim(6);
   lf_lim << 1, 2, 3, 4, 5, 6;
-  dg::Vector uf_lim(6);
+  dynamicgraph::Vector uf_lim(6);
   uf_lim << 10, 20, 30, 40, 50, 60;
   robot_util->m_force_util.set_force_id_to_limits(1, lf_lim, uf_lim);
   if (robot_util->m_force_util.get_id_from_name(rf) == 0 &&