From ce0a4978db5a1bfb1e91f6624990251c51dda39b Mon Sep 17 00:00:00 2001
From: Francois Bleibel <fbleibel@gmail.com>
Date: Tue, 22 Jun 2010 13:14:40 +0900
Subject: [PATCH] Finished renaming of SOT objects.

---
 include/CMakeLists.txt                        |   6 +
 include/sot-core/constraint.h                 |   6 +-
 include/sot-core/derivator.h                  |   8 +-
 include/sot-core/exception-factory.h          |  12 +-
 include/sot-core/exception-feature.h          |  12 +-
 include/sot-core/exception-signal.h           |  10 +-
 include/sot-core/exception-task.h             |  10 +-
 include/sot-core/exception-tools.h            |  10 +-
 include/sot-core/exception-traces.h           |  10 +-
 include/sot-core/factory.h                    |  28 +--
 include/sot-core/feature-1d.h                 |  16 +-
 include/sot-core/feature-abstract.h           |  12 +-
 include/sot-core/feature-generic.h            |  16 +-
 include/sot-core/feature-joint-limits.h       |  20 +--
 include/sot-core/feature-line-distance.h      |  22 +--
 include/sot-core/feature-point6d-relative.h   |  16 +-
 include/sot-core/feature-point6d.h            |  40 ++---
 include/sot-core/feature-task.h               |  10 +-
 include/sot-core/feature-vector3.h            |  22 +--
 include/sot-core/feature-visual-point.h       |  24 +--
 include/sot-core/fir-filter.h                 |   8 +-
 include/sot-core/flags.h                      |  50 +++---
 include/sot-core/gain-adaptive.h              |   8 +-
 include/sot-core/gain-hyperbolic.h            |   8 +-
 .../sot-core/import-default-paths.h.cmake     |   2 +-
 .../command => include/sot-core}/import.h     |   0
 include/sot-core/integrator-abstract.h        |   8 +-
 include/sot-core/integrator-euler.h           |  20 +--
 include/sot-core/matrix-constant.h            |   6 +-
 include/sot-core/matrix-force.h               |  28 +--
 include/sot-core/matrix-homogeneous.h         |  22 +--
 include/sot-core/matrix-rotation.h            |  12 +-
 include/sot-core/matrix-twist.h               |  28 +--
 include/sot-core/memory-task-sot.h            |   4 +-
 include/sot-core/multi-bound.h                |  22 +--
 include/sot-core/op-point-modifier.h          |  16 +-
 include/sot-core/pool.h                       |  26 +--
 include/sot-core/rotation-simple.h            |  40 ++---
 include/sot-core/signal-cast.h                |  20 +--
 .../solver-hierarchical-inequalities.h        |   6 +-
 include/sot-core/sot-h.h                      |  26 +--
 include/sot-core/sot-qr.h                     |  24 +--
 include/sot-core/sot.h                        |  28 +--
 include/sot-core/task-abstract.h              |   4 +-
 include/sot-core/task-conti.h                 |   6 +-
 include/sot-core/task-pd.h                    |   6 +-
 include/sot-core/task-unilateral.h            |   8 +-
 include/sot-core/task.h                       |  18 +-
 include/sot-core/unary-op.h                   |  10 +-
 include/sot-core/vector-constant.h            |   6 +-
 include/sot-core/vector-quaternion.h          |  16 +-
 include/sot-core/vector-roll-pitch-yaw.h      |  10 +-
 include/sot-core/vector-rotation.h            |   4 +-
 include/sot-core/vector-to-rotation.h         |  12 +-
 include/sot-core/vector-utheta.h              |  10 +-
 include/sot-core/weighted-sot.h               |   6 +-
 src/CMakeLists.txt                            |   3 +-
 src/exception/exception-factory.cpp           |  12 +-
 src/exception/exception-feature.cpp           |  12 +-
 src/exception/exception-signal.cpp            |  12 +-
 src/exception/exception-task.cpp              |  12 +-
 src/exception/exception-tools.cpp             |  62 -------
 src/exception/exception-traces.cpp            |  62 -------
 src/factory/additional-functions.cpp          |   6 +-
 src/factory/command/import.cpp                |   4 +-
 src/factory/factory.cpp                       |  36 ++--
 src/factory/pool.cpp                          |  38 ++--
 src/feature/feature-1d.cpp                    |  22 +--
 src/feature/feature-abstract.cpp              |  22 +--
 src/feature/feature-generic.cpp               |  54 +++---
 src/feature/feature-joint-limits.cpp          |  40 ++---
 src/feature/feature-line-distance.cpp         |  36 ++--
 src/feature/feature-point6d-relative.cpp      | 106 +++++------
 src/feature/feature-point6d.cpp               |  78 ++++----
 src/feature/feature-task.cpp                  |  30 ++--
 src/feature/feature-vector3.cpp               |  32 ++--
 src/feature/feature-visual-point.cpp          |  38 ++--
 src/math/matrix-force.cpp                     |  24 +--
 src/math/matrix-homogeneous.cpp               |  22 +--
 src/math/matrix-rotation.cpp                  |   4 +-
 src/math/matrix-twist.cpp                     |  24 +--
 src/math/op-point-modifier.cpp                |  32 ++--
 src/math/vector-quaternion.cpp                |  18 +-
 src/math/vector-roll-pitch-yaw.cpp            |  10 +-
 src/math/vector-utheta.cpp                    |  10 +-
 src/matrix/binary-op.cpp                      | 126 ++++++-------
 src/matrix/derivator.cpp                      |  18 +-
 src/matrix/fir-filter.cpp                     |  12 +-
 src/matrix/integrator-abstract.cpp            |   6 +-
 src/matrix/integrator-euler.cpp               |   4 +-
 src/matrix/matrix-constant.cpp                |   6 +-
 src/matrix/unary-op.cpp                       | 168 +++++++++---------
 src/matrix/vector-constant.cpp                |   6 +-
 src/matrix/vector-to-rotation.cpp             |  18 +-
 src/signal/signal-cast.cpp                    |  28 +--
 src/sot/flags.cpp                             | 100 +++++------
 src/sot/memory-task-sot.cpp                   |  14 +-
 src/sot/rotation-simple.cpp                   |   2 +-
 src/sot/solver-hierarchical-inequalities.cpp  |  96 +++++-----
 src/sot/sot-h.cpp                             |  74 ++++----
 src/sot/sot-qr.cpp                            | 132 +++++++-------
 src/sot/sot.cpp                               | 138 +++++++-------
 src/sot/weighted-sot.cpp                      |  36 ++--
 src/task/constraint.cpp                       |  14 +-
 src/task/gain-adaptative.cpp                  |  36 ++--
 src/task/gain-hyperbolic.cpp                  |  36 ++--
 src/task/multi-bound.cpp                      |  66 +++----
 src/task/task-abstract.cpp                    |  10 +-
 src/task/task-conti.cpp                       |  24 +--
 src/task/task-pd.cpp                          |  24 +--
 src/task/task-unilateral.cpp                  |  18 +-
 src/task/task.cpp                             |  94 +++++-----
 112 files changed, 1443 insertions(+), 1562 deletions(-)
 rename src/include/sot/import-default-paths.h => include/sot-core/import-default-paths.h.cmake (79%)
 rename {src/factory/command => include/sot-core}/import.h (100%)
 delete mode 100644 src/exception/exception-tools.cpp
 delete mode 100644 src/exception/exception-traces.cpp

diff --git a/include/CMakeLists.txt b/include/CMakeLists.txt
index 2121db12..1a149b3d 100644
--- a/include/CMakeLists.txt
+++ b/include/CMakeLists.txt
@@ -2,6 +2,11 @@
 #  Copyright 
 # 
 
+# Generate header with default script directory.
+SET(SOT_IMPORT_DEFAULT_PATHS \"${CMAKE_INSTALL_PREFIX}/script\")
+CONFIGURE_FILE(sot-core/import-default-paths.h.cmake
+		       sot-core/import-default-paths.h)
+
 SET(${PROJECT_NAME}_HEADERS
 sot-core-api.h
 
@@ -38,6 +43,7 @@ additional-functions.h
 factory.h
 macros-signal.h
 pool.h
+import-default-paths.h
 
 #math
 matrix-force.h
diff --git a/include/sot-core/constraint.h b/include/sot-core/constraint.h
index 29c3e7ba..8955065e 100644
--- a/include/sot-core/constraint.h
+++ b/include/sot-core/constraint.h
@@ -65,7 +65,7 @@ namespace sot {
 
 
 class SOTCONSTRAINT_EXPORT Constraint
-: public sotTaskAbstract
+: public TaskAbstract
 {
  protected:
   typedef std::list< Signal<ml::Matrix,int>* > JacobianList;
@@ -81,8 +81,8 @@ class SOTCONSTRAINT_EXPORT Constraint
   void addJacobian( Signal<ml::Matrix,int>& sig );
   void clearJacobianList( void );
 
-  void setControlSelection( const sotFlags& act );
-  void addControlSelection( const sotFlags& act );
+  void setControlSelection( const Flags& act );
+  void addControlSelection( const Flags& act );
   void clearControlSelection( void );
 
   /* --- COMPUTATION --- */
diff --git a/include/sot-core/derivator.h b/include/sot-core/derivator.h
index 81107f0c..ac024504 100644
--- a/include/sot-core/derivator.h
+++ b/include/sot-core/derivator.h
@@ -46,7 +46,7 @@ namespace sot {
 /* --------------------------------------------------------------------- */
 
 template< class T >
-class sotDerivator
+class Derivator
 :public Entity
 {
  protected:
@@ -60,12 +60,12 @@ class sotDerivator
   static std::string getTypeName( void ) { return "Unknown"; }
   static const std::string CLASS_NAME;
 
-  sotDerivator( const std::string& name )
+  Derivator( const std::string& name )
     : Entity(name)
     ,memory(),initialized(false)
     ,timestep(TIMESTEP_DEFAULT)
     ,SIN(NULL,"sotDerivator<"+getTypeName()+">("+name+")::input("+getTypeName()+")::in") 
-    ,SOUT( boost::bind(&sotDerivator<T>::computeDerivation,this,_1,_2), 
+    ,SOUT( boost::bind(&Derivator<T>::computeDerivation,this,_1,_2), 
 	   SIN,"sotDerivator<"+getTypeName()+">("+name+")::output("+getTypeName()+")::out")
     ,timestepSIN("sotDerivator<"+getTypeName()+">("+name+")::input(double)::dt")
     {
@@ -75,7 +75,7 @@ class sotDerivator
     }
 
 
-  virtual ~sotDerivator( void ) {};
+  virtual ~Derivator( void ) {};
 
  public: /* --- SIGNAL --- */
 
diff --git a/include/sot-core/exception-factory.h b/include/sot-core/exception-factory.h
index fc446311..545c3654 100644
--- a/include/sot-core/exception-factory.h
+++ b/include/sot-core/exception-factory.h
@@ -34,9 +34,9 @@
 
 namespace sot {
 
-/* \class sotExceptionFactory
+/* \class ExceptionFactory
  */
-class SOT_CORE_EXPORT sotExceptionFactory 
+class SOT_CORE_EXPORT ExceptionFactory 
 :public ExceptionAbstract
 
 {
@@ -57,13 +57,13 @@ public:
     };
 
   static const std::string EXCEPTION_NAME;
-  virtual const std::string& getExceptionName( void )const{ return sotExceptionFactory::EXCEPTION_NAME; }
+  virtual const std::string& getExceptionName( void )const{ return ExceptionFactory::EXCEPTION_NAME; }
 
-  sotExceptionFactory ( const sotExceptionFactory::ErrorCodeEnum& errcode,
+  ExceptionFactory ( const ExceptionFactory::ErrorCodeEnum& errcode,
 			const std::string & msg = "" );
-  sotExceptionFactory ( const sotExceptionFactory::ErrorCodeEnum& errcode,
+  ExceptionFactory ( const ExceptionFactory::ErrorCodeEnum& errcode,
 			const std::string & msg,const char* format, ... );
-  virtual ~sotExceptionFactory( void ){}
+  virtual ~ExceptionFactory( void ){}
 
 };
 
diff --git a/include/sot-core/exception-feature.h b/include/sot-core/exception-feature.h
index 1d640c28..9b58eca8 100644
--- a/include/sot-core/exception-feature.h
+++ b/include/sot-core/exception-feature.h
@@ -34,9 +34,9 @@
 
 namespace sot {
 
-/* \class sotExceptionFeature
+/* \class ExceptionFeature
  */
-class SOT_CORE_EXPORT sotExceptionFeature 
+class SOT_CORE_EXPORT ExceptionFeature 
 :public ExceptionAbstract
 
 {
@@ -50,15 +50,15 @@ public:
     };
 
   static const std::string EXCEPTION_NAME;
-  virtual const std::string& getExceptionName( void ) const { return sotExceptionFeature::EXCEPTION_NAME; }
+  virtual const std::string& getExceptionName( void ) const { return ExceptionFeature::EXCEPTION_NAME; }
 
-  sotExceptionFeature ( const sotExceptionFeature::ErrorCodeEnum& errcode,
+  ExceptionFeature ( const ExceptionFeature::ErrorCodeEnum& errcode,
 		     const std::string & msg = "" );
 
-  sotExceptionFeature ( const sotExceptionFeature::ErrorCodeEnum& errcode,
+  ExceptionFeature ( const ExceptionFeature::ErrorCodeEnum& errcode,
 			const std::string & msg,const char* format, ... );
 
-  virtual ~sotExceptionFeature( void ){}
+  virtual ~ExceptionFeature( void ){}
 };
 
 
diff --git a/include/sot-core/exception-signal.h b/include/sot-core/exception-signal.h
index 2590de7b..f63e395c 100644
--- a/include/sot-core/exception-signal.h
+++ b/include/sot-core/exception-signal.h
@@ -34,9 +34,9 @@
 
 namespace sot {
 
-/* \class sotExceptionSignal
+/* \class ExceptionSignal
  */
-class SOT_CORE_EXPORT sotExceptionSignal 
+class SOT_CORE_EXPORT ExceptionSignal 
 :public ExceptionAbstract
 
 {
@@ -58,11 +58,11 @@ class SOT_CORE_EXPORT sotExceptionSignal
 
 public:
 
-  sotExceptionSignal ( const sotExceptionSignal::ErrorCodeEnum& errcode,
+  ExceptionSignal ( const ExceptionSignal::ErrorCodeEnum& errcode,
 		       const std::string & msg = "" );
-  sotExceptionSignal( const sotExceptionSignal::ErrorCodeEnum& errcode,
+  ExceptionSignal( const ExceptionSignal::ErrorCodeEnum& errcode,
 			const std::string & msg,const char* format, ... );
-  virtual ~sotExceptionSignal( void ){}
+  virtual ~ExceptionSignal( void ){}
 
 
 };
diff --git a/include/sot-core/exception-task.h b/include/sot-core/exception-task.h
index 482d459f..c465fe09 100644
--- a/include/sot-core/exception-task.h
+++ b/include/sot-core/exception-task.h
@@ -34,9 +34,9 @@
 
 namespace sot {
 
-/* \class sotExceptionTask
+/* \class ExceptionTask
  */
-class SOT_CORE_EXPORT sotExceptionTask 
+class SOT_CORE_EXPORT ExceptionTask 
 :public ExceptionAbstract
 
 {
@@ -55,11 +55,11 @@ public:
   static const std::string EXCEPTION_NAME;
   virtual const std::string& getExceptionName( void ) const { return EXCEPTION_NAME; }
 
-  sotExceptionTask ( const sotExceptionTask::ErrorCodeEnum& errcode,
+  ExceptionTask ( const ExceptionTask::ErrorCodeEnum& errcode,
 		     const std::string & msg = "" );
-  sotExceptionTask( const sotExceptionTask::ErrorCodeEnum& errcode,
+  ExceptionTask( const ExceptionTask::ErrorCodeEnum& errcode,
 		    const std::string & msg,const char* format, ... );
-  virtual ~sotExceptionTask( void ){}
+  virtual ~ExceptionTask( void ){}
 
 };
 
diff --git a/include/sot-core/exception-tools.h b/include/sot-core/exception-tools.h
index 43799c0d..c924870e 100644
--- a/include/sot-core/exception-tools.h
+++ b/include/sot-core/exception-tools.h
@@ -34,9 +34,9 @@
 
 namespace sot {
 
-/* \class sotExceptionTools
+/* \class ExceptionTools
  */
-class SOT_CORE_EXPORT sotExceptionTools 
+class SOT_CORE_EXPORT ExceptionTools 
 :public ExceptionAbstract
 
 {
@@ -54,11 +54,11 @@ class SOT_CORE_EXPORT sotExceptionTools
 
 public:
 
-  sotExceptionTools ( const sotExceptionTools::ErrorCodeEnum& errcode,
+  ExceptionTools ( const ExceptionTools::ErrorCodeEnum& errcode,
 		       const std::string & msg = "" );
-  sotExceptionTools( const sotExceptionTools::ErrorCodeEnum& errcode,
+  ExceptionTools( const ExceptionTools::ErrorCodeEnum& errcode,
 			const std::string & msg,const char* format, ... );
-  virtual ~sotExceptionTools( void ){}
+  virtual ~ExceptionTools( void ){}
 
 
 };
diff --git a/include/sot-core/exception-traces.h b/include/sot-core/exception-traces.h
index 635c3ba1..c0e3bb22 100644
--- a/include/sot-core/exception-traces.h
+++ b/include/sot-core/exception-traces.h
@@ -34,9 +34,9 @@
 
 namespace sot {
 
-/* \class sotExceptionTraces
+/* \class ExceptionTraces
  */
-class SOT_CORE_EXPORT sotExceptionTraces 
+class SOT_CORE_EXPORT ExceptionTraces 
 :public ExceptionAbstract
 
 {
@@ -53,11 +53,11 @@ class SOT_CORE_EXPORT sotExceptionTraces
 
 public:
 
-  sotExceptionTraces ( const sotExceptionTraces::ErrorCodeEnum& errcode,
+  ExceptionTraces ( const ExceptionTraces::ErrorCodeEnum& errcode,
 		       const std::string & msg = "" );
-  sotExceptionTraces( const sotExceptionTraces::ErrorCodeEnum& errcode,
+  ExceptionTraces( const ExceptionTraces::ErrorCodeEnum& errcode,
 			const std::string & msg,const char* format, ... );
-  virtual ~sotExceptionTraces( void ){}
+  virtual ~ExceptionTraces( void ){}
 
 
 };
diff --git a/include/sot-core/factory.h b/include/sot-core/factory.h
index 8939c0e4..ed1dbf30 100644
--- a/include/sot-core/factory.h
+++ b/include/sot-core/factory.h
@@ -37,8 +37,8 @@
 
 namespace sot {
 
-class sotFeatureAbstract;
-class sotTaskAbstract;
+class FeatureAbstract;
+class TaskAbstract;
 
 /* --------------------------------------------------------------------- */
 /* --- FACTORY ---------------------------------------------------------- */
@@ -51,14 +51,14 @@ class sotTaskAbstract;
   public "new" methods (newEntity, newFeature or newTask).
   The factory instance (singleton) is publicly available under the name sotFactory
   (include factory.h).  A task, feature or entity can register itself by
-   using the SOT_FACTORY_{ENTITY,TASK,FEATURE}_PLUGIN macro. See sotTask.cpp for
+   using the SOT_FACTORY_{ENTITY,TASK,FEATURE}_PLUGIN macro. See Task.cpp for
    an example.
 */
-class SOT_CORE_EXPORT sotFactoryStorage
+class SOT_CORE_EXPORT FactoryStorage
 {
  public:
-  typedef sotFeatureAbstract* (*FeatureConstructor_ptr)( const std::string& );
-  typedef sotTaskAbstract* (*TaskConstructor_ptr)( const std::string& );
+  typedef FeatureAbstract* (*FeatureConstructor_ptr)( const std::string& );
+  typedef TaskAbstract* (*TaskConstructor_ptr)( const std::string& );
   
  protected:
   typedef std::map< std::string,TaskConstructor_ptr > TaskMap;
@@ -69,15 +69,15 @@ class SOT_CORE_EXPORT sotFactoryStorage
 
  public:
 
-  ~sotFactoryStorage( void );
+  ~FactoryStorage( void );
 
   void registerTask( const std::string& entname,TaskConstructor_ptr ent );
-  sotTaskAbstract* newTask( const std::string& name,const std::string& objname );
+  TaskAbstract* newTask( const std::string& name,const std::string& objname );
   bool existTask( const std::string& name, TaskMap::iterator& entPtr );
   bool existTask( const std::string& name );
 
   void registerFeature( const std::string& entname,FeatureConstructor_ptr ent );
-  sotFeatureAbstract* newFeature( const std::string& name,const std::string& objname );
+  FeatureAbstract* newFeature( const std::string& name,const std::string& objname );
   bool existFeature( const std::string& name, FeatureMap::iterator& entPtr );
   bool existFeature( const std::string& name );
 
@@ -87,7 +87,7 @@ class SOT_CORE_EXPORT sotFactoryStorage
 
 };
 
-SOT_CORE_EXPORT extern sotFactoryStorage sotFactory;
+SOT_CORE_EXPORT extern FactoryStorage sotFactory;
 
 /* --- REGISTERER ----------------------------------------------------------- */
 /* --- REGISTERER ----------------------------------------------------------- */
@@ -112,13 +112,13 @@ class SOT_CORE_EXPORT sotFeatureRegisterer
 
  public:
   sotFeatureRegisterer( const std::string& featureClassName,
-			sotFactoryStorage::FeatureConstructor_ptr maker);
+			FactoryStorage::FeatureConstructor_ptr maker);
 };
 
 #define SOT_FACTORY_FEATURE_PLUGIN(sotFeatureType,className) \
   const std::string sotFeatureType::CLASS_NAME = className;  \
   extern "C" {                                               \
-    sotFeatureAbstract *sotFeatureMaker##_##sotFeatureType( const std::string& objname )\
+    FeatureAbstract *sotFeatureMaker##_##sotFeatureType( const std::string& objname )\
     {                                                        \
       return new sotFeatureType( objname );                  \
     }                                                        \
@@ -138,14 +138,14 @@ class SOT_CORE_EXPORT sotTaskRegisterer
 
  public:
   sotTaskRegisterer( const std::string& taskClassName,
-		     sotFactoryStorage::TaskConstructor_ptr maker);
+		     FactoryStorage::TaskConstructor_ptr maker);
 };
 
 
 #define SOT_FACTORY_TASK_PLUGIN(sotTaskType,className) \
   const std::string sotTaskType::CLASS_NAME = className; \
   extern "C" {                                            \
-    sotTaskAbstract *sotTaskMaker##_##sotTaskType( const std::string& objname )    \
+    TaskAbstract *sotTaskMaker##_##sotTaskType( const std::string& objname )    \
     {                                                     \
       return new sotTaskType( objname );                 \
     }                                                     \
diff --git a/include/sot-core/feature-1d.h b/include/sot-core/feature-1d.h
index a906f5d7..afd7f11b 100644
--- a/include/sot-core/feature-1d.h
+++ b/include/sot-core/feature-1d.h
@@ -50,14 +50,14 @@
 namespace sot {
 
 /*!
-  \class sotFeature1D
+  \class Feature1D
   \brief Simple test: the task is defined to be e_2 = .5 . e'.e, with
   e the mother task. The jacobian is then J_2 = e'.J, J being the jacobian
   of the mother task.
   
 */
-class SOTFEATURE1D_EXPORT sotFeature1D 
-: public sotFeatureAbstract
+class SOTFEATURE1D_EXPORT Feature1D 
+: public FeatureAbstract
 {
 
  public: 
@@ -90,21 +90,21 @@ class SOTFEATURE1D_EXPORT sotFeature1D
     @{
   */
   /*! \brief Publish the jacobian of the feature according to the robot state. */
-  using sotFeatureAbstract::jacobianSOUT;
+  using FeatureAbstract::jacobianSOUT;
 
   /*! \brief Publish the error between the desired and the current value of the feature. */
-  using sotFeatureAbstract::errorSOUT;
+  using FeatureAbstract::errorSOUT;
 
   /*! \brief Publish the activation of this feature. */
-  using sotFeatureAbstract::activationSOUT;
+  using FeatureAbstract::activationSOUT;
 
  public:
 
   /*! \brief Default constructor */
-  sotFeature1D( const std::string& name );
+  Feature1D( const std::string& name );
 
   /*! \brief Default destructor */
-  virtual ~sotFeature1D( void ) {}
+  virtual ~Feature1D( void ) {}
 
   /*! \brief Get the dimension of the feature. */
   virtual unsigned int& getDimension( unsigned int & dim, int time );
diff --git a/include/sot-core/feature-abstract.h b/include/sot-core/feature-abstract.h
index 2e09c8f0..65fd9812 100644
--- a/include/sot-core/feature-abstract.h
+++ b/include/sot-core/feature-abstract.h
@@ -45,7 +45,7 @@ namespace sot {
 /* --- CLASS ----------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-/*! \class sotFeatureAbstract
+/*! \class FeatureAbstract
   \ingroup features
   \brief This class gives the abstract definition of a feature.
 
@@ -58,7 +58,7 @@ namespace sot {
   A feature is supposed to compute a Jacobian according to the robot state vector
   \f$ \frac{\delta {\bf s}(t)}{\delta {\bf q}(t)}\f$.
  */
-class SOT_CORE_EXPORT sotFeatureAbstract
+class SOT_CORE_EXPORT FeatureAbstract
 :public Entity
 {
  public:
@@ -73,9 +73,9 @@ class SOT_CORE_EXPORT sotFeatureAbstract
 
  public:
   /*! \brief Default constructor: the name of the class should be given. */
-  sotFeatureAbstract( const std::string& name );
+  FeatureAbstract( const std::string& name );
   /*! \brief Default destructor */
-  virtual ~sotFeatureAbstract( void ) {};
+  virtual ~FeatureAbstract( void ) {};
 
   /*! \name Methods returning the dimension of the feature.
     @{ */
@@ -150,13 +150,13 @@ class SOT_CORE_EXPORT sotFeatureAbstract
   /*! \name Input signals: 
    @{ */
   /*! \brief This signal specifies the desired value \f$ {\bf s}^*(t) \f$ */
-  SignalPtr< sotFeatureAbstract*,int > desiredValueSIN;
+  SignalPtr< FeatureAbstract*,int > desiredValueSIN;
 
   /*! \brief This vector specifies which dimension are used to perform the computation.
    For instance let us assume that the feature is a 3D point. If only the Y-axis should
    be used for computing error, activation and Jacobian, then the vector to specify
    is \f$ [ 0 1 0] \f$.*/
-  SignalPtr< sotFlags,int > selectionSIN;
+  SignalPtr< Flags,int > selectionSIN;
   /*! @} */
 
   /*! \name Output signals: 
diff --git a/include/sot-core/feature-generic.h b/include/sot-core/feature-generic.h
index 27407155..15511c09 100644
--- a/include/sot-core/feature-generic.h
+++ b/include/sot-core/feature-generic.h
@@ -50,7 +50,7 @@
 namespace sot {
 
 /*!
-  \class sotFeatureGeneric
+  \class FeatureGeneric
   \brief Class that defines a generic implementation of the abstract interface for features. 
   
   This class is very useful if the feature can be easily computed using
@@ -62,8 +62,8 @@ namespace sot {
   generic feature implementation.
   
 */
-class SOTFEATUREGENERIC_EXPORT sotFeatureGeneric 
-: public sotFeatureAbstract
+class SOTFEATUREGENERIC_EXPORT FeatureGeneric 
+: public FeatureAbstract
 {
 
  public: 
@@ -100,13 +100,13 @@ class SOTFEATUREGENERIC_EXPORT sotFeatureGeneric
     @{
   */
   /*! \brief Publish the jacobian of the feature according to the robot state. */
-  using sotFeatureAbstract::jacobianSOUT;
+  using FeatureAbstract::jacobianSOUT;
 
   /*! \brief Publish the error between the desired and the current value of the feature. */
-  using sotFeatureAbstract::errorSOUT;
+  using FeatureAbstract::errorSOUT;
 
   /*! \brief Publish the activation of this feature. */
-  using sotFeatureAbstract::activationSOUT;
+  using FeatureAbstract::activationSOUT;
 
   /*! \brief New signal the errordot. */
   SignalTimeDependant< ml::Vector,int > errordotSOUT;
@@ -114,10 +114,10 @@ class SOTFEATUREGENERIC_EXPORT sotFeatureGeneric
  public:
 
   /*! \brief Default constructor */
-  sotFeatureGeneric( const std::string& name );
+  FeatureGeneric( const std::string& name );
 
   /*! \brief Default destructor */
-  virtual ~sotFeatureGeneric( void ) {}
+  virtual ~FeatureGeneric( void ) {}
 
   /*! \brief Get the dimension of the feature. */
   virtual unsigned int& getDimension( unsigned int & dim, int time );
diff --git a/include/sot-core/feature-joint-limits.h b/include/sot-core/feature-joint-limits.h
index 6b81bbe8..3912ae88 100644
--- a/include/sot-core/feature-joint-limits.h
+++ b/include/sot-core/feature-joint-limits.h
@@ -50,11 +50,11 @@
 namespace sot {
 
 /*!
-  \class sotFeatureJointLimits
+  \class FeatureJointLimits
   \brief Class that defines gradient vector for jl avoidance.
 */
-class SOTFEATUREJOINTLIMITS_EXPORT sotFeatureJointLimits 
-: public sotFeatureAbstract
+class SOTFEATUREJOINTLIMITS_EXPORT FeatureJointLimits 
+: public FeatureAbstract
 {
 
  public: 
@@ -78,15 +78,15 @@ class SOTFEATUREJOINTLIMITS_EXPORT sotFeatureJointLimits
   SignalPtr< ml::Vector,int > lowerJlSIN;
   SignalTimeDependant< ml::Vector,int > widthJlSINTERN;
 
-  using sotFeatureAbstract::selectionSIN;
+  using FeatureAbstract::selectionSIN;
 
-  using sotFeatureAbstract::jacobianSOUT;
-  using sotFeatureAbstract::errorSOUT;
-  using sotFeatureAbstract::activationSOUT;
+  using FeatureAbstract::jacobianSOUT;
+  using FeatureAbstract::errorSOUT;
+  using FeatureAbstract::activationSOUT;
 
  public:
-  sotFeatureJointLimits( const std::string& name );
-  virtual ~sotFeatureJointLimits( void ) {}
+  FeatureJointLimits( const std::string& name );
+  virtual ~FeatureJointLimits( void ) {}
 
   virtual unsigned int& getDimension( unsigned int & dim, int time );
   
@@ -96,7 +96,7 @@ class SOTFEATUREJOINTLIMITS_EXPORT sotFeatureJointLimits
   ml::Vector& computeWidthJl( ml::Vector& res,const int& time );
 
   /** Static Feature selection. */
-  inline static sotFlags selectActuated( void ); 
+  inline static Flags selectActuated( void ); 
   
   virtual void display( std::ostream& os ) const;
   void commandLine( const std::string& cmdLine,
diff --git a/include/sot-core/feature-line-distance.h b/include/sot-core/feature-line-distance.h
index f19fe1ef..0d5d0944 100644
--- a/include/sot-core/feature-line-distance.h
+++ b/include/sot-core/feature-line-distance.h
@@ -51,11 +51,11 @@
 namespace sot {
 
 /*!
-  \class sotFeatureLineDistance
+  \class FeatureLineDistance
   \brief Class that defines point-3d control feature
 */
-class SOTFEATURELINEDISTANCE_EXPORT sotFeatureLineDistance
-: public sotFeatureAbstract
+class SOTFEATURELINEDISTANCE_EXPORT FeatureLineDistance
+: public FeatureAbstract
 {
 
  public:
@@ -66,22 +66,22 @@ class SOTFEATURELINEDISTANCE_EXPORT sotFeatureLineDistance
 
   /* --- SIGNALS ------------------------------------------------------------ */
  public:
-  SignalPtr< sotMatrixHomogeneous,int > positionSIN;
+  SignalPtr< MatrixHomogeneous,int > positionSIN;
   SignalPtr< ml::Matrix,int > articularJacobianSIN;
   SignalPtr< ml::Vector,int > positionRefSIN;
   SignalPtr< ml::Vector,int > vectorSIN;
   SignalTimeDependant<ml::Vector,int> lineSOUT;
 
-  using sotFeatureAbstract::desiredValueSIN;
-  using sotFeatureAbstract::selectionSIN;
+  using FeatureAbstract::desiredValueSIN;
+  using FeatureAbstract::selectionSIN;
 
-  using sotFeatureAbstract::jacobianSOUT;
-  using sotFeatureAbstract::errorSOUT;
-  using sotFeatureAbstract::activationSOUT;
+  using FeatureAbstract::jacobianSOUT;
+  using FeatureAbstract::errorSOUT;
+  using FeatureAbstract::activationSOUT;
 
  public:
-  sotFeatureLineDistance( const std::string& name );
-  virtual ~sotFeatureLineDistance( void ) {}
+  FeatureLineDistance( const std::string& name );
+  virtual ~FeatureLineDistance( void ) {}
 
   virtual unsigned int& getDimension( unsigned int & dim, int time );
 
diff --git a/include/sot-core/feature-point6d-relative.h b/include/sot-core/feature-point6d-relative.h
index 3bc31071..29c4c549 100644
--- a/include/sot-core/feature-point6d-relative.h
+++ b/include/sot-core/feature-point6d-relative.h
@@ -52,12 +52,12 @@
 namespace sot {
 
 /*!
-  \class sotFeaturePoint6dRelative
+  \class FeaturePoint6dRelative
   \brief Class that defines the motion of a point of the body wrt. another
   point.
 */
-class SOTFEATUREPOINT6DRELATIVE_EXPORT sotFeaturePoint6dRelative 
-: public sotFeaturePoint6d
+class SOTFEATUREPOINT6DRELATIVE_EXPORT FeaturePoint6dRelative 
+: public FeaturePoint6d
 {
 
  public: 
@@ -71,7 +71,7 @@ class SOTFEATUREPOINT6DRELATIVE_EXPORT sotFeaturePoint6dRelative
 
   /* --- SIGNALS ------------------------------------------------------------ */
  public:
-  SignalPtr< sotMatrixHomogeneous,int > positionReferenceSIN;
+  SignalPtr< MatrixHomogeneous,int > positionReferenceSIN;
   SignalPtr< ml::Matrix,int > articularJacobianReferenceSIN;
 
   /*! Signals related to the computation of the derivative of 
@@ -81,17 +81,17 @@ class SOTFEATUREPOINT6DRELATIVE_EXPORT sotFeaturePoint6dRelative
   /*! Signals giving the derivative of the input signals. 
     @{*/
   /*! Derivative of the relative position. */
-  SignalPtr< sotMatrixHomogeneous,int > dotpositionSIN;
+  SignalPtr< MatrixHomogeneous,int > dotpositionSIN;
   /*! Derivative of the reference position. */
-  SignalPtr< sotMatrixHomogeneous,int > dotpositionReferenceSIN;
+  SignalPtr< MatrixHomogeneous,int > dotpositionReferenceSIN;
   /*! @} */
   /*! The derivative of the error.*/
   SignalTimeDependant<ml::Vector,int> errordotSOUT;
   /*! @} */
 
  public:
-  sotFeaturePoint6dRelative( const std::string& name );
-  virtual ~sotFeaturePoint6dRelative( void ) {}
+  FeaturePoint6dRelative( const std::string& name );
+  virtual ~FeaturePoint6dRelative( void ) {}
   
   virtual ml::Vector& computeError( ml::Vector& res,int time ); 
   virtual ml::Vector& computeErrorDot( ml::Vector& res,int time ); 
diff --git a/include/sot-core/feature-point6d.h b/include/sot-core/feature-point6d.h
index c9b460c4..f6fad3b0 100644
--- a/include/sot-core/feature-point6d.h
+++ b/include/sot-core/feature-point6d.h
@@ -51,11 +51,11 @@
 namespace sot {
 
 /*!
-  \class sotFeaturePoint6d
+  \class FeaturePoint6d
   \brief Class that defines point-3d control feature
 */
-class SOTFEATUREPOINT6D_EXPORT sotFeaturePoint6d 
-: public sotFeatureAbstract
+class SOTFEATUREPOINT6D_EXPORT FeaturePoint6d 
+: public FeatureAbstract
 {
 
  public: 
@@ -73,19 +73,19 @@ class SOTFEATUREPOINT6D_EXPORT sotFeaturePoint6d
 
   /* --- SIGNALS ------------------------------------------------------------ */
  public:
-  SignalPtr< sotMatrixHomogeneous,int > positionSIN;
+  SignalPtr< MatrixHomogeneous,int > positionSIN;
   SignalPtr< ml::Matrix,int > articularJacobianSIN;
 
-  using sotFeatureAbstract::desiredValueSIN;
-  using sotFeatureAbstract::selectionSIN;
+  using FeatureAbstract::desiredValueSIN;
+  using FeatureAbstract::selectionSIN;
 
-  using sotFeatureAbstract::jacobianSOUT;
-  using sotFeatureAbstract::errorSOUT;
-  using sotFeatureAbstract::activationSOUT;
+  using FeatureAbstract::jacobianSOUT;
+  using FeatureAbstract::errorSOUT;
+  using FeatureAbstract::activationSOUT;
 
  public:
-  sotFeaturePoint6d( const std::string& name );
-  virtual ~sotFeaturePoint6d( void ) {}
+  FeaturePoint6d( const std::string& name );
+  virtual ~FeaturePoint6d( void ) {}
 
   virtual unsigned int& getDimension( unsigned int & dim, int time );
   
@@ -94,15 +94,15 @@ class SOTFEATUREPOINT6D_EXPORT sotFeaturePoint6d
   virtual ml::Vector& computeActivation( ml::Vector& res,int time ); 
 
   /** Static Feature selection. */
-  inline static sotFlags selectX( void )  { return FLAG_LINE_1; }
-  inline static sotFlags selectY( void )  { return FLAG_LINE_2; }
-  inline static sotFlags selectZ( void )  { return FLAG_LINE_3; }
-  inline static sotFlags selectRX( void ) { return FLAG_LINE_4; }
-  inline static sotFlags selectRY( void ) { return FLAG_LINE_5; }
-  inline static sotFlags selectRZ( void ) { return FLAG_LINE_6; }
-
-  inline static sotFlags selectTranslation( void ) { return sotFlags(7); }
-  inline static sotFlags selectRotation( void ) { return sotFlags(56); }
+  inline static Flags selectX( void )  { return FLAG_LINE_1; }
+  inline static Flags selectY( void )  { return FLAG_LINE_2; }
+  inline static Flags selectZ( void )  { return FLAG_LINE_3; }
+  inline static Flags selectRX( void ) { return FLAG_LINE_4; }
+  inline static Flags selectRY( void ) { return FLAG_LINE_5; }
+  inline static Flags selectRZ( void ) { return FLAG_LINE_6; }
+
+  inline static Flags selectTranslation( void ) { return Flags(7); }
+  inline static Flags selectRotation( void ) { return Flags(56); }
 
   virtual void display( std::ostream& os ) const;
 
diff --git a/include/sot-core/feature-task.h b/include/sot-core/feature-task.h
index d8f9aa8a..979f89d7 100644
--- a/include/sot-core/feature-task.h
+++ b/include/sot-core/feature-task.h
@@ -50,8 +50,8 @@
 
 namespace sot {
 
-class SOTFEATURETASK_EXPORT sotFeatureTask 
-: public sotFeatureGeneric
+class SOTFEATURETASK_EXPORT FeatureTask 
+: public FeatureGeneric
 {
 
  public: 
@@ -61,7 +61,7 @@ class SOTFEATURETASK_EXPORT sotFeatureTask
   virtual const std::string& getClassName( void ) const { return CLASS_NAME; }
 
  protected:
-  sotTaskAbstract * taskPtr;
+  TaskAbstract * taskPtr;
 
   /* --- SIGNALS ------------------------------------------------------------ */
  public:
@@ -69,10 +69,10 @@ class SOTFEATURETASK_EXPORT sotFeatureTask
  public:
 
   /*! \brief Default constructor */
-  sotFeatureTask( const std::string& name );
+  FeatureTask( const std::string& name );
 
   /*! \brief Default destructor */
-  virtual ~sotFeatureTask( void ) {}
+  virtual ~FeatureTask( void ) {}
 
   /*! \name Methods to trigger computation related to this feature. 
     @{
diff --git a/include/sot-core/feature-vector3.h b/include/sot-core/feature-vector3.h
index 27b98615..0ec9e9ce 100644
--- a/include/sot-core/feature-vector3.h
+++ b/include/sot-core/feature-vector3.h
@@ -51,11 +51,11 @@
 namespace sot {
 
 /*!
-  \class sotFeatureVector3
+  \class FeatureVector3
   \brief Class that defines point-3d control feature
 */
-class SOTFEATUREVECTOR3_EXPORT sotFeatureVector3
-: public sotFeatureAbstract
+class SOTFEATUREVECTOR3_EXPORT FeatureVector3
+: public FeatureAbstract
 {
 
  public:
@@ -67,20 +67,20 @@ class SOTFEATUREVECTOR3_EXPORT sotFeatureVector3
   /* --- SIGNALS ------------------------------------------------------------ */
  public:
   SignalPtr< ml::Vector,int > vectorSIN;
-  SignalPtr< sotMatrixHomogeneous,int > positionSIN;
+  SignalPtr< MatrixHomogeneous,int > positionSIN;
   SignalPtr< ml::Matrix,int > articularJacobianSIN;
   SignalPtr< ml::Vector,int > positionRefSIN;
 
-  using sotFeatureAbstract::desiredValueSIN;
-  using sotFeatureAbstract::selectionSIN;
+  using FeatureAbstract::desiredValueSIN;
+  using FeatureAbstract::selectionSIN;
 
-  using sotFeatureAbstract::jacobianSOUT;
-  using sotFeatureAbstract::errorSOUT;
-  using sotFeatureAbstract::activationSOUT;
+  using FeatureAbstract::jacobianSOUT;
+  using FeatureAbstract::errorSOUT;
+  using FeatureAbstract::activationSOUT;
 
  public:
-  sotFeatureVector3( const std::string& name );
-  virtual ~sotFeatureVector3( void ) {}
+  FeatureVector3( const std::string& name );
+  virtual ~FeatureVector3( void ) {}
 
   virtual unsigned int& getDimension( unsigned int & dim, int time );
 
diff --git a/include/sot-core/feature-visual-point.h b/include/sot-core/feature-visual-point.h
index a6272ec5..2c5e851a 100644
--- a/include/sot-core/feature-visual-point.h
+++ b/include/sot-core/feature-visual-point.h
@@ -50,11 +50,11 @@
 namespace sot {
 
 /*!
-  \class sotFeatureVisualPoint
+  \class FeatureVisualPoint
   \brief Class that defines 2D visualPoint visual feature
 */
-class SOTFEATUREVISUALPOINT_EXPORT sotFeatureVisualPoint 
-: public sotFeatureAbstract
+class SOTFEATUREVISUALPOINT_EXPORT FeatureVisualPoint 
+: public FeatureAbstract
 {
 
  public: 
@@ -74,16 +74,16 @@ class SOTFEATUREVISUALPOINT_EXPORT sotFeatureVisualPoint
   SignalPtr< double,int > ZSIN;
   SignalPtr< ml::Matrix,int > articularJacobianSIN;
 
-  using sotFeatureAbstract::desiredValueSIN;
-  using sotFeatureAbstract::selectionSIN;
+  using FeatureAbstract::desiredValueSIN;
+  using FeatureAbstract::selectionSIN;
 
-  using sotFeatureAbstract::jacobianSOUT;
-  using sotFeatureAbstract::errorSOUT;
-  using sotFeatureAbstract::activationSOUT;
+  using FeatureAbstract::jacobianSOUT;
+  using FeatureAbstract::errorSOUT;
+  using FeatureAbstract::activationSOUT;
 
  public:
-  sotFeatureVisualPoint( const std::string& name );
-  virtual ~sotFeatureVisualPoint( void ) {}
+  FeatureVisualPoint( const std::string& name );
+  virtual ~FeatureVisualPoint( void ) {}
 
   virtual unsigned int& getDimension( unsigned int & dim, int time );
   
@@ -92,8 +92,8 @@ class SOTFEATUREVISUALPOINT_EXPORT sotFeatureVisualPoint
   virtual ml::Vector& computeActivation( ml::Vector& res,int time ); 
 
   /** Static Feature selection. */
-  inline static sotFlags selectX( void ) { return FLAG_LINE_1; }
-  inline static sotFlags selectY( void ) { return FLAG_LINE_2; }
+  inline static Flags selectX( void ) { return FLAG_LINE_1; }
+  inline static Flags selectY( void ) { return FLAG_LINE_2; }
 
   virtual void display( std::ostream& os ) const;
 
diff --git a/include/sot-core/fir-filter.h b/include/sot-core/fir-filter.h
index e7a641f6..d760147f 100644
--- a/include/sot-core/fir-filter.h
+++ b/include/sot-core/fir-filter.h
@@ -75,7 +75,7 @@ namespace detail
 }
 
 template<class sigT, class coefT>
-class sotFIRFilter
+class FIRFilter
   : public Entity
 {
 public:
@@ -84,17 +84,17 @@ public:
   static const std::string CLASS_NAME;
 
 public:
-  sotFIRFilter( const std::string& name )
+  FIRFilter( const std::string& name )
     : Entity(name)
     , SIN(NULL,"sotFIRFilter("+name+")::input(T)::in")
-    , SOUT(boost::bind(&sotFIRFilter::compute,this,_1,_2),
+    , SOUT(boost::bind(&FIRFilter::compute,this,_1,_2),
 	   SIN,
 	   "sotFIRFilter("+name+")::output(T)::out")
   {
     signalRegistration( SIN<<SOUT );
   }
 
-  virtual ~sotFIRFilter() {}
+  virtual ~FIRFilter() {}
 
   virtual sigT& compute( sigT& res,int time )
   {
diff --git a/include/sot-core/flags.h b/include/sot-core/flags.h
index d044e0cd..5883c5e6 100644
--- a/include/sot-core/flags.h
+++ b/include/sot-core/flags.h
@@ -39,7 +39,7 @@
 
 namespace sot {
 
-class SOT_CORE_EXPORT sotFlags
+class SOT_CORE_EXPORT Flags
 {
  protected:
   std::vector<char> flags;
@@ -50,27 +50,27 @@ class SOT_CORE_EXPORT sotFlags
   
  public:
   
-  sotFlags( const bool& b=false ) ;
-  sotFlags( const char& c ) ;
-  sotFlags( const int& c4 ) ;
+  Flags( const bool& b=false ) ;
+  Flags( const char& c ) ;
+  Flags( const int& c4 ) ;
 
   void add( const char& c ) ;
   void add( const int& c4 ) ;
     
-  sotFlags operator! (void) const;
-  SOT_CORE_EXPORT friend sotFlags operator& ( const sotFlags& f1,const sotFlags& f2 ) ;
-  SOT_CORE_EXPORT friend sotFlags operator| ( const sotFlags& f1,const sotFlags& f2 ) ;
-  sotFlags& operator&= ( const sotFlags& f2 ) ;
-  sotFlags& operator|= ( const sotFlags& f2 ) ;
+  Flags operator! (void) const;
+  SOT_CORE_EXPORT friend Flags operator& ( const Flags& f1,const Flags& f2 ) ;
+  SOT_CORE_EXPORT friend Flags operator| ( const Flags& f1,const Flags& f2 ) ;
+  Flags& operator&= ( const Flags& f2 ) ;
+  Flags& operator|= ( const Flags& f2 ) ;
    
-  SOT_CORE_EXPORT friend sotFlags operator& ( const sotFlags& f1,const bool& b ) ;
-  SOT_CORE_EXPORT friend sotFlags operator| ( const sotFlags& f1,const bool& b ) ;
-  sotFlags& operator&= ( const bool& b );
-  sotFlags& operator|= ( const bool& b );
+  SOT_CORE_EXPORT friend Flags operator& ( const Flags& f1,const bool& b ) ;
+  SOT_CORE_EXPORT friend Flags operator| ( const Flags& f1,const bool& b ) ;
+  Flags& operator&= ( const bool& b );
+  Flags& operator|= ( const bool& b );
   
-  SOT_CORE_EXPORT friend std::ostream& operator<< (std::ostream& os, const sotFlags& fl );
-  SOT_CORE_EXPORT friend char operator>> (const sotFlags& flags, const int& i);
-  SOT_CORE_EXPORT friend std::istream& operator>> (std::istream& is, sotFlags& fl );
+  SOT_CORE_EXPORT friend std::ostream& operator<< (std::ostream& os, const Flags& fl );
+  SOT_CORE_EXPORT friend char operator>> (const Flags& flags, const int& i);
+  SOT_CORE_EXPORT friend std::istream& operator>> (std::istream& is, Flags& fl );
   bool operator() (const int& i) const;
 
   operator bool (void) const;
@@ -84,21 +84,21 @@ class SOT_CORE_EXPORT sotFlags
 			       unsigned int & indexStart,
 			       unsigned int & indexEnd,
 			       bool& unspecifiedEnd );
-  static sotFlags readIndexMatlab( std::istream & iss );
+  static Flags readIndexMatlab( std::istream & iss );
 
 	  
 
 
 };
 
-SOT_CORE_EXPORT extern const sotFlags FLAG_LINE_1;
-SOT_CORE_EXPORT extern const sotFlags FLAG_LINE_2;
-SOT_CORE_EXPORT extern const sotFlags FLAG_LINE_3;
-SOT_CORE_EXPORT extern const sotFlags FLAG_LINE_4;
-SOT_CORE_EXPORT extern const sotFlags FLAG_LINE_5;
-SOT_CORE_EXPORT extern const sotFlags FLAG_LINE_6;
-SOT_CORE_EXPORT extern const sotFlags FLAG_LINE_7;
-SOT_CORE_EXPORT extern const sotFlags FLAG_LINE_8;
+SOT_CORE_EXPORT extern const Flags FLAG_LINE_1;
+SOT_CORE_EXPORT extern const Flags FLAG_LINE_2;
+SOT_CORE_EXPORT extern const Flags FLAG_LINE_3;
+SOT_CORE_EXPORT extern const Flags FLAG_LINE_4;
+SOT_CORE_EXPORT extern const Flags FLAG_LINE_5;
+SOT_CORE_EXPORT extern const Flags FLAG_LINE_6;
+SOT_CORE_EXPORT extern const Flags FLAG_LINE_7;
+SOT_CORE_EXPORT extern const Flags FLAG_LINE_8;
 
 } // namespace sot
 
diff --git a/include/sot-core/gain-adaptive.h b/include/sot-core/gain-adaptive.h
index 8965a763..254ce752 100644
--- a/include/sot-core/gain-adaptive.h
+++ b/include/sot-core/gain-adaptive.h
@@ -54,7 +54,7 @@ namespace ml = maal::boost;
 
 namespace sot {
 
-class SOTGAINADAPTATIVE_EXPORT sotGainAdaptative
+class SOTGAINADAPTATIVE_EXPORT GainAdaptative
 : public Entity
 {
 
@@ -81,9 +81,9 @@ class SOTGAINADAPTATIVE_EXPORT sotGainAdaptative
 
  public: /* --- CONSTRUCTORS ---- */
 
-  sotGainAdaptative( const std::string & name );
-  sotGainAdaptative( const std::string & name,const double& lambda );
-  sotGainAdaptative( const std::string & name,
+  GainAdaptative( const std::string & name );
+  GainAdaptative( const std::string & name,const double& lambda );
+  GainAdaptative( const std::string & name,
 		     const double& valueAt0, 
 		     const double& valueAtInfty,
 		     const double& tanAt0 );
diff --git a/include/sot-core/gain-hyperbolic.h b/include/sot-core/gain-hyperbolic.h
index 3de809e0..aa7be6e6 100644
--- a/include/sot-core/gain-hyperbolic.h
+++ b/include/sot-core/gain-hyperbolic.h
@@ -55,7 +55,7 @@ namespace ml = maal::boost;
 
 namespace sot {
 
-class SOTGAINHYPERBOLIC_EXPORT sotGainHyperbolic
+class SOTGAINHYPERBOLIC_EXPORT GainHyperbolic
 : public Entity
 {
 
@@ -83,9 +83,9 @@ class SOTGAINHYPERBOLIC_EXPORT sotGainHyperbolic
 
  public: /* --- CONSTRUCTORS ---- */
 
-  sotGainHyperbolic( const std::string & name );
-  sotGainHyperbolic( const std::string & name,const double& lambda );
-  sotGainHyperbolic( const std::string & name,
+  GainHyperbolic( const std::string & name );
+  GainHyperbolic( const std::string & name,const double& lambda );
+  GainHyperbolic( const std::string & name,
 		     const double& valueAt0, 
 		     const double& valueAtInfty,
 		     const double& tanAt0,
diff --git a/src/include/sot/import-default-paths.h b/include/sot-core/import-default-paths.h.cmake
similarity index 79%
rename from src/include/sot/import-default-paths.h
rename to include/sot-core/import-default-paths.h.cmake
index d0495ae6..abf9c7c6 100644
--- a/src/include/sot/import-default-paths.h
+++ b/include/sot-core/import-default-paths.h.cmake
@@ -3,6 +3,6 @@
 # define SOT_FACTORY_COMMAND_IMPORT_DEFAULT_PATHS_H
 
 /// Default script path as known by CMake at configure time.
-# define SOT_IMPORT_DEFAULT_PATHS "/home/blue/sot-lib/script"
+# define SOT_IMPORT_DEFAULT_PATHS @SOT_IMPORT_DEFAULT_PATHS@
 
 #endif //! SOT_FACTORY_COMMAND_IMPORT_DEFAULT_PATHS_H
diff --git a/src/factory/command/import.h b/include/sot-core/import.h
similarity index 100%
rename from src/factory/command/import.h
rename to include/sot-core/import.h
diff --git a/include/sot-core/integrator-abstract.h b/include/sot-core/integrator-abstract.h
index 4b8b3b2a..9ddd5507 100644
--- a/include/sot-core/integrator-abstract.h
+++ b/include/sot-core/integrator-abstract.h
@@ -54,7 +54,7 @@ namespace sot {
  * function between X and Y, while the b_i are those of the numerator.
 */
 template<class sigT, class coefT>
-class sotIntegratorAbstract
+class IntegratorAbstract
 :public Entity
 {
  public:
@@ -63,17 +63,17 @@ class sotIntegratorAbstract
   static const std::string CLASS_NAME;
 
  public:
-  sotIntegratorAbstract ( const std::string& name )
+  IntegratorAbstract ( const std::string& name )
     :Entity(name)
      ,SIN(NULL,"sotIntegratorAbstract("+name+")::input(vector)::in")
-     ,SOUT(boost::bind(&sotIntegratorAbstract<sigT,coefT>::integrate,this,_1,_2),
+     ,SOUT(boost::bind(&IntegratorAbstract<sigT,coefT>::integrate,this,_1,_2),
 		 SIN,
 		 "sotIntegratorAbstract("+name+")::output(vector)::out")
   {
     signalRegistration( SIN<<SOUT );
   }
 
-  virtual ~sotIntegratorAbstract() {}
+  virtual ~IntegratorAbstract() {}
 
   virtual sigT& integrate( sigT& res,int time ) = 0;
 
diff --git a/include/sot-core/integrator-euler.h b/include/sot-core/integrator-euler.h
index c786f02a..138b1019 100644
--- a/include/sot-core/integrator-euler.h
+++ b/include/sot-core/integrator-euler.h
@@ -36,7 +36,7 @@
 namespace sot {
 
 /*!
- * \class sotIntegratorEuler
+ * \class IntegratorEuler
  * \brief integrates an ODE using a naive Euler integration.
  * TODO: change the integration method. For the moment, the highest
  * derivative of the output signal is computed using the
@@ -45,8 +45,8 @@ namespace sot {
  * induce a huge drift for ODEs with a high order at the denominator.
 */
 template<class sigT,class coefT>
-class sotIntegratorEuler
-  : public sotIntegratorAbstract<sigT,coefT>
+class IntegratorEuler
+  : public IntegratorAbstract<sigT,coefT>
 {
 
  public: 
@@ -55,19 +55,19 @@ class sotIntegratorEuler
   static const std::string CLASS_NAME;
 
  public:
-  using sotIntegratorAbstract<sigT,coefT>::SIN;
-  using sotIntegratorAbstract<sigT,coefT>::SOUT;
-  using sotIntegratorAbstract<sigT,coefT>::numerator;
-  using sotIntegratorAbstract<sigT,coefT>::denominator;
+  using IntegratorAbstract<sigT,coefT>::SIN;
+  using IntegratorAbstract<sigT,coefT>::SOUT;
+  using IntegratorAbstract<sigT,coefT>::numerator;
+  using IntegratorAbstract<sigT,coefT>::denominator;
 
  public:
-  sotIntegratorEuler( const std::string& name )
-    : sotIntegratorAbstract<sigT,coefT>( name )
+  IntegratorEuler( const std::string& name )
+    : IntegratorAbstract<sigT,coefT>( name )
   {
     SOUT.addDependancy(SIN);
   }
 
-  virtual ~sotIntegratorEuler( void ) {}
+  virtual ~IntegratorEuler( void ) {}
 
 protected:
   std::vector<sigT> inputMemory;
diff --git a/include/sot-core/matrix-constant.h b/include/sot-core/matrix-constant.h
index 6c096cbd..19789cc3 100644
--- a/include/sot-core/matrix-constant.h
+++ b/include/sot-core/matrix-constant.h
@@ -32,7 +32,7 @@ namespace ml = maal::boost;
 
 namespace sot {
 
-class sotMatrixConstant
+class MatrixConstant
 : public Entity
 {
  public: 
@@ -43,7 +43,7 @@ class sotMatrixConstant
   double color;
 
 public:
-  sotMatrixConstant( const std::string& name )
+  MatrixConstant( const std::string& name )
     :Entity( name )
     ,rows(0),cols(0),color(0.)
     ,SOUT( "sotMatrixConstant("+name+")::output(matrix)::out" )
@@ -52,7 +52,7 @@ public:
       signalRegistration( SOUT );
     }
 
-  virtual ~sotMatrixConstant( void ){}
+  virtual ~MatrixConstant( void ){}
 
   SignalTimeDependant<ml::Matrix,int> SOUT;
 
diff --git a/include/sot-core/matrix-force.h b/include/sot-core/matrix-force.h
index ea34b5fa..a2cf0acc 100644
--- a/include/sot-core/matrix-force.h
+++ b/include/sot-core/matrix-force.h
@@ -34,32 +34,32 @@ namespace ml = maal::boost;
 namespace sot {
 
 
-class sotMatrixHomogeneous;
-class sotMatrixTwist;
+class MatrixHomogeneous;
+class MatrixTwist;
 
 
-class SOT_CORE_EXPORT sotMatrixForce
+class SOT_CORE_EXPORT MatrixForce
 : public ml::Matrix
 {
 
  public: 
 
-  sotMatrixForce( void ) : ml::Matrix(6,6) { setIdentity(); }
-  ~sotMatrixForce( void ) { }
-  explicit sotMatrixForce( const sotMatrixHomogeneous& M ) 
+  MatrixForce( void ) : ml::Matrix(6,6) { setIdentity(); }
+  ~MatrixForce( void ) { }
+  explicit MatrixForce( const MatrixHomogeneous& M ) 
     : ml::Matrix(6,6) 
     { buildFrom(M); }
 
-  sotMatrixForce& buildFrom( const sotMatrixHomogeneous& trans );
+  MatrixForce& buildFrom( const MatrixHomogeneous& trans );
 
-  sotMatrixForce& operator=( const ml::Matrix& );
-  sotMatrixForce&
-    inverse( sotMatrixForce& invMatrix ) const ;
-  inline sotMatrixForce inverse( void )  const 
-    { sotMatrixForce Ainv; return inverse(Ainv); }
+  MatrixForce& operator=( const ml::Matrix& );
+  MatrixForce&
+    inverse( MatrixForce& invMatrix ) const ;
+  inline MatrixForce inverse( void )  const 
+    { MatrixForce Ainv; return inverse(Ainv); }
 
-  sotMatrixTwist& transpose( sotMatrixTwist& Vt ) const;
-  sotMatrixTwist transpose( void ) const;
+  MatrixTwist& transpose( MatrixTwist& Vt ) const;
+  MatrixTwist transpose( void ) const;
 
  };
 
diff --git a/include/sot-core/matrix-homogeneous.h b/include/sot-core/matrix-homogeneous.h
index cdaaf15b..63ec449c 100644
--- a/include/sot-core/matrix-homogeneous.h
+++ b/include/sot-core/matrix-homogeneous.h
@@ -31,27 +31,27 @@ namespace ml = maal::boost;
 /* --------------------------------------------------------------------- */
 namespace sot {
 
-class sotMatrixRotation;
+class MatrixRotation;
 
-class SOT_CORE_EXPORT sotMatrixHomogeneous
+class SOT_CORE_EXPORT MatrixHomogeneous
 : public ml::Matrix
 {
 
  public: 
 
-  sotMatrixHomogeneous( void ) : ml::Matrix(4,4) { setIdentity(); }
-  ~sotMatrixHomogeneous( void ) { }
+  MatrixHomogeneous( void ) : ml::Matrix(4,4) { setIdentity(); }
+  ~MatrixHomogeneous( void ) { }
 
-  sotMatrixHomogeneous& buildFrom( const sotMatrixRotation& rot, const ml::Vector& trans );
-  sotMatrixRotation& extract( sotMatrixRotation& rot ) const;
+  MatrixHomogeneous& buildFrom( const MatrixRotation& rot, const ml::Vector& trans );
+  MatrixRotation& extract( MatrixRotation& rot ) const;
   ml::Vector& extract( ml::Vector& trans ) const;
 
-  sotMatrixHomogeneous& operator=( const ml::Matrix& );
+  MatrixHomogeneous& operator=( const ml::Matrix& );
 
-  sotMatrixHomogeneous&
-    inverse( sotMatrixHomogeneous& invMatrix ) const ;
-  inline sotMatrixHomogeneous inverse( void )  const 
-    { sotMatrixHomogeneous Ainv; return inverse(Ainv); }
+  MatrixHomogeneous&
+    inverse( MatrixHomogeneous& invMatrix ) const ;
+  inline MatrixHomogeneous inverse( void )  const 
+    { MatrixHomogeneous Ainv; return inverse(Ainv); }
 
   ml::Vector& multiply( const ml::Vector& v1,ml::Vector& res ) const;
   inline ml::Vector multiply( const ml::Vector& v1 )  const
diff --git a/include/sot-core/matrix-rotation.h b/include/sot-core/matrix-rotation.h
index 2fc4cfad..29f1fcd2 100644
--- a/include/sot-core/matrix-rotation.h
+++ b/include/sot-core/matrix-rotation.h
@@ -28,22 +28,22 @@
 namespace ml = maal::boost;
 
 namespace sot {
-class sotVectorUTheta;
+class VectorUTheta;
 
 /* --------------------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
-class SOT_CORE_EXPORT sotMatrixRotation
+class SOT_CORE_EXPORT MatrixRotation
 : public ml::Matrix
 {
 
  public: 
 
-  sotMatrixRotation( void ) : ml::Matrix(3,3) { setIdentity(); }
-  ~sotMatrixRotation( void ) { }
+  MatrixRotation( void ) : ml::Matrix(3,3) { setIdentity(); }
+  ~MatrixRotation( void ) { }
 
-  void fromVector( sotVectorUTheta& );
-  sotMatrixRotation& operator= ( sotVectorUTheta&th ) { fromVector(th); return *this; } 
+  void fromVector( VectorUTheta& );
+  MatrixRotation& operator= ( VectorUTheta&th ) { fromVector(th); return *this; } 
 };
     
 } // namespace sot
diff --git a/include/sot-core/matrix-twist.h b/include/sot-core/matrix-twist.h
index 54174a58..352f0d93 100644
--- a/include/sot-core/matrix-twist.h
+++ b/include/sot-core/matrix-twist.h
@@ -33,31 +33,31 @@ namespace ml = maal::boost;
 namespace sot {
 
 
-class sotMatrixHomogeneous;
-class sotMatrixForce;
+class MatrixHomogeneous;
+class MatrixForce;
 
-class SOT_CORE_EXPORT sotMatrixTwist
+class SOT_CORE_EXPORT MatrixTwist
 : public ml::Matrix
 {
 
  public: 
 
-  sotMatrixTwist( void ) : ml::Matrix(6,6) { setIdentity(); }
-  ~sotMatrixTwist( void ) { }
-  explicit sotMatrixTwist( const sotMatrixHomogeneous& M ) 
+  MatrixTwist( void ) : ml::Matrix(6,6) { setIdentity(); }
+  ~MatrixTwist( void ) { }
+  explicit MatrixTwist( const MatrixHomogeneous& M ) 
     : ml::Matrix(6,6) 
     { buildFrom(M); }
 
-  sotMatrixTwist& buildFrom( const sotMatrixHomogeneous& trans );
+  MatrixTwist& buildFrom( const MatrixHomogeneous& trans );
 
-  sotMatrixTwist& operator=( const ml::Matrix& );
-  sotMatrixTwist&
-    inverse( sotMatrixTwist& invMatrix ) const ;
-  inline sotMatrixTwist inverse( void )  const 
-    { sotMatrixTwist Ainv; return inverse(Ainv); }
+  MatrixTwist& operator=( const ml::Matrix& );
+  MatrixTwist&
+    inverse( MatrixTwist& invMatrix ) const ;
+  inline MatrixTwist inverse( void )  const 
+    { MatrixTwist Ainv; return inverse(Ainv); }
 
-  sotMatrixForce& transpose( sotMatrixForce& Vt ) const;
-  sotMatrixForce transpose( void ) const;
+  MatrixForce& transpose( MatrixForce& Vt ) const;
+  MatrixForce transpose( void ) const;
  };
 
 } // namespace sot
diff --git a/include/sot-core/memory-task-sot.h b/include/sot-core/memory-task-sot.h
index 9c3c859f..4897f793 100644
--- a/include/sot-core/memory-task-sot.h
+++ b/include/sot-core/memory-task-sot.h
@@ -46,8 +46,8 @@
 
 namespace sot {
 
-class SOTSOT_CORE_EXPORT sotMemoryTaskSOT
-: public sotTaskAbstract::sotMemoryTaskAbstract, public Entity
+class SOTSOT_CORE_EXPORT MemoryTaskSOT
+: public TaskAbstract::sotMemoryTaskAbstract, public Entity
 {
  public://   protected:
   /* Internal memory to reduce the dynamic allocation at task resolution. */
diff --git a/include/sot-core/multi-bound.h b/include/sot-core/multi-bound.h
index 815e4c20..98a35148 100644
--- a/include/sot-core/multi-bound.h
+++ b/include/sot-core/multi-bound.h
@@ -19,8 +19,8 @@
 
 
 
-#ifndef __SOT_sotMultiBound_H__
-#define __SOT_sotMultiBound_H__
+#ifndef __SOT_MultiBound_H__
+#define __SOT_MultiBound_H__
 
 /* --------------------------------------------------------------------- */
 /* --- INCLUDE --------------------------------------------------------- */
@@ -41,7 +41,7 @@
 
 namespace sot {
 
-class SOT_CORE_EXPORT sotMultiBound
+class SOT_CORE_EXPORT MultiBound
 {
  public:
   enum MultiBoundModeType { MODE_SINGLE, MODE_DOUBLE };
@@ -54,10 +54,10 @@ class SOT_CORE_EXPORT sotMultiBound
   bool boundSupSetup,boundInfSetup;
 
  public:
-  sotMultiBound( const double x = 0.);
-  sotMultiBound( const double xi,const double xs );
-  sotMultiBound( const double x,const SupInfType bound );
-  sotMultiBound( const sotMultiBound& clone );
+  MultiBound( const double x = 0.);
+  MultiBound( const double xi,const double xs );
+  MultiBound( const double x,const SupInfType bound );
+  MultiBound( const MultiBound& clone );
 
  public: // Acessors
   MultiBoundModeType getMode( void ) const;
@@ -71,16 +71,16 @@ class SOT_CORE_EXPORT sotMultiBound
   void setSingleBound( double boundValue );
 
  public:
-  SOT_CORE_EXPORT friend std::ostream& operator<< ( std::ostream& os, const sotMultiBound & m  );
-  SOT_CORE_EXPORT friend std::istream& operator>> ( std::istream& is, sotMultiBound & m  );
+  SOT_CORE_EXPORT friend std::ostream& operator<< ( std::ostream& os, const MultiBound & m  );
+  SOT_CORE_EXPORT friend std::istream& operator>> ( std::istream& is, MultiBound & m  );
 };
 
 /* --------------------------------------------------------------------- */
-typedef std::vector< sotMultiBound > sotVectorMultiBound;
+typedef std::vector< MultiBound > sotVectorMultiBound;
 SOT_CORE_EXPORT std::ostream& operator<< (std::ostream& os, const sotVectorMultiBound& v );
 SOT_CORE_EXPORT std::istream& operator>> (std::istream& os, sotVectorMultiBound& v );
 
 } // namespace sot
 
 
-#endif // #ifndef __SOT_sotMultiBound_H__
+#endif // #ifndef __SOT_MultiBound_H__
diff --git a/include/sot-core/op-point-modifier.h b/include/sot-core/op-point-modifier.h
index 8486bf80..e0438a74 100644
--- a/include/sot-core/op-point-modifier.h
+++ b/include/sot-core/op-point-modifier.h
@@ -50,31 +50,31 @@ namespace ml = maal::boost;
 
 namespace sot {
 
-class SOTOPPOINTMODIFIOR_EXPORT sotOpPointModifior
+class SOTOPPOINTMODIFIOR_EXPORT OpPointModifior
 : public Entity
 {
  public:
   static const std::string CLASS_NAME;
   virtual const std::string& getClassName( void ) const { return CLASS_NAME; }
   
-  sotMatrixHomogeneous transformation;
+  MatrixHomogeneous transformation;
 
  public:
 
   SignalPtr<ml::Matrix,int> jacobianSIN;
-  SignalPtr<sotMatrixHomogeneous,int> positionSIN;
+  SignalPtr<MatrixHomogeneous,int> positionSIN;
   
   SignalTimeDependant<ml::Matrix,int> jacobianSOUT;
-  SignalTimeDependant<sotMatrixHomogeneous,int> positionSOUT;
+  SignalTimeDependant<MatrixHomogeneous,int> positionSOUT;
 
 public:
-  sotOpPointModifior( const std::string& name );
+  OpPointModifior( const std::string& name );
 
-  virtual ~sotOpPointModifior( void ){}
+  virtual ~OpPointModifior( void ){}
 
   ml::Matrix& computeJacobian( ml::Matrix& res,const int& time );
-  sotMatrixHomogeneous& computePosition( sotMatrixHomogeneous& res,const int& time );
-  void setTransformation( const sotMatrixHomogeneous& tr );
+  MatrixHomogeneous& computePosition( MatrixHomogeneous& res,const int& time );
+  void setTransformation( const MatrixHomogeneous& tr );
 
   virtual void commandLine( const std::string& cmdLine,
 			    std::istringstream& cmdArgs, 
diff --git a/include/sot-core/pool.h b/include/sot-core/pool.h
index 1c8cd35d..7e67cf20 100644
--- a/include/sot-core/pool.h
+++ b/include/sot-core/pool.h
@@ -45,16 +45,16 @@
 namespace sot {
 
 // Preliminary declarations
-class sotFeatureAbstract;
-class sotTaskAbstract;
+class FeatureAbstract;
+class TaskAbstract;
 
 
 /*! @ingroup factory
   \brief This class keep tracks of all the objects in the stack of Tasks.
 
   Three kinds of objects are handled:
-  \li The controllers, i.e. the tasks which inherits from sotTaskAbstract.
-  \li The features, i.e. the information which inherits from sotFeatureAbstract.
+  \li The controllers, i.e. the tasks which inherits from TaskAbstract.
+  \li The features, i.e. the information which inherits from FeatureAbstract.
 
   \li Any object which need to be inside the SoT and which inherits from Entity.
 
@@ -71,17 +71,17 @@ class sotTaskAbstract;
 
   It also returns references to signals from their fully-qualified names.
  */
-class SOT_CORE_EXPORT sotPoolStorage
+class SOT_CORE_EXPORT PoolStorage
 {
  public:
   /*! \name Define types to simplify the writing
     @{
    */
   /*! \brief Sorted set of tasks with unique key (name). */
-  typedef std::map< std::string,sotTaskAbstract* > Tasks;
+  typedef std::map< std::string,TaskAbstract* > Tasks;
 
   /*! \brief Sorted set of features with unique key (name). */
-  typedef std::map< std::string,sotFeatureAbstract* > Features;
+  typedef std::map< std::string,FeatureAbstract* > Features;
   /*! @} */
 
  protected:
@@ -99,25 +99,25 @@ class SOT_CORE_EXPORT sotPoolStorage
 
  public:
   /*! \brief Default destructor */
-  ~sotPoolStorage( void );
+  ~PoolStorage( void );
 
   /*! \name Methods related to the handling of the features
     @{
    */
   /*! \brief Registering a feature. */
-  void registerFeature( const std::string& entname,sotFeatureAbstract* ent );
+  void registerFeature( const std::string& entname,FeatureAbstract* ent );
 
   /*! \brief Get a reference to a feature. */
-  sotFeatureAbstract& getFeature( const std::string& name );
+  FeatureAbstract& getFeature( const std::string& name );
   /*! @} */
 
   /*! \name Methods related to the handling of the tasks
     @{
    */
   /*! \brief Registering a task. */
-  void registerTask( const std::string& entname,sotTaskAbstract* ent );
+  void registerTask( const std::string& entname,TaskAbstract* ent );
   /*! \brief Get a reference to a task. */
-  sotTaskAbstract& getTask( const std::string& name );
+  TaskAbstract& getTask( const std::string& name );
   /*! @} */
 
   /*! \brief This method looks for the object named objectName,
@@ -139,7 +139,7 @@ class SOT_CORE_EXPORT sotPoolStorage
 };
 
 
-SOT_CORE_EXPORT extern sotPoolStorage sotPool;
+SOT_CORE_EXPORT extern PoolStorage sotPool;
 
 } // namespace sot
 
diff --git a/include/sot-core/rotation-simple.h b/include/sot-core/rotation-simple.h
index 2b218efa..92aa754d 100644
--- a/include/sot-core/rotation-simple.h
+++ b/include/sot-core/rotation-simple.h
@@ -52,7 +52,7 @@ void bubClearMatrix( const bubTemplateMatrix& m )
 /* --- DEBUG ---------------------------------------------------------------- */
 /* --- DEBUG ---------------------------------------------------------------- */
 /* --- DEBUG ---------------------------------------------------------------- */
-class sotRotationSimple;
+class RotationSimple;
 class SOTSOTH_EXPORT MATLAB
 {
  public:
@@ -119,7 +119,7 @@ class SOTSOTH_EXPORT MATLAB
   MATLAB( const bubMatrix& m1)
     {initFromBubMatrix(m1);}
 
-  MATLAB( const sotRotationSimple& m1,const unsigned int nJ );
+  MATLAB( const RotationSimple& m1,const unsigned int nJ );
 
 };
 
@@ -181,10 +181,10 @@ typedef bub::matrix_column<__SRS_matcolmaj> __SRS_col_matcolmaj;
 
 
   /* Virtual Pure. */
-class SOTSOTH_EXPORT sotRotationSimple
+class SOTSOTH_EXPORT RotationSimple
 {
  public:
-  virtual ~sotRotationSimple( void ) {}
+  virtual ~RotationSimple( void ) {}
 
  public:
   /* --- STANDARD (FULL-RANGE) MULTIPLICATIONS. */
@@ -303,7 +303,7 @@ class SOTSOTH_EXPORT sotRotationSimple
 
 public:
   virtual std::ostream & display( std::ostream & os ) const = 0;
-  friend std::ostream& operator << ( std::ostream & os,const sotRotationSimple& Q ) { return Q.display(os); }
+  friend std::ostream& operator << ( std::ostream & os,const RotationSimple& Q ) { return Q.display(os); }
 };
 
 
@@ -313,7 +313,7 @@ public:
 /* ---------------------------------------------------------- */
 
 class SOTSOTH_EXPORT sotRotationSimpleHouseholder
-  : public sotRotationSimple
+  : public RotationSimple
 {
 public: // protected:
   bubVector v;
@@ -460,7 +460,7 @@ public:
 /* ---------------------------------------------------------- */
 
 class SOTSOTH_EXPORT sotRotationSimpleGiven
-  : public sotRotationSimple
+  : public RotationSimple
 {
 public: // protected:
   double cosF,sinF;
@@ -686,10 +686,10 @@ public: /* --- MULTIPLIERS -------------------------------------------------- */
 /* ---------------------------------------------------------- */
 /* ---------------------------------------------------------- */
 class SOTSOTH_EXPORT sotRotationComposed
-  :public sotRotationSimple
+  :public RotationSimple
 {
 public: // protected
-  std::list< sotRotationSimple* > listRotationSimple;
+  std::list< RotationSimple* > listRotationSimple;
   std::list< sotRotationSimpleHouseholder > listHouseholder;
   std::list< sotRotationSimpleGiven > listGivenRotation;
 
@@ -721,7 +721,7 @@ public:
     listHouseholder.push_back(R);
     listRotationSimple.push_back(&listHouseholder.back());
   }
-  void pushBack( const sotRotationSimple * R )
+  void pushBack( const RotationSimple * R )
   {
     const sotRotationSimpleGiven * GR = dynamic_cast<const sotRotationSimpleGiven *>(R);
     if( GR ) pushBack(*GR);
@@ -739,10 +739,10 @@ public:
   void pushBack( const sotRotationComposed & R )
   {
     //sotDEBUG(15) << "PB size clone = " << R.listRotationSimple.size() << std::endl;
-    for( std::list<sotRotationSimple*>::const_iterator Pi = R.listRotationSimple.begin();
+    for( std::list<RotationSimple*>::const_iterator Pi = R.listRotationSimple.begin();
 Pi!=R.listRotationSimple.end(); ++Pi )
       {
-        const sotRotationSimple* R = *Pi;
+        const RotationSimple* R = *Pi;
         const sotRotationSimpleHouseholder * Rh = dynamic_cast<const sotRotationSimpleHouseholder*>(R);
         const sotRotationSimpleGiven * Rg = dynamic_cast<const sotRotationSimpleGiven*>(R);
         if(NULL!=Rh) pushBack(*Rh);
@@ -761,7 +761,7 @@ Pi!=R.listRotationSimple.end(); ++Pi )
 
   void popBack( void )
   {
-    sotRotationSimple * R = listRotationSimple.back();
+    RotationSimple * R = listRotationSimple.back();
     listRotationSimple.pop_back();
     if( dynamic_cast<sotRotationSimpleHouseholder*>(R) ) { listHouseholder.pop_back(); }
     if( dynamic_cast<sotRotationSimpleGiven*>(R) ) { listGivenRotation.pop_back(); }
@@ -847,7 +847,7 @@ Pi!=R.listRotationSimple.end(); ++Pi )
   template< typename bubTemplate >
   void multiplyLeftTemplate( bubTemplate & Rx ) const // Rx <- Rx*U1*...*Un
   {
-    for( std::list<sotRotationSimple*>::const_iterator Pi
+    for( std::list<RotationSimple*>::const_iterator Pi
            = listRotationSimple.begin();
 	 Pi!=listRotationSimple.end(); ++Pi )
       {	(*Pi)->multiplyLeft(Rx);      }
@@ -855,7 +855,7 @@ Pi!=R.listRotationSimple.end(); ++Pi )
   template< typename bubTemplate >
   void multiplyRightTemplate( bubTemplate & Rx ) const // Rx <- U1*...*Un*Rx
   {
-    for( std::list<sotRotationSimple*>::const_reverse_iterator Pi
+    for( std::list<RotationSimple*>::const_reverse_iterator Pi
            = listRotationSimple.rbegin();
 	 Pi!=listRotationSimple.rend(); ++Pi )
       {      (*Pi)->multiplyRight(Rx);      }
@@ -863,7 +863,7 @@ Pi!=R.listRotationSimple.end(); ++Pi )
   template< typename bubTemplate >
   void multiplyLeftTransposeTemplate( bubTemplate & Rx ) const // Rx <- Rx*Un*...*U1
   {
-    for( std::list<sotRotationSimple*>::const_reverse_iterator Pi
+    for( std::list<RotationSimple*>::const_reverse_iterator Pi
            = listRotationSimple.rbegin();
 	 Pi!=listRotationSimple.rend(); ++Pi )
       {	(*Pi)->multiplyLeftTranspose(Rx);      }
@@ -871,7 +871,7 @@ Pi!=R.listRotationSimple.end(); ++Pi )
   template< typename bubTemplate >
   void multiplyRightTransposeTemplate( bubTemplate & Rx ) const // Rx <- Un*...*U1*Rx
   {
-    for( std::list<sotRotationSimple*>::const_iterator Pi
+    for( std::list<RotationSimple*>::const_iterator Pi
            = listRotationSimple.begin();
 	 Pi!=listRotationSimple.end(); ++Pi )
       {        (*Pi)->multiplyRightTranspose(Rx);      }
@@ -880,7 +880,7 @@ Pi!=R.listRotationSimple.end(); ++Pi )
   /* --- DISPLAY --- */
   virtual std::ostream& display(  std::ostream& os ) const
   {
-    for( std::list<sotRotationSimple*>::const_iterator Pi = listRotationSimple.begin();
+    for( std::list<RotationSimple*>::const_iterator Pi = listRotationSimple.begin();
 	 Pi!=listRotationSimple.end(); ++Pi )
       {
 	os << (**Pi) << " ";
@@ -970,7 +970,7 @@ sotDEBUG(1)<<std::endl;
 /* ---------------------------------------------------------- */
 /* ---------------------------------------------------------- */
 class SOTSOTH_EXPORT sotRotationComposedInExtenso
-  :public sotRotationSimple
+  :public RotationSimple
 {
 public: // protected
   bubMatrix Q;
@@ -992,7 +992,7 @@ public:
   { // Q=U1*...*Un <- Q*Un+1
     R.multiplyLeft(Q);
   }
-  void pushBack( const sotRotationSimple * R )
+  void pushBack( const RotationSimple * R )
   {
     R->multiplyLeft(Q);
   }
diff --git a/include/sot-core/signal-cast.h b/include/sot-core/signal-cast.h
index b4d5f823..f55cb6c6 100644
--- a/include/sot-core/signal-cast.h
+++ b/include/sot-core/signal-cast.h
@@ -45,7 +45,7 @@
 namespace sot {
 
 
-class sotFeatureAbstract;
+class FeatureAbstract;
 
 
 /*!
@@ -161,10 +161,10 @@ public:            																\
 /* -------------------------------------------------------------------------- */
 
 /* --- OTHER --- */
-SOT_SIGNAL_CAST_DEFINITION(sotFlags);
+SOT_SIGNAL_CAST_DEFINITION(Flags);
 SOT_SIGNAL_CAST_DEFINITION_TRACE(sotVectorMultiBound);
 
-typedef sotFeatureAbstract* SignalCast_sotFeatureAbstractPtr  ;
+typedef FeatureAbstract* SignalCast_sotFeatureAbstractPtr  ;
 
 SOT_SIGNAL_CAST_DEFINITION_HPP( SignalCast_sotFeatureAbstractPtr );
 SOT_SIGNAL_CAST_DEFINITION_HPP( struct timeval );
@@ -188,13 +188,13 @@ SOT_SIGNAL_CAST_FULL_DEFINITION(maal::boost::Matrix,;,;,;);
 /* All the followings are defined with proxys on the equivalent
  * functions ml:: based.
  */
-SOT_SIGNAL_CAST_DEFINITION_VECTOR(sotVectorUTheta);
-SOT_SIGNAL_CAST_DEFINITION_VECTOR(sotVectorQuaternion);
-SOT_SIGNAL_CAST_DEFINITION_VECTOR(sotVectorRollPitchYaw);
-SOT_SIGNAL_CAST_DEFINITION_MATRIX(sotMatrixRotation);
-SOT_SIGNAL_CAST_DEFINITION_MATRIX(sotMatrixHomogeneous);
-SOT_SIGNAL_CAST_DEFINITION_MATRIX(sotMatrixTwist);
-SOT_SIGNAL_CAST_DEFINITION_MATRIX(sotMatrixForce);
+SOT_SIGNAL_CAST_DEFINITION_VECTOR(VectorUTheta);
+SOT_SIGNAL_CAST_DEFINITION_VECTOR(VectorQuaternion);
+SOT_SIGNAL_CAST_DEFINITION_VECTOR(VectorRollPitchYaw);
+SOT_SIGNAL_CAST_DEFINITION_MATRIX(MatrixRotation);
+SOT_SIGNAL_CAST_DEFINITION_MATRIX(MatrixHomogeneous);
+SOT_SIGNAL_CAST_DEFINITION_MATRIX(MatrixTwist);
+SOT_SIGNAL_CAST_DEFINITION_MATRIX(MatrixForce);
 
 } // namespace sot
 
diff --git a/include/sot-core/solver-hierarchical-inequalities.h b/include/sot-core/solver-hierarchical-inequalities.h
index 8a79b239..3417c66e 100644
--- a/include/sot-core/solver-hierarchical-inequalities.h
+++ b/include/sot-core/solver-hierarchical-inequalities.h
@@ -118,7 +118,7 @@ public:
   /* ---------------------------------------------------------- */
   /* ---------------------------------------------------------- */
 
-class SOTSOTH_EXPORT sotSolverHierarchicalInequalities
+class SOTSOTH_EXPORT SolverHierarchicalInequalities
 {
 public: // protected:
   typedef bub::matrix<double,bub::column_major> bubMatrixQRWide;
@@ -183,7 +183,7 @@ public: // protected:
 
   /* ---------------------------------------------------------- */
 public:
-  sotSolverHierarchicalInequalities( unsigned int _nJ,
+  SolverHierarchicalInequalities( unsigned int _nJ,
                                      sotRotationComposedInExtenso& _Qh,
                                      bubMatrix &_Rh,
                                      ConstraintList &_cH )
@@ -193,7 +193,7 @@ public:
     u0*=0;
   }
  private:
-  sotSolverHierarchicalInequalities( const sotSolverHierarchicalInequalities& clone )
+  SolverHierarchicalInequalities( const SolverHierarchicalInequalities& clone )
     : nJ(clone.nJ),Qh(clone.Qh),Rh(clone.Rh),constraintH(clone.constraintH){ /* forbiden */ }
 
  public:
diff --git a/include/sot-core/sot-h.h b/include/sot-core/sot-h.h
index d0ebe4e9..359e1eaa 100644
--- a/include/sot-core/sot-h.h
+++ b/include/sot-core/sot-h.h
@@ -52,8 +52,8 @@
 
 namespace sot {
 
-class SOTSOTH_EXPORT sotSOTH
-:public sotSOT
+class SOTSOTH_EXPORT SotH
+:public Sot
 {
  public:
   /*! \brief Specify the name of the class entity. */
@@ -63,19 +63,19 @@ class SOTSOTH_EXPORT sotSOTH
 
   /* --- SPECIFIC MEM -------------------------------------------------- */
   class sotMemoryTaskSOTH
-    : public sotTaskAbstract::sotMemoryTaskAbstract,public Entity
+    : public TaskAbstract::sotMemoryTaskAbstract,public Entity
     {
     public:
-      const sotSOTH * referenceKey;
-      sotSolverHierarchicalInequalities solver;
+      const SotH * referenceKey;
+      SolverHierarchicalInequalities solver;
       ml::Matrix JK,Jff,Jact;
     public:
     sotMemoryTaskSOTH( const std::string & name,
-                       const sotSOTH * ref,
+                       const SotH * ref,
                        unsigned int nJ,
                        sotRotationComposedInExtenso& Qh,
                        bubMatrix &Rh,
-                       sotSolverHierarchicalInequalities::ConstraintList &cH );
+                       SolverHierarchicalInequalities::ConstraintList &cH );
 
     public: // Entity heritage
       static const std::string CLASS_NAME;
@@ -91,20 +91,20 @@ class SOTSOTH_EXPORT sotSOTH
 
 
  protected:
-  //typedef std::vector<sotSolverHierarchicalInequalities *> SolversList;
+  //typedef std::vector<SolverHierarchicalInequalities *> SolversList;
   //SolversList solvers;
   sotRotationComposedInExtenso Qh;
   bubMatrix Rh;
-  sotSolverHierarchicalInequalities::ConstraintList constraintH;
-  sotSolverHierarchicalInequalities solverNorm;
-  sotSolverHierarchicalInequalities * solverPrec;
+  SolverHierarchicalInequalities::ConstraintList constraintH;
+  SolverHierarchicalInequalities solverNorm;
+  SolverHierarchicalInequalities * solverPrec;
   bool fillMemorySignal;
 
  public:
 
   /*! \brief Default constructor */
-  sotSOTH( const std::string& name );
-  ~sotSOTH( void );
+  SotH( const std::string& name );
+  ~SotH( void );
 
  public: /* --- CONTROL --- */
 
diff --git a/include/sot-core/sot-qr.h b/include/sot-core/sot-qr.h
index 991b6692..935256c1 100644
--- a/include/sot-core/sot-qr.h
+++ b/include/sot-core/sot-qr.h
@@ -69,7 +69,7 @@ namespace ml = maal::boost;
 
 namespace sot {
 
-class SOTSOTQR_EXPORT sotSOTQr
+class SOTSOTQR_EXPORT SotQr
 :public Entity
 {
  public:
@@ -81,7 +81,7 @@ class SOTSOTQR_EXPORT sotSOTQr
  protected:
 
   /*! \brief Defines a type for a list of tasks */
-  typedef std::list<sotTaskAbstract*> StackType;
+  typedef std::list<TaskAbstract*> StackType;
 
 
   /*! \brief This field is a list of controllers
@@ -108,7 +108,7 @@ class SOTSOTQR_EXPORT sotSOTQr
   unsigned int nbJoints;
 
   /*! \brief Store a pointer to compute the gradient */
-  sotTaskAbstract* taskGradient;
+  TaskAbstract* taskGradient;
 
   /*! Projection used to compute the control law. */
   ml::Matrix Proj;
@@ -127,7 +127,7 @@ class SOTSOTQR_EXPORT sotSOTQr
  public:
 
   /*! \brief Default constructor */
-  sotSOTQr( const std::string& name );
+  SotQr( const std::string& name );
 
   /*! \name Methods to handle the stack.
     @{
@@ -137,30 +137,30 @@ class SOTSOTQR_EXPORT sotSOTQr
     It has a lowest priority than the previous ones.
     If this is the first task, then it has the highest
     priority. */
-  void push( sotTaskAbstract& task );
+  void push( TaskAbstract& task );
   /*! \brief Pop the task from the stack.
     This method removes the task with the smallest
     priority in the task. The other are projected
     in the null-space of their predecessors. */
-  sotTaskAbstract& pop( void );
+  TaskAbstract& pop( void );
 
   /*! \brief This method allows to know if a task exists or not */
-  bool exist( const sotTaskAbstract& task );
+  bool exist( const TaskAbstract& task );
 
   /*! \brief Remove a task regardless to its position in the stack.
     It removes also the signals connected to the output signal of this stack.*/
-  void remove( const sotTaskAbstract& task );
+  void remove( const TaskAbstract& task );
 
   /*! \brief This method removes the output signals depending on this task. */
-  void removeDependancy( const sotTaskAbstract& key );
+  void removeDependancy( const TaskAbstract& key );
 
   /*! \brief This method makes the task to swap with the task having the
     immediate superior priority. */
-  void up( const sotTaskAbstract& task );
+  void up( const TaskAbstract& task );
 
   /*! \brief This method makes the task to swap with the task having the
     immediate inferior priority. */
-  void down( const sotTaskAbstract& task );
+  void down( const TaskAbstract& task );
 
   /*! \brief Remove all the tasks from the stack. */
   void clear( void );
@@ -215,7 +215,7 @@ class SOTSOTQR_EXPORT sotSOTQr
   /*! Display the stack of tasks in text mode as a tree. */
   virtual void display( std::ostream& os ) const;
   /*! Wrap the previous method around an operator. */
-  SOTSOTQR_EXPORT friend std::ostream& operator<< ( std::ostream& os,const sotSOTQr& sot );
+  SOTSOTQR_EXPORT friend std::ostream& operator<< ( std::ostream& os,const SotQr& sot );
   /*! @} */
  public: /* --- SIGNALS --- */
 
diff --git a/include/sot-core/sot.h b/include/sot-core/sot.h
index 63fb0238..4aeb2007 100644
--- a/include/sot-core/sot.h
+++ b/include/sot-core/sot.h
@@ -69,7 +69,7 @@ namespace sot {
   
   
 */
-class SOTSOT_CORE_EXPORT sotSOT
+class SOTSOT_CORE_EXPORT Sot
 :public Entity
 {
  public:
@@ -82,7 +82,7 @@ class SOTSOT_CORE_EXPORT sotSOT
  protected:
 
   /*! \brief Defines a type for a list of tasks */
-  typedef std::list<sotTaskAbstract*> StackType;
+  typedef std::list<TaskAbstract*> StackType;
 
 
   /*! \brief This field is a list of controllers 
@@ -109,7 +109,7 @@ class SOTSOT_CORE_EXPORT sotSOT
   unsigned int nbJoints;
   
   /*! \brief Store a pointer to compute the gradient */
-  sotTaskAbstract* taskGradient;
+  TaskAbstract* taskGradient;
 
   /*! Projection used to compute the control law. */
   ml::Matrix Proj;
@@ -133,15 +133,15 @@ class SOTSOT_CORE_EXPORT sotSOT
                                            ml::Matrix& JK,
                                            ml::Matrix& Jff,
                                            ml::Matrix& Jact );
-  static ml::Matrix & computeJacobianConstrained( const sotTaskAbstract& task,
+  static ml::Matrix & computeJacobianConstrained( const TaskAbstract& task,
                                            const ml::Matrix& K );
   static ml::Vector taskVectorToMlVector( const sotVectorMultiBound& taskVector );
 
  public:
   
   /*! \brief Default constructor */
-  sotSOT( const std::string& name );
-  ~sotSOT( void ) { /* TODO!! */ }
+  Sot( const std::string& name );
+  ~Sot( void ) { /* TODO!! */ }
 
   /*! \name Methods to handle the stack. 
     @{
@@ -151,30 +151,30 @@ class SOTSOT_CORE_EXPORT sotSOT
     It has a lowest priority than the previous ones.
     If this is the first task, then it has the highest
     priority. */
-  virtual void push( sotTaskAbstract& task );
+  virtual void push( TaskAbstract& task );
   /*! \brief Pop the task from the stack.
     This method removes the task with the smallest
     priority in the task. The other are projected
     in the null-space of their predecessors. */
-  virtual sotTaskAbstract& pop( void );
+  virtual TaskAbstract& pop( void );
 
   /*! \brief This method allows to know if a task exists or not */
-  virtual bool exist( const sotTaskAbstract& task );
+  virtual bool exist( const TaskAbstract& task );
 
   /*! \brief Remove a task regardless to its position in the stack. 
     It removes also the signals connected to the output signal of this stack.*/
-  virtual void remove( const sotTaskAbstract& task );
+  virtual void remove( const TaskAbstract& task );
 
   /*! \brief This method removes the output signals depending on this task. */
-  virtual void removeDependancy( const sotTaskAbstract& key );
+  virtual void removeDependancy( const TaskAbstract& key );
 
   /*! \brief This method makes the task to swap with the task having the 
     immediate superior priority. */
-  virtual void up( const sotTaskAbstract& task );
+  virtual void up( const TaskAbstract& task );
 
   /*! \brief This method makes the task to swap with the task having the 
     immediate inferior priority. */
-  virtual void down( const sotTaskAbstract& task );
+  virtual void down( const TaskAbstract& task );
 
   /*! \brief Remove all the tasks from the stack. */
   virtual void clear( void );
@@ -230,7 +230,7 @@ class SOTSOT_CORE_EXPORT sotSOT
   /*! Display the stack of tasks in text mode as a tree. */
   virtual void display( std::ostream& os ) const;
   /*! Wrap the previous method around an operator. */
-  SOTSOT_CORE_EXPORT friend std::ostream& operator<< ( std::ostream& os,const sotSOT& sot );
+  SOTSOT_CORE_EXPORT friend std::ostream& operator<< ( std::ostream& os,const Sot& sot );
   /*! @} */
  public: /* --- SIGNALS --- */
   
diff --git a/include/sot-core/task-abstract.h b/include/sot-core/task-abstract.h
index ab639ed9..445f88b5 100644
--- a/include/sot-core/task-abstract.h
+++ b/include/sot-core/task-abstract.h
@@ -47,7 +47,7 @@ namespace ml = maal::boost;
 
 namespace sot {
 
-class SOT_CORE_EXPORT sotTaskAbstract
+class SOT_CORE_EXPORT TaskAbstract
 : public Entity
 {
  public:
@@ -77,7 +77,7 @@ class SOT_CORE_EXPORT sotTaskAbstract
   void taskRegistration( void );
 
  public:
-  sotTaskAbstract( const std::string& n );
+  TaskAbstract( const std::string& n );
 
  public: /* --- SIGNALS --- */
 
diff --git a/include/sot-core/task-conti.h b/include/sot-core/task-conti.h
index 992f89a6..cf9c2d5b 100644
--- a/include/sot-core/task-conti.h
+++ b/include/sot-core/task-conti.h
@@ -60,8 +60,8 @@ namespace ml = maal::boost;
 
 namespace sot {
 
-class SOTTASKCONTI_EXPORT sotTaskConti
-: public sotTask
+class SOTTASKCONTI_EXPORT TaskConti
+: public Task
 {
  protected:
   enum TimeRefValues
@@ -80,7 +80,7 @@ class SOTTASKCONTI_EXPORT sotTaskConti
   virtual const std::string& getClassName( void ) const { return CLASS_NAME; }
 
  public:
-  sotTaskConti( const std::string& n );
+  TaskConti( const std::string& n );
 
   void referenceTime( const unsigned int & t ) { timeRef = t; }
   const int &  referenceTime( void ) { return timeRef; }
diff --git a/include/sot-core/task-pd.h b/include/sot-core/task-pd.h
index fbabd245..c7fe053b 100644
--- a/include/sot-core/task-pd.h
+++ b/include/sot-core/task-pd.h
@@ -50,8 +50,8 @@
 
 namespace sot {
 
-class SOTTASKPD_EXPORT sotTaskPD
-: public sotTask
+class SOTTASKPD_EXPORT TaskPD
+: public Task
 {
  public:
   static const std::string CLASS_NAME;
@@ -61,7 +61,7 @@ class SOTTASKPD_EXPORT sotTaskPD
   double beta;
 
  public:
-  sotTaskPD( const std::string& n );
+  TaskPD( const std::string& n );
 
 
   /* --- COMPUTATION --- */
diff --git a/include/sot-core/task-unilateral.h b/include/sot-core/task-unilateral.h
index 2ddd8865..56ca84a7 100644
--- a/include/sot-core/task-unilateral.h
+++ b/include/sot-core/task-unilateral.h
@@ -62,18 +62,18 @@ namespace ml = maal::boost;
 
 namespace sot {
 
-class SOTTASKUNILATERAL_EXPORT sotTaskUnilateral
-: public sotTask
+class SOTTASKUNILATERAL_EXPORT TaskUnilateral
+: public Task
 {
  protected:
-  std::list< sotFeatureAbstract* > featureList;
+  std::list< FeatureAbstract* > featureList;
 
  public:
   static const std::string CLASS_NAME;
   virtual const std::string& getClassName( void ) const { return CLASS_NAME; }
 
  public:
-  sotTaskUnilateral( const std::string& n );
+  TaskUnilateral( const std::string& n );
 
   /* --- COMPUTATION --- */
   sotVectorMultiBound& computeTaskUnilateral( sotVectorMultiBound& res,int time );
diff --git a/include/sot-core/task.h b/include/sot-core/task.h
index 6e981637..39a106f1 100644
--- a/include/sot-core/task.h
+++ b/include/sot-core/task.h
@@ -84,11 +84,11 @@ namespace ml = maal::boost;
 
 namespace sot {
 
-class SOTTASK_EXPORT sotTask
-: public sotTaskAbstract
+class SOTTASK_EXPORT Task
+: public TaskAbstract
 {
  protected:
-  std::list< sotFeatureAbstract* > featureList;
+  std::list< FeatureAbstract* > featureList;
 
  public:
  private: //HACK
@@ -97,13 +97,13 @@ class SOTTASK_EXPORT sotTask
   virtual const std::string& getClassName( void ) const { return CLASS_NAME; }
 
  public:
-  sotTask( const std::string& n );
+  Task( const std::string& n );
 
-  void addFeature( sotFeatureAbstract& s );
+  void addFeature( FeatureAbstract& s );
   void clearFeatureList( void );
 
-  void setControlSelection( const sotFlags& act );
-  void addControlSelection( const sotFlags& act );
+  void setControlSelection( const Flags& act );
+  void addControlSelection( const Flags& act );
   void clearControlSelection( void );
 
   /* --- COMPUTATION --- */
@@ -118,14 +118,14 @@ class SOTTASK_EXPORT sotTask
  public:
   SignalPtr< double,int > controlGainSIN;
   SignalPtr< double,int > dampingGainSINOUT;
-  SignalPtr< sotFlags,int > controlSelectionSIN; // At the task level or at the feature level?
+  SignalPtr< Flags,int > controlSelectionSIN; // At the task level or at the feature level?
 
  public:
   SignalTimeDependant< ml::Vector,int > errorSOUT;
 
   /* --- DISPLAY ------------------------------------------------------------ */
   void display( std::ostream& os ) const;
-  //  friend std::ostream& operator<< ( std::ostream& os,const sotTask& t );
+  //  friend std::ostream& operator<< ( std::ostream& os,const Task& t );
 
   /* --- PARAMS --- */
   virtual void commandLine( const std::string& cmdLine
diff --git a/include/sot-core/unary-op.h b/include/sot-core/unary-op.h
index e9888d72..24fd4eec 100644
--- a/include/sot-core/unary-op.h
+++ b/include/sot-core/unary-op.h
@@ -49,7 +49,7 @@ namespace ml = maal::boost;
 namespace sot {
 
 template< class Tin,class Tout,typename Operator >
-class sotUnaryOp
+class UnaryOp
 :public Entity
 {
   Operator op;
@@ -60,17 +60,17 @@ class sotUnaryOp
   static std::string getTypeOutName( void ) { return "UnknownOut"; }
   static const std::string CLASS_NAME;
 
-  sotUnaryOp( const std::string& name )
+  UnaryOp( const std::string& name )
     : Entity(name)
-    ,SIN(NULL,sotUnaryOp::CLASS_NAME+"("+name+")::input("+getTypeInName()+")::in") 
-    ,SOUT( boost::bind(&sotUnaryOp<Tin,Tout,Operator>::computeOperation,this,_1,_2), 
+    ,SIN(NULL,UnaryOp::CLASS_NAME+"("+name+")::input("+getTypeInName()+")::in") 
+    ,SOUT( boost::bind(&UnaryOp<Tin,Tout,Operator>::computeOperation,this,_1,_2), 
 	   SIN,CLASS_NAME+"("+name+")::output("+getTypeOutName()+")::out") 
     {
       signalRegistration( SIN<<SOUT );
     }
 
 
-  virtual ~sotUnaryOp( void ) {};
+  virtual ~UnaryOp( void ) {};
 
  public: /* --- SIGNAL --- */
 
diff --git a/include/sot-core/vector-constant.h b/include/sot-core/vector-constant.h
index 84a4fbce..9f0efb18 100644
--- a/include/sot-core/vector-constant.h
+++ b/include/sot-core/vector-constant.h
@@ -30,7 +30,7 @@ namespace ml = maal::boost;
 /* --------------------------------------------------------------------- */
 namespace sot{
 
-class sotVectorConstant
+class VectorConstant
 : public Entity
 {
   static const std::string CLASS_NAME;
@@ -40,7 +40,7 @@ class sotVectorConstant
   double color;
 
 public:
-  sotVectorConstant( const std::string& name )
+  VectorConstant( const std::string& name )
     :Entity( name )
     ,rows(0),color(0.)
     ,SOUT( "sotVectorConstant("+name+")::output(vector)::out" )
@@ -49,7 +49,7 @@ public:
       signalRegistration( SOUT );
     }
 
-  virtual ~sotVectorConstant( void ){}
+  virtual ~VectorConstant( void ){}
 
   SignalTimeDependant<ml::Vector,int> SOUT;
 
diff --git a/include/sot-core/vector-quaternion.h b/include/sot-core/vector-quaternion.h
index 28a75301..afac639b 100644
--- a/include/sot-core/vector-quaternion.h
+++ b/include/sot-core/vector-quaternion.h
@@ -29,21 +29,21 @@
 /* --------------------------------------------------------------------- */
 namespace sot {
 
-class SOT_CORE_EXPORT sotVectorQuaternion
+class SOT_CORE_EXPORT VectorQuaternion
 : public sotVectorRotation
 {
  public: 
 
-  sotVectorQuaternion( void ) : sotVectorRotation() { ml::Vector::resize(4); }
-  virtual ~sotVectorQuaternion( void ) { }
+  VectorQuaternion( void ) : sotVectorRotation() { ml::Vector::resize(4); }
+  virtual ~VectorQuaternion( void ) { }
 
-  virtual sotVectorRotation& fromMatrix( const sotMatrixRotation& rot );
-  virtual sotMatrixRotation& toMatrix( sotMatrixRotation& rot ) const;
+  virtual sotVectorRotation& fromMatrix( const MatrixRotation& rot );
+  virtual MatrixRotation& toMatrix( MatrixRotation& rot ) const;
 
-  sotVectorRotation& fromVector( const sotVectorUTheta& ut );
+  sotVectorRotation& fromVector( const VectorUTheta& ut );
 
-  sotVectorQuaternion& conjugate(sotVectorQuaternion& res) const;
-  sotVectorQuaternion& multiply(const sotVectorQuaternion& q2, sotVectorQuaternion& res) const;
+  VectorQuaternion& conjugate(VectorQuaternion& res) const;
+  VectorQuaternion& multiply(const VectorQuaternion& q2, VectorQuaternion& res) const;
 
 };
     
diff --git a/include/sot-core/vector-roll-pitch-yaw.h b/include/sot-core/vector-roll-pitch-yaw.h
index 7e9eda4d..6dc8fd4a 100644
--- a/include/sot-core/vector-roll-pitch-yaw.h
+++ b/include/sot-core/vector-roll-pitch-yaw.h
@@ -29,16 +29,16 @@
 /* --------------------------------------------------------------------- */
 namespace sot {
 
-class SOT_CORE_EXPORT sotVectorRollPitchYaw
+class SOT_CORE_EXPORT VectorRollPitchYaw
 : public sotVectorRotation
 {
  public: 
 
-  sotVectorRollPitchYaw( void ) : sotVectorRotation() { }
-  virtual ~sotVectorRollPitchYaw( void ) { }
+  VectorRollPitchYaw( void ) : sotVectorRotation() { }
+  virtual ~VectorRollPitchYaw( void ) { }
 
-  virtual sotVectorRotation& fromMatrix( const sotMatrixRotation& rot );
-  virtual sotMatrixRotation& toMatrix( sotMatrixRotation& rot ) const;
+  virtual sotVectorRotation& fromMatrix( const MatrixRotation& rot );
+  virtual MatrixRotation& toMatrix( MatrixRotation& rot ) const;
 
 };
     
diff --git a/include/sot-core/vector-rotation.h b/include/sot-core/vector-rotation.h
index 829e5333..b4eeb48d 100644
--- a/include/sot-core/vector-rotation.h
+++ b/include/sot-core/vector-rotation.h
@@ -42,8 +42,8 @@ class SOT_CORE_EXPORT sotVectorRotation
   sotVectorRotation( void ) : ml::Vector(3) { fill(0.); } 
   virtual ~sotVectorRotation( void ) { }
 
-  virtual sotVectorRotation& fromMatrix( const sotMatrixRotation& rot ) = 0;
-  virtual sotMatrixRotation& toMatrix( sotMatrixRotation& rot ) const = 0;
+  virtual sotVectorRotation& fromMatrix( const MatrixRotation& rot ) = 0;
+  virtual MatrixRotation& toMatrix( MatrixRotation& rot ) const = 0;
 };
 
 } // namespace sot
diff --git a/include/sot-core/vector-to-rotation.h b/include/sot-core/vector-to-rotation.h
index 29e5da1b..e2e0b338 100644
--- a/include/sot-core/vector-to-rotation.h
+++ b/include/sot-core/vector-to-rotation.h
@@ -37,7 +37,7 @@ namespace ml = maal::boost;
 /* --------------------------------------------------------------------- */
 namespace sot {
 
-class sotVectorToRotation
+class VectorToRotation
 : public Entity
 {
   static const std::string CLASS_NAME;
@@ -55,15 +55,15 @@ class sotVectorToRotation
   
 
 public:
-  sotVectorToRotation( const std::string& name );
+  VectorToRotation( const std::string& name );
 
-  virtual ~sotVectorToRotation( void ){}
+  virtual ~VectorToRotation( void ){}
 
   SignalPtr<ml::Vector,int> SIN;
-  SignalTimeDependant<sotMatrixRotation,int> SOUT;
+  SignalTimeDependant<MatrixRotation,int> SOUT;
 
-  sotMatrixRotation& computeRotation( const ml::Vector& angles,
-				      sotMatrixRotation& res );
+  MatrixRotation& computeRotation( const ml::Vector& angles,
+				      MatrixRotation& res );
 
 
   virtual void commandLine( const std::string& cmdLine,
diff --git a/include/sot-core/vector-utheta.h b/include/sot-core/vector-utheta.h
index 5f859468..eb9449dd 100644
--- a/include/sot-core/vector-utheta.h
+++ b/include/sot-core/vector-utheta.h
@@ -31,16 +31,16 @@
 namespace sot {
 
 
-class SOT_CORE_EXPORT sotVectorUTheta
+class SOT_CORE_EXPORT VectorUTheta
 : public sotVectorRotation
 {
  public: 
 
-  sotVectorUTheta( void ) : sotVectorRotation() { }
-  virtual ~sotVectorUTheta( void ) { }
+  VectorUTheta( void ) : sotVectorRotation() { }
+  virtual ~VectorUTheta( void ) { }
 
-  virtual sotVectorRotation& fromMatrix( const sotMatrixRotation& rot );
-  virtual sotMatrixRotation& toMatrix( sotMatrixRotation& rot ) const;
+  virtual sotVectorRotation& fromMatrix( const MatrixRotation& rot );
+  virtual MatrixRotation& toMatrix( MatrixRotation& rot ) const;
 
 };
 
diff --git a/include/sot-core/weighted-sot.h b/include/sot-core/weighted-sot.h
index f1e09fd1..32d9b6d3 100644
--- a/include/sot-core/weighted-sot.h
+++ b/include/sot-core/weighted-sot.h
@@ -66,8 +66,8 @@ namespace ml = maal::boost;
 
 namespace sot {
 
-class SOTWEIGHTEDSOT_CORE_EXPORT sotWeightedSOT
-:public sotSOT
+class SOTWEIGHTEDSOT_CORE_EXPORT WeightedSot
+:public Sot
 {
  public:
   /*! \brief Specify the name of the class entity. */
@@ -77,7 +77,7 @@ class SOTWEIGHTEDSOT_CORE_EXPORT sotWeightedSOT
 
  public:
   /*! \brief Default constructor */
-  sotWeightedSOT( const std::string& name );
+  WeightedSot( const std::string& name );
 
  public: /* --- CONTROL --- */
 
diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt
index 67ce12ce..17f61533 100644
--- a/src/CMakeLists.txt
+++ b/src/CMakeLists.txt
@@ -16,8 +16,6 @@ SET(${LIBRARY_NAME}_SOURCES
 	exception/exception-feature.cpp
 	exception/exception-signal.cpp
 	exception/exception-task.cpp
-	exception/exception-tools.cpp
-	exception/exception-traces.cpp
 	
 	signal/signal-cast.cpp
 	
@@ -74,6 +72,7 @@ SET(${LIBRARY_NAME}_SOURCES
 	factory/additional-functions.cpp
 	factory/factory.cpp
 	factory/pool.cpp
+	factory/command/import.cpp
 )
 
 INCLUDE_DIRECTORIES(${CMAKE_SOURCE_DIR}/include)
diff --git a/src/exception/exception-factory.cpp b/src/exception/exception-factory.cpp
index 763e5405..2fcd5241 100644
--- a/src/exception/exception-factory.cpp
+++ b/src/exception/exception-factory.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotExceptionFactory.cpp
+ * File:      ExceptionFactory.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -28,10 +28,10 @@ using namespace sot;
 /* --- CLASS ----------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-const std::string sotExceptionFactory::EXCEPTION_NAME = "Factory";
+const std::string ExceptionFactory::EXCEPTION_NAME = "Factory";
 
-sotExceptionFactory::
-sotExceptionFactory ( const sotExceptionFactory::ErrorCodeEnum& errcode,
+ExceptionFactory::
+ExceptionFactory ( const ExceptionFactory::ErrorCodeEnum& errcode,
 		      const std::string & msg )
   :ExceptionAbstract(errcode,msg)
 {
@@ -39,8 +39,8 @@ sotExceptionFactory ( const sotExceptionFactory::ErrorCodeEnum& errcode,
   sotDEBUG( 1) <<"Created with message <%s>."<<msg<<std::endl;
 }
 
-sotExceptionFactory::
-sotExceptionFactory ( const sotExceptionFactory::ErrorCodeEnum& errcode,
+ExceptionFactory::
+ExceptionFactory ( const ExceptionFactory::ErrorCodeEnum& errcode,
 			const std::string & msg,const char* format, ... )
   :ExceptionAbstract(errcode,msg)
 {
diff --git a/src/exception/exception-feature.cpp b/src/exception/exception-feature.cpp
index 5e8719a0..1a93bf5b 100644
--- a/src/exception/exception-feature.cpp
+++ b/src/exception/exception-feature.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotExceptionFeature.cpp
+ * File:      ExceptionFeature.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -27,17 +27,17 @@ using namespace sot;
 /* --- CLASS ----------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-const std::string sotExceptionFeature::EXCEPTION_NAME = "Feature";
+const std::string ExceptionFeature::EXCEPTION_NAME = "Feature";
 
-sotExceptionFeature::
-sotExceptionFeature ( const sotExceptionFeature::ErrorCodeEnum& errcode,
+ExceptionFeature::
+ExceptionFeature ( const ExceptionFeature::ErrorCodeEnum& errcode,
 		      const std::string & msg )
   :ExceptionAbstract(errcode,msg)
 {
 }
 
-sotExceptionFeature::
-sotExceptionFeature ( const sotExceptionFeature::ErrorCodeEnum& errcode,
+ExceptionFeature::
+ExceptionFeature ( const ExceptionFeature::ErrorCodeEnum& errcode,
 			const std::string & msg,const char* format, ... )
   :ExceptionAbstract(errcode,msg)
 {
diff --git a/src/exception/exception-signal.cpp b/src/exception/exception-signal.cpp
index f89144b7..53d5aa1d 100644
--- a/src/exception/exception-signal.cpp
+++ b/src/exception/exception-signal.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotExceptionSignal.cpp
+ * File:      ExceptionSignal.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -27,17 +27,17 @@ using namespace sot;
 /* --- CLASS ----------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-const std::string sotExceptionSignal::EXCEPTION_NAME = "Signal";
+const std::string ExceptionSignal::EXCEPTION_NAME = "Signal";
 
-sotExceptionSignal::
-sotExceptionSignal ( const sotExceptionSignal::ErrorCodeEnum& errcode,
+ExceptionSignal::
+ExceptionSignal ( const ExceptionSignal::ErrorCodeEnum& errcode,
 		     const std::string & msg )
   :ExceptionAbstract(errcode,msg)
 {
 }
 
-sotExceptionSignal::
-sotExceptionSignal ( const sotExceptionSignal::ErrorCodeEnum& errcode,
+ExceptionSignal::
+ExceptionSignal ( const ExceptionSignal::ErrorCodeEnum& errcode,
 			const std::string & msg,const char* format, ... )
   :ExceptionAbstract(errcode,msg)
 {
diff --git a/src/exception/exception-task.cpp b/src/exception/exception-task.cpp
index 9b0d490a..ab1223e3 100644
--- a/src/exception/exception-task.cpp
+++ b/src/exception/exception-task.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotExceptionTask.cpp
+ * File:      ExceptionTask.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -28,17 +28,17 @@ using namespace sot;
 /* --- CLASS ----------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-const std::string sotExceptionTask::EXCEPTION_NAME = "Task";
+const std::string ExceptionTask::EXCEPTION_NAME = "Task";
 
-sotExceptionTask::
-sotExceptionTask ( const sotExceptionTask::ErrorCodeEnum& errcode,
+ExceptionTask::
+ExceptionTask ( const ExceptionTask::ErrorCodeEnum& errcode,
 		   const std::string & msg )
   :ExceptionAbstract(errcode,msg)
 {
 }
 
-sotExceptionTask::
-sotExceptionTask ( const sotExceptionTask::ErrorCodeEnum& errcode,
+ExceptionTask::
+ExceptionTask ( const ExceptionTask::ErrorCodeEnum& errcode,
 			const std::string & msg,const char* format, ... )
   :ExceptionAbstract(errcode,msg)
 {
diff --git a/src/exception/exception-tools.cpp b/src/exception/exception-tools.cpp
deleted file mode 100644
index 36c2a460..00000000
--- a/src/exception/exception-tools.cpp
+++ /dev/null
@@ -1,62 +0,0 @@
-/*+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
- * Copyright Projet JRL-Japan, 2007
- *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
- *
- * File:      sotExceptionTools.cpp
- * Project:   SOT
- * Author:    Nicolas Mansard
- *
- * Version control
- * ===============
- *
- *  $Id$
- *
- * Description
- * ============
- *
- *
- * ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++*/
-
-#include <sot-core/exception-tools.h>
-#include <stdarg.h>
-#include <cstdio>
-
-using namespace sot;
-
-/* --------------------------------------------------------------------- */
-/* --- CLASS ----------------------------------------------------------- */
-/* --------------------------------------------------------------------- */
-
-const std::string sotExceptionTools::EXCEPTION_NAME = "Tools";
-
-sotExceptionTools::
-sotExceptionTools ( const sotExceptionTools::ErrorCodeEnum& errcode,
-		     const std::string & msg )
-  :ExceptionAbstract(errcode,msg)
-{
-}
-
-sotExceptionTools::
-sotExceptionTools ( const sotExceptionTools::ErrorCodeEnum& errcode,
-			const std::string & msg,const char* format, ... )
-  :ExceptionAbstract(errcode,msg)
-{
-  va_list args;
-  va_start(args,format);
-
-  const unsigned int SIZE = 256;
-  char  buffer[SIZE];
-  vsnprintf(buffer,SIZE,format,args);
-
-  message += buffer;
-
-  va_end(args);
-}
-
-
-
-/*
- * Local variables:
- * c-basic-offset: 2
- * End:
- */
diff --git a/src/exception/exception-traces.cpp b/src/exception/exception-traces.cpp
deleted file mode 100644
index 54309fc6..00000000
--- a/src/exception/exception-traces.cpp
+++ /dev/null
@@ -1,62 +0,0 @@
-/*+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
- * Copyright Projet JRL-Japan, 2007
- *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
- *
- * File:      sotExceptionTraces.cpp
- * Project:   SOT
- * Author:    Nicolas Mansard
- *
- * Version control
- * ===============
- *
- *  $Id$
- *
- * Description
- * ============
- *
- *
- * ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++*/
-
-#include <sot-core/exception-traces.h>
-#include <stdarg.h>
-#include <cstdio>
-
-using namespace sot;
-
-/* --------------------------------------------------------------------- */
-/* --- CLASS ----------------------------------------------------------- */
-/* --------------------------------------------------------------------- */
-
-const std::string sotExceptionTraces::EXCEPTION_NAME = "Traces";
-
-sotExceptionTraces::
-sotExceptionTraces ( const sotExceptionTraces::ErrorCodeEnum& errcode,
-		     const std::string & msg )
-  :ExceptionAbstract(errcode,msg)
-{
-}
-
-sotExceptionTraces::
-sotExceptionTraces ( const sotExceptionTraces::ErrorCodeEnum& errcode,
-			const std::string & msg,const char* format, ... )
-  :ExceptionAbstract(errcode,msg)
-{
-  va_list args;
-  va_start(args,format);
-
-  const unsigned int SIZE = 256;
-  char  buffer[SIZE];
-  vsnprintf(buffer,SIZE,format,args);
-
-  message += buffer;
-
-  va_end(args);
-}
-
-
-
-/*
- * Local variables:
- * c-basic-offset: 2
- * End:
- */
diff --git a/src/factory/additional-functions.cpp b/src/factory/additional-functions.cpp
index 2255e487..a071720b 100644
--- a/src/factory/additional-functions.cpp
+++ b/src/factory/additional-functions.cpp
@@ -129,11 +129,11 @@ cmdFlagSet( const std::string& cmdLine, istringstream& cmdArg, std::ostream& os
     }
 
   try {
-    Signal<sotFlags,int> &sig1
-      = dynamic_cast< Signal<sotFlags,int>& >( pool.getSignal(cmdArg) );
+    Signal<Flags,int> &sig1
+      = dynamic_cast< Signal<Flags,int>& >( pool.getSignal(cmdArg) );
 
     dgDEBUG(25) << "set..."<<endl;
-    sotFlags fl; try { fl = sig1.accessCopy(); } catch(...) {}
+    Flags fl; try { fl = sig1.accessCopy(); } catch(...) {}
     cmdArg >> std::ws >> fl;
     dgDEBUG(15) << "Fl=" << fl <<std::endl;
     sig1 = fl;
diff --git a/src/factory/command/import.cpp b/src/factory/command/import.cpp
index fe13ca39..df3bf1af 100644
--- a/src/factory/command/import.cpp
+++ b/src/factory/command/import.cpp
@@ -162,8 +162,8 @@ namespace sot
 	    ("failed to import module ``%1%'' (import paths: %2%).");
 	  fmt % module;
 	  fmt % scriptDirectories;
-	  SOT_THROW sotExceptionFactory
-	    (sotExceptionFactory::READ_FILE, fmt.str ());
+	  SOT_THROW ExceptionFactory
+	    (ExceptionFactory::READ_FILE, fmt.str ());
 	  return;
 	}
 
diff --git a/src/factory/factory.cpp b/src/factory/factory.cpp
index d6b9f484..4bb59986 100644
--- a/src/factory/factory.cpp
+++ b/src/factory/factory.cpp
@@ -35,20 +35,20 @@ using namespace sot;
 /* --------------------------------------------------------------------- */
 
 
-sotFactoryStorage::
-~sotFactoryStorage( void )
+FactoryStorage::
+~FactoryStorage( void )
 {
   sotDEBUGINOUT(25);
 }
 
 /* --------------------------------------------------------------------- */
-void sotFactoryStorage::
+void FactoryStorage::
 registerTask( const std::string& entname,TaskConstructor_ptr ent )
 {
   TaskMap::iterator entkey;
   if( existTask(entname,entkey) ) // key does exist
     {
-//       SOT_THROW sotExceptionFactory( sotExceptionFactory::OBJECT_CONFLICT,
+//       SOT_THROW ExceptionFactory( ExceptionFactory::OBJECT_CONFLICT,
 // 				 "Another task class already defined with the same name. ",
 // 				 "( while adding task class <%s> inside the factory).",
 // 				 entname.c_str() );
@@ -64,25 +64,25 @@ registerTask( const std::string& entname,TaskConstructor_ptr ent )
     }
 }
 
-sotTaskAbstract* sotFactoryStorage::
+TaskAbstract* FactoryStorage::
 newTask( const std::string& classname,const std::string& objname  )
 {
   TaskMap::iterator entPtr;
   if(! existTask(classname,entPtr) ) // key does not exist
     {
-      SOT_THROW sotExceptionFactory( sotExceptionFactory::UNREFERED_OBJECT,
+      SOT_THROW ExceptionFactory( ExceptionFactory::UNREFERED_OBJECT,
 				     "Unknown task."," (while calling new_task <%s>)",
 				     classname.c_str() );
     }
   return entPtr->second(objname);
 }
-bool sotFactoryStorage::
+bool FactoryStorage::
 existTask( const std::string& name, TaskMap::iterator& entPtr )
 {
   entPtr = taskMap .find( name );
   return ( entPtr != taskMap.end() );
 }
-bool sotFactoryStorage::
+bool FactoryStorage::
 existTask( const std::string& name )
 {
   TaskMap::iterator entPtr;return existTask( name,entPtr );
@@ -90,13 +90,13 @@ existTask( const std::string& name )
 
 
 /* --------------------------------------------------------------------- */
-void sotFactoryStorage::
+void FactoryStorage::
 registerFeature( const std::string& entname,FeatureConstructor_ptr ent )
 {
   FeatureMap::iterator entkey;
   if( existFeature(entname,entkey) ) // key does exist
     {
-//       SOT_THROW sotExceptionFactory( sotExceptionFactory::OBJECT_CONFLICT,
+//       SOT_THROW ExceptionFactory( ExceptionFactory::OBJECT_CONFLICT,
 // 				 "Another feature already defined with the same name. ",
 // 				 "(while adding feature class <%s> inside the factory).",
 // 				 entname.c_str() );
@@ -112,19 +112,19 @@ registerFeature( const std::string& entname,FeatureConstructor_ptr ent )
     }
 }
 
-sotFeatureAbstract* sotFactoryStorage::
+FeatureAbstract* FactoryStorage::
 newFeature( const std::string& classname,const std::string& objname  )
 {
   FeatureMap::iterator entPtr;
   if(! existFeature(classname,entPtr) ) // key does not exist
     {
-      SOT_THROW sotExceptionFactory( sotExceptionFactory::UNREFERED_OBJECT,
+      SOT_THROW ExceptionFactory( ExceptionFactory::UNREFERED_OBJECT,
 				     "Unknown feature."," (while calling new_feature <%s>)",
 				     classname.c_str() );
     }
   return entPtr->second(objname);
 }
-bool sotFactoryStorage::
+bool FactoryStorage::
 existFeature( const std::string& name, FeatureMap::iterator& entPtr )
 {
   //  sotDEBUGINOUT(25) << "(name=<"<<name<<">)."<<std::endl;
@@ -133,7 +133,7 @@ existFeature( const std::string& name, FeatureMap::iterator& entPtr )
   //  sotDEBUG(6) << "ptr: "<< entPtr->second <<std::endl;
   return ( entPtr != featureMap.end() );
 }
-bool sotFactoryStorage::
+bool FactoryStorage::
 existFeature( const std::string& name )
 {
   FeatureMap::iterator entPtr;return existFeature( name,entPtr );
@@ -147,7 +147,7 @@ existFeature( const std::string& name )
 
 sotFeatureRegisterer::
 sotFeatureRegisterer( const std::string& featureClassName,
-		      sotFactoryStorage::FeatureConstructor_ptr maker)
+		      FactoryStorage::FeatureConstructor_ptr maker)
 { 
   //sotDEBUG(3) << "Register feature class: "<< featureClassName << std::endl;
   sotFactory.registerFeature(featureClassName,maker);
@@ -155,7 +155,7 @@ sotFeatureRegisterer( const std::string& featureClassName,
 
 sotTaskRegisterer::
 sotTaskRegisterer( const std::string& taskClassName,
-		   sotFactoryStorage::TaskConstructor_ptr maker) 
+		   FactoryStorage::TaskConstructor_ptr maker) 
 {  
   //sotDEBUG(3) << "Register task class: "<< taskClassName << std::endl;
   sotFactory.registerTask(taskClassName,maker);
@@ -165,7 +165,7 @@ sotTaskRegisterer( const std::string& taskClassName,
 /* --------------------------------------------------------------------- */
 /* ---  COMMAND LINE ---------------------------------------------------- */
 /* --------------------------------------------------------------------- */
-void sotFactoryStorage::
+void FactoryStorage::
 commandLine( const std::string& cmdLine,std::istringstream& cmdArgs,
 	     std::ostream& os )
 {
@@ -206,5 +206,5 @@ commandLine( const std::string& cmdLine,std::istringstream& cmdArgs,
 
 /// The global sotFactory object
 namespace sot {
-sotFactoryStorage sotFactory;
+FactoryStorage sotFactory;
 }
diff --git a/src/factory/pool.cpp b/src/factory/pool.cpp
index b7ed526b..0bc25dab 100644
--- a/src/factory/pool.cpp
+++ b/src/factory/pool.cpp
@@ -35,8 +35,8 @@ using namespace sot;
 /* --- CLASS ----------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-sotPoolStorage::
-~sotPoolStorage( void )
+PoolStorage::
+~PoolStorage( void )
 {
   sotDEBUGIN(15);
 
@@ -47,13 +47,13 @@ sotPoolStorage::
 
 
 /* --------------------------------------------------------------------- */
-void sotPoolStorage::
-registerTask( const std::string& entname,sotTaskAbstract* ent )
+void PoolStorage::
+registerTask( const std::string& entname,TaskAbstract* ent )
 {
   Tasks::iterator entkey = task.find(entname);
   if( entkey != task.end() ) // key does exist
     {
-      throw sotExceptionFactory( sotExceptionFactory::OBJECT_CONFLICT,
+      throw ExceptionFactory( ExceptionFactory::OBJECT_CONFLICT,
 				 "Another task already defined with the same name. ",
 				 "Task name is <%s>.",entname.c_str() );
     }
@@ -65,13 +65,13 @@ registerTask( const std::string& entname,sotTaskAbstract* ent )
     }
 }
 
-sotTaskAbstract& sotPoolStorage::
+TaskAbstract& PoolStorage::
 getTask( const std::string& name )
 {
   Tasks::iterator entPtr = task .find( name );
   if( entPtr == task.end() )
     {
-      SOT_THROW sotExceptionFactory( sotExceptionFactory::UNREFERED_OBJECT,
+      SOT_THROW ExceptionFactory( ExceptionFactory::UNREFERED_OBJECT,
 				     "Unknown task."," (while calling <%s>)",
 				     name.c_str() );
     }
@@ -81,13 +81,13 @@ getTask( const std::string& name )
 
 
 /* --------------------------------------------------------------------- */
-void sotPoolStorage::
-registerFeature( const std::string& entname,sotFeatureAbstract* ent )
+void PoolStorage::
+registerFeature( const std::string& entname,FeatureAbstract* ent )
 {
   Features::iterator entkey = feature.find(entname);
   if( entkey != feature.end() ) // key does exist
     {
-      throw sotExceptionFactory( sotExceptionFactory::OBJECT_CONFLICT,
+      throw ExceptionFactory( ExceptionFactory::OBJECT_CONFLICT,
 				 "Another feature already defined with the same name. ",
 				 "Feature name is <%s>.",entname.c_str() );
     }
@@ -99,13 +99,13 @@ registerFeature( const std::string& entname,sotFeatureAbstract* ent )
     }
 }
 
-sotFeatureAbstract& sotPoolStorage::
+FeatureAbstract& PoolStorage::
 getFeature( const std::string& name )
 {
   Features::iterator entPtr = feature .find( name );
   if( entPtr == feature.end() )
     {
-      SOT_THROW sotExceptionFactory( sotExceptionFactory::UNREFERED_OBJECT,
+      SOT_THROW ExceptionFactory( ExceptionFactory::UNREFERED_OBJECT,
 				     "Unknown feature."," (while calling <%s>)",
 				     name.c_str() );
     }
@@ -125,7 +125,7 @@ getFeature( const std::string& name )
 #include <time.h>
 #endif /*WIN32*/
 
-void sotPoolStorage::
+void PoolStorage::
 writeGraph(const std::string &aFileName)
 {
   size_t IdxPointFound = aFileName.rfind(".");
@@ -166,7 +166,7 @@ writeGraph(const std::string &aFileName)
   for( Tasks::iterator iter=task.begin();
        iter!=task.end();iter++ )
     {
-      sotTaskAbstract* ent = iter->second;
+      TaskAbstract* ent = iter->second;
       GraphFile << "\t\t" << ent->getName()
 		<<" [ label = \"" << ent->getName() << "\" ," << std::endl
 		<<"\t\t   fontcolor = black, color = black, fillcolor = magenta, style=filled, shape=box ]" << std::endl;
@@ -179,7 +179,7 @@ writeGraph(const std::string &aFileName)
   GraphFile.close();
 }
 
-void sotPoolStorage::
+void PoolStorage::
 writeCompletionList(std::ostream& os)
 {
 
@@ -187,7 +187,7 @@ writeCompletionList(std::ostream& os)
 }
 
 
-void sotPoolStorage::
+void PoolStorage::
 commandLine( const std::string& objectName,const std::string& functionName,
 	     std::istringstream& cmdArg, std::ostream& os )
 {
@@ -214,7 +214,7 @@ commandLine( const std::string& objectName,const std::string& functionName,
 	  for( Tasks::iterator iter=task.begin();
 	       iter!=task.end();iter++ )
 	    {
-	      sotTaskAbstract* ent = iter->second;
+	      TaskAbstract* ent = iter->second;
 	      os << ent->getName()
 		 <<" (" << ent->getClassName() << ")" << std::endl;
 	    }
@@ -225,7 +225,7 @@ commandLine( const std::string& objectName,const std::string& functionName,
 	  for( Features::iterator iter=feature.begin();
 	       iter!=feature.end();iter++ )
 	    {
-	      sotFeatureAbstract* ent = iter->second;
+	      FeatureAbstract* ent = iter->second;
 	      os << ent->getName()
 		 <<" (" << ent->getClassName() << ")" << std::endl;
 	    }
@@ -249,5 +249,5 @@ commandLine( const std::string& objectName,const std::string& functionName,
 
 /// The global sotPool object
 namespace sot {
-sotPoolStorage sotPool;
+PoolStorage sotPool;
 }
diff --git a/src/feature/feature-1d.cpp b/src/feature/feature-1d.cpp
index 17bb8561..168bb12f 100644
--- a/src/feature/feature-1d.cpp
+++ b/src/feature/feature-1d.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotFeature1D.cpp
+ * File:      Feature1D.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -32,7 +32,7 @@ using namespace std;
 
 
 using namespace sot;
-SOT_FACTORY_FEATURE_PLUGIN(sotFeature1D,"Feature1D");
+SOT_FACTORY_FEATURE_PLUGIN(Feature1D,"Feature1D");
 
 /* --------------------------------------------------------------------- */
 /* --- CLASS ----------------------------------------------------------- */
@@ -40,9 +40,9 @@ SOT_FACTORY_FEATURE_PLUGIN(sotFeature1D,"Feature1D");
 
 
 
-sotFeature1D::
-sotFeature1D( const string& pointName )
-  : sotFeatureAbstract( pointName )
+Feature1D::
+Feature1D( const string& pointName )
+  : FeatureAbstract( pointName )
     ,errorSIN( NULL,"sotFeature1D("+name+")::input(vector)::errorIN" )
     ,jacobianSIN( NULL,"sotFeature1D("+name+")::input(matrix)::jacobianIN" )
     ,activationSIN( NULL,"sotFeature1D("+name+")::input(matrix)::activationIN" )
@@ -58,7 +58,7 @@ sotFeature1D( const string& pointName )
 /* --------------------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-unsigned int& sotFeature1D::
+unsigned int& Feature1D::
 getDimension( unsigned int & dim, int time ) 
 {  
   sotDEBUG(25)<<"# In {"<<endl;
@@ -70,7 +70,7 @@ getDimension( unsigned int & dim, int time )
 }
 
 
-ml::Vector& sotFeature1D::
+ml::Vector& Feature1D::
 computeError( ml::Vector& res,int time )
 { 
   const ml::Vector& err = errorSIN.access(time);
@@ -82,7 +82,7 @@ computeError( ml::Vector& res,int time )
 
 
 
-ml::Matrix& sotFeature1D::
+ml::Matrix& Feature1D::
 computeJacobian( ml::Matrix& res,int time )
 { 
   sotDEBUGIN(15);
@@ -99,7 +99,7 @@ computeJacobian( ml::Matrix& res,int time )
   return res; 
 }
 
-ml::Vector& sotFeature1D::
+ml::Vector& Feature1D::
 computeActivation( ml::Vector& res,int time )
 { 
   if( activationSIN )
@@ -121,7 +121,7 @@ computeActivation( ml::Vector& res,int time )
 /* --------------------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-void sotFeature1D::
+void Feature1D::
 display( std::ostream& os ) const
 {
   os <<"1D <"<<name<<">: " <<std::endl;
@@ -134,7 +134,7 @@ display( std::ostream& os ) const
 }
 
 
-// void sotFeature1D::
+// void Feature1D::
 // commandLine( const std::string& cmdLine,
 // 	     std::istringstream& cmdArgs,
 // 	     std::ostream& os )
diff --git a/src/feature/feature-abstract.cpp b/src/feature/feature-abstract.cpp
index 5165bf3e..dbbc566c 100644
--- a/src/feature/feature-abstract.cpp
+++ b/src/feature/feature-abstract.cpp
@@ -23,24 +23,24 @@
 using namespace sot;
 
 const std::string 
-sotFeatureAbstract::CLASS_NAME = "FeatureAbstract";
+FeatureAbstract::CLASS_NAME = "FeatureAbstract";
 
 
-sotFeatureAbstract::
-sotFeatureAbstract( const std::string& name ) 
+FeatureAbstract::
+FeatureAbstract( const std::string& name ) 
   :Entity(name)
    ,desiredValueSIN(NULL,"sotFeatureAbstract("+name+")::input(feature)::sdes")
    ,selectionSIN(NULL,"sotFeatureAbstract("+name+")::input(flag)::selec")
-   ,errorSOUT( boost::bind(&sotFeatureAbstract::computeError,this,_1,_2),
+   ,errorSOUT( boost::bind(&FeatureAbstract::computeError,this,_1,_2),
 	       selectionSIN<<desiredValueSIN,
 	       "sotFeatureAbstract("+name+")::output(vector)::error" )
-   ,jacobianSOUT( boost::bind(&sotFeatureAbstract::computeJacobian,this,_1,_2),
+   ,jacobianSOUT( boost::bind(&FeatureAbstract::computeJacobian,this,_1,_2),
 		  selectionSIN,
 		  "sotFeatureAbstract("+name+")::output(matrix)::jacobian" )
-   ,activationSOUT( boost::bind(&sotFeatureAbstract::computeActivation,this,_1,_2),
+   ,activationSOUT( boost::bind(&FeatureAbstract::computeActivation,this,_1,_2),
 		    selectionSIN<<desiredValueSIN,
 		    "sotFeatureAbstract("+name+")::output(vector)::activation" )
-   ,dimensionSOUT( boost::bind(&sotFeatureAbstract::getDimension,this,_1,_2),
+   ,dimensionSOUT( boost::bind(&FeatureAbstract::getDimension,this,_1,_2),
 		   selectionSIN,
 		   "sotFeatureAbstract("+name+")::output(uint)::dim" )
 {
@@ -52,14 +52,14 @@ sotFeatureAbstract( const std::string& name )
 }
 
 
-void sotFeatureAbstract::
+void FeatureAbstract::
 featureRegistration( void )
 {
   sotPool.registerFeature(name,this);
 }
 
 
-std::ostream& sotFeatureAbstract::
+std::ostream& FeatureAbstract::
 writeGraph( std::ostream& os ) const
 {
   Entity::writeGraph(os);
@@ -67,11 +67,11 @@ writeGraph( std::ostream& os ) const
   if( desiredValueSIN )
     {
       //      const SignalAbstract<int> & sdesAbs = desiredValueSIN;
-      const SignalPtr<sotFeatureAbstract *,int>  & sdesSig = desiredValueSIN;
+      const SignalPtr<FeatureAbstract *,int>  & sdesSig = desiredValueSIN;
       
       if (sdesSig!=0)
 	{
-	  sotFeatureAbstract *asotFA = sdesSig.accessCopy();
+	  FeatureAbstract *asotFA = sdesSig.accessCopy();
 	  if (asotFA!=0)
 	    {
 	      os << "\t\"" << asotFA->getName() << "\" -> \"" << getName() << "\""
diff --git a/src/feature/feature-generic.cpp b/src/feature/feature-generic.cpp
index 82f68f88..07fa7a9c 100644
--- a/src/feature/feature-generic.cpp
+++ b/src/feature/feature-generic.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotFeatureGeneric.cpp
+ * File:      FeatureGeneric.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -33,7 +33,7 @@ using namespace std;
 
 using namespace sot;
 
-SOT_FACTORY_FEATURE_PLUGIN(sotFeatureGeneric,"FeatureGeneric");
+SOT_FACTORY_FEATURE_PLUGIN(FeatureGeneric,"FeatureGeneric");
 
 /* --------------------------------------------------------------------- */
 /* --- CLASS ----------------------------------------------------------- */
@@ -41,15 +41,15 @@ SOT_FACTORY_FEATURE_PLUGIN(sotFeatureGeneric,"FeatureGeneric");
 
 
 
-sotFeatureGeneric::
-sotFeatureGeneric( const string& pointName )
-  : sotFeatureAbstract( pointName )
+FeatureGeneric::
+FeatureGeneric( const string& pointName )
+  : FeatureAbstract( pointName )
     ,dimensionDefault(0)
     ,errorSIN( NULL,"sotFeatureGeneric("+name+")::input(vector)::errorIN" )
     ,errordotSIN( NULL,"sotFeatureGeneric("+name+")::input(vector)::errordotIN" )
     ,jacobianSIN( NULL,"sotFeatureGeneric("+name+")::input(matrix)::jacobianIN" )
     ,activationSIN( NULL,"sotFeatureGeneric("+name+")::input(matrix)::activationIN" )
-    ,errordotSOUT(  boost::bind(&sotFeatureGeneric::computeErrorDot,this,_1,_2),
+    ,errordotSOUT(  boost::bind(&FeatureGeneric::computeErrorDot,this,_1,_2),
 		    selectionSIN<<desiredValueSIN,
 		    "sotFeatureAbstract("+name+")::output(vector)::errordot" )
 
@@ -66,12 +66,12 @@ sotFeatureGeneric( const string& pointName )
 /* --------------------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-unsigned int& sotFeatureGeneric::
+unsigned int& FeatureGeneric::
 getDimension( unsigned int & dim, int time ) 
 {  
   sotDEBUG(25)<<"# In {"<<endl;
 
-  const sotFlags &fl = selectionSIN.access(time);
+  const Flags &fl = selectionSIN.access(time);
   
   if( dimensionDefault==0 )  dimensionDefault = errorSIN.access(time).size();
 
@@ -83,25 +83,25 @@ getDimension( unsigned int & dim, int time )
 }
 
 
-ml::Vector& sotFeatureGeneric::
+ml::Vector& FeatureGeneric::
 computeError( ml::Vector& res,int time )
 { 
   const ml::Vector& err = errorSIN.access(time);
-  const sotFlags &fl = selectionSIN.access(time);
+  const Flags &fl = selectionSIN.access(time);
   const unsigned int & dim = dimensionSOUT(time);
 
   unsigned int curr = 0;
   res.resize( dim );
   if( err.size()<dim )
-    { SOT_THROW sotExceptionFeature( sotExceptionFeature::UNCOMPATIBLE_SIZE,
+    { SOT_THROW ExceptionFeature( ExceptionFeature::UNCOMPATIBLE_SIZE,
 				     "Error: dimension uncompatible with des->errorIN size."
 				     " (while considering feature <%s>).",getName().c_str() ); }
 
-  sotFeatureGeneric * sdes = NULL;
+  FeatureGeneric * sdes = NULL;
   if( desiredValueSIN )
     {
-      sotFeatureAbstract* sdesAbs = desiredValueSIN(time);
-      sdes = dynamic_cast<sotFeatureGeneric*>(sdesAbs);
+      FeatureAbstract* sdesAbs = desiredValueSIN(time);
+      sdes = dynamic_cast<FeatureGeneric*>(sdesAbs);
     }
   
   sotDEBUG(15) << "Err = " << err;
@@ -112,7 +112,7 @@ computeError( ml::Vector& res,int time )
       const ml::Vector& errDes = sdes->errorSIN(time);
       sotDEBUG(15) << "Err* = " << errDes;
       if( errDes.size()<dim )
-	{ SOT_THROW sotExceptionFeature( sotExceptionFeature::UNCOMPATIBLE_SIZE,
+	{ SOT_THROW ExceptionFeature( ExceptionFeature::UNCOMPATIBLE_SIZE,
 					 "Error: dimension uncompatible with des->errorIN size."
 					 " (while considering feature <%s>).",getName().c_str() ); }
 
@@ -126,20 +126,20 @@ computeError( ml::Vector& res,int time )
 
 }
 
-ml::Vector& sotFeatureGeneric::
+ml::Vector& FeatureGeneric::
 computeErrorDot( ml::Vector& res,int time )
 { 
-  const sotFlags &fl = selectionSIN.access(time);
+  const Flags &fl = selectionSIN.access(time);
   const unsigned int & dim = dimensionSOUT(time);
 
   unsigned int curr = 0;
   res.resize( dim );
 
-  sotFeatureGeneric * sdes = NULL;
+  FeatureGeneric * sdes = NULL;
   if( desiredValueSIN )
     {
-      sotFeatureAbstract* sdesAbs = desiredValueSIN(time);
-      sdes = dynamic_cast<sotFeatureGeneric*>(sdesAbs);
+      FeatureAbstract* sdesAbs = desiredValueSIN(time);
+      sdes = dynamic_cast<FeatureGeneric*>(sdesAbs);
     }
   
   sotDEBUG(25) << "Dim = " << dim << endl;
@@ -149,7 +149,7 @@ computeErrorDot( ml::Vector& res,int time )
       const ml::Vector& errdotDes = sdes->errordotSIN(time);
       sotDEBUG(15) << "Err* = " << errdotDes;
       if( errdotDes.size()<dim )
-	{ SOT_THROW sotExceptionFeature( sotExceptionFeature::UNCOMPATIBLE_SIZE,
+	{ SOT_THROW ExceptionFeature( ExceptionFeature::UNCOMPATIBLE_SIZE,
 					 "Error: dimension uncompatible with des->errorIN size."
 					 " (while considering feature <%s>).",getName().c_str() ); }
 
@@ -164,13 +164,13 @@ computeErrorDot( ml::Vector& res,int time )
 }
 
 
-ml::Matrix& sotFeatureGeneric::
+ml::Matrix& FeatureGeneric::
 computeJacobian( ml::Matrix& res,int time )
 { 
   sotDEBUGIN(15);
 
   const ml::Matrix& Jac = jacobianSIN.access(time);
-  const sotFlags &fl = selectionSIN.access(time);
+  const Flags &fl = selectionSIN.access(time);
   const unsigned int &dim = dimensionSOUT(time);
 
   unsigned int curr = 0;
@@ -188,13 +188,13 @@ computeJacobian( ml::Matrix& res,int time )
   return res; 
 }
 
-ml::Vector& sotFeatureGeneric::
+ml::Vector& FeatureGeneric::
 computeActivation( ml::Vector& res,int time )
 { 
   if( activationSIN )
     {
       const ml::Vector& err = activationSIN.access(time);
-      const sotFlags &fl = selectionSIN.access(time);
+      const Flags &fl = selectionSIN.access(time);
       
       unsigned int curr = 0;
       res.resize( dimensionSOUT(time) );
@@ -213,7 +213,7 @@ computeActivation( ml::Vector& res,int time )
 /* --------------------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-void sotFeatureGeneric::
+void FeatureGeneric::
 display( std::ostream& os ) const
 {
   os <<"Generic <"<<name<<">: " <<std::endl;
@@ -226,7 +226,7 @@ display( std::ostream& os ) const
 }
 
 
-void sotFeatureGeneric::
+void FeatureGeneric::
 commandLine( const std::string& cmdLine,
 	     std::istringstream& cmdArgs,
 	     std::ostream& os )
diff --git a/src/feature/feature-joint-limits.cpp b/src/feature/feature-joint-limits.cpp
index d9ad313e..03470652 100644
--- a/src/feature/feature-joint-limits.cpp
+++ b/src/feature/feature-joint-limits.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotFeatureJointLimits.cpp
+ * File:      FeatureJointLimits.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -35,14 +35,14 @@ using namespace std;
 /* --------------------------------------------------------------------- */
 
 using namespace sot;
-SOT_FACTORY_FEATURE_PLUGIN(sotFeatureJointLimits,"FeatureJointLimits");
+SOT_FACTORY_FEATURE_PLUGIN(FeatureJointLimits,"FeatureJointLimits");
 
-const double sotFeatureJointLimits::THRESHOLD_DEFAULT = .9;
+const double FeatureJointLimits::THRESHOLD_DEFAULT = .9;
 
 
-sotFeatureJointLimits::
-sotFeatureJointLimits( const string& fName )
-  : sotFeatureAbstract( fName )
+FeatureJointLimits::
+FeatureJointLimits( const string& fName )
+  : FeatureAbstract( fName )
     ,threshold(THRESHOLD_DEFAULT)
 //     ,freeFloatingIndex( FREE_FLOATING_INDEX )
 //     ,freeFloatingSize( FREE_FLOATING_SIZE )
@@ -50,7 +50,7 @@ sotFeatureJointLimits( const string& fName )
     ,jointSIN( NULL,"sotFeatureJointLimits("+name+")::input(vector)::joint" )
     ,upperJlSIN( NULL,"sotFeatureJointLimits("+name+")::input(vector)::upperJl" )
     ,lowerJlSIN( NULL,"sotFeatureJointLimits("+name+")::input(vector)::lowerJl" )
-    ,widthJlSINTERN( boost::bind(&sotFeatureJointLimits::computeWidthJl,this,_1,_2),
+    ,widthJlSINTERN( boost::bind(&FeatureJointLimits::computeWidthJl,this,_1,_2),
 		     upperJlSIN<<lowerJlSIN,
 		     "sotFeatureJointLimits("+name+")::input(vector)::widthJl" )
 {
@@ -76,12 +76,12 @@ sotFeatureJointLimits( const string& fName )
 /* --------------------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-unsigned int& sotFeatureJointLimits::
+unsigned int& FeatureJointLimits::
 getDimension( unsigned int & dim, int time ) 
 {
   sotDEBUG(25)<<"# In {"<<endl;
 
-  const sotFlags &fl = selectionSIN.access(time);
+  const Flags &fl = selectionSIN.access(time);
   const unsigned int NBJL  = upperJlSIN.access(time).size();
 
   dim = 0;
@@ -93,7 +93,7 @@ getDimension( unsigned int & dim, int time )
 }
 
 ml::Vector&
-sotFeatureJointLimits::computeWidthJl( ml::Vector& res,const int& time )
+FeatureJointLimits::computeWidthJl( ml::Vector& res,const int& time )
 {
   sotDEBUGIN(15);
 
@@ -112,14 +112,14 @@ sotFeatureJointLimits::computeWidthJl( ml::Vector& res,const int& time )
 /** Compute the interaction matrix from a subset of
  * the possible features. 
  */
-ml::Matrix& sotFeatureJointLimits::
+ml::Matrix& FeatureJointLimits::
 computeJacobian( ml::Matrix& J,int time )
 {
   sotDEBUG(15)<<"# In {"<<endl;
 
   const unsigned int SIZE=dimensionSOUT.access(time);
   const ml::Vector q = jointSIN.access(time);
-  const sotFlags &fl = selectionSIN(time);
+  const Flags &fl = selectionSIN(time);
   //const unsigned int SIZE_FF=SIZE+freeFloatingSize;
   const unsigned int SIZE_TOTAL=q.size();
   const ml::Vector WJL = widthJlSINTERN.access(time);
@@ -156,11 +156,11 @@ computeJacobian( ml::Matrix& J,int time )
  * a the possible features.
  */
 ml::Vector&
-sotFeatureJointLimits::computeError( ml::Vector& error,int time )
+FeatureJointLimits::computeError( ml::Vector& error,int time )
 {
   sotDEBUGIN(15);
 
-  const sotFlags &fl = selectionSIN(time);
+  const Flags &fl = selectionSIN(time);
   const ml::Vector q = jointSIN.access(time);
   const ml::Vector UJL = upperJlSIN.access(time);
   const ml::Vector LJL = lowerJlSIN.access(time);
@@ -196,10 +196,10 @@ sotFeatureJointLimits::computeError( ml::Vector& error,int time )
  * a the possible features.
  */
 ml::Vector&
-sotFeatureJointLimits::computeActivation( ml::Vector& act,int time )
+FeatureJointLimits::computeActivation( ml::Vector& act,int time )
 {
   const ml::Vector err = errorSOUT.access(time);
-  //const sotFlags &fl = selectionSIN(time);
+  //const Flags &fl = selectionSIN(time);
   const unsigned int SIZE=dimensionSOUT.access(time);
   //const unsigned int SIZE_TOTAL=jointSIN.access(time).size();
   act.resize(SIZE);
@@ -220,7 +220,7 @@ sotFeatureJointLimits::computeActivation( ml::Vector& act,int time )
 }
 
 
-void sotFeatureJointLimits::
+void FeatureJointLimits::
 display( std::ostream& os ) const
 {
   
@@ -232,7 +232,7 @@ display( std::ostream& os ) const
 
 
 
-void sotFeatureJointLimits::
+void FeatureJointLimits::
 commandLine( const std::string& cmdLine,
 	     std::istringstream& cmdArgs,
 	     std::ostream& os )
@@ -255,10 +255,10 @@ commandLine( const std::string& cmdLine,
     }
   else if( cmdLine == "actuate" )
     {
-      sotFlags fl( 63 );
+      Flags fl( 63 );
       selectionSIN =  (! fl);
     }
-  else { sotFeatureAbstract::commandLine( cmdLine,cmdArgs,os ); }
+  else { FeatureAbstract::commandLine( cmdLine,cmdArgs,os ); }
 }
 
 
diff --git a/src/feature/feature-line-distance.cpp b/src/feature/feature-line-distance.cpp
index 3b491522..4344475d 100644
--- a/src/feature/feature-line-distance.cpp
+++ b/src/feature/feature-line-distance.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotFeatureLineDistance.cpp
+ * File:      FeatureLineDistance.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -36,20 +36,20 @@ using namespace std;
 using namespace sot;
 
 #include <sot-core/factory.h>
-SOT_FACTORY_FEATURE_PLUGIN(sotFeatureLineDistance,"FeatureLineDistance");
+SOT_FACTORY_FEATURE_PLUGIN(FeatureLineDistance,"FeatureLineDistance");
 
 /* --------------------------------------------------------------------- */
 /* --- CLASS ----------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-sotFeatureLineDistance::
-sotFeatureLineDistance( const string& pointName )
-  : sotFeatureAbstract( pointName )
+FeatureLineDistance::
+FeatureLineDistance( const string& pointName )
+  : FeatureAbstract( pointName )
     ,positionSIN( NULL,"sotFeatureLineDistance("+name+")::input(matrixHomo)::position" )
     ,articularJacobianSIN( NULL,"sotFeatureLineDistance("+name+")::input(matrix)::Jq" )
     ,positionRefSIN( NULL,"sotFeatureLineDistance("+name+")::input(vector)::positionRef" )
     ,vectorSIN( NULL,"sotFeatureVector3("+name+")::input(vector3)::vector" )
-  ,lineSOUT( boost::bind(&sotFeatureLineDistance::computeLineCoordinates,this,_1,_2),
+  ,lineSOUT( boost::bind(&FeatureLineDistance::computeLineCoordinates,this,_1,_2),
              positionSIN<<positionRefSIN,
              "sotFeatureAbstract("+name+")::output(vector)::line" )
 {
@@ -69,7 +69,7 @@ sotFeatureLineDistance( const string& pointName )
 /* --------------------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-unsigned int& sotFeatureLineDistance::
+unsigned int& FeatureLineDistance::
 getDimension( unsigned int & dim, int time )
 {
   sotDEBUG(25)<<"# In {"<<endl;
@@ -78,7 +78,7 @@ getDimension( unsigned int & dim, int time )
 }
 
 /* --------------------------------------------------------------------- */
-ml::Vector& sotFeatureLineDistance::
+ml::Vector& FeatureLineDistance::
 computeLineCoordinates( ml::Vector& cood,int time )
 {
   sotDEBUGIN(15);
@@ -86,9 +86,9 @@ computeLineCoordinates( ml::Vector& cood,int time )
   cood.resize(6);
 
   /* Line coordinates */
-  const sotMatrixHomogeneous &pos = positionSIN(time);
+  const MatrixHomogeneous &pos = positionSIN(time);
   const ml::Vector & vect = vectorSIN(time);
-  sotMatrixRotation R; pos.extract(R);
+  MatrixRotation R; pos.extract(R);
   ml::Vector v(3); R.multiply(vect,v);
 
   cood(0)= pos(0,3);
@@ -107,7 +107,7 @@ computeLineCoordinates( ml::Vector& cood,int time )
 /** Compute the interaction matrix from a subset of
  * the possible features.
  */
-ml::Matrix& sotFeatureLineDistance::
+ml::Matrix& FeatureLineDistance::
 computeJacobian( ml::Matrix& J,int time )
 {
   sotDEBUG(15)<<"# In {"<<endl;
@@ -118,8 +118,8 @@ computeJacobian( ml::Matrix& J,int time )
     const ml::Matrix & Jq = articularJacobianSIN(time);
 
     const ml::Vector & vect = vectorSIN(time);
-    const sotMatrixHomogeneous & M = positionSIN(time);
-    sotMatrixRotation R; M.extract(R); // wRh
+    const MatrixHomogeneous & M = positionSIN(time);
+    MatrixRotation R; M.extract(R); // wRh
 
     ml::Matrix Skew(3,3);
     Skew( 0,0 ) = 0        ; Skew( 0,1 )=-vect( 2 );  Skew( 0,2 ) = vect( 1 );
@@ -196,7 +196,7 @@ computeJacobian( ml::Matrix& J,int time )
 *a the possible features.
  */
 ml::Vector&
-sotFeatureLineDistance::computeError( ml::Vector& error,int time )
+FeatureLineDistance::computeError( ml::Vector& error,int time )
 {
   sotDEBUGIN(15);
 
@@ -236,14 +236,14 @@ sotFeatureLineDistance::computeError( ml::Vector& error,int time )
 *a the possible features.
  */
 ml::Vector&
-sotFeatureLineDistance::computeActivation( ml::Vector& act,int time )
+FeatureLineDistance::computeActivation( ml::Vector& act,int time )
 {
   selectionSIN(time);
   act.resize(dimensionSOUT(time)) ; act.fill(1);
   return act ;
 }
 
-void sotFeatureLineDistance::
+void FeatureLineDistance::
 display( std::ostream& os ) const
 {
   os <<"LineDistance <"<<name<<">";
@@ -251,7 +251,7 @@ display( std::ostream& os ) const
 
 
 
-void sotFeatureLineDistance::
+void FeatureLineDistance::
 commandLine( const std::string& cmdLine,
 	     std::istringstream& cmdArgs,
 	     std::ostream& os )
@@ -261,7 +261,7 @@ commandLine( const std::string& cmdLine,
       os << "FeaturePoint: "<<endl;
       Entity::commandLine( cmdLine,cmdArgs,os );
     }
-  else  //sotFeatureAbstract::
+  else  //FeatureAbstract::
     Entity::commandLine( cmdLine,cmdArgs,os );
 
 }
diff --git a/src/feature/feature-point6d-relative.cpp b/src/feature/feature-point6d-relative.cpp
index 13c86540..df2d687a 100644
--- a/src/feature/feature-point6d-relative.cpp
+++ b/src/feature/feature-point6d-relative.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotFeaturePoint6dRelative.cpp
+ * File:      FeaturePoint6dRelative.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -37,7 +37,7 @@ using namespace sot;
 
 
 #include <sot-core/factory.h>
-SOT_FACTORY_FEATURE_PLUGIN(sotFeaturePoint6dRelative,"FeaturePoint6dRelative");
+SOT_FACTORY_FEATURE_PLUGIN(FeaturePoint6dRelative,"FeaturePoint6dRelative");
 
 /* --------------------------------------------------------------------- */
 /* --- CLASS ----------------------------------------------------------- */
@@ -45,14 +45,14 @@ SOT_FACTORY_FEATURE_PLUGIN(sotFeaturePoint6dRelative,"FeaturePoint6dRelative");
 
 
 
-sotFeaturePoint6dRelative::
-sotFeaturePoint6dRelative( const string& pointName )
-  : sotFeaturePoint6d( pointName )
+FeaturePoint6dRelative::
+FeaturePoint6dRelative( const string& pointName )
+  : FeaturePoint6d( pointName )
   ,positionReferenceSIN( NULL,"sotFeaturePoint6dRelative("+name+")::input(matrixHomo)::positionRef" )
   ,articularJacobianReferenceSIN( NULL,"sotFeaturePoint6dRelative("+name+")::input(matrix)::JqRef" )
   ,dotpositionSIN(NULL,"sotFeaturePoint6dRelative("+name+")::input(matrixHomo)::dotposition" )
   ,dotpositionReferenceSIN(NULL,"sotFeaturePoint6dRelative("+name+")::input(matrixHomo)::dotpositionRef" )
-  ,errordotSOUT(boost::bind(&sotFeaturePoint6dRelative::computeErrorDot,this,_1,_2),
+  ,errordotSOUT(boost::bind(&FeaturePoint6dRelative::computeErrorDot,this,_1,_2),
 		selectionSIN<<desiredValueSIN,
 		"sotFeatureAbstract("+name+")::output(vector)::errordot" )
 {
@@ -81,27 +81,27 @@ sotFeaturePoint6dRelative( const string& pointName )
 /** Compute the interaction matrix from a subset of
  * the possible features. 
  */
-ml::Matrix& sotFeaturePoint6dRelative::
+ml::Matrix& FeaturePoint6dRelative::
 computeJacobian( ml::Matrix& Jres,int time )
 {
   sotDEBUG(15)<<"# In {"<<endl;
 
   const ml::Matrix & Jq = articularJacobianSIN(time);
   const ml::Matrix & JqRef = articularJacobianReferenceSIN(time);
-  const sotMatrixHomogeneous & wMp = positionSIN(time);
-  const sotMatrixHomogeneous & wMpref = positionReferenceSIN(time);
+  const MatrixHomogeneous & wMp = positionSIN(time);
+  const MatrixHomogeneous & wMpref = positionReferenceSIN(time);
 
   const unsigned int cJ = Jq.nbCols();
   ml::Matrix J(6,cJ);
   {
-    sotMatrixHomogeneous pMw;  wMp.inverse(pMw);
-    sotMatrixHomogeneous pMpref; pMw.multiply( wMpref,pMpref );
-    sotMatrixTwist pVpref; pVpref.buildFrom(pMpref );
+    MatrixHomogeneous pMw;  wMp.inverse(pMw);
+    MatrixHomogeneous pMpref; pMw.multiply( wMpref,pMpref );
+    MatrixTwist pVpref; pVpref.buildFrom(pMpref );
     pVpref.multiply( JqRef,J );
     J -= Jq;
   }
 
-  const sotFlags &fl = selectionSIN(time);
+  const Flags &fl = selectionSIN(time);
   const int dim = dimensionSOUT(time);
   sotDEBUG(15) <<"Dimension="<<dim<<std::endl;
   Jres.resize(dim,cJ) ;
@@ -123,50 +123,50 @@ computeJacobian( ml::Matrix& Jres,int time )
  * a the possible features.
  */
 ml::Vector&
-sotFeaturePoint6dRelative::computeError( ml::Vector& error,int time )
+FeaturePoint6dRelative::computeError( ml::Vector& error,int time )
 {
   sotDEBUGIN(15);
 
 //   /* TODO */
 //   error.resize(6); error.fill(.0);
 
-  const sotMatrixHomogeneous & wMp = positionSIN(time);
-  const sotMatrixHomogeneous & wMpref = positionReferenceSIN(time);
+  const MatrixHomogeneous & wMp = positionSIN(time);
+  const MatrixHomogeneous & wMpref = positionReferenceSIN(time);
 
-  sotMatrixHomogeneous pMw;  wMp.inverse(pMw);
-  sotMatrixHomogeneous pMpref; pMw.multiply( wMpref,pMpref );
+  MatrixHomogeneous pMw;  wMp.inverse(pMw);
+  MatrixHomogeneous pMpref; pMw.multiply( wMpref,pMpref );
   
-  sotMatrixHomogeneous Merr;
+  MatrixHomogeneous Merr;
   try
     {
-      sotFeatureAbstract * sdesAbs = desiredValueSIN(time);
+      FeatureAbstract * sdesAbs = desiredValueSIN(time);
     
-      sotFeaturePoint6dRelative * sdes = dynamic_cast<sotFeaturePoint6dRelative*>(sdesAbs);
+      FeaturePoint6dRelative * sdes = dynamic_cast<FeaturePoint6dRelative*>(sdesAbs);
       if( sdes )
 	{
-	  const sotMatrixHomogeneous & wMp_des = sdes->positionSIN(time);
-	  const sotMatrixHomogeneous & wMpref_des = sdes->positionReferenceSIN(time);
+	  const MatrixHomogeneous & wMp_des = sdes->positionSIN(time);
+	  const MatrixHomogeneous & wMpref_des = sdes->positionReferenceSIN(time);
 	  
-	  sotMatrixHomogeneous pMw_des;  wMp_des.inverse(pMw_des);
-	  sotMatrixHomogeneous pMpref_des; pMw_des.multiply( wMpref_des,pMpref_des );
-	  sotMatrixHomogeneous Minv; pMpref_des.inverse(Minv);
+	  MatrixHomogeneous pMw_des;  wMp_des.inverse(pMw_des);
+	  MatrixHomogeneous pMpref_des; pMw_des.multiply( wMpref_des,pMpref_des );
+	  MatrixHomogeneous Minv; pMpref_des.inverse(Minv);
 	  pMpref.multiply(Minv,Merr);
 	} else {
 
-	  sotFeaturePoint6d * sdes6d = dynamic_cast<sotFeaturePoint6d*>(sdesAbs);
+	  FeaturePoint6d * sdes6d = dynamic_cast<FeaturePoint6d*>(sdesAbs);
 	  if( sdes6d )
 	    {
-	      const sotMatrixHomogeneous & Mref = sdes6d->positionSIN(time);
-	      sotMatrixHomogeneous Minv; Mref.inverse(Minv);
+	      const MatrixHomogeneous & Mref = sdes6d->positionSIN(time);
+	      MatrixHomogeneous Minv; Mref.inverse(Minv);
 	      pMpref.multiply(Minv,Merr);
 	    } else Merr=pMpref;
 	}
     } catch( ... ) { Merr=pMpref; }
   
-  sotMatrixRotation Rerr; Merr.extract( Rerr );
-  sotVectorUTheta rerr; rerr.fromMatrix( Rerr );
+  MatrixRotation Rerr; Merr.extract( Rerr );
+  VectorUTheta rerr; rerr.fromMatrix( Rerr );
 
-  const sotFlags &fl = selectionSIN(time);
+  const Flags &fl = selectionSIN(time);
   error.resize(dimensionSOUT(time)) ;
   unsigned int cursor = 0;
   for( unsigned int i=0;i<3;++i )
@@ -184,29 +184,29 @@ sotFeaturePoint6dRelative::computeError( ml::Vector& error,int time )
  * This is computed by the desired feature.
  */
 ml::Vector&
-sotFeaturePoint6dRelative::computeErrorDot( ml::Vector& errordot,int time )
+FeaturePoint6dRelative::computeErrorDot( ml::Vector& errordot,int time )
 {
   sotDEBUGIN(15);
 
   //   /* TODO */
   //   error.resize(6); error.fill(.0);
-  const sotMatrixHomogeneous & wMp = positionSIN(time);
-  const sotMatrixHomogeneous & wMpref = positionReferenceSIN(time);  
-  const sotMatrixHomogeneous & wdMp = dotpositionSIN(time);
-  const sotMatrixHomogeneous & wdMpref = dotpositionReferenceSIN(time);
+  const MatrixHomogeneous & wMp = positionSIN(time);
+  const MatrixHomogeneous & wMpref = positionReferenceSIN(time);  
+  const MatrixHomogeneous & wdMp = dotpositionSIN(time);
+  const MatrixHomogeneous & wdMpref = dotpositionReferenceSIN(time);
 
   sotDEBUG(15) << "wdMp :" <<wdMp << endl;
   sotDEBUG(15) << "wdMpref :" <<wdMpref << endl;
 
-  sotMatrixRotation dRerr;
+  MatrixRotation dRerr;
   ml::Vector dtrerr;
 
   try
     {
-      sotMatrixRotation wRp;    wMp.extract(wRp);
-      sotMatrixRotation wRpref; wMpref.extract(wRpref );
-      sotMatrixRotation wdRp; wdMp.extract(wdRp);
-      sotMatrixRotation wdRpref; wdMpref.extract(wdRpref );
+      MatrixRotation wRp;    wMp.extract(wRp);
+      MatrixRotation wRpref; wMpref.extract(wRpref );
+      MatrixRotation wdRp; wdMp.extract(wdRp);
+      MatrixRotation wdRpref; wdMpref.extract(wdRpref );
       
       ml::Vector trp(3); wMp.extract(trp);
       ml::Vector trpref(3); wMpref.extract(trpref);
@@ -214,7 +214,7 @@ sotFeaturePoint6dRelative::computeErrorDot( ml::Vector& errordot,int time )
       ml::Vector trdpref(3); wdMpref.extract(trdpref);
       
       sotDEBUG(15) << "Everything is extracted" <<endl;
-      sotMatrixRotation wdRpt,wRpt,op1,op2; 
+      MatrixRotation wdRpt,wRpt,op1,op2; 
       wdRp.transpose(wdRpt);wdRpt.multiply(wRpref, op1);
       wRp.transpose(wRpt);wRpt.multiply(wdRpref,op2);
       op1.addition(op2,dRerr);
@@ -232,9 +232,9 @@ sotFeaturePoint6dRelative::computeErrorDot( ml::Vector& errordot,int time )
 
     } catch( ... ) { sotDEBUG(15) << "You've got a problem with errordot." << std::endl; }
   
-  sotVectorUTheta rerr; rerr.fromMatrix( dRerr );
+  VectorUTheta rerr; rerr.fromMatrix( dRerr );
 
-  const sotFlags &fl = selectionSIN(time);
+  const Flags &fl = selectionSIN(time);
   errordot.resize(dimensionSOUT(time)) ;
   unsigned int cursor = 0;
   for( unsigned int i=0;i<3;++i )
@@ -250,7 +250,7 @@ sotFeaturePoint6dRelative::computeErrorDot( ml::Vector& errordot,int time )
  * a the possible features.
  */
 ml::Vector&
-sotFeaturePoint6dRelative::computeActivation( ml::Vector& act,int time )
+FeaturePoint6dRelative::computeActivation( ml::Vector& act,int time )
 {
   selectionSIN(time);
   act.resize(dimensionSOUT(time)) ; act.fill(1);
@@ -265,13 +265,13 @@ static const char * featureNames  []
     "RX",
     "RY",
     "RZ"  };
-void sotFeaturePoint6dRelative::
+void FeaturePoint6dRelative::
 display( std::ostream& os ) const
 {
   os <<"Point6dRelative <"<<name<<">: (" ;
 
   try{ 
-    const sotFlags &fl = selectionSIN.accessCopy();
+    const Flags &fl = selectionSIN.accessCopy();
     bool first = true;
     for( int i=0;i<6;++i ) 
       if( fl(i) ) 
@@ -284,7 +284,7 @@ display( std::ostream& os ) const
 }
 
 
-void sotFeaturePoint6dRelative::
+void FeaturePoint6dRelative::
 commandLine( const std::string& cmdLine,
 	     std::istringstream& cmdArgs,
 	     std::ostream& os )
@@ -293,7 +293,7 @@ commandLine( const std::string& cmdLine,
     {
       os << "FeaturePoint6dRelative: "<<endl
 	 << "  - initSdes <feature>: init <feature> by copy of the current value."<<endl;
-      sotFeaturePoint6d::commandLine( cmdLine,cmdArgs,os );
+      FeaturePoint6d::commandLine( cmdLine,cmdArgs,os );
     }
   else if( cmdLine=="initSdes" )
     {
@@ -301,8 +301,8 @@ commandLine( const std::string& cmdLine,
       if(cmdArgs.good())
 	{
 	  std::string nameSdes; cmdArgs >> nameSdes;
-	  sotFeaturePoint6dRelative & sdes 
-	    = dynamic_cast< sotFeaturePoint6dRelative &> (pool.getEntity( nameSdes ));
+	  FeaturePoint6dRelative & sdes 
+	    = dynamic_cast< FeaturePoint6dRelative &> (pool.getEntity( nameSdes ));
 	  const int timeCurr = positionSIN.getTime() +1;
 	  positionSIN.recompute( timeCurr );
 	  positionReferenceSIN.recompute( timeCurr );
@@ -313,7 +313,7 @@ commandLine( const std::string& cmdLine,
 	}
     }
   else  
-    sotFeaturePoint6d::commandLine( cmdLine,cmdArgs,os );
+    FeaturePoint6d::commandLine( cmdLine,cmdArgs,os );
 
 }
 
diff --git a/src/feature/feature-point6d.cpp b/src/feature/feature-point6d.cpp
index f328d6db..febbc331 100644
--- a/src/feature/feature-point6d.cpp
+++ b/src/feature/feature-point6d.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotFeaturePoint6d.cpp
+ * File:      FeaturePoint6d.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -38,19 +38,19 @@ using namespace std;
 using namespace sot;
 
 #include <sot-core/factory.h>
-SOT_FACTORY_FEATURE_PLUGIN(sotFeaturePoint6d,"FeaturePoint6d");
+SOT_FACTORY_FEATURE_PLUGIN(FeaturePoint6d,"FeaturePoint6d");
 
 /* --------------------------------------------------------------------- */
 /* --- CLASS ----------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
 
-const sotFeaturePoint6d::ComputationFrameType sotFeaturePoint6d::
+const FeaturePoint6d::ComputationFrameType FeaturePoint6d::
 COMPUTATION_FRAME_DEFAULT = FRAME_DESIRED;
 
-sotFeaturePoint6d::
-sotFeaturePoint6d( const string& pointName )
-  : sotFeatureAbstract( pointName )
+FeaturePoint6d::
+FeaturePoint6d( const string& pointName )
+  : FeatureAbstract( pointName )
     ,computationFrame( COMPUTATION_FRAME_DEFAULT )
     ,positionSIN( NULL,"sotFeaturePoint6d("+name+")::input(matrixHomo)::position" )
     ,articularJacobianSIN( NULL,"sotFeaturePoint6d("+name+")::input(matrix)::Jq" )
@@ -70,12 +70,12 @@ sotFeaturePoint6d( const string& pointName )
 /* --------------------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-unsigned int& sotFeaturePoint6d::
+unsigned int& FeaturePoint6d::
 getDimension( unsigned int & dim, int time )
 {
   sotDEBUG(25)<<"# In {"<<endl;
 
-  const sotFlags &fl = selectionSIN.access(time);
+  const Flags &fl = selectionSIN.access(time);
 
   dim = 0;
   for( int i=0;i<6;++i ) if( fl(i) ) dim++;
@@ -88,14 +88,14 @@ getDimension( unsigned int & dim, int time )
 /** Compute the interaction matrix from a subset of
  * the possible features.
  */
-ml::Matrix& sotFeaturePoint6d::
+ml::Matrix& FeaturePoint6d::
 computeJacobian( ml::Matrix& J,int time )
 {
   sotDEBUG(15)<<"# In {"<<endl;
 
   const ml::Matrix & Jq = articularJacobianSIN(time);
   const int & dim = dimensionSOUT(time);
-  const sotFlags &fl = selectionSIN(time);
+  const Flags &fl = selectionSIN(time);
 
   sotDEBUG(25)<<"dim = "<<dimensionSOUT(time)<<" time:" << time << " "
               << dimensionSOUT.getTime() << " " << dimensionSOUT.getReady() << endl;
@@ -112,17 +112,17 @@ computeJacobian( ml::Matrix& J,int time )
     {
       /* The Jacobian on rotation is equal to Jr = - hdRh Jr6d.
        * The Jacobian in translation is equalt to Jt = [hRw(wthd-wth)]x Jr - Jt. */
-      sotFeatureAbstract * sdesAbs = desiredValueSIN(time);
-      sotFeaturePoint6d * sdes = dynamic_cast<sotFeaturePoint6d*>(sdesAbs);
+      FeatureAbstract * sdesAbs = desiredValueSIN(time);
+      FeaturePoint6d * sdes = dynamic_cast<FeaturePoint6d*>(sdesAbs);
 
-      const sotMatrixHomogeneous& wMh = positionSIN(time);
-      sotMatrixRotation wRh;      wMh.extract(wRh);
-      sotMatrixRotation wRhd;
+      const MatrixHomogeneous& wMh = positionSIN(time);
+      MatrixRotation wRh;      wMh.extract(wRh);
+      MatrixRotation wRhd;
       ml::Vector hdth(3),Rhdth(3);
 
       if(NULL!=sdes)
         {
-          const sotMatrixHomogeneous& wMhd = sdes->positionSIN(time);
+          const MatrixHomogeneous& wMhd = sdes->positionSIN(time);
           wMhd.extract(wRhd);
           for( unsigned int i=0;i<3;++i ) hdth(i)=wMhd(i,3)-wMh(i,3);
         }
@@ -132,7 +132,7 @@ computeJacobian( ml::Matrix& J,int time )
           for( unsigned int i=0;i<3;++i ) hdth(i)=-wMh(i,3);
         }
       wRh.inverse().multiply(hdth,Rhdth);
-      sotMatrixRotation hdRh; wRhd.inverse().multiply(wRh,hdRh);
+      MatrixRotation hdRh; wRhd.inverse().multiply(wRh,hdRh);
 
       ml::Matrix Lx(6,6);
       for(unsigned int i=0;i<3;i++)
@@ -155,17 +155,17 @@ computeJacobian( ml::Matrix& J,int time )
       /* The Jacobian in rotation is equal to Jr = hdJ = hdRh Jr.
        * The Jacobian in translation is equal to Jr = hdJ = hdRh Jr. */
 
-      sotFeatureAbstract * sdesAbs = desiredValueSIN(time);
-      sotFeaturePoint6d * sdes = dynamic_cast<sotFeaturePoint6d*>(sdesAbs);
+      FeatureAbstract * sdesAbs = desiredValueSIN(time);
+      FeaturePoint6d * sdes = dynamic_cast<FeaturePoint6d*>(sdesAbs);
 
-      const sotMatrixHomogeneous& wMh = positionSIN(time);
-      sotMatrixRotation wRh; wMh.extract(wRh);
-      sotMatrixRotation hdRh;
+      const MatrixHomogeneous& wMh = positionSIN(time);
+      MatrixRotation wRh; wMh.extract(wRh);
+      MatrixRotation hdRh;
 
       if( NULL!=sdes )
         {
-          const sotMatrixHomogeneous& wMhd = sdes->positionSIN(time);
-          sotMatrixRotation wRhd; wMhd.extract(wRhd);
+          const MatrixHomogeneous& wMhd = sdes->positionSIN(time);
+          MatrixRotation wRhd; wMhd.extract(wRhd);
           wRhd.inverse().multiply( wRh,hdRh );
         }
       else
@@ -198,7 +198,7 @@ computeJacobian( ml::Matrix& J,int time )
 }
 
 #define SOT_COMPUTE_H1MH2(wMh,wMhd,hMhd) {                 \
-	sotMatrixHomogeneous hMw; wMh.inverse(hMw);        \
+	MatrixHomogeneous hMw; wMh.inverse(hMw);        \
 	sotDEBUG(15)<<"hMw = "<<hMw<<endl;                 \
 	hMw.multiply( wMhd,hMhd );                         \
 	sotDEBUG(15)<<"hMhd = "<<hMhd<<endl;               \
@@ -209,15 +209,15 @@ computeJacobian( ml::Matrix& J,int time )
  * a the possible features.
  */
 ml::Vector&
-sotFeaturePoint6d::computeError( ml::Vector& error,int time )
+FeaturePoint6d::computeError( ml::Vector& error,int time )
 {
   sotDEBUGIN(15);
 
-  const sotFlags &fl = selectionSIN(time);
-  sotFeatureAbstract * sdesAbs = desiredValueSIN(time);
-  sotFeaturePoint6d * sdes = dynamic_cast<sotFeaturePoint6d*>(sdesAbs);
+  const Flags &fl = selectionSIN(time);
+  FeatureAbstract * sdesAbs = desiredValueSIN(time);
+  FeaturePoint6d * sdes = dynamic_cast<FeaturePoint6d*>(sdesAbs);
 
-  const sotMatrixHomogeneous& wMh = positionSIN(time);
+  const MatrixHomogeneous& wMh = positionSIN(time);
   sotDEBUG(15)<<"wMh = "<<wMh<<endl;
 
   /* Computing only translation:                                        *
@@ -226,10 +226,10 @@ sotFeaturePoint6d::computeError( ml::Vector& error,int time )
    *                   = hRw ( wthd - wth )                             *
    * The second line is obtained by writting hMw as the inverse of wMh. */
 
-  sotMatrixHomogeneous hMhd;
+  MatrixHomogeneous hMhd;
   if(NULL!=sdes)
     {
-      const sotMatrixHomogeneous& wMhd = sdes->positionSIN(time);
+      const MatrixHomogeneous& wMhd = sdes->positionSIN(time);
       sotDEBUG(15)<<"wMhd = "<<wMhd<<endl;
       switch(computationFrame)
         {
@@ -262,8 +262,8 @@ sotFeaturePoint6d::computeError( ml::Vector& error,int time )
 
   if(fl(3)||fl(4)||fl(5))
     {
-      sotMatrixRotation hRhd; hMhd.extract( hRhd );
-      sotVectorUTheta hrhd; hrhd.fromMatrix( hRhd );
+      MatrixRotation hRhd; hMhd.extract( hRhd );
+      VectorUTheta hrhd; hrhd.fromMatrix( hRhd );
       for( unsigned int i=0;i<3;++i )
         { if( fl(i+3) ) error(cursor++) = hrhd(i); }
     }
@@ -277,7 +277,7 @@ sotFeaturePoint6d::computeError( ml::Vector& error,int time )
  * a the possible features.
  */
 ml::Vector&
-sotFeaturePoint6d::computeActivation( ml::Vector& act,int time )
+FeaturePoint6d::computeActivation( ml::Vector& act,int time )
 {
   selectionSIN(time);
   act.resize(dimensionSOUT(time)) ; act.fill(1);
@@ -292,13 +292,13 @@ static const char * featureNames  []
     "RX",
     "RY",
     "RZ"  };
-void sotFeaturePoint6d::
+void FeaturePoint6d::
 display( std::ostream& os ) const
 {
   os <<"Point6d <"<<name<<">: (" ;
 
   try{
-    const sotFlags &fl = selectionSIN.accessCopy();
+    const Flags &fl = selectionSIN.accessCopy();
     bool first = true;
     for( int i=0;i<6;++i )
       if( fl(i) )
@@ -312,7 +312,7 @@ display( std::ostream& os ) const
 
 
 
-void sotFeaturePoint6d::
+void FeaturePoint6d::
 commandLine( const std::string& cmdLine,
 	     std::istringstream& cmdArgs,
 	     std::ostream& os )
@@ -338,7 +338,7 @@ commandLine( const std::string& cmdLine,
 	else if( FRAME_CURRENT==computationFrame ) os << "current" << std::endl;
       }
     }
-  else  //sotFeatureAbstract::
+  else  //FeatureAbstract::
     Entity::commandLine( cmdLine,cmdArgs,os );
 
 }
diff --git a/src/feature/feature-task.cpp b/src/feature/feature-task.cpp
index 72d79f9b..7e123cca 100644
--- a/src/feature/feature-task.cpp
+++ b/src/feature/feature-task.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotFeatureTask.cpp
+ * File:      FeatureTask.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -32,7 +32,7 @@ using namespace sot;
 
 
 #include <sot-core/factory.h>
-SOT_FACTORY_FEATURE_PLUGIN(sotFeatureTask,"FeatureTask");
+SOT_FACTORY_FEATURE_PLUGIN(FeatureTask,"FeatureTask");
 
 /* --------------------------------------------------------------------- */
 /* --- CLASS ----------------------------------------------------------- */
@@ -40,9 +40,9 @@ SOT_FACTORY_FEATURE_PLUGIN(sotFeatureTask,"FeatureTask");
 
 
 
-sotFeatureTask::
-sotFeatureTask( const string& pointName )
-  : sotFeatureGeneric( pointName )
+FeatureTask::
+FeatureTask( const string& pointName )
+  : FeatureGeneric( pointName )
 {
 }
 
@@ -51,25 +51,25 @@ sotFeatureTask( const string& pointName )
 /* --------------------------------------------------------------------- */
 
 
-ml::Vector& sotFeatureTask::
+ml::Vector& FeatureTask::
 computeError( ml::Vector& res,int time )
 { 
   const ml::Vector& err = errorSIN.access(time);
-  const sotFlags &fl = selectionSIN.access(time);
+  const Flags &fl = selectionSIN.access(time);
   const unsigned int & dim = dimensionSOUT(time);
 
   unsigned int curr = 0;
   res.resize( dim );
   if( err.size()<dim )
-    { SOT_THROW sotExceptionFeature( sotExceptionFeature::UNCOMPATIBLE_SIZE,
+    { SOT_THROW ExceptionFeature( ExceptionFeature::UNCOMPATIBLE_SIZE,
 				     "Error: dimension uncompatible with des->errorIN size."
 				     " (while considering feature <%s>).",getName().c_str() ); }
 
-  sotFeatureTask * sdes = NULL;
+  FeatureTask * sdes = NULL;
   if( desiredValueSIN )
     {
-      sotFeatureAbstract* sdesAbs = desiredValueSIN(time);
-      sdes = dynamic_cast<sotFeatureTask*>(sdesAbs);
+      FeatureAbstract* sdesAbs = desiredValueSIN(time);
+      sdes = dynamic_cast<FeatureTask*>(sdesAbs);
     }
   
   sotDEBUG(15) << "Err = " << err;
@@ -80,7 +80,7 @@ computeError( ml::Vector& res,int time )
       const ml::Vector& errDes = sdes->errorSIN(time);
       sotDEBUG(15) << "Err* = " << errDes;
       if( errDes.size()<dim )
-	{ SOT_THROW sotExceptionFeature( sotExceptionFeature::UNCOMPATIBLE_SIZE,
+	{ SOT_THROW ExceptionFeature( ExceptionFeature::UNCOMPATIBLE_SIZE,
 					 "Error: dimension uncompatible with des->errorIN size."
 					 " (while considering feature <%s>).",getName().c_str() ); }
 
@@ -100,7 +100,7 @@ computeError( ml::Vector& res,int time )
 /* --------------------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-void sotFeatureTask::
+void FeatureTask::
 display( std::ostream& os ) const
 {
   os << "Feature from task <" << getName();
@@ -109,7 +109,7 @@ display( std::ostream& os ) const
 }
 
 
-void sotFeatureTask::
+void FeatureTask::
 commandLine( const std::string& cmdLine,
 	     std::istringstream& cmdArgs,
 	     std::ostream& os )
@@ -125,7 +125,7 @@ commandLine( const std::string& cmdLine,
       if( cmdArgs.good() )
 	{
 	  std::string name; cmdArgs >> name;
-	  sotTaskAbstract& task = dynamic_cast< sotTaskAbstract & > (pool .getEntity( name ));
+	  TaskAbstract& task = dynamic_cast< TaskAbstract & > (pool .getEntity( name ));
 	  taskPtr = &task;
 
 	  errorSIN.plug( &task.taskSOUT );
diff --git a/src/feature/feature-vector3.cpp b/src/feature/feature-vector3.cpp
index 1e691586..7b9568df 100644
--- a/src/feature/feature-vector3.cpp
+++ b/src/feature/feature-vector3.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotFeatureVector3.cpp
+ * File:      FeatureVector3.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -38,15 +38,15 @@ using namespace sot;
 using namespace std;
 
 
-SOT_FACTORY_FEATURE_PLUGIN(sotFeatureVector3,"FeatureVector3");
+SOT_FACTORY_FEATURE_PLUGIN(FeatureVector3,"FeatureVector3");
 
 /* --------------------------------------------------------------------- */
 /* --- CLASS ----------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-sotFeatureVector3::
-sotFeatureVector3( const string& pointName )
-  : sotFeatureAbstract( pointName )
+FeatureVector3::
+FeatureVector3( const string& pointName )
+  : FeatureAbstract( pointName )
     ,vectorSIN( NULL,"sotFeatureVector3("+name+")::input(vector3)::vector" )
     ,positionSIN( NULL,"sotFeaturePoint6d("+name+")::input(matrixHomo)::position" )
     ,articularJacobianSIN( NULL,"sotFeatureVector3("+name+")::input(matrix)::Jq" )
@@ -70,7 +70,7 @@ sotFeatureVector3( const string& pointName )
 /* --------------------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-unsigned int& sotFeatureVector3::
+unsigned int& FeatureVector3::
 getDimension( unsigned int & dim, int time )
 {
   sotDEBUG(25)<<"# In {"<<endl;
@@ -84,15 +84,15 @@ getDimension( unsigned int & dim, int time )
 /** Compute the interaction matrix from a subset of
  * the possible features.
  */
-ml::Matrix& sotFeatureVector3::
+ml::Matrix& FeatureVector3::
 computeJacobian( ml::Matrix& J,int time )
 {
   sotDEBUG(15)<<"# In {"<<endl;
 
   const ml::Matrix & Jq = articularJacobianSIN(time);
   const ml::Vector & vect = vectorSIN(time);
-  const sotMatrixHomogeneous & M = positionSIN(time);
-  sotMatrixRotation R; M.extract(R);
+  const MatrixHomogeneous & M = positionSIN(time);
+  MatrixRotation R; M.extract(R);
 
   ml::Matrix Skew(3,3);
   Skew( 0,0 ) = 0        ; Skew( 0,1 )=-vect( 2 );  Skew( 0,2 ) = vect( 1 );
@@ -118,11 +118,11 @@ computeJacobian( ml::Matrix& J,int time )
 *a the possible features.
  */
 ml::Vector&
-sotFeatureVector3::computeError( ml::Vector& Mvect3,int time )
+FeatureVector3::computeError( ml::Vector& Mvect3,int time )
 {
   sotDEBUGIN(15);
 
-  const sotMatrixHomogeneous & M = positionSIN(time);
+  const MatrixHomogeneous & M = positionSIN(time);
   const ml::Vector & vect = vectorSIN(time);
   const ml::Vector & vectdes = positionRefSIN(time);
 
@@ -130,7 +130,7 @@ sotFeatureVector3::computeError( ml::Vector& Mvect3,int time )
   sotDEBUG(15) << "v = " << vect << std::endl;
   sotDEBUG(15) << "vd = " << vectdes << std::endl;
 
-  sotMatrixRotation R; M.extract(R);
+  MatrixRotation R; M.extract(R);
   Mvect3.resize(3);
   R.multiply(vect,Mvect3);
   Mvect3 -= vectdes;
@@ -143,14 +143,14 @@ sotFeatureVector3::computeError( ml::Vector& Mvect3,int time )
 *a the possible features.
  */
 ml::Vector&
-sotFeatureVector3::computeActivation( ml::Vector& act,int time )
+FeatureVector3::computeActivation( ml::Vector& act,int time )
 {
   selectionSIN(time);
   act.resize(dimensionSOUT(time)) ; act.fill(1);
   return act ;
 }
 
-void sotFeatureVector3::
+void FeatureVector3::
 display( std::ostream& os ) const
 {
   os <<"Vector3 <"<<name<<">";
@@ -158,7 +158,7 @@ display( std::ostream& os ) const
 
 
 
-void sotFeatureVector3::
+void FeatureVector3::
 commandLine( const std::string& cmdLine,
 	     std::istringstream& cmdArgs,
 	     std::ostream& os )
@@ -168,7 +168,7 @@ commandLine( const std::string& cmdLine,
       os << "FeatureVector: "<<endl;
       Entity::commandLine( cmdLine,cmdArgs,os );
     }
-  else  //sotFeatureAbstract::
+  else  //FeatureAbstract::
     Entity::commandLine( cmdLine,cmdArgs,os );
 
 }
diff --git a/src/feature/feature-visual-point.cpp b/src/feature/feature-visual-point.cpp
index 9c666f61..4965c93a 100644
--- a/src/feature/feature-visual-point.cpp
+++ b/src/feature/feature-visual-point.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotFeatureVisualPoint.cpp
+ * File:      FeatureVisualPoint.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -32,7 +32,7 @@ using namespace sot;
 
 
 
-SOT_FACTORY_FEATURE_PLUGIN(sotFeatureVisualPoint,"FeatureVisualPoint");
+SOT_FACTORY_FEATURE_PLUGIN(FeatureVisualPoint,"FeatureVisualPoint");
 
 /* --------------------------------------------------------------------- */
 /* --- CLASS ----------------------------------------------------------- */
@@ -40,9 +40,9 @@ SOT_FACTORY_FEATURE_PLUGIN(sotFeatureVisualPoint,"FeatureVisualPoint");
 
 
 
-sotFeatureVisualPoint::
-sotFeatureVisualPoint( const string& pointName )
-  : sotFeatureAbstract( pointName )
+FeatureVisualPoint::
+FeatureVisualPoint( const string& pointName )
+  : FeatureAbstract( pointName )
     ,L()
     ,xySIN( NULL,"sotFeatureVisualPoint("+name+")::input(vector)::xy" )
     ,ZSIN( NULL,"sotFeatureVisualPoint("+name+")::input(double)::Z" )
@@ -67,12 +67,12 @@ sotFeatureVisualPoint( const string& pointName )
 /* --------------------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-unsigned int& sotFeatureVisualPoint::
+unsigned int& FeatureVisualPoint::
 getDimension( unsigned int & dim, int time ) 
 {
   sotDEBUG(25)<<"# In {"<<endl;
 
-  const sotFlags &fl = selectionSIN.access(time);
+  const Flags &fl = selectionSIN.access(time);
 
   dim = 0;
   if( fl(0) ) dim++;
@@ -86,13 +86,13 @@ getDimension( unsigned int & dim, int time )
 /** Compute the interaction matrix from a subset of
  * the possible features. 
  */
-ml::Matrix& sotFeatureVisualPoint::
+ml::Matrix& FeatureVisualPoint::
 computeJacobian( ml::Matrix& J,int time )
 {
   sotDEBUG(15)<<"# In {"<<endl;
 
   sotDEBUG(15) << "Get selection flags." << endl;
-  const sotFlags &fl = selectionSIN(time);
+  const Flags &fl = selectionSIN(time);
 
   const int dim = dimensionSOUT(time);
   std::cout<<" Dimension="<<dim<<std::endl;
@@ -109,11 +109,11 @@ computeJacobian( ml::Matrix& J,int time )
 
 
   if( Z<0 )
-    { throw(sotExceptionFeature(sotExceptionFeature::BAD_INIT,
+    { throw(ExceptionFeature(ExceptionFeature::BAD_INIT,
 				"VisualPoint is behind the camera"," (Z=%.1f).",Z)); }
 
   if( fabs(Z)<1e-6 )
-    { throw(sotExceptionFeature(sotExceptionFeature::BAD_INIT,
+    { throw(ExceptionFeature(ExceptionFeature::BAD_INIT,
 				"VisualPoint Z coordinates is null"," (Z=%.3f)",Z)); }
 
   if( fl(0) )
@@ -152,18 +152,18 @@ computeJacobian( ml::Matrix& J,int time )
  * a the possible features.
  */
 ml::Vector&
-sotFeatureVisualPoint::computeError( ml::Vector& error,int time )
+FeatureVisualPoint::computeError( ml::Vector& error,int time )
 {
-  const sotFlags &fl = selectionSIN(time);
+  const Flags &fl = selectionSIN(time);
   sotDEBUGIN(15);
   error.resize(dimensionSOUT(time)) ;
   unsigned int cursorL = 0;
 
-  sotFeatureVisualPoint * sdes 
-    = dynamic_cast<sotFeatureVisualPoint*>(desiredValueSIN(time));
+  FeatureVisualPoint * sdes 
+    = dynamic_cast<FeatureVisualPoint*>(desiredValueSIN(time));
   
   if( NULL==sdes )
-    { throw(sotExceptionFeature(sotExceptionFeature::BAD_INIT,
+    { throw(ExceptionFeature(ExceptionFeature::BAD_INIT,
 				"S* is not of adequate type.")); }
   if( fl(0) )
     { error( cursorL++ ) = xySIN(time)(0) - sdes->xySIN(time)(0) ;   }
@@ -179,7 +179,7 @@ sotFeatureVisualPoint::computeError( ml::Vector& error,int time )
  * a the possible features.
  */
 ml::Vector&
-sotFeatureVisualPoint::computeActivation( ml::Vector& act,int time )
+FeatureVisualPoint::computeActivation( ml::Vector& act,int time )
 {
   selectionSIN(time);
   act.resize(dimensionSOUT(time)) ; act.fill(1);
@@ -187,7 +187,7 @@ sotFeatureVisualPoint::computeActivation( ml::Vector& act,int time )
 }
 
 
-void sotFeatureVisualPoint::
+void FeatureVisualPoint::
 display( std::ostream& os ) const
 {
   
@@ -196,7 +196,7 @@ display( std::ostream& os ) const
 
   try{
     const ml::Vector& xy = xySIN;
-    const sotFlags& fl = selectionSIN;
+    const Flags& fl = selectionSIN;
     if( fl(0) ) os << " x=" << xy(0) ;
     if( fl(1) ) os << " y=" << xy(1) ;
   }  catch(ExceptionAbstract e){ os<< " XY or select not set."; }
diff --git a/src/math/matrix-force.cpp b/src/math/matrix-force.cpp
index 32b21089..72dd4acb 100644
--- a/src/math/matrix-force.cpp
+++ b/src/math/matrix-force.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotMatrixForce.cpp
+ * File:      MatrixForce.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -26,14 +26,14 @@
 using namespace sot;
 
 
-sotMatrixForce& sotMatrixForce::
-buildFrom( const sotMatrixHomogeneous& M )
+MatrixForce& MatrixForce::
+buildFrom( const MatrixHomogeneous& M )
 {
   ml::Matrix Tx(3,3);
   Tx( 0,0 )=  0       ;  Tx( 0,1 ) = -M( 2,3 ); Tx( 0,2 ) =  M( 1,3 );
   Tx( 1,0 )=  M( 2,3 );  Tx( 1,1 ) =  0       ; Tx( 1,2 ) = -M( 0,3 );
   Tx( 2,0 )= -M( 1,3 );  Tx( 2,1 ) =  M( 0,3 ); Tx( 2,2 )=   0       ;
-  sotMatrixRotation R; M.extract(R);
+  MatrixRotation R; M.extract(R);
   ml::Matrix sk(3,3); Tx.multiply(R,sk);
   
   sotDEBUG(15) << "Tx = " << Tx << std::endl;
@@ -53,8 +53,8 @@ buildFrom( const sotMatrixHomogeneous& M )
 
 
 
-sotMatrixForce& sotMatrixForce::
-inverse( sotMatrixForce& Vi ) const
+MatrixForce& MatrixForce::
+inverse( MatrixForce& Vi ) const
 {
   ml::Matrix Rt(3,3); 
   ml::Matrix Sk(3,3); 
@@ -82,7 +82,7 @@ inverse( sotMatrixForce& Vi ) const
 
 
 
-sotMatrixForce& sotMatrixForce::
+MatrixForce& MatrixForce::
 operator=( const ml::Matrix& m2)
 {
   if( (m2.nbRows()==6)&&(m2.nbCols()==6) )
@@ -92,10 +92,10 @@ operator=( const ml::Matrix& m2)
 
 }
 
-sotMatrixTwist& sotMatrixForce::
-transpose( sotMatrixTwist& Vt ) const
-{ return (sotMatrixTwist&)ml::Matrix::transpose((ml::Matrix&)Vt);}
+MatrixTwist& MatrixForce::
+transpose( MatrixTwist& Vt ) const
+{ return (MatrixTwist&)ml::Matrix::transpose((ml::Matrix&)Vt);}
 
-sotMatrixTwist sotMatrixForce::
+MatrixTwist MatrixForce::
 transpose( void ) const
-{ sotMatrixTwist F; return transpose(F); }
+{ MatrixTwist F; return transpose(F); }
diff --git a/src/math/matrix-homogeneous.cpp b/src/math/matrix-homogeneous.cpp
index 364c4258..26990eba 100644
--- a/src/math/matrix-homogeneous.cpp
+++ b/src/math/matrix-homogeneous.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotMatrixHomogeneous.cpp
+ * File:      MatrixHomogeneous.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -24,8 +24,8 @@
 using namespace sot;
 
 
-sotMatrixHomogeneous& sotMatrixHomogeneous::
-buildFrom( const sotMatrixRotation& rot, const ml::Vector& trans )
+MatrixHomogeneous& MatrixHomogeneous::
+buildFrom( const MatrixRotation& rot, const ml::Vector& trans )
 {
   for( int i=0;i<3;++i )
     {
@@ -40,8 +40,8 @@ buildFrom( const sotMatrixRotation& rot, const ml::Vector& trans )
   return *this;
 }
 
-sotMatrixRotation& sotMatrixHomogeneous::
-extract( sotMatrixRotation& rot ) const
+MatrixRotation& MatrixHomogeneous::
+extract( MatrixRotation& rot ) const
 {
   for( int i=0;i<3;++i )
     for( int j=0;j<3;++j )
@@ -50,7 +50,7 @@ extract( sotMatrixRotation& rot ) const
   return rot;
 }
 
-ml::Vector& sotMatrixHomogeneous::
+ml::Vector& MatrixHomogeneous::
 extract( ml::Vector& trans ) const
 {
   for( int i=0;i<3;++i )
@@ -60,7 +60,7 @@ extract( ml::Vector& trans ) const
 }
 
 
-sotMatrixHomogeneous& sotMatrixHomogeneous::
+MatrixHomogeneous& MatrixHomogeneous::
 operator=( const ml::Matrix& m2)
 {
   if( (m2.nbRows()==4)&&(m2.nbCols()==4) )
@@ -71,19 +71,19 @@ operator=( const ml::Matrix& m2)
 }
 
 
-sotMatrixHomogeneous& sotMatrixHomogeneous::
-inverse( sotMatrixHomogeneous& invMatrix ) const 
+MatrixHomogeneous& MatrixHomogeneous::
+inverse( MatrixHomogeneous& invMatrix ) const 
 {
   sotDEBUGIN(25);
 
   ml::Matrix & inv = this->ml::Matrix::inverse( invMatrix );
 
   sotDEBUGOUT(25);
-  return dynamic_cast< sotMatrixHomogeneous& > (inv);
+  return dynamic_cast< MatrixHomogeneous& > (inv);
 }
 
 
-ml::Vector& sotMatrixHomogeneous::
+ml::Vector& MatrixHomogeneous::
 multiply( const ml::Vector& v1,ml::Vector& res ) const
 {
   sotDEBUGIN(15);
diff --git a/src/math/matrix-rotation.cpp b/src/math/matrix-rotation.cpp
index 4f81cc09..eb954791 100644
--- a/src/math/matrix-rotation.cpp
+++ b/src/math/matrix-rotation.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotMatrixRotation.cpp
+ * File:      MatrixRotation.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -24,7 +24,7 @@ using namespace std;
 using namespace sot;
 
 
-void sotMatrixRotation::fromVector( sotVectorUTheta& vec )
+void MatrixRotation::fromVector( VectorUTheta& vec )
 {
   vec.toMatrix( *this );
 }
diff --git a/src/math/matrix-twist.cpp b/src/math/matrix-twist.cpp
index 806e20e2..be1fd044 100644
--- a/src/math/matrix-twist.cpp
+++ b/src/math/matrix-twist.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotMatrixTwist.cpp
+ * File:      MatrixTwist.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -26,14 +26,14 @@
 using namespace sot;
 
 
-sotMatrixTwist& sotMatrixTwist::
-buildFrom( const sotMatrixHomogeneous& M )
+MatrixTwist& MatrixTwist::
+buildFrom( const MatrixHomogeneous& M )
 {
   ml::Matrix Tx(3,3);
   Tx( 0,0 ) = 0       ;  Tx( 0,1 )=-M( 2,3 );  Tx( 0,2 ) = M( 1,3 );
   Tx( 1,0 ) = M( 2,3 );  Tx( 1,1 )= 0       ;  Tx( 1,2 ) =-M( 0,3 );
   Tx( 2,0 ) =-M( 1,3 );  Tx( 2,1 )= M( 0,3 );  Tx( 2,2 ) = 0       ;
-  sotMatrixRotation R; M.extract(R);
+  MatrixRotation R; M.extract(R);
   ml::Matrix sk(3,3); Tx.multiply(R,sk);
   
   sotDEBUG(15) << "Tx = " << Tx << std::endl;
@@ -53,8 +53,8 @@ buildFrom( const sotMatrixHomogeneous& M )
 
 
 
-sotMatrixTwist& sotMatrixTwist::
-inverse( sotMatrixTwist& Vi ) const
+MatrixTwist& MatrixTwist::
+inverse( MatrixTwist& Vi ) const
 {
   ml::Matrix Rt(3,3); 
   ml::Matrix Sk(3,3); 
@@ -82,7 +82,7 @@ inverse( sotMatrixTwist& Vi ) const
 
 
 
-sotMatrixTwist& sotMatrixTwist::
+MatrixTwist& MatrixTwist::
 operator=( const ml::Matrix& m2)
 {
   if( (m2.nbRows()==6)&&(m2.nbCols()==6) )
@@ -92,10 +92,10 @@ operator=( const ml::Matrix& m2)
 
 }
 
-sotMatrixForce& sotMatrixTwist::
-transpose( sotMatrixForce& Vt ) const
-{ return (sotMatrixForce&)ml::Matrix::transpose((ml::Matrix&)Vt);}
+MatrixForce& MatrixTwist::
+transpose( MatrixForce& Vt ) const
+{ return (MatrixForce&)ml::Matrix::transpose((ml::Matrix&)Vt);}
 
-sotMatrixForce sotMatrixTwist::
+MatrixForce MatrixTwist::
 transpose( void ) const
-{ sotMatrixForce F; return transpose(F); }
+{ MatrixForce F; return transpose(F); }
diff --git a/src/math/op-point-modifier.cpp b/src/math/op-point-modifier.cpp
index 8c4fbdf1..fe097556 100644
--- a/src/math/op-point-modifier.cpp
+++ b/src/math/op-point-modifier.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotOpPointModifior.cp
+ * File:      OpPointModifior.cp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -29,7 +29,7 @@ using namespace std;
 using namespace sot;
 
 namespace sot {
-SOT_FACTORY_ENTITY_PLUGIN(sotOpPointModifior,"OpPointModifior");
+SOT_FACTORY_ENTITY_PLUGIN(OpPointModifior,"OpPointModifior");
 }
 
 
@@ -37,16 +37,16 @@ SOT_FACTORY_ENTITY_PLUGIN(sotOpPointModifior,"OpPointModifior");
 /* --------------------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-sotOpPointModifior::
-sotOpPointModifior( const std::string& name )
+OpPointModifior::
+OpPointModifior( const std::string& name )
   :Entity( name )
    ,transformation()
    ,jacobianSIN(NULL,"OpPointModifior("+name+")::input(matrix)::jacobianIN")
    ,positionSIN(NULL,"OpPointModifior("+name+")::input(matrixhomo)::positionIN")
-   ,jacobianSOUT( boost::bind(&sotOpPointModifior::computeJacobian,this,_1,_2),
+   ,jacobianSOUT( boost::bind(&OpPointModifior::computeJacobian,this,_1,_2),
 		  jacobianSIN,
 		  "OpPointModifior("+name+")::output(matrix)::jacobian" )
-   ,positionSOUT( boost::bind(&sotOpPointModifior::computePosition,this,_1,_2),
+   ,positionSOUT( boost::bind(&OpPointModifior::computePosition,this,_1,_2),
 		  jacobianSIN,
 		  "OpPointModifior("+name+")::output(matrixhomo)::position" )
 
@@ -57,45 +57,45 @@ sotOpPointModifior( const std::string& name )
 }
 
 ml::Matrix&
-sotOpPointModifior::computeJacobian( ml::Matrix& res,const int& time )
+OpPointModifior::computeJacobian( ml::Matrix& res,const int& time )
 {
   const ml::Matrix& jacobian = jacobianSIN( time );
-  sotMatrixTwist V( transformation );
+  MatrixTwist V( transformation );
   res = V*jacobian;
   return res;
 }
 
-sotMatrixHomogeneous&
-sotOpPointModifior::computePosition( sotMatrixHomogeneous& res,const int& time )
+MatrixHomogeneous&
+OpPointModifior::computePosition( MatrixHomogeneous& res,const int& time )
 {
   sotDEBUGIN(15);
   sotDEBUGIN(15) << time << " " << positionSIN.getTime() << positionSOUT.getTime() << endl;
-  const sotMatrixHomogeneous& position = positionSIN( time );
+  const MatrixHomogeneous& position = positionSIN( time );
   position.multiply(transformation,res);
   sotDEBUGOUT(15);
   return res;
 }
 
 void
-sotOpPointModifior::setTransformation( const sotMatrixHomogeneous& tr )
+OpPointModifior::setTransformation( const MatrixHomogeneous& tr )
 { transformation = tr; }
 
 
-void sotOpPointModifior::
+void OpPointModifior::
 commandLine( const std::string& cmdLine,
 	     std::istringstream& cmdArgs, 
 	     std::ostream& os )
 {
   if( cmdLine == "transfo" ) 
     {
-      sotMatrixHomogeneous tr;
+      MatrixHomogeneous tr;
       cmdArgs >> tr;
       setTransformation(tr);
     }
   else if( cmdLine == "transfoSignal" ) 
     {
-      Signal< sotMatrixHomogeneous,int > &sig 
-	= dynamic_cast< Signal< sotMatrixHomogeneous,int >& > 
+      Signal< MatrixHomogeneous,int > &sig 
+	= dynamic_cast< Signal< MatrixHomogeneous,int >& > 
 	(pool.getSignal( cmdArgs ));
       setTransformation(sig.accessCopy());
     }
diff --git a/src/math/vector-quaternion.cpp b/src/math/vector-quaternion.cpp
index 8c41f267..baefd496 100644
--- a/src/math/vector-quaternion.cpp
+++ b/src/math/vector-quaternion.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotVectorQuaternion.cpp
+ * File:      VectorQuaternion.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -27,8 +27,8 @@ static const double ANGLE_MINIMUM = 0.0001;
 static const double SINC_MINIMUM = 1e-8;
 static const double COSC_MINIMUM = 2.5e-4;
 
-sotVectorRotation& sotVectorQuaternion::
-fromMatrix( const sotMatrixRotation& rot )
+sotVectorRotation& VectorQuaternion::
+fromMatrix( const MatrixRotation& rot )
 {
   sotDEBUGIN(15) ;
   
@@ -125,8 +125,8 @@ fromMatrix( const sotMatrixRotation& rot )
 
 #include <sot-core/vector-utheta.h>
 
-sotVectorRotation& sotVectorQuaternion::
-fromVector( const sotVectorUTheta& ut )
+sotVectorRotation& VectorQuaternion::
+fromVector( const VectorUTheta& ut )
 {
   sotDEBUGIN(15) ;
   
@@ -143,8 +143,8 @@ fromVector( const sotVectorUTheta& ut )
 }
 
 
-sotMatrixRotation& sotVectorQuaternion::
-toMatrix( sotMatrixRotation& rot ) const
+MatrixRotation& VectorQuaternion::
+toMatrix( MatrixRotation& rot ) const
 {
   sotDEBUGIN(15) ;
 
@@ -234,7 +234,7 @@ toMatrix( sotMatrixRotation& rot ) const
   return rot;
 }
 
-sotVectorQuaternion& sotVectorQuaternion::conjugate(sotVectorQuaternion& res) const
+VectorQuaternion& VectorQuaternion::conjugate(VectorQuaternion& res) const
 {
   res.vector(0) = vector(0);
   res.vector(1) = -vector(1);
@@ -243,7 +243,7 @@ sotVectorQuaternion& sotVectorQuaternion::conjugate(sotVectorQuaternion& res) co
   return res;
 }
 
-sotVectorQuaternion& sotVectorQuaternion::multiply(const sotVectorQuaternion& q2, sotVectorQuaternion& res) const
+VectorQuaternion& VectorQuaternion::multiply(const VectorQuaternion& q2, VectorQuaternion& res) const
 {
   double & a1 = vector(0);
   double & b1 = vector(1);
diff --git a/src/math/vector-roll-pitch-yaw.cpp b/src/math/vector-roll-pitch-yaw.cpp
index db7719e3..4705813c 100644
--- a/src/math/vector-roll-pitch-yaw.cpp
+++ b/src/math/vector-roll-pitch-yaw.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotVectorRollPitchYaw.cpp
+ * File:      VectorRollPitchYaw.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -27,8 +27,8 @@ static const double ANGLE_MINIMUM = 0.0001;
 static const double SINC_MINIMUM = 1e-8;
 static const double COSC_MINIMUM = 2.5e-4;
 
-sotVectorRotation& sotVectorRollPitchYaw::
-fromMatrix( const sotMatrixRotation& rot )
+sotVectorRotation& VectorRollPitchYaw::
+fromMatrix( const MatrixRotation& rot )
 {
   sotDEBUGIN(15) ;
   
@@ -45,8 +45,8 @@ fromMatrix( const sotMatrixRotation& rot )
 }
 
 
-sotMatrixRotation& sotVectorRollPitchYaw::
-toMatrix( sotMatrixRotation& rot ) const
+MatrixRotation& VectorRollPitchYaw::
+toMatrix( MatrixRotation& rot ) const
 {
   sotDEBUGIN(15) ;
 
diff --git a/src/math/vector-utheta.cpp b/src/math/vector-utheta.cpp
index 3a3b76a8..ded8574e 100644
--- a/src/math/vector-utheta.cpp
+++ b/src/math/vector-utheta.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotVectorUTheta.cpp
+ * File:      VectorUTheta.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -26,8 +26,8 @@ static const double ANGLE_MINIMUM = 0.0001;
 static const double SINC_MINIMUM = 1e-8;
 static const double COSC_MINIMUM = 2.5e-4;
 
-sotVectorRotation& sotVectorUTheta::
-fromMatrix( const sotMatrixRotation& rot )
+sotVectorRotation& VectorUTheta::
+fromMatrix( const MatrixRotation& rot )
 {
   sotDEBUGIN(15) ;
   
@@ -63,8 +63,8 @@ fromMatrix( const sotMatrixRotation& rot )
 }
 
 
-sotMatrixRotation& sotVectorUTheta::
-toMatrix( sotMatrixRotation& rot ) const
+MatrixRotation& VectorUTheta::
+toMatrix( MatrixRotation& rot ) const
 {
   sotDEBUGIN(15) ;
 
diff --git a/src/matrix/binary-op.cpp b/src/matrix/binary-op.cpp
index 9fb0373c..1109a3fb 100644
--- a/src/matrix/binary-op.cpp
+++ b/src/matrix/binary-op.cpp
@@ -67,13 +67,13 @@ namespace sot {
 using namespace ml;
 
 template< typename T>
-struct sotAdder
+struct Adder
 {
   double coeff1, coeff2;
   void operator()( const T& v1,const T& v2,T& res ) const { res=v1; res+=v2; }
 };
 
-typedef BinaryOp<Vector,Vector,Vector,sotAdder<Vector> > advector;
+typedef BinaryOp<Vector,Vector,Vector,Adder<Vector> > advector;
 
 
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E_CMD
@@ -84,10 +84,10 @@ else if( cmdLine=="print" ){ os<<"Add ["<<op.coeff1<<","<<op.coeff2<<"]"<<std::e
 "Add<vector>: \n - coeff{1|2} value.");
 
 
-typedef BinaryOp<Matrix,Matrix,Matrix,sotAdder<Matrix> > admatrix;
+typedef BinaryOp<Matrix,Matrix,Matrix,Adder<Matrix> > admatrix;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E(admatrix,matrix,ad_matrix,"Add<matrix>");
 
-typedef BinaryOp<double,double,double,sotAdder<double> > addouble; 
+typedef BinaryOp<double,double,double,Adder<double> > addouble; 
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E(addouble,double,ad_double,"Add<double>");
 
 /* -------------------------------------------------------------------------- */
@@ -95,74 +95,74 @@ SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E(addouble,double,ad_double,"Add<double>"
 /* -------------------------------------------------------------------------- */
 
 template< typename T>
-struct sotMultiplier
+struct Multiplier
 {
   void operator()( const T& v1,const T& v2,T& res ) const { res=v1; res*=v2; }
 };
 template<>
-void sotMultiplier<Matrix>::
+void Multiplier<Matrix>::
 operator()( const Matrix& v1,const Matrix& v2,Matrix& res ) const { v1.multiply(v2,res); }
 template<>
-void sotMultiplier<sotMatrixHomogeneous>::
-operator()( const sotMatrixHomogeneous& v1,const sotMatrixHomogeneous& v2,
-	    sotMatrixHomogeneous& res ) const 
+void Multiplier<MatrixHomogeneous>::
+operator()( const MatrixHomogeneous& v1,const MatrixHomogeneous& v2,
+	    MatrixHomogeneous& res ) const 
 { v1.multiply(v2,res); }
 template<>
-void sotMultiplier<sotMatrixRotation>::
-operator()( const sotMatrixRotation& v1,const sotMatrixRotation& v2,
-	    sotMatrixRotation& res ) const 
+void Multiplier<MatrixRotation>::
+operator()( const MatrixRotation& v1,const MatrixRotation& v2,
+	    MatrixRotation& res ) const 
 { v1.multiply(v2,res); }
 template<>
-void sotMultiplier<sotMatrixTwist>::
-operator()( const sotMatrixTwist& v1,const sotMatrixTwist& v2,
-	    sotMatrixTwist& res ) const 
+void Multiplier<MatrixTwist>::
+operator()( const MatrixTwist& v1,const MatrixTwist& v2,
+	    MatrixTwist& res ) const 
 { v1.multiply(v2,res); }
 template<>
-void sotMultiplier<sotVectorQuaternion>::
-operator()(const sotVectorQuaternion& q1,const sotVectorQuaternion& q2,
-	   sotVectorQuaternion& res) const
+void Multiplier<VectorQuaternion>::
+operator()(const VectorQuaternion& q1,const VectorQuaternion& q2,
+	   VectorQuaternion& res) const
 { q1.multiply(q2,res); }
 
-typedef BinaryOp<Vector,Vector,Vector,sotMultiplier<Vector> > multvector;
+typedef BinaryOp<Vector,Vector,Vector,Multiplier<Vector> > multvector;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E(multvector,vector,mult_vector,"Multiply<vector>");
 
-typedef BinaryOp<Matrix,Matrix,Matrix,sotMultiplier<Matrix> > multmatrix;
+typedef BinaryOp<Matrix,Matrix,Matrix,Multiplier<Matrix> > multmatrix;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E(multmatrix,matrix,mult_matrix,"Multiply<matrix>");
-typedef BinaryOp<sotMatrixHomogeneous,sotMatrixHomogeneous,sotMatrixHomogeneous,sotMultiplier<sotMatrixHomogeneous> > multmatrixhomo;
+typedef BinaryOp<MatrixHomogeneous,MatrixHomogeneous,MatrixHomogeneous,Multiplier<MatrixHomogeneous> > multmatrixhomo;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E(multmatrixhomo,matrixhomo,mult_matrixhomo,"Multiply<matrixhomo>");
-typedef BinaryOp<sotMatrixRotation,sotMatrixRotation,sotMatrixRotation,sotMultiplier<sotMatrixRotation> > multmatrixrot;
+typedef BinaryOp<MatrixRotation,MatrixRotation,MatrixRotation,Multiplier<MatrixRotation> > multmatrixrot;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E(multmatrixrot,matrixrot,mult_matrixrot,"Multiply<matrixrotation>");
-typedef BinaryOp<sotMatrixTwist,sotMatrixTwist,sotMatrixTwist,sotMultiplier<sotMatrixTwist> > multmatrixtwist;
+typedef BinaryOp<MatrixTwist,MatrixTwist,MatrixTwist,Multiplier<MatrixTwist> > multmatrixtwist;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E(multmatrixtwist,matrixtwist,mult_matrixtwist,"Multiply<matrixtwist>");
-typedef BinaryOp<sotVectorQuaternion,sotVectorQuaternion,sotVectorQuaternion,sotMultiplier<sotVectorQuaternion> > multquat;
+typedef BinaryOp<VectorQuaternion,VectorQuaternion,VectorQuaternion,Multiplier<VectorQuaternion> > multquat;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E(multquat,q,mult_q,"Multiply<quaternion>");
 
-typedef BinaryOp<double,double,double,sotMultiplier<double> > multdouble;
+typedef BinaryOp<double,double,double,Multiplier<double> > multdouble;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E(multdouble,double,mult_double,"Multiply<double>");
 /* -------------------------------------------------------------------------- */
 /* --- SUBSTRACTION --------------------------------------------------------- */
 /* -------------------------------------------------------------------------- */
 
 template< typename T>
-struct sotSubstract
+struct Substract
 {
   void operator()( const T& v1,const T& v2,T& res ) const { res=v1; res-=v2; }
 };
 
-typedef BinaryOp<Vector,Vector,Vector,sotSubstract<Vector> > subsvector;
+typedef BinaryOp<Vector,Vector,Vector,Substract<Vector> > subsvector;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E(subsvector,vector,subs_vector,"Substract<vector>");
 
-typedef BinaryOp<Matrix,Matrix,Matrix,sotSubstract<Matrix> > subsmatrix;
+typedef BinaryOp<Matrix,Matrix,Matrix,Substract<Matrix> > subsmatrix;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E(subsmatrix,matrix,subs_matrix,"Substract<matrix>");
 
-typedef BinaryOp<double,double,double,sotSubstract<double> > subsdouble;
+typedef BinaryOp<double,double,double,Substract<double> > subsdouble;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E(subsdouble,double,subs_double,"Substract<double>");
 /* -------------------------------------------------------------------------- */
 /* --- STACK ---------------------------------------------------------------- */
 /* -------------------------------------------------------------------------- */
 
 
-struct sotVectorStack
+struct VectorStack
 {
 public:
   unsigned int v1min,v1max;
@@ -188,7 +188,7 @@ public:
       { res(v1size+i) = v2(i+v2min_local); }
   }
 };
-typedef BinaryOp< Vector,Vector,Vector,sotVectorStack > stackvector;
+typedef BinaryOp< Vector,Vector,Vector,VectorStack > stackvector;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E_CMD(stackvector,vector,stack_vector,"Stack<vector>",else if( cmdLine=="selec1" ){ cmdArgs>>op.v1min>>op.v1max; } 
    else if( cmdLine=="selec2" ){ cmdArgs>>op.v2min>>op.v2max; } 
    else if( cmdLine=="print" ){ os<<"Stack ["<<op.v1min<<","<<op.v1max<<"] - ["<<op.v2min<<","<<op.v2max<<"] "<<std::endl; }, 
@@ -199,7 +199,7 @@ SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E_CMD(stackvector,vector,stack_vector,"St
 /* -------------------------------------------------------------------------- */
 
 
-struct sotWeightedAdder
+struct WeightedAdder
 {
 public:
   double gain1,gain2;
@@ -209,7 +209,7 @@ public:
     res += gain2*v2;
   }
 };
-typedef BinaryOp< Vector,Vector,Vector,sotWeightedAdder > weightadd;
+typedef BinaryOp< Vector,Vector,Vector,WeightedAdder > weightadd;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E_CMD(weightadd,vector,weight_add,"WeightAdd<vector>",else if( cmdLine=="gain1" ){ cmdArgs>>op.gain1; } 
    else if( cmdLine=="gain2" ){ cmdArgs>>op.gain2;}
    else if( cmdLine=="print" ){os<<"WeightAdd: "<<op.gain1<<" "<<op.gain2<<std::endl; }, 
@@ -217,7 +217,7 @@ SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E_CMD(weightadd,vector,weight_add,"Weight
 
 /* -------------------------------------------------------------------------- */
 
-struct sotWeightedDirection
+struct WeightedDirection
 {
 public:
   void operator()( const ml::Vector& v1,const ml::Vector& v2,ml::Vector& res ) const 
@@ -228,13 +228,13 @@ public:
     res*= (1/norm2);
   }
 };
-typedef BinaryOp< Vector,Vector,Vector,sotWeightedDirection > weightdir;
+typedef BinaryOp< Vector,Vector,Vector,WeightedDirection > weightdir;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E(weightdir,vector,weight_dir,"WeightDir");
 
 
 /* -------------------------------------------------------------------------- */
 
-struct sotNullificator
+struct Nullificator
 {
 public:
   void operator()( const ml::Vector& v1,const ml::Vector& v2,ml::Vector& res ) const 
@@ -249,7 +249,7 @@ public:
       }
   }
 };
-typedef BinaryOp< Vector,Vector,Vector,sotNullificator > vectNil;
+typedef BinaryOp< Vector,Vector,Vector,Nullificator > vectNil;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E(vectNil,vector,vectnil_,"Nullificator");
 
 
@@ -260,7 +260,7 @@ SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E(vectNil,vector,vectnil_,"Nullificator")
   cmdArgs>>std::ws; if(! cmdArgs.good() ) os << #varname" = " << varname << std::endl; \
   else cmdArgs >> varname
 
-struct sotVirtualSpring
+struct VirtualSpring
 {
 public:
   double spring;
@@ -275,7 +275,7 @@ public:
     res *= spring;
   }
 };
-typedef BinaryOp< Vector,Vector,Vector,sotVirtualSpring > virtspring;
+typedef BinaryOp< Vector,Vector,Vector,VirtualSpring > virtspring;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E_CMD
 (virtspring,vector,virtspring_,
  "VirtualSpring"
@@ -357,9 +357,9 @@ SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExE_E_CMD
   }
 
 
-struct sotComposer
+struct Composer
 {
-  void operator() ( const ml::Matrix& R,const ml::Vector& t, sotMatrixHomogeneous& H ) const 
+  void operator() ( const ml::Matrix& R,const ml::Vector& t, MatrixHomogeneous& H ) const 
   { 
     for( int i=0;i<3;++i )
       {
@@ -371,11 +371,11 @@ struct sotComposer
     H(3,3)=1.;
   };
 };
-typedef BinaryOp<ml::Matrix,ml::Vector,sotMatrixHomogeneous,sotComposer > TandRtoH;
+typedef BinaryOp<ml::Matrix,ml::Vector,MatrixHomogeneous,Composer > TandRtoH;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExF_E(TandRtoH,matrix,vector,composeTR,"Compose<R+T>");
-struct sotVectorComposerPRPY
+struct VectorComposerPRPY
 {
-  void operator() ( const sotVectorRollPitchYaw& R,const ml::Vector& t, ml::Vector& H ) const 
+  void operator() ( const VectorRollPitchYaw& R,const ml::Vector& t, ml::Vector& H ) const 
   { 
     H.resize(6);
     for( int i=0;i<3;++i )
@@ -385,10 +385,10 @@ struct sotVectorComposerPRPY
       }
   };
 };
-typedef BinaryOp<sotVectorRollPitchYaw,ml::Vector,ml::Vector,sotVectorComposerPRPY > TandRPYtoV;
+typedef BinaryOp<VectorRollPitchYaw,ml::Vector,ml::Vector,VectorComposerPRPY > TandRPYtoV;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExF_E(TandRPYtoV,matrix,vector,composeTRPYV,"ComposeVector<RPY+T>");
 
-struct sotVectorScalarMultiplyer
+struct VectorScalarMultiplyer
 {
   void operator()(const ml::Vector& v, double a, ml::Vector& res)
   {
@@ -399,20 +399,20 @@ struct sotVectorScalarMultiplyer
     }
   }
 };
-typedef BinaryOp<ml::Vector,double,ml::Vector,sotVectorScalarMultiplyer> VAndScalToV;
+typedef BinaryOp<ml::Vector,double,ml::Vector,VectorScalarMultiplyer> VAndScalToV;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExF_E(VAndScalToV,vec,scal,newvec,"Multiply<vector,double>");
 
-struct sotMatrixHomeComposerPRPY
+struct MatrixHomeComposerPRPY
 {
-  void operator() ( const sotVectorRollPitchYaw& r,const ml::Vector& t, sotMatrixHomogeneous& Mres ) const 
+  void operator() ( const VectorRollPitchYaw& r,const ml::Vector& t, MatrixHomogeneous& Mres ) const 
   { 
-    sotMatrixRotation R;  r.toMatrix(R);
+    MatrixRotation R;  r.toMatrix(R);
     
     Mres.buildFrom(R,t);
 
   };
 };
-typedef BinaryOp<sotVectorRollPitchYaw,ml::Vector,sotMatrixHomogeneous,sotMatrixHomeComposerPRPY > TandRPYtoM;
+typedef BinaryOp<VectorRollPitchYaw,ml::Vector,MatrixHomogeneous,MatrixHomeComposerPRPY > TandRPYtoM;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExF_G(TandRPYtoM,vectorRPY,vector,matrixHomo,composeTRPYM,"Compose<RPY+T>");
 
 
@@ -422,17 +422,17 @@ SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExF_G(TandRPYtoM,vectorRPY,vector,matrixHomo,
  * The result is P.M.P' = [ P.R.P' P.t ].
  * Strange, isn't it?
  */
-struct sotEndomorphismBasis
+struct EndomorphismBasis
 {
-  void operator() ( const sotMatrixHomogeneous& M, 
-		    const sotMatrixRotation& P,
-		    sotMatrixHomogeneous& res ) const 
+  void operator() ( const MatrixHomogeneous& M, 
+		    const MatrixRotation& P,
+		    MatrixHomogeneous& res ) const 
   { 
-    sotMatrixRotation R; M.extract(R);
+    MatrixRotation R; M.extract(R);
     ml::Vector t(3); M.extract(t);
 
     ml::Vector tres(3); P.multiply(t,tres);
-    sotMatrixRotation PR,PRP;
+    MatrixRotation PR,PRP;
     P.multiply(R,PR);
     PR.multiply(P.transpose(),PRP);
 
@@ -442,28 +442,28 @@ struct sotEndomorphismBasis
 
 
 
-typedef BinaryOp<sotMatrixHomogeneous,sotMatrixRotation,sotMatrixHomogeneous,sotEndomorphismBasis > endoMRM;
+typedef BinaryOp<MatrixHomogeneous,MatrixRotation,MatrixHomogeneous,EndomorphismBasis > endoMRM;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExF_E(endoMRM,matrixhomo,matrixrotation,endoMRM_,"EndomorphismBasis");
 
 
 
 template< typename T1,typename T2 >
-struct sotMultiplierE_F
+struct MultiplierE_F
 {
   void operator()( const T1& v1,const T2& m2,T1& res ) const 
   { m2.multiply(v1,res); }
 };
 
-typedef BinaryOp<ml::Vector,ml::Matrix,ml::Vector,sotMultiplierE_F<ml::Vector,ml::Matrix> > multmatrixvector;
+typedef BinaryOp<ml::Vector,ml::Matrix,ml::Vector,MultiplierE_F<ml::Vector,ml::Matrix> > multmatrixvector;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExF_E(multmatrixvector,vector,matrix,multmatrixvector,"Multiply<vector,matrix>");
 
-typedef BinaryOp<ml::Vector,sotMatrixHomogeneous,ml::Vector,sotMultiplierE_F<ml::Vector,sotMatrixHomogeneous> > multmatrixhomovector;
+typedef BinaryOp<ml::Vector,MatrixHomogeneous,ml::Vector,MultiplierE_F<ml::Vector,MatrixHomogeneous> > multmatrixhomovector;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExF_E(multmatrixhomovector,vector,matrixHomo,multmatrixhomovector,"Multiply<vector,matrixHomo>");
 
 
 
 /* --- CONVOLUTION PRODUCT --- */
-struct sotConvolutionTemporal
+struct ConvolutionTemporal
 {
   typedef std::deque<ml::Vector> MemoryType;
   MemoryType memory;
@@ -502,7 +502,7 @@ struct sotConvolutionTemporal
 
 };
 
-typedef BinaryOp<ml::Vector,ml::Matrix,ml::Vector,sotConvolutionTemporal> convtemp;
+typedef BinaryOp<ml::Vector,ml::Matrix,ml::Vector,ConvolutionTemporal> convtemp;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_ExF_E(convtemp,vector,matrix,convtemp,"ConvolutionTemporal");
 
 } // namespace sot
diff --git a/src/matrix/derivator.cpp b/src/matrix/derivator.cpp
index 42bf4f76..9ee42067 100644
--- a/src/matrix/derivator.cpp
+++ b/src/matrix/derivator.cpp
@@ -25,7 +25,7 @@ using namespace ml;
 
 #define SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(sotClassType,sotType,className)              \
   template<>                                                                            \
-  const double sotDerivator<sotType>::TIMESTEP_DEFAULT = 1.;                            \
+  const double Derivator<sotType>::TIMESTEP_DEFAULT = 1.;                            \
   template<>                                                                            \
   std::string sotClassType<sotType>::                                                   \
   getTypeName( void ) { return #sotType; }                                              \
@@ -42,13 +42,13 @@ using namespace ml;
   }
 
 namespace sot {
-SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(sotDerivator,double,"Derivator");
-SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(sotDerivator,Vector,"Derivator");
-SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(sotDerivator,Matrix,"Derivator");
-SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(sotDerivator,sotVectorQuaternion,"Derivator");
+SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(Derivator,double,"Derivator");
+SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(Derivator,Vector,"Derivator");
+SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(Derivator,Matrix,"Derivator");
+SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(Derivator,VectorQuaternion,"Derivator");
 }
 
-//SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(sotDerivator,double,"T");
+//SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(Derivator,double,"T");
 
 
 /*
@@ -67,9 +67,9 @@ SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(sotDerivator,sotVectorQuaternion,"Derivator")
   }
 
 
-SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(sotDerivator,double,"derivator","Double",rfd,rod);
-SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(sotDerivator,ml::Vector,"derivator","Vector",rfv,rov);
-SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(sotDerivator,ml::Matrix,"derivator","Matrix",rfm,rom);
+SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(Derivator,double,"derivator","Double",rfd,rod);
+SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(Derivator,ml::Vector,"derivator","Vector",rfv,rov);
+SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(Derivator,ml::Matrix,"derivator","Matrix",rfm,rom);
 
 */
 
diff --git a/src/matrix/fir-filter.cpp b/src/matrix/fir-filter.cpp
index 04594d71..69f1f089 100644
--- a/src/matrix/fir-filter.cpp
+++ b/src/matrix/fir-filter.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2008
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotFIRFilter.cpp
+ * File:      FIRFilter.cpp
  * Project:   SOT
  * Author:    Paul Evrard
  *
@@ -48,19 +48,19 @@ extern "C" {								\
 
 
 using namespace ml;
-SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(sotFIRFilter,double,double,double_double,"FIRFilter");
-SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(sotFIRFilter,Vector,double,vec_double,"FIRFilter");
-SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(sotFIRFilter,Vector,Matrix,vec_mat,"FIRFilter");
+SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(FIRFilter,double,double,double_double,"FIRFilter");
+SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(FIRFilter,Vector,double,vec_double,"FIRFilter");
+SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(FIRFilter,Vector,Matrix,vec_mat,"FIRFilter");
 
 template<>
-void sotFIRFilter<Vector, double>::reset_signal( Vector& res, const Vector& sample )
+void FIRFilter<Vector, double>::reset_signal( Vector& res, const Vector& sample )
 {
   res.resize(sample.size());
   res.fill(0);
 }
 
 template<>
-void sotFIRFilter<Vector, Matrix>::reset_signal( Vector& res, const Vector& sample )
+void FIRFilter<Vector, Matrix>::reset_signal( Vector& res, const Vector& sample )
 {
   res.resize(sample.size());
   res.fill(0);
diff --git a/src/matrix/integrator-abstract.cpp b/src/matrix/integrator-abstract.cpp
index 43eb2414..984ded1b 100644
--- a/src/matrix/integrator-abstract.cpp
+++ b/src/matrix/integrator-abstract.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotIntegratorAbstract.cpp
+ * File:      IntegratorAbstract.cpp
  * Project:   SOT
  * Author:    Paul Evrard and Nicolas Mansard
  *
@@ -37,8 +37,8 @@ using namespace sot;
 
 using namespace ml;
 namespace sot {
-SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(sotIntegratorAbstract,double,double,"integratorAbstract");
-SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(sotIntegratorAbstract,Vector,Matrix,"integratorAbstract");
+SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(IntegratorAbstract,double,double,"integratorAbstract");
+SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(IntegratorAbstract,Vector,Matrix,"integratorAbstract");
 }
 
 #if 0
diff --git a/src/matrix/integrator-euler.cpp b/src/matrix/integrator-euler.cpp
index 472bfbaf..fdd37e3c 100644
--- a/src/matrix/integrator-euler.cpp
+++ b/src/matrix/integrator-euler.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotIntegratorEuler.cpp
+ * File:      IntegratorEuler.cpp
  * Project:   SOT
  * Author:    Paul Evrard and Nicolas Mansard
  *
@@ -46,5 +46,5 @@ using namespace sot;
 using namespace ml;
 using namespace std;
 namespace sot {
-SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(sotIntegratorEuler,Vector,Matrix,"integratorEuler");
+SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN(IntegratorEuler,Vector,Matrix,"integratorEuler");
 }
diff --git a/src/matrix/matrix-constant.cpp b/src/matrix/matrix-constant.cpp
index e68b9175..6e885509 100644
--- a/src/matrix/matrix-constant.cpp
+++ b/src/matrix/matrix-constant.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotMatrixConstant.cpp
+ * File:      MatrixConstant.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -24,12 +24,12 @@ using namespace std;
 using namespace sot;
 
 
-SOT_FACTORY_ENTITY_PLUGIN(sotMatrixConstant,"MatrixConstant");
+SOT_FACTORY_ENTITY_PLUGIN(MatrixConstant,"MatrixConstant");
 
 /* --------------------------------------------------------------------- */
 /* --- MATRIX ---------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
-void sotMatrixConstant::
+void MatrixConstant::
 commandLine( const std::string& cmdLine,
 	     std::istringstream& cmdArgs, 
 	     std::ostream& os )
diff --git a/src/matrix/unary-op.cpp b/src/matrix/unary-op.cpp
index cc05a161..fb74cc53 100644
--- a/src/matrix/unary-op.cpp
+++ b/src/matrix/unary-op.cpp
@@ -65,41 +65,41 @@ using namespace ml;
 namespace sot {
 
 template< typename matrixgen >
-struct sotInverser
+struct Inverser
 {
   void operator()( const matrixgen& m,matrixgen& res ) const { m.inverse(res); }
 };
 
-typedef sotUnaryOp<Matrix,Matrix,sotInverser<Matrix> > invMat;
+typedef UnaryOp<Matrix,Matrix,Inverser<Matrix> > invMat;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_E(invMat,matrix,inv_mat,"Inverse<matrix>", ,"");
 
-typedef sotUnaryOp<sotMatrixHomogeneous,sotMatrixHomogeneous,sotInverser<sotMatrixHomogeneous> > invMatHomo;
+typedef UnaryOp<MatrixHomogeneous,MatrixHomogeneous,Inverser<MatrixHomogeneous> > invMatHomo;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_E(invMatHomo,matrixHomo,inv_mathomo,"Inverse<matrixhomo>", ,"");
 
-typedef sotUnaryOp<sotMatrixTwist,sotMatrixTwist,sotInverser<sotMatrixTwist> > invMatTwist;
+typedef UnaryOp<MatrixTwist,MatrixTwist,Inverser<MatrixTwist> > invMatTwist;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_E(invMatTwist,matrixTwist,inv_mattwist,"Inverse<matrixtwist>", ,"");
 
 
-struct sotInverserRot
+struct InverserRot
 {
-  void operator()( const sotMatrixRotation& m,sotMatrixRotation& res ) const { m.transpose(res); }
+  void operator()( const MatrixRotation& m,MatrixRotation& res ) const { m.transpose(res); }
 };
 
-typedef sotUnaryOp<sotMatrixRotation,sotMatrixRotation,sotInverserRot > invMatRot;
+typedef UnaryOp<MatrixRotation,MatrixRotation,InverserRot > invMatRot;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_E(invMatRot,matrixRot,inv_matrot,"Inverse<matrixrotation>", ,"");
 
-struct sotInverserQuat
+struct InverserQuat
 {
-  void operator()( const sotVectorQuaternion& q, sotVectorQuaternion& res ) const
+  void operator()( const VectorQuaternion& q, VectorQuaternion& res ) const
   {
     q.conjugate(res);
   }
 };
 
-typedef sotUnaryOp<sotVectorQuaternion,sotVectorQuaternion,sotInverserQuat> invQuat;
+typedef UnaryOp<VectorQuaternion,VectorQuaternion,InverserQuat> invQuat;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_E(invQuat,q,qstar,"Inverse<unitquat>", ,"");
 
-struct sotVectorSelector
+struct VectorSelector
 {
 public:
   unsigned int imin,imax;
@@ -111,13 +111,13 @@ public:
   }
 };
 
-typedef sotUnaryOp<Vector,Vector,sotVectorSelector > selcVec;
+typedef UnaryOp<Vector,Vector,VectorSelector > selcVec;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_E(selcVec,vector,sec_vec,"Selec<vector>",   
   else if( cmdLine == "selec" ) 
     {  cmdArgs >> op.imin >> op.imax; },
   "Selec<vector>\n  - selec min max\t\t");
 
-struct sotMatrixSelector
+struct MatrixSelector
 {
 public:
   unsigned int imin,imax;
@@ -133,7 +133,7 @@ public:
   }
 };
 
-typedef sotUnaryOp<Matrix,Matrix,sotMatrixSelector > selcMat;
+typedef UnaryOp<Matrix,Matrix,MatrixSelector > selcMat;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_E(selcMat,matrix,sec_mat,"Selec<matrix>",   
   else if( cmdLine == "iselec" ) 
     {  cmdArgs >> op.imin >> op.imax; }
@@ -173,7 +173,7 @@ SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_E(selcMat,matrix,sec_mat,"Selec<matrix>",
 
 
 
-struct sotMatrixColumnSelector
+struct MatrixColumnSelector
 {
 public:
   unsigned int imin,imax;
@@ -189,7 +189,7 @@ public:
   }
 };
 
-typedef sotUnaryOp<Matrix,Vector,sotMatrixColumnSelector > selcMatCol;
+typedef UnaryOp<Matrix,Vector,MatrixColumnSelector > selcMatCol;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_F(selcMatCol,matrix,vector,sec_mat_col,"Selec<matrix,column>",   
   else if( cmdLine == "iselec" ) 
     {  cmdArgs >> op.imin >> op.imax; }
@@ -199,12 +199,12 @@ SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_F(selcMatCol,matrix,vector,sec_mat_col,"Sel
 
 
 
-struct sotHomogeneousMatrixToVector
+struct HomogeneousMatrixToVector
 {
-  void operator()( const sotMatrixHomogeneous& M,ml::Vector& res )
+  void operator()( const MatrixHomogeneous& M,ml::Vector& res )
   {
-    sotMatrixRotation R; M.extract(R);
-    sotVectorUTheta r; r.fromMatrix(R);
+    MatrixRotation R; M.extract(R);
+    VectorUTheta r; r.fromMatrix(R);
     ml::Vector t(3); M.extract(t);
     res.resize(6);
     for( int i=0;i<3;++i ) res(i)=t(i);
@@ -212,11 +212,11 @@ struct sotHomogeneousMatrixToVector
   }
 };
 
-typedef sotUnaryOp<sotMatrixHomogeneous,Vector,sotHomogeneousMatrixToVector> RT2V;
+typedef UnaryOp<MatrixHomogeneous,Vector,HomogeneousMatrixToVector> RT2V;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_F(RT2V,matrixHomo,matrix,RT2V_,"MatrixHomoToPoseUTheta", ,"");
 
 
-struct sotSkewSymToVector
+struct SkewSymToVector
 {
   void operator()( const Matrix& M,Vector& res )
   {
@@ -227,34 +227,34 @@ struct sotSkewSymToVector
   }
 };
 
-typedef sotUnaryOp<Matrix,Vector,sotSkewSymToVector> SS2V;
+typedef UnaryOp<Matrix,Vector,SkewSymToVector> SS2V;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_F(SS2V,matrix,vector,SS2V_,"SkewSymToVector", ,"");
 
-struct sotVectorUThetaToHomogeneousMatrix
+struct VectorUThetaToHomogeneousMatrix
 {
-  void operator()( const ml::Vector& v,sotMatrixHomogeneous& res )
+  void operator()( const ml::Vector& v,MatrixHomogeneous& res )
   {
-    sotVectorUTheta ruth; ml::Vector trans(3); 
+    VectorUTheta ruth; ml::Vector trans(3); 
     for( int i=0;i<3;++i )
       {
  	trans(i)=v(i); 
 	ruth(i)=v(i+3); 
       }
 
-    sotMatrixRotation R; ruth.toMatrix(R);
+    MatrixRotation R; ruth.toMatrix(R);
     res.buildFrom(R,trans);
   }
 };
 
-typedef sotUnaryOp<Vector,sotMatrixHomogeneous,sotVectorUThetaToHomogeneousMatrix> PUTH2M;
+typedef UnaryOp<Vector,MatrixHomogeneous,VectorUThetaToHomogeneousMatrix> PUTH2M;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_F(PUTH2M,vector6,matrixhome,PUTH2M_,"PoseUThetaToMatrixHomo", ,"");
 
-struct sotHomogeneousMatrixToVectorQuaternion
+struct HomogeneousMatrixToVectorQuaternion
 {
-  void operator()( const sotMatrixHomogeneous& M,ml::Vector& res )
+  void operator()( const MatrixHomogeneous& M,ml::Vector& res )
   {
-    sotMatrixRotation R; M.extract(R);
-    sotVectorQuaternion r; r.fromMatrix(R);
+    MatrixRotation R; M.extract(R);
+    VectorQuaternion r; r.fromMatrix(R);
     ml::Vector t(3); M.extract(t);
     res.resize(7);
     for( int i=0;i<3;++i ) res(i)=t(i);
@@ -262,15 +262,15 @@ struct sotHomogeneousMatrixToVectorQuaternion
   }
 };
 
-typedef sotUnaryOp<sotMatrixHomogeneous,Vector,sotHomogeneousMatrixToVectorQuaternion> RT2VQ;
+typedef UnaryOp<MatrixHomogeneous,Vector,HomogeneousMatrixToVectorQuaternion> RT2VQ;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_F(RT2VQ,matrixHomo,matrix,RT2VQ_,"MatrixHomoToPoseQuaternion", ,"");
 
-struct sotHomogeneousMatrixToVectorRPY
+struct HomogeneousMatrixToVectorRPY
 {
-  void operator()( const sotMatrixHomogeneous& M,ml::Vector& res )
+  void operator()( const MatrixHomogeneous& M,ml::Vector& res )
   {
-    sotMatrixRotation R; M.extract(R);
-    sotVectorRollPitchYaw r; r.fromMatrix(R);
+    MatrixRotation R; M.extract(R);
+    VectorRollPitchYaw r; r.fromMatrix(R);
     ml::Vector t(3); M.extract(t);
     res.resize(6);
     for( unsigned int i=0;i<3;++i ) res(i)=t(i);
@@ -278,17 +278,17 @@ struct sotHomogeneousMatrixToVectorRPY
   }
 };
 
-typedef sotUnaryOp<sotMatrixHomogeneous,Vector,sotHomogeneousMatrixToVectorRPY> RT2VRPY;
+typedef UnaryOp<MatrixHomogeneous,Vector,HomogeneousMatrixToVectorRPY> RT2VRPY;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_F(RT2VRPY,matrixHomo,matrix,RT2VRPY_,"MatrixHomoToPoseRollPitchYaw", ,"");
 
-struct sotVectorRPYToHomogeneousMatrix
+struct VectorRPYToHomogeneousMatrix
 {
-  void operator()( const ml::Vector& vect, sotMatrixHomogeneous& Mres )
+  void operator()( const ml::Vector& vect, MatrixHomogeneous& Mres )
   {
 
-    sotVectorRollPitchYaw r; 
+    VectorRollPitchYaw r; 
     for( unsigned int i=0;i<3;++i ) r(i)=vect(i+3);
-    sotMatrixRotation R;  r.toMatrix(R);
+    MatrixRotation R;  r.toMatrix(R);
     
     ml::Vector t(3); 
     for( unsigned int i=0;i<3;++i ) t(i)=vect(i);
@@ -296,19 +296,19 @@ struct sotVectorRPYToHomogeneousMatrix
   }
 };
 
-typedef sotUnaryOp<Vector,sotMatrixHomogeneous,sotVectorRPYToHomogeneousMatrix> VRPY2RT;
+typedef UnaryOp<Vector,MatrixHomogeneous,VectorRPYToHomogeneousMatrix> VRPY2RT;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_F(VRPY2RT,vector,matrixHomo,VRPY2RT_,"PoseRollPitchYawToMatrixHomo", ,"");
 
-struct sotVectorRPYToVector6D
+struct VectorRPYToVector6D
 {
   void operator()( const ml::Vector& vect,ml::Vector& vectres )
   {
 
-    sotVectorRollPitchYaw r; 
+    VectorRollPitchYaw r; 
     for( unsigned int i=0;i<3;++i ) r(i)=vect(i+3);
-    sotMatrixRotation R;  r.toMatrix(R);
+    MatrixRotation R;  r.toMatrix(R);
     
-    sotVectorUTheta rrot; rrot.fromMatrix(R);
+    VectorUTheta rrot; rrot.fromMatrix(R);
 
     vectres .resize(6); 
     for( unsigned int i=0;i<3;++i )
@@ -319,124 +319,124 @@ struct sotVectorRPYToVector6D
   }
 };
 
-typedef sotUnaryOp<Vector,Vector,sotVectorRPYToVector6D> VRPY2VRUT;
+typedef UnaryOp<Vector,Vector,VectorRPYToVector6D> VRPY2VRUT;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_F(VRPY2VRUT,vector,vector,VRPY2RUT_,"PoseRollPitchYawToPoseUTheta", ,"");
 
-struct sotHomoToMatrix
+struct HomoToMatrix
 {
-  void operator()( const sotMatrixHomogeneous& M,ml::Matrix& res )
+  void operator()( const MatrixHomogeneous& M,ml::Matrix& res )
   {  res=(ml::Matrix&)M;  }
 };
 
-typedef sotUnaryOp<sotMatrixHomogeneous,Matrix,sotHomoToMatrix> H2M;
+typedef UnaryOp<MatrixHomogeneous,Matrix,HomoToMatrix> H2M;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_F(H2M,matrixHomo,matrix,H2M_,"HomoToMatrix", ,"");
 
-struct sotMatrixToHomo
+struct MatrixToHomo
 {
-  void operator()( const ml::Matrix& M,sotMatrixHomogeneous& res )
+  void operator()( const ml::Matrix& M,MatrixHomogeneous& res )
   {  res=M;  }
 };
 
-typedef sotUnaryOp<Matrix,sotMatrixHomogeneous,sotMatrixToHomo> M2H;
+typedef UnaryOp<Matrix,MatrixHomogeneous,MatrixToHomo> M2H;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_F(M2H,matrixHomo,matrix,M2H_,"MatrixToHomo", ,"");
 
 
 
-struct sotHomogeneousMatrixToTwist
+struct HomogeneousMatrixToTwist
 {
-  void operator()( const sotMatrixHomogeneous& M,sotMatrixTwist& res )
+  void operator()( const MatrixHomogeneous& M,MatrixTwist& res )
   {
     res.buildFrom( M );
   }
 };
 
-typedef sotUnaryOp<sotMatrixHomogeneous,sotMatrixTwist,sotHomogeneousMatrixToTwist> H2Tw;
+typedef UnaryOp<MatrixHomogeneous,MatrixTwist,HomogeneousMatrixToTwist> H2Tw;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_F(H2Tw,matrixHomo,matrixTwist,H2Tw_,"HomoToTwist", ,"");
 
-struct sotExtractRotation
+struct ExtractRotation
 {
-  void operator()( const sotMatrixHomogeneous& M,sotMatrixRotation& res )
+  void operator()( const MatrixHomogeneous& M,MatrixRotation& res )
   {
     M.extract(res);
   }
 };
 
-typedef sotUnaryOp<sotMatrixHomogeneous,sotMatrixRotation,sotExtractRotation> H2R;
+typedef UnaryOp<MatrixHomogeneous,MatrixRotation,ExtractRotation> H2R;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_F(H2R,matrixHomo,matrixRot,H2R_,"HomoToRotation", ,"");
 
-struct sotRPYtoMatrix
+struct RPYtoMatrix
 {
-  void operator()( const sotVectorRollPitchYaw& r,sotMatrixRotation& res )
+  void operator()( const VectorRollPitchYaw& r,MatrixRotation& res )
   {
     r.toMatrix(res);
   }
 };
 
-typedef sotUnaryOp<sotVectorRollPitchYaw,sotMatrixRotation,sotRPYtoMatrix> rpy2R;
+typedef UnaryOp<VectorRollPitchYaw,MatrixRotation,RPYtoMatrix> rpy2R;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_F(rpy2R,vectorRPY,matrixRot,rpy2R_,"RPYToMatrix", ,"");
 
-struct sotMatrixToRPY
+struct MatrixToRPY
 {
-  void operator()( const sotMatrixRotation& r,sotVectorRollPitchYaw & res )
+  void operator()( const MatrixRotation& r,VectorRollPitchYaw & res )
   {
     res.fromMatrix(r);
   }
 };
 
-typedef sotUnaryOp<sotMatrixRotation,sotVectorRollPitchYaw,sotMatrixToRPY> R2rpy;
+typedef UnaryOp<MatrixRotation,VectorRollPitchYaw,MatrixToRPY> R2rpy;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_F(R2rpy,matrixRot,vectorRPY,R2rpy_,"MatrixToRPY", ,"");
 
-struct sotQuaterniontoMatrix
+struct QuaterniontoMatrix
 {
-  void operator()( const sotVectorQuaternion& r,sotMatrixRotation& res )
+  void operator()( const VectorQuaternion& r,MatrixRotation& res )
   {
     r.toMatrix(res);
   }
 };
 
-typedef sotUnaryOp<sotVectorQuaternion,sotMatrixRotation,sotQuaterniontoMatrix> Quaternion2R;
+typedef UnaryOp<VectorQuaternion,MatrixRotation,QuaterniontoMatrix> Quaternion2R;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_F(Quaternion2R,vectorQuaternion,matrixRot,Quaternion2R_,"QuaternionToMatrix", ,"");
 
-struct sotMatrixToQuaternion
+struct MatrixToQuaternion
 {
-  void operator()( const sotMatrixRotation& r,sotVectorQuaternion & res )
+  void operator()( const MatrixRotation& r,VectorQuaternion & res )
   {
     res.fromMatrix(r);
   }
 };
 
 
-typedef sotUnaryOp<sotMatrixRotation,sotVectorQuaternion,sotMatrixToQuaternion> R2Quaternion;
+typedef UnaryOp<MatrixRotation,VectorQuaternion,MatrixToQuaternion> R2Quaternion;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_F(R2Quaternion,matrixRot,vectorQuaternion,R2Quaternion_,"MatrixToQuaternion", ,"");
 
-struct sotMatrixToUTheta
+struct MatrixToUTheta
 {
-  void operator()( const sotMatrixRotation& r,sotVectorUTheta & res )
+  void operator()( const MatrixRotation& r,VectorUTheta & res )
   {
     res.fromMatrix(r);
   }
 };
 
 
-typedef sotUnaryOp<sotMatrixRotation,sotVectorUTheta,sotMatrixToUTheta> R2UTheta;
+typedef UnaryOp<MatrixRotation,VectorUTheta,MatrixToUTheta> R2UTheta;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_F(R2UTheta,matrixRot,vectorUTheta,R2UTheta_,"MatrixToUTheta", ,"");
 
 
-struct sotUThetaToQuaternion
+struct UThetaToQuaternion
 {
-  void operator()( const sotVectorUTheta& r,sotVectorQuaternion& res )
+  void operator()( const VectorUTheta& r,VectorQuaternion& res )
   {
     res.fromVector(r);
   }
 };
 
-typedef sotUnaryOp<sotVectorUTheta,sotVectorQuaternion,sotUThetaToQuaternion> UT2Quaternion;
+typedef UnaryOp<VectorUTheta,VectorQuaternion,UThetaToQuaternion> UT2Quaternion;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_F(UT2Quaternion,vectorQuaternion,vectorUTheta,UT2Quaternion_,"UThetaToQuaternion", ,"");
 
-struct sotDiagonalizer
+struct Diagonalizer
 {
 public:
-  sotDiagonalizer( void ) : nbr(0),nbc(0) {}
+  Diagonalizer( void ) : nbr(0),nbc(0) {}
   unsigned int nbr, nbc;
   void operator()( const ml::Vector& r,ml::Matrix & res )
   {
@@ -448,17 +448,17 @@ public:
   }
 };
 
-typedef sotUnaryOp<ml::Vector,ml::Matrix,sotDiagonalizer> v2mDiagonalizer;
+typedef UnaryOp<ml::Vector,ml::Matrix,Diagonalizer> v2mDiagonalizer;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_F(v2mDiagonalizer,vector,matrix,v2mDiag_,"MatrixDiagonal",
 else if( cmdLine == "resize" ) 
 {  cmdArgs>>std::ws; if( cmdArgs.good()) {cmdArgs >> op.nbr >> op.nbc;}
  else { os << "size = " << op.nbr << " x " << op.nbc << std::endl; } },"");
 
 
-struct sotDirtyMemory
+struct DirtyMemory
 {
 public:
-sotDirtyMemory( void ) {}
+DirtyMemory( void ) {}
 unsigned int nbr, nbc;
 void operator()( const ml::Vector& r,ml::Vector & res )
 {
@@ -466,7 +466,7 @@ res=r;
 }
 };
 
-typedef sotUnaryOp<ml::Vector,ml::Vector,sotDirtyMemory> v2mDirtyMemory;
+typedef UnaryOp<ml::Vector,ml::Vector,DirtyMemory> v2mDirtyMemory;
 SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_E_E(v2mDirtyMemory,vector,v2mDM_,"DirtyMemory", ,"");
 
 } // namespace sot
diff --git a/src/matrix/vector-constant.cpp b/src/matrix/vector-constant.cpp
index f0b13307..376a49c3 100644
--- a/src/matrix/vector-constant.cpp
+++ b/src/matrix/vector-constant.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotVectorConstant.cp
+ * File:      VectorConstant.cp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -22,7 +22,7 @@
 #include <sot-core/factory.h>
 
 namespace sot  {
-SOT_FACTORY_ENTITY_PLUGIN(sotVectorConstant,"VectorConstant");
+SOT_FACTORY_ENTITY_PLUGIN(VectorConstant,"VectorConstant");
 }
 
 using namespace std;
@@ -32,7 +32,7 @@ using namespace sot;
 /* --------------------------------------------------------------------- */
 /* --- VECTOR ---------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
-void sotVectorConstant::
+void VectorConstant::
 commandLine( const std::string& cmdLine,
 	     std::istringstream& cmdArgs, 
 	     std::ostream& os )
diff --git a/src/matrix/vector-to-rotation.cpp b/src/matrix/vector-to-rotation.cpp
index 26fdd38e..7d206935 100644
--- a/src/matrix/vector-to-rotation.cpp
+++ b/src/matrix/vector-to-rotation.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotVectorToRotation.cp
+ * File:      VectorToRotation.cp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -27,19 +27,19 @@ using namespace std;
 using namespace sot;
 
 namespace sot {
-SOT_FACTORY_ENTITY_PLUGIN(sotVectorToRotation,"VectorToRotation");
+SOT_FACTORY_ENTITY_PLUGIN(VectorToRotation,"VectorToRotation");
 }
 
 /* --------------------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-sotVectorToRotation::
-sotVectorToRotation( const std::string& name )
+VectorToRotation::
+VectorToRotation( const std::string& name )
   :Entity( name )
   ,size(0),axes(0)
   ,SIN( NULL,"sotVectorToRotation("+name+")::output(vector)::in" )
-  ,SOUT( SOT_MEMBER_SIGNAL_1( sotVectorToRotation::computeRotation,
+  ,SOUT( SOT_MEMBER_SIGNAL_1( VectorToRotation::computeRotation,
 			    SIN,ml::Vector),
 	 "sotVectorToRotation("+name+")::output(matrixRotation)::out" )
 {
@@ -50,12 +50,12 @@ sotVectorToRotation( const std::string& name )
 /* --------------------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-sotMatrixRotation& sotVectorToRotation::
+MatrixRotation& VectorToRotation::
 computeRotation( const ml::Vector& angles,
-		 sotMatrixRotation& res )
+		 MatrixRotation& res )
 {
   res.setIdentity();
-  sotMatrixRotation Ra,Rtmp;
+  MatrixRotation Ra,Rtmp;
   for( unsigned int i=0;i<size;++i )
     {
       Ra.setIdentity();
@@ -96,7 +96,7 @@ computeRotation( const ml::Vector& angles,
 /* --------------------------------------------------------------------- */
 /* --- VECTOR ---------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
-void sotVectorToRotation::
+void VectorToRotation::
 commandLine( const std::string& cmdLine,
 	     std::istringstream& cmdArgs, 
 	     std::ostream& os )
diff --git a/src/signal/signal-cast.cpp b/src/signal/signal-cast.cpp
index c3e104d8..95b114b5 100644
--- a/src/signal/signal-cast.cpp
+++ b/src/signal/signal-cast.cpp
@@ -72,15 +72,15 @@ trace( const sotVectorMultiBound& t,std::ostream& os )
     {
       switch( iter->mode )
         {
-        case sotMultiBound::MODE_SINGLE:
+        case MultiBound::MODE_SINGLE:
           os << iter->getSingleBound() << "\t";
           break;
-        case sotMultiBound::MODE_DOUBLE:
-          if( iter->getDoubleBoundSetup(sotMultiBound::BOUND_INF) )
-            os << iter->getDoubleBound(sotMultiBound::BOUND_INF)<<"\t";
+        case MultiBound::MODE_DOUBLE:
+          if( iter->getDoubleBoundSetup(MultiBound::BOUND_INF) )
+            os << iter->getDoubleBound(MultiBound::BOUND_INF)<<"\t";
           else os <<"-inf\t";
-          if( iter->getDoubleBoundSetup(sotMultiBound::BOUND_SUP) )
-            os << iter->getDoubleBound(sotMultiBound::BOUND_SUP)<<"\t";
+          if( iter->getDoubleBoundSetup(MultiBound::BOUND_SUP) )
+            os << iter->getDoubleBound(MultiBound::BOUND_SUP)<<"\t";
           else os <<"+inf\t";
           break;
         }
@@ -190,17 +190,17 @@ trace( const ml::Matrix& t,std::ostream& os )
 
 namespace {
 	SOT_SIGNAL_CAST_DECLARATION(SignalCast_sotFeatureAbstractPtr);
-	SOT_SIGNAL_CAST_DECLARATION(sotFlags);
+	SOT_SIGNAL_CAST_DECLARATION(Flags);
 	SOT_SIGNAL_CAST_DECLARATION(sotVectorMultiBound);
 	SOT_SIGNAL_CAST_DECLARATION(timeval );
 	SOT_SIGNAL_CAST_DECLARATION_NAMED(maal::boost::Vector, maal_boost_Vector);
 	SOT_SIGNAL_CAST_DECLARATION_NAMED(maal::boost::Matrix, maal_boost_Matrix);
-	SOT_SIGNAL_CAST_DECLARATION(sotVectorUTheta);
-	SOT_SIGNAL_CAST_DECLARATION(sotVectorQuaternion);
-	SOT_SIGNAL_CAST_DECLARATION(sotVectorRollPitchYaw);
-	SOT_SIGNAL_CAST_DECLARATION(sotMatrixRotation);
-	SOT_SIGNAL_CAST_DECLARATION(sotMatrixHomogeneous);
-	SOT_SIGNAL_CAST_DECLARATION(sotMatrixTwist);
-	SOT_SIGNAL_CAST_DECLARATION(sotMatrixForce);
+	SOT_SIGNAL_CAST_DECLARATION(VectorUTheta);
+	SOT_SIGNAL_CAST_DECLARATION(VectorQuaternion);
+	SOT_SIGNAL_CAST_DECLARATION(VectorRollPitchYaw);
+	SOT_SIGNAL_CAST_DECLARATION(MatrixRotation);
+	SOT_SIGNAL_CAST_DECLARATION(MatrixHomogeneous);
+	SOT_SIGNAL_CAST_DECLARATION(MatrixTwist);
+	SOT_SIGNAL_CAST_DECLARATION(MatrixForce);
 
 }
diff --git a/src/sot/flags.cpp b/src/sot/flags.cpp
index 0ba1216d..23907b1f 100644
--- a/src/sot/flags.cpp
+++ b/src/sot/flags.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotFlags.cpp
+ * File:      Flags.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -60,16 +60,16 @@ static string displaybool(const char c, const bool reverse=false )
 /* --------------------------------------------------------------------- */
 
   
-sotFlags::
-sotFlags( const bool& b ) : flags(),reverse(b) { }
+Flags::
+Flags( const bool& b ) : flags(),reverse(b) { }
 
-sotFlags::
-sotFlags( const char& c ) : flags(),reverse(false) { add(c); }
+Flags::
+Flags( const char& c ) : flags(),reverse(false) { add(c); }
 
-sotFlags::
-sotFlags( const int& c4 ) : flags(),reverse(false) { add(c4);}
+Flags::
+Flags( const int& c4 ) : flags(),reverse(false) { add(c4);}
 
-sotFlags::
+Flags::
 operator bool ( void ) const
 {
   if(reverse) return true;
@@ -78,7 +78,7 @@ operator bool ( void ) const
 }
 
 /* --------------------------------------------------------------------- */
-char sotFlags::
+char Flags::
 operator[] (const unsigned int& i) const
 { 
   char res;
@@ -91,7 +91,7 @@ operator[] (const unsigned int& i) const
 }
 
 namespace sot {
-char operator>> (const sotFlags& f,const int& i)
+char operator>> (const Flags& f,const int& i)
 {
   const div_t q = div(i,8); 
 
@@ -102,7 +102,7 @@ char operator>> (const sotFlags& f,const int& i)
 }
 } // namespace sot
 
-bool sotFlags::
+bool Flags::
 operator() (const int& i) const
 {
   return ((*this)>>i)&0x01;
@@ -110,11 +110,11 @@ operator() (const int& i) const
 
 
 /* --------------------------------------------------------------------- */
-void sotFlags::
+void Flags::
 add( const char& c ) 
 { flags.push_back( c );    }
 
-void sotFlags::
+void Flags::
 add( const int& c4 ) 
 {
   const char* c4p = (const char*)&c4; 
@@ -123,28 +123,28 @@ add( const int& c4 )
  
 
 /* --------------------------------------------------------------------- */
-sotFlags sotFlags::
+Flags Flags::
 operator! (void) const
 {
-  sotFlags res = *this;
+  Flags res = *this;
   res.reverse=!reverse; 
   return res;
 }
 
-sotFlags operator& ( const sotFlags& f1,const sotFlags& f2 ) 
+Flags operator& ( const Flags& f1,const Flags& f2 ) 
 {
-  sotFlags res = f1; res &= f2; return res;
+  Flags res = f1; res &= f2; return res;
 }
 
-sotFlags operator| ( const sotFlags& f1,const sotFlags& f2 ) 
+Flags operator| ( const Flags& f1,const Flags& f2 ) 
 {
-  sotFlags res = f1; res |= f2; return res;
+  Flags res = f1; res |= f2; return res;
 }
 
-sotFlags& sotFlags::
-operator&= ( const sotFlags& f2 ) 
+Flags& Flags::
+operator&= ( const Flags& f2 ) 
 { 
-  sotFlags &f1=*this;
+  Flags &f1=*this;
   const unsigned int max=std::max(flags.size(),f2.flags.size());
   if( flags.size()<max ){ flags.resize(max); }
   bool revres = reverse&&f2.reverse;
@@ -158,10 +158,10 @@ operator&= ( const sotFlags& f2 )
   return *this;
 }
 
-sotFlags& sotFlags::
-operator|= ( const sotFlags& f2 ) 
+Flags& Flags::
+operator|= ( const Flags& f2 ) 
 { 
-  sotFlags &f1=*this;
+  Flags &f1=*this;
   const unsigned int max=std::max(flags.size(),f2.flags.size());
   if( flags.size()<max ){ flags.resize(max); }
   bool revres = reverse||f2.reverse;
@@ -178,15 +178,15 @@ operator|= ( const sotFlags& f2 )
   return *this;
 }
 
-sotFlags operator& ( const sotFlags& f1,const bool& b ){ if(b)return f1; else return sotFlags();}
-sotFlags operator| ( const sotFlags& f1,const bool& b ){ if(b)return sotFlags(true); else return f1;}
-sotFlags& sotFlags::
+Flags operator& ( const Flags& f1,const bool& b ){ if(b)return f1; else return Flags();}
+Flags operator| ( const Flags& f1,const bool& b ){ if(b)return Flags(true); else return f1;}
+Flags& Flags::
 operator&= ( const bool& b ){ if(!b) { flags.clear(); reverse=false; } return *this; }
-sotFlags& sotFlags::
+Flags& Flags::
 operator|= ( const bool& b ){ if(b) { flags.clear(); reverse=true; } return *this;}
 
 /* --------------------------------------------------------------------- */
-void sotFlags::
+void Flags::
 set( const unsigned int & idx )
 {
   unsigned int d= (idx/8), m=(idx%8);
@@ -212,7 +212,7 @@ set( const unsigned int & idx )
   sotDEBUG(45) << "New flag: "<< *this << endl;
 }
 
-void sotFlags::
+void Flags::
 unset( const unsigned int & idx )
 {
   unsigned int d= (idx/8), m=(idx%8);
@@ -240,7 +240,7 @@ unset( const unsigned int & idx )
 
 /* --------------------------------------------------------------------- */
 namespace sot {
-std::ostream& operator<< (std::ostream& os, const sotFlags& fl )
+std::ostream& operator<< (std::ostream& os, const Flags& fl )
 {
   if( fl.reverse ) os << "...11111 ";
   unsigned int s = fl.flags.size();
@@ -255,7 +255,7 @@ std::ostream& operator<< (std::ostream& os, const sotFlags& fl )
 
 static char MASK [] = { 0,1,3,7,15,31,63,127,255 };
 
-std::istream& operator>> (std::istream& is, sotFlags& fl )
+std::istream& operator>> (std::istream& is, Flags& fl )
 {
   sotDEBUGIN(15);
   std::list<char> listing;
@@ -286,9 +286,9 @@ std::istream& operator>> (std::istream& is, sotFlags& fl )
 	  {
 	    char cnot; is.get(cnot);
 	    if( cnot=='!' ) 
-	      fl = (! sotFlags::readIndexMatlab( is ));
+	      fl = (! Flags::readIndexMatlab( is ));
 	    else 
-	      { is.unget(); fl = sotFlags::readIndexMatlab( is ); }
+	      { is.unget(); fl = Flags::readIndexMatlab( is ); }
 
 	    return is;
 	  }
@@ -296,18 +296,18 @@ std::istream& operator>> (std::istream& is, sotFlags& fl )
 	  {
 	    char cnot; is.get(cnot);
 	    if( cnot=='!' ) 
-	      fl &= (! sotFlags::readIndexMatlab( is ));
+	      fl &= (! Flags::readIndexMatlab( is ));
 	    else 
-	      { is.unget(); fl &= sotFlags::readIndexMatlab( is ); }
+	      { is.unget(); fl &= Flags::readIndexMatlab( is ); }
 	    return is;
 	  }
 	case '|': 
 	  {
 	    char cnot; is.get(cnot);
 	    if( cnot=='!' ) 
-	      fl |= (! sotFlags::readIndexMatlab( is ));
+	      fl |= (! Flags::readIndexMatlab( is ));
 	    else 
-	      { is.unget(); fl |= (sotFlags::readIndexMatlab( is )); }
+	      { is.unget(); fl |= (Flags::readIndexMatlab( is )); }
 	    return is;
 	  }
 	default: 
@@ -374,18 +374,18 @@ std::istream& operator>> (std::istream& is, sotFlags& fl )
 } // namespace sot
 
 /* --------------------------------------------------------------------- */
-const sotFlags FLAG_LINE_1( (char)0x1 );
-const sotFlags FLAG_LINE_2( (char)0x2 );
-const sotFlags FLAG_LINE_3( (char)0x4 );
-const sotFlags FLAG_LINE_4( (char)0x8 );
-const sotFlags FLAG_LINE_5( (char)0x10 );
-const sotFlags FLAG_LINE_6( (char)0x20 );
-const sotFlags FLAG_LINE_7( (char)0x40 );
-const sotFlags FLAG_LINE_8( (char)0x80 );
+const Flags FLAG_LINE_1( (char)0x1 );
+const Flags FLAG_LINE_2( (char)0x2 );
+const Flags FLAG_LINE_3( (char)0x4 );
+const Flags FLAG_LINE_4( (char)0x8 );
+const Flags FLAG_LINE_5( (char)0x10 );
+const Flags FLAG_LINE_6( (char)0x20 );
+const Flags FLAG_LINE_7( (char)0x40 );
+const Flags FLAG_LINE_8( (char)0x80 );
 
 /* --------------------------------------------------------------------- */
 
-void sotFlags::
+void Flags::
 readIndexMatlab( std::istream& cmdArgs,
 		 unsigned int & idx_beg,
 		 unsigned int &idx_end,
@@ -415,7 +415,7 @@ readIndexMatlab( std::istream& cmdArgs,
 	       << "(" << no_end <<")"<<endl;
 }
 
-sotFlags sotFlags::
+Flags Flags::
 readIndexMatlab( std::istream& cmdArgs )
 {
   sotDEBUGIN(15) ;
@@ -424,7 +424,7 @@ readIndexMatlab( std::istream& cmdArgs )
   
   readIndexMatlab( cmdArgs,idxStart,idxEnd,idxUnspec );
   
-  sotFlags newFlag( idxUnspec );
+  Flags newFlag( idxUnspec );
   if( idxUnspec )
     {    for( unsigned int i=0;i<idxStart;++i )       newFlag.unset(i);  }
   else { for( unsigned int i=idxStart;i<=idxEnd;++i ) newFlag.set(i);    }
diff --git a/src/sot/memory-task-sot.cpp b/src/sot/memory-task-sot.cpp
index 384727ca..f1ed0743 100644
--- a/src/sot/memory-task-sot.cpp
+++ b/src/sot/memory-task-sot.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet Gepetto, LAAS, CNRS, 2009
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotMemoryTaskSOT.cpp
+ * File:      MemoryTaskSOT.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -24,11 +24,11 @@
 using namespace sot;
 
 
-const std::string sotMemoryTaskSOT::CLASS_NAME = "MemoryTaskSOT";
+const std::string MemoryTaskSOT::CLASS_NAME = "MemoryTaskSOT";
 
 
-sotMemoryTaskSOT::
-sotMemoryTaskSOT( const std::string & name
+MemoryTaskSOT::
+MemoryTaskSOT( const std::string & name
                   ,const unsigned int nJ
                   ,const unsigned int mJ
                   ,const unsigned int ffsize )
@@ -47,7 +47,7 @@ sotMemoryTaskSOT( const std::string & name
 }
 
 
-void sotMemoryTaskSOT::
+void MemoryTaskSOT::
 initMemory( const unsigned int nJ,const unsigned int mJ,const unsigned int ffsize )
 {
    sotDEBUG(15) << "Task-mermory " << getName() << ": resize " 
@@ -70,7 +70,7 @@ initMemory( const unsigned int nJ,const unsigned int mJ,const unsigned int ffsiz
  }
 
 
- void sotMemoryTaskSOT::
+ void MemoryTaskSOT::
  commandLine( const std::string& cmdLine,std::istringstream& cmdArgs,
               std::ostream& os )
  {
@@ -93,6 +93,6 @@ initMemory( const unsigned int nJ,const unsigned int mJ,const unsigned int ffsiz
      }
  }
 
-void sotMemoryTaskSOT::
+void MemoryTaskSOT::
 display( std::ostream& os ) const {} //TODO
 
diff --git a/src/sot/rotation-simple.cpp b/src/sot/rotation-simple.cpp
index 2b5b5fe5..d4d8c029 100644
--- a/src/sot/rotation-simple.cpp
+++ b/src/sot/rotation-simple.cpp
@@ -2,7 +2,7 @@
 
 
 bool MATLAB::fullPrec = false;
-MATLAB::MATLAB( const sotRotationSimple& Qh,const unsigned int nJ)
+MATLAB::MATLAB( const RotationSimple& Qh,const unsigned int nJ)
 {
 
   bubMatrix eye(nJ,nJ); eye.assign(bub::identity_matrix<double>(nJ));
diff --git a/src/sot/solver-hierarchical-inequalities.cpp b/src/sot/solver-hierarchical-inequalities.cpp
index fc8fb7de..08c100a6 100644
--- a/src/sot/solver-hierarchical-inequalities.cpp
+++ b/src/sot/solver-hierarchical-inequalities.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet Gepetto, LAAS, 2009
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotSolverHierarchicalInequalities.cpp
+ * File:      SolverHierarchicalInequalities.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -220,7 +220,7 @@ std::ostream & operator<< (std::ostream& os,const ConstraintMem &c )
 
 /* ---------------------------------------------------------- */
 /* Specify the size of the constraint matrix, for pre-alocation. */
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 initConstraintSize( const unsigned int size )
 {
   if(Rh.size1()!=nJ) {Rh.resize(nJ,nJ,false); Rh.clear();}
@@ -230,7 +230,7 @@ initConstraintSize( const unsigned int size )
   constraintS.reserve(size+1);
 }
 
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 setInitialCondition( const bubVector& _u0,
                      const unsigned int _rankh )
 {
@@ -238,13 +238,13 @@ setInitialCondition( const bubVector& _u0,
   rankh=_rankh; freeRank=nJ-rankh;
 }
 
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 setInitialConditionVoid( void )
 {
   u0.resize(nJ,false); u0.clear();
   rankh=0; freeRank=nJ;
 }
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 setNbDof( const unsigned int _nJ )
 {
   sotDEBUGIN(15);
@@ -257,7 +257,7 @@ setNbDof( const unsigned int _nJ )
 
 /* ---------------------------------------------------------- */
 
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 recordInitialConditions( void )
 {
   initialActiveH.resize(constraintH.size()); initialSideH.resize(constraintH.size());
@@ -274,7 +274,7 @@ recordInitialConditions( void )
 
   du0.resize(u0.size(),false); du0.assign(-u0);
 }
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 computeDifferentialCondition( void )
 {
   if( constraintH.size()>initialActiveH.size() )
@@ -314,7 +314,7 @@ computeDifferentialCondition( void )
   warmStartReady = true;
 }
 
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 printDifferentialCondition( std::ostream & os ) const
 {
   if(! warmStartReady ) return; 
@@ -343,32 +343,32 @@ printDifferentialCondition( std::ostream & os ) const
 /* ---------------------------------------------------------- */
 
 
-// sotSolverHierarchicalInequalities::bubMatrixQROrdered
-// sotSolverHierarchicalInequalities::
+// SolverHierarchicalInequalities::bubMatrixQROrdered
+// SolverHierarchicalInequalities::
 // accessQRs( void )
 // {
 //   bubMatrixQR QRs( QhJsU,freerange(),bub::range::all() );
 //   bubMatrixQROrdered QRord( QRs,bubOrder::all(),orderS );
 //   return QRord;
 // }
-// sotSolverHierarchicalInequalities::bubMatrixQROrderedConst
-// sotSolverHierarchicalInequalities::
+// SolverHierarchicalInequalities::bubMatrixQROrderedConst
+// SolverHierarchicalInequalities::
 // accessQRs( void ) const
 // {
 //   bubMatrixQRConst QRs( QhJsU,freerange(),bub::range::all() );
 //   bubMatrixQROrderedConst QRord( QRs,bubOrder::all(),orderS );
 //   return QRord;
 // }
-// sotSolverHierarchicalInequalities::bubMatrixQROrderedTri
-// sotSolverHierarchicalInequalities::
+// SolverHierarchicalInequalities::bubMatrixQROrderedTri
+// SolverHierarchicalInequalities::
 // accessRs( void )
 // {
 //   bubMatrixQR QRs( QhJsU,freeranges(),bub::range::all() );
 //    bubMatrixQROrdered QRord( QRs,bubOrder::all(),orderS );
 //    return QRord;
 //  }
-sotSolverHierarchicalInequalities::bubMatrixQROrderedTriConst
-sotSolverHierarchicalInequalities::
+SolverHierarchicalInequalities::bubMatrixQROrderedTriConst
+SolverHierarchicalInequalities::
 accessRsConst( void ) const
 {
   bubMatrixQRConst QRs( QhJsU,freeranges(),bub::range(0,sizes) );
@@ -379,7 +379,7 @@ accessRsConst( void ) const
 }
 
 bub::triangular_adaptor<bub::matrix_range< const bubMatrix >,bub::upper>
-sotSolverHierarchicalInequalities::
+SolverHierarchicalInequalities::
 accessRhConst( void ) const
 {
   bub::matrix_range< const bubMatrix >
@@ -388,7 +388,7 @@ accessRhConst( void ) const
 }
 
 bub::triangular_adaptor<bub::matrix_range< bubMatrix >,bub::upper>
-sotSolverHierarchicalInequalities::
+SolverHierarchicalInequalities::
 accessRh( void )
 {
   bub::matrix_range< bubMatrix >
@@ -398,7 +398,7 @@ accessRh( void )
 
 /* Assuming a diagonal-ordered triangular matrix. */
 template< typename bubTemplateMatrix >
-unsigned int sotSolverHierarchicalInequalities::
+unsigned int SolverHierarchicalInequalities::
 rankDetermination( const bubTemplateMatrix& A,
                    const double threshold )
 {
@@ -409,7 +409,7 @@ rankDetermination( const bubTemplateMatrix& A,
 }
 
 /* ---------------------------------------------------------- */
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 displayConstraint( ConstraintList & cs )
 {
 #ifdef VP_DEBUG
@@ -424,7 +424,7 @@ displayConstraint( ConstraintList & cs )
 
 
 
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 printDebug( void )
 {
 #ifdef VP_DEBUG
@@ -504,7 +504,7 @@ printDebug( void )
 /* ---------------------------------------------------------- */
 /* ---------------------------------------------------------- */
 
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 warmStart( void )
 {
   if(! warmStartReady ) return; 
@@ -529,7 +529,7 @@ warmStart( void )
   if( toActivateCH.size()>0 )forceUpdateHierachic(toActivateCH,toActivateSide);
 }
 
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 applyFreeSpaceMotion( const bubVector& _du )
 {
   printDebug();
@@ -547,7 +547,7 @@ applyFreeSpaceMotion( const bubVector& _du )
   u0+=du;
 }
 
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 forceUpdateHierachic( ConstraintRefList& toUpdate,
                       const ConstraintMem::BoundSideVector& boundSide )
 {
@@ -648,7 +648,7 @@ forceUpdateHierachic( ConstraintRefList& toUpdate,
   Qh.pushBack(Qlast);
 }
 
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 forceDowndateHierachic( ConstraintRefList& toDowndate )
 {
   {
@@ -791,7 +791,7 @@ forceDowndateHierachic( ConstraintRefList& toDowndate )
 /* ---------------------------------------------------------- */
 
 SOT_DEFINE_CHRONO;
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 solve( const bubMatrix& Jse, const bubVector& ese,
        const bubMatrix& Jsi, const bubVector& esiInf, const bubVector& esiSup,
        const std::vector<ConstraintMem::BoundSideType> esiBoundSide,
@@ -801,7 +801,7 @@ solve( const bubMatrix& Jse, const bubVector& ese,
   solve(Jse,ese,Jsi,esiInf,esiSup,esiBoundSide,vectVoid,pushBackAtTheEnd);
 }
 
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 solve( const bubMatrix& Jse, const bubVector& ese,
        const bubMatrix& Jsi, const bubVector& esiInf, const bubVector& esiSup,
        const ConstraintMem::BoundSideVector & esiBoundSide,
@@ -933,7 +933,7 @@ solve( const bubMatrix& Jse, const bubVector& ese,
 }
 
 /* ---------------------------------------------------------- */
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 initializeConstraintMemory( const bubMatrix& Jse, const bubVector& ese,
                             const bubMatrix& Jsi, const bubVector& esiInf, const bubVector& esiSup,
                             const ConstraintMem::BoundSideVector& esiBoundSide,
@@ -1017,7 +1017,7 @@ initializeConstraintMemory( const bubMatrix& Jse, const bubVector& ese,
     }
 }
 
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 initializeDecompositionSlack(void)
 {
   QhJsU.resize(nJ,constraintS.size(),false); QhJsU.clear();
@@ -1122,7 +1122,7 @@ initializeDecompositionSlack(void)
 
 /* ---------------------------------------------------------- */
 /* <constraintId> is the number of the constraint in the constraintH list. */
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 updateConstraintHierarchic( const unsigned int constraintId,
                             const ConstraintMem::BoundSideType side )
 {
@@ -1176,7 +1176,7 @@ updateConstraintHierarchic( const unsigned int constraintId,
 
 
 /* <constraintId> is the number of the constraint in the constraintH list. */
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 downdateConstraintHierarchic( const unsigned int kdown )
 {
   ConstraintMem & cdown = constraintH[kdown];
@@ -1240,7 +1240,7 @@ downdateConstraintHierarchic( const unsigned int kdown )
 
 /* ---------------------------------------------------------- */
 /* <kup> is the number of the constraint in the constraintS list. */
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 updateConstraintSlack( const unsigned int kup,const ConstraintMem::BoundSideType activeSide )
 {
   sotDEBUG(15) << "kup = " << activeSide << kup << std::endl;
@@ -1312,7 +1312,7 @@ updateConstraintSlack( const unsigned int kup,const ConstraintMem::BoundSideType
 }
 
 /* Regularize from right (Q.J from Q.J.U). */
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 regularizeQhJs( void )
 {
   typedef bub::matrix_column<bubMatrixQRWide> bubQJsCol;
@@ -1347,7 +1347,7 @@ regularizeQhJs( void )
 }
 
 /* Regularize from right (Q.J from Q.J.U). */
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 regularizeQhJsU( void )
 {
   if( ranks==sizes ) return;
@@ -1374,7 +1374,7 @@ regularizeQhJsU( void )
 
 
 /* <constraintId> is the number of the constraint in the constraintS list. */
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 downdateConstraintSlack( const unsigned int kdown )
 {
   /* Remove the column. */
@@ -1416,14 +1416,14 @@ downdateConstraintSlack( const unsigned int kdown )
     .assign(bub::zero_matrix<double>(nJ,QhJsU.size2()-sizes));
   regularizeQhJsU();
 
-  //     std::cerr << "Not implemented yet (sotRotationSimple l" << __LINE__
+  //     std::cerr << "Not implemented yet (RotationSimple l" << __LINE__
   //               << ")." << std::endl;
   //     throw  "Not implemented yet.";
 }
 
 
 /* ---------------------------------------------------------- */
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 updateRankOneDowndate( void )
 {
   sotDEBUG(15) << "/* Apply the last corrections of Qh. */"<<std::endl;
@@ -1475,7 +1475,7 @@ updateRankOneDowndate( void )
     }
 }
 
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 updateRankOneUpdate( void )
 {
   sotDEBUG(15) << "ranks = " << ranks << std::endl;
@@ -1620,7 +1620,7 @@ updateRankOneUpdate( void )
  * of the active slack constraints.
  * <gradient> must be of size <nJ> (no resize).
  */
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 computeGradient( bubVector& gradientWide )
 {
   //     bubVector gse(ese.size()); gse=ese;
@@ -1642,7 +1642,7 @@ computeGradient( bubVector& gradientWide )
  * using the Null-Space method:
  *   du = Nh Ms Rs^-T Rs^-1 Ms' Nh' Js' ( es - Js u0 )
  */
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 computePrimal( void )
 {
   if( (0==freeRank)||(0==ranks) )
@@ -1677,7 +1677,7 @@ computePrimal( void )
 /* Compute the slack w = es-Js(u0+du). Since esi<Jsi.u, the slack
  * w = esi-Jsi.u should be negative. Since Jss.u<ess, the slack
  * w = Jss.u-ess should also be negative. */
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 computeSlack( void )
 {
   slackInf.resize(constraintS.size(),false); slackInf.clear();
@@ -1705,7 +1705,7 @@ computeSlack( void )
   sotDEBUG(5) << "slackInf = " << (MATLAB)slackInf << std::endl;
   sotDEBUG(5) << "slackSup = " << (MATLAB)slackSup << std::endl;
 }
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 computeLagrangian( void )
 {
   if(rankh==0) return;
@@ -1745,7 +1745,7 @@ computeLagrangian( void )
 
 
 /* ---------------------------------------------------------- */
-bool sotSolverHierarchicalInequalities::
+bool SolverHierarchicalInequalities::
 selecActivationHierarchic( double & tau )
 {
   tau=1-THRESHOLD_ZERO; unsigned int constraintRef = 0;
@@ -1780,7 +1780,7 @@ selecActivationHierarchic( double & tau )
                        << HactivationRef << ">" << std::endl;}
   return res;
 }
-bool sotSolverHierarchicalInequalities::
+bool SolverHierarchicalInequalities::
 selecInactivationHierarchic( void )
 {
   bool res=false; double HinactivationScore=-THRESHOLD_ZERO;
@@ -1800,7 +1800,7 @@ selecInactivationHierarchic( void )
   return res;
 }
 /* The slack w = es-Js.u should be negative. */
-bool sotSolverHierarchicalInequalities::
+bool SolverHierarchicalInequalities::
 selecActivationSlack( void )
 {
   unsigned int row = 0; SactivationScore=THRESHOLD_ZERO;
@@ -1823,7 +1823,7 @@ selecActivationSlack( void )
   return SactivationScore>THRESHOLD_ZERO;
 }
 /* The slack should be negative. If strickly negative: unactivate. */
-bool sotSolverHierarchicalInequalities::
+bool SolverHierarchicalInequalities::
 selecInactivationSlack( void )
 {
   unsigned int row = 0; SinactivationScore=-THRESHOLD_ZERO;
@@ -1845,7 +1845,7 @@ selecInactivationSlack( void )
 }
 
 /* ---------------------------------------------------------- */
-void sotSolverHierarchicalInequalities::
+void SolverHierarchicalInequalities::
 pushBackSlackToHierarchy( void )
 {
   if( freeRank>0 )
@@ -1934,4 +1934,4 @@ pushBackSlackToHierarchy( void )
 }
 
 
-double sotSolverHierarchicalInequalities::THRESHOLD_ZERO = 1e-6;
+double SolverHierarchicalInequalities::THRESHOLD_ZERO = 1e-6;
diff --git a/src/sot/sot-h.cpp b/src/sot/sot-h.cpp
index 23a8180a..98525d96 100644
--- a/src/sot/sot-h.cpp
+++ b/src/sot/sot-h.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet Gepetto, LAAS, 2009
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotSOTH.cpp
+ * File:      SotH.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -44,24 +44,24 @@ sotSOTH__INIT sotSOTH_initiator;
 /* --- CLASS ----------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-SOT_FACTORY_ENTITY_PLUGIN(sotSOTH,"SOTH");
+SOT_FACTORY_ENTITY_PLUGIN(SotH,"SOTH");
 
 
 /* --------------------------------------------------------------------- */
 /* --- CLASS ----------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-sotSOTH::
-sotSOTH( const std::string& name )
-  :sotSOT(name),Qh(nbJoints),Rh(nbJoints,nbJoints),constraintH()
+SotH::
+SotH( const std::string& name )
+  :Sot(name),Qh(nbJoints),Rh(nbJoints,nbJoints),constraintH()
   ,solverNorm(nbJoints,Qh,Rh,constraintH),solverPrec(NULL)
   ,fillMemorySignal(false)
 {
 }
 
 
-sotSOTH::
-~sotSOTH( void )
+SotH::
+~SotH( void )
 {
 
 
@@ -69,11 +69,11 @@ sotSOTH::
 }
 
 
-void sotSOTH::
+void SotH::
 defineNbDof( const unsigned int& nbDof )
 {
   sotDEBUGIN(15);
-  sotSOT::defineNbDof(nbDof);
+  Sot::defineNbDof(nbDof);
   for(StackType::iterator iter=stack.begin();stack.end()!=iter;++iter )
     {
       sotMemoryTaskSOTH * mem
@@ -84,7 +84,7 @@ defineNbDof( const unsigned int& nbDof )
   sotDEBUGOUT(15);
 }
 
-void sotSOTH::
+void SotH::
 commandLine( const std::string& cmdLine,std::istringstream& cmdArgs,
 	     std::ostream& os )
 {
@@ -94,7 +94,7 @@ commandLine( const std::string& cmdLine,std::istringstream& cmdArgs,
     {
       os << "Stack of Tasks Inequality: "<<endl
 	 << " - fillMemorySignal [boolean] "<<endl;
-      sotSOT::commandLine( cmdLine,cmdArgs,os );
+      Sot::commandLine( cmdLine,cmdArgs,os );
     }
   else if( cmdLine == "fillMemorySignal")
     {
@@ -106,7 +106,7 @@ commandLine( const std::string& cmdLine,std::istringstream& cmdArgs,
     }
  else
    {
-     sotSOT::commandLine( cmdLine,cmdArgs,os );
+     Sot::commandLine( cmdLine,cmdArgs,os );
    }
 
 
@@ -129,7 +129,7 @@ void buildTaskVectors( const sotVectorMultiBound& err,
   unsigned int sizei=0,sizee=0;
   for( sotVectorMultiBound::const_iterator iter=err.begin();
        err.end()!=iter;++iter )
-    { if( iter->getMode()==sotMultiBound::MODE_SINGLE )
+    { if( iter->getMode()==MultiBound::MODE_SINGLE )
         sizee++; else sizei++; }
 
   Ji.resize(sizei,nJ); eiinf.resize(sizei),eisup.resize(sizei);
@@ -143,25 +143,25 @@ void buildTaskVectors( const sotVectorMultiBound& err,
     sotDEBUG(25) << "i = "<<i<< std::endl;
     switch( err[i].getMode() )
         {
-        case sotMultiBound::MODE_SINGLE:
+        case MultiBound::MODE_SINGLE:
           {
             ee(--sizee) = err[i].getSingleBound();
             for( unsigned int j=0;j<nJ;++j )
               { Je(sizee,j) = JK(i,j); }
             break;
           }
-        case sotMultiBound::MODE_DOUBLE:
+        case MultiBound::MODE_DOUBLE:
           {
             --sizei;
             bounds[sizei] = ConstraintMem::BOUND_VOID;
-            if( err[i].getDoubleBoundSetup( sotMultiBound::BOUND_INF ) )
+            if( err[i].getDoubleBoundSetup( MultiBound::BOUND_INF ) )
               {
-                eiinf(sizei) = err[i].getDoubleBound( sotMultiBound::BOUND_INF );
+                eiinf(sizei) = err[i].getDoubleBound( MultiBound::BOUND_INF );
                 bounds[sizei] = ConstraintMem::BOUND_INF;
               }
-            if( err[i].getDoubleBoundSetup( sotMultiBound::BOUND_SUP ) )
+            if( err[i].getDoubleBoundSetup( MultiBound::BOUND_SUP ) )
               {
-                eisup(sizei) = err[i].getDoubleBound( sotMultiBound::BOUND_SUP );
+                eisup(sizei) = err[i].getDoubleBound( MultiBound::BOUND_SUP );
                 if( bounds[sizei]==ConstraintMem::BOUND_INF )
                   bounds[sizei]= ConstraintMem::BOUND_BOTH;
                 else bounds[sizei]= ConstraintMem::BOUND_SUP;
@@ -212,14 +212,14 @@ void buildTaskVectors( const sotVectorMultiBound& err,
 
 SOT_DEFINE_CHRONO;
 
-ml::Vector& sotSOTH::
+ml::Vector& SotH::
 computeControlLaw( ml::Vector& control,const int& iterTime )
 {
   sotDEBUGIN(15);
 
   SOT_INIT_CHRONO;
 
-  sotSolverHierarchicalInequalities::THRESHOLD_ZERO = inversionThresholdSIN(iterTime);
+  SolverHierarchicalInequalities::THRESHOLD_ZERO = inversionThresholdSIN(iterTime);
   const ml::Matrix &K = constraintSOUT(iterTime);
   const unsigned int nJ = K.nbCols();
 
@@ -245,7 +245,7 @@ computeControlLaw( ml::Vector& control,const int& iterTime )
 //         {
 //           if(*iter==NULL)
 //             {
-//               (*iter)=new sotSolverHierarchicalInequalities(nJ,Qh,Rh,constraintH);
+//               (*iter)=new SolverHierarchicalInequalities(nJ,Qh,Rh,constraintH);
 //             }
 //           /* TODO: free memory */
 //         }
@@ -263,7 +263,7 @@ computeControlLaw( ml::Vector& control,const int& iterTime )
   for( StackType::iterator iter = stack.begin(); iter!=stack.end();++iter,++iterTask )
     {
       sotDEBUGF(5,"Rank %d.",iterTask);
-      sotTaskAbstract & task = **iter;
+      TaskAbstract & task = **iter;
       sotDEBUG(15) << "Task: e_" << task.getName() << std::endl;
       const ml::Matrix &Jac = task.jacobianSOUT(iterTime);
       const sotVectorMultiBound &err = task.taskSOUT(iterTime);
@@ -285,7 +285,7 @@ computeControlLaw( ml::Vector& control,const int& iterTime )
       mem->Jact.resize( ntask,nJ );
 
       sotDEBUG(25) << "/* --- COMPUTE JK --- */" << std::endl;
-      sotSOT::computeJacobianConstrained( Jac,K,mem->JK,mem->Jff,mem->Jact );
+      Sot::computeJacobianConstrained( Jac,K,mem->JK,mem->Jff,mem->Jact );
       if( fillMemorySignal )
         {
           mem->jacobianConstrainedSINOUT = mem->JK;
@@ -293,7 +293,7 @@ computeControlLaw( ml::Vector& control,const int& iterTime )
         }
 
       sotDEBUG(25) << "/* Set initial conditions. */" << std::endl;
-      sotSolverHierarchicalInequalities & solver = mem->solver;
+      SolverHierarchicalInequalities & solver = mem->solver;
       if( NULL==solverPrec ) solver.setInitialConditionVoid();
       else
         { solver.setInitialCondition( solverPrec->u0,solverPrec->rankh ); }
@@ -372,7 +372,7 @@ computeControlLaw( ml::Vector& control,const int& iterTime )
   if( fillMemorySignal )
     for( StackType::iterator iter = stack.begin(); iter!=stack.end();++iter,++iterTask )
       {
-        sotTaskAbstract & task = **iter;
+        TaskAbstract & task = **iter;
         sotMemoryTaskSOTH * mem = dynamic_cast<sotMemoryTaskSOTH *>( task.memoryInternal );
         if( mem == NULL ) continue;
         sotVectorMultiBound taskVector = task.taskSOUT(iterTime);
@@ -382,15 +382,15 @@ computeControlLaw( ml::Vector& control,const int& iterTime )
 
         for( unsigned int i=0;i<taskVector.size();++i )
           {
-            const sotMultiBound & Xi = taskVector[i];
+            const MultiBound & Xi = taskVector[i];
             switch( Xi.getMode() )
               {
-              case sotMultiBound::MODE_SINGLE:
+              case MultiBound::MODE_SINGLE:
                 diff(i) = Xi.getSingleBound()-JKu(i);
                 break;
-              case sotMultiBound::MODE_DOUBLE:
-                diff(i) = std::min( JKu(i)-Xi.getDoubleBound(sotMultiBound::BOUND_INF ),
-                                    Xi.getDoubleBound(sotMultiBound::BOUND_SUP)-JKu(i) );
+              case MultiBound::MODE_DOUBLE:
+                diff(i) = std::min( JKu(i)-Xi.getDoubleBound(MultiBound::BOUND_INF ),
+                                    Xi.getDoubleBound(MultiBound::BOUND_SUP)-JKu(i) );
                 break;
               }
           }
@@ -408,26 +408,26 @@ computeControlLaw( ml::Vector& control,const int& iterTime )
 /* --------------------------------------------------------------------- */
 
 
-const std::string sotSOTH::sotMemoryTaskSOTH::CLASS_NAME = "MemoryTaskSOTH";
+const std::string SotH::sotMemoryTaskSOTH::CLASS_NAME = "MemoryTaskSOTH";
 
-void sotSOTH::sotMemoryTaskSOTH::
+void SotH::sotMemoryTaskSOTH::
 commandLine( const std::string& cmdLine,std::istringstream& cmdArgs,
              std::ostream& os )
 {
   Entity::commandLine( cmdLine,cmdArgs,os );
 }
 
-void sotSOTH::sotMemoryTaskSOTH::
+void SotH::sotMemoryTaskSOTH::
 display( std::ostream& os ) const {} //TODO
 
 
-sotSOTH::sotMemoryTaskSOTH::
+SotH::sotMemoryTaskSOTH::
 sotMemoryTaskSOTH( const std::string & name,
-                   const sotSOTH * ref,
+                   const SotH * ref,
                    unsigned int nJ,
                    sotRotationComposedInExtenso& Qh,
                    bubMatrix &Rh,
-                   sotSolverHierarchicalInequalities::ConstraintList &cH )
+                   SolverHierarchicalInequalities::ConstraintList &cH )
   :Entity(name),referenceKey(ref),solver(nJ,Qh,Rh,cH)
   ,jacobianConstrainedSINOUT( "sotTaskAbstract("+name+")::inout(matrix)::JK" )
   ,diffErrorSINOUT( "sotTaskAbstract("+name+")::inout(vector)::diff" )
diff --git a/src/sot/sot-qr.cpp b/src/sot/sot-qr.cpp
index 34d36738..b3592404 100644
--- a/src/sot/sot-qr.cpp
+++ b/src/sot/sot-qr.cpp
@@ -48,17 +48,17 @@ using namespace sot;
 
 
 #include <sot-core/factory.h>
-SOT_FACTORY_ENTITY_PLUGIN(sotSOTQr,"SOTQr");
+SOT_FACTORY_ENTITY_PLUGIN(SotQr,"SOTQr");
 
 
-const double sotSOTQr::INVERSION_THRESHOLD_DEFAULT = 1e-4;
-const unsigned int sotSOTQr::NB_JOINTS_DEFAULT = 46;
+const double SotQr::INVERSION_THRESHOLD_DEFAULT = 1e-4;
+const unsigned int SotQr::NB_JOINTS_DEFAULT = 46;
 
 /* --------------------------------------------------------------------- */
 /* --- CONSTRUCTION ---------------------------------------------------- */
 /* --------------------------------------------------------------------- */
-sotSOTQr::
-sotSOTQr( const std::string& name )
+SotQr::
+SotQr( const std::string& name )
   :Entity(name)
   ,stack()
   ,constraintList()
@@ -69,10 +69,10 @@ sotSOTQr( const std::string& name )
   ,taskGradient(0)
   ,q0SIN( NULL,"sotSOTQr("+name+")::input(double)::q0" )
    ,inversionThresholdSIN( NULL,"sotSOTQr("+name+")::input(double)::damping" )
-   ,constraintSOUT( boost::bind(&sotSOTQr::computeConstraintProjector,this,_1,_2),
+   ,constraintSOUT( boost::bind(&SotQr::computeConstraintProjector,this,_1,_2),
 		   sotNOSIGNAL,
 		    "sotSOTQr("+name+")::output(matrix)::constraint" )
-  ,controlSOUT( boost::bind(&sotSOTQr::computeControlLaw,this,_1,_2),
+  ,controlSOUT( boost::bind(&SotQr::computeControlLaw,this,_1,_2),
 		constraintSOUT<<inversionThresholdSIN<<q0SIN,
 		"sotSOTQr("+name+")::output(vector)::control" )
 {
@@ -84,8 +84,8 @@ sotSOTQr( const std::string& name )
 /* --------------------------------------------------------------------- */
 /* --- STACK MANIPULATION --- */
 /* --------------------------------------------------------------------- */
-void sotSOTQr::
-push( sotTaskAbstract& task )
+void SotQr::
+push( TaskAbstract& task )
 {
   stack.push_back( &task );
   controlSOUT.addDependancy( task.taskSOUT );
@@ -93,10 +93,10 @@ push( sotTaskAbstract& task )
   //controlSOUT.addDependancy( task.featureActivationSOUT );
   controlSOUT.setReady();
 }
-sotTaskAbstract& sotSOTQr::
+TaskAbstract& SotQr::
 pop( void )
 {
-  sotTaskAbstract* res = stack.back();
+  TaskAbstract* res = stack.back();
   stack.pop_back();
   controlSOUT.removeDependancy( res->taskSOUT );
   controlSOUT.removeDependancy( res->jacobianSOUT );
@@ -104,20 +104,20 @@ pop( void )
   controlSOUT.setReady();
   return *res;
 }
-bool sotSOTQr::
-exist( const sotTaskAbstract& key )
+bool SotQr::
+exist( const TaskAbstract& key )
 {
-  std::list<sotTaskAbstract*>::iterator it;
+  std::list<TaskAbstract*>::iterator it;
   for ( it=stack.begin();stack.end()!=it;++it )
     {
       if( *it == &key ) { return true; }
     }
   return false;
 }
-void sotSOTQr::
-remove( const sotTaskAbstract& key )
+void SotQr::
+remove( const TaskAbstract& key )
 {
-  bool find =false; std::list<sotTaskAbstract*>::iterator it;
+  bool find =false; std::list<TaskAbstract*>::iterator it;
   for ( it=stack.begin();stack.end()!=it;++it )
     {
       if( *it == &key ) { find=true; break; }
@@ -128,8 +128,8 @@ remove( const sotTaskAbstract& key )
   removeDependancy( key );
 }
 
-void sotSOTQr::
-removeDependancy( const sotTaskAbstract& key )
+void SotQr::
+removeDependancy( const TaskAbstract& key )
 {
   controlSOUT.removeDependancy( key.taskSOUT );
   controlSOUT.removeDependancy( key.jacobianSOUT );
@@ -137,10 +137,10 @@ removeDependancy( const sotTaskAbstract& key )
   controlSOUT.setReady();
 }
 
-void sotSOTQr::
-up( const sotTaskAbstract& key )
+void SotQr::
+up( const TaskAbstract& key )
 {
-  bool find =false; std::list<sotTaskAbstract*>::iterator it;
+  bool find =false; std::list<TaskAbstract*>::iterator it;
   for ( it=stack.begin();stack.end()!=it;++it )
     {
       if( *it == &key ) { find=true; break; }
@@ -148,16 +148,16 @@ up( const sotTaskAbstract& key )
   if( stack.begin()==it ) { return; }
   if(! find ){ return; }
 
-  std::list<sotTaskAbstract*>::iterator pos=it; pos--;
-  sotTaskAbstract * task = *it;
+  std::list<TaskAbstract*>::iterator pos=it; pos--;
+  TaskAbstract * task = *it;
   stack.erase( it );
   stack.insert( pos,task );
   controlSOUT.setReady();
 }
-void sotSOTQr::
-down( const sotTaskAbstract& key )
+void SotQr::
+down( const TaskAbstract& key )
 {
-  bool find =false; std::list<sotTaskAbstract*>::iterator it;
+  bool find =false; std::list<TaskAbstract*>::iterator it;
   for ( it=stack.begin();stack.end()!=it;++it )
     {
       if( *it == &key ) { find=true; break; }
@@ -165,8 +165,8 @@ down( const sotTaskAbstract& key )
   if( stack.end()==it ) { return; }
   if(! find ){ return; }
 
-  std::list<sotTaskAbstract*>::iterator pos=it; pos++;
-  sotTaskAbstract* task=*it;
+  std::list<TaskAbstract*>::iterator pos=it; pos++;
+  TaskAbstract* task=*it;
   stack.erase( it );
   if( stack.end()==pos ){ stack.push_back(task); }
   else
@@ -177,10 +177,10 @@ down( const sotTaskAbstract& key )
   controlSOUT.setReady();
 }
 
-void sotSOTQr::
+void SotQr::
 clear( void )
 {
-  for (  std::list<sotTaskAbstract*>::iterator it=stack.begin();stack.end()!=it;++it )
+  for (  std::list<TaskAbstract*>::iterator it=stack.begin();stack.end()!=it;++it )
     {
       removeDependancy( **it );
     }
@@ -192,14 +192,14 @@ clear( void )
 /* --- CONSTRAINTS ----------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-void sotSOTQr::
+void SotQr::
 addConstraint( Constraint& constraint )
 {
   constraintList.push_back( &constraint );
   constraintSOUT.addDependancy( constraint.jacobianSOUT );
 }
 
-void sotSOTQr::
+void SotQr::
 removeConstraint( const Constraint& key )
 {
   bool find =false; ConstraintListType::iterator it;
@@ -213,7 +213,7 @@ removeConstraint( const Constraint& key )
 
   constraintSOUT.removeDependancy( key.jacobianSOUT );
 }
-void sotSOTQr::
+void SotQr::
 clearConstraint( void )
 {
   for (  ConstraintListType::iterator it=constraintList.begin();
@@ -224,7 +224,7 @@ clearConstraint( void )
   constraintList.clear();
 }
 
-void sotSOTQr::
+void SotQr::
 defineFreeFloatingJoints( const unsigned int& first,const unsigned int& last )
 {
   ffJointIdFirst = first ;
@@ -657,7 +657,7 @@ unsigned int rankDetermination( const bubMatrix& A,
 #   define sotPRINTCOUNTER(nbc1)
 #endif // #ifdef  WITH_CHRONO
 
-ml::Vector& sotSOTQr::
+ml::Vector& SotQr::
 computeControlLaw( ml::Vector& control,const int& iterTime )
 {
   sotDEBUGIN(15);
@@ -679,18 +679,18 @@ computeControlLaw( ml::Vector& control,const int& iterTime )
   sotDEBUGF(5, " --- Time %d -------------------", iterTime );
   /* First stage. */
   {
-    sotTaskAbstract & task = **(stack.begin());
+    TaskAbstract & task = **(stack.begin());
     const ml::Matrix &Jac = task.jacobianSOUT(iterTime);
-    const ml::Vector err = sotSOT::taskVectorToMlVector(task.taskSOUT(iterTime));
+    const ml::Vector err = Sot::taskVectorToMlVector(task.taskSOUT(iterTime));
     const unsigned int mJ = Jac.nbRows();
     /***/sotCOUNTER(0,1); // Direct Dynamic
 
     /* --- INIT MEMORY --- */
-    sotMemoryTaskSOT * mem = dynamic_cast<sotMemoryTaskSOT *>( task.memoryInternal );
+    MemoryTaskSOT * mem = dynamic_cast<MemoryTaskSOT *>( task.memoryInternal );
     if( NULL==mem )
       {
         if( NULL!=task.memoryInternal ) delete task.memoryInternal;
-        mem = new sotMemoryTaskSOT( task.getName()+"_memSOT",nJ,mJ );
+        mem = new MemoryTaskSOT( task.getName()+"_memSOT",nJ,mJ );
         task.memoryInternal = mem;
       }
     /***/sotCOUNTER(1,2); // Direct Dynamic
@@ -700,7 +700,7 @@ computeControlLaw( ml::Vector& control,const int& iterTime )
     JK.resize( mJ,nJ );
     mem->Jff.resize( mJ,Jac.nbCols()-nJ );
     mem->Jact.resize( mJ,nJ );
-    sotSOT::computeJacobianConstrained( task,K );
+    Sot::computeJacobianConstrained( task,K );
     /***/sotCOUNTER(2,3); // compute JK
 
     const bubMatrix & J1 = JK.accessToMotherLib();
@@ -770,18 +770,18 @@ computeControlLaw( ml::Vector& control,const int& iterTime )
     {
       sotDEBUG(45) << " * --- Stage " << stage << " ----------------------- *" << std::endl;
 
-      sotTaskAbstract & task = **iter;
+      TaskAbstract & task = **iter;
       const ml::Matrix &Jac = task.jacobianSOUT(iterTime);
-      const ml::Vector err = sotSOT::taskVectorToMlVector(task.taskSOUT(iterTime));
+      const ml::Vector err = Sot::taskVectorToMlVector(task.taskSOUT(iterTime));
       const unsigned int mJ = Jac.nbRows();
       /***/sotCOUNTER(0,1); // Direct Dynamic
 
       /* --- INIT MEMORY --- */
-      sotMemoryTaskSOT * mem = dynamic_cast<sotMemoryTaskSOT *>( task.memoryInternal );
+      MemoryTaskSOT * mem = dynamic_cast<MemoryTaskSOT *>( task.memoryInternal );
       if( NULL==mem )
         {
           if( NULL!=task.memoryInternal ) delete task.memoryInternal;
-          mem = new sotMemoryTaskSOT( task.getName()+"_memSOT",nJ,mJ );
+          mem = new MemoryTaskSOT( task.getName()+"_memSOT",nJ,mJ );
           task.memoryInternal = mem;
         }
       ml::Matrix &JK = mem->JK;
@@ -790,7 +790,7 @@ computeControlLaw( ml::Vector& control,const int& iterTime )
       JK.resize( mJ,nJ );
       mem->Jff.resize( mJ,Jac.nbCols()-nJ );
       mem->Jact.resize( mJ,nJ );
-      sotSOT::computeJacobianConstrained( task,K );
+      Sot::computeJacobianConstrained( task,K );
       /***/sotCOUNTER(2,3); // compute JK
 
       const bubMatrix & J2 = JK.accessToMotherLib();
@@ -879,8 +879,8 @@ computeControlLaw( ml::Vector& control,const int& iterTime )
 #ifdef VP_DEBUG
   for( StackType::iterator iter = stack.begin(); iter!=stack.end();++iter )
     {
-      sotTaskAbstract & task = **iter;
-      sotMemoryTaskSOT * mem = dynamic_cast<sotMemoryTaskSOT *>( task.memoryInternal );
+      TaskAbstract & task = **iter;
+      MemoryTaskSOT * mem = dynamic_cast<MemoryTaskSOT *>( task.memoryInternal );
       const ml::Matrix &Jac = mem->JK;
       const ml::Vector &err = task.taskSOUT.accessCopy();
 
@@ -897,7 +897,7 @@ computeControlLaw( ml::Vector& control,const int& iterTime )
 
 
 
-ml::Matrix& sotSOTQr::
+ml::Matrix& SotQr::
 computeConstraintProjector( ml::Matrix& ProjK, const int& time )
 {
   sotDEBUGIN(15);
@@ -913,7 +913,7 @@ computeConstraintProjector( ml::Matrix& ProjK, const int& time )
     { Jptr = &(*constraintList.begin())->jacobianSOUT(time); }
   else
     {
-      SOT_THROW sotExceptionTask( sotExceptionTask::EMPTY_LIST,
+      SOT_THROW ExceptionTask( ExceptionTask::EMPTY_LIST,
 				  "Not implemented yet." );
     }
 
@@ -954,13 +954,13 @@ computeConstraintProjector( ml::Matrix& ProjK, const int& time )
 /* --------------------------------------------------------------------- */
 /* --- DISPLAY --------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
-void sotSOTQr::
+void SotQr::
 display( std::ostream& os ) const
 {
 
   os << "+-----------------"<<std::endl<<"+   SOT     "
      << std::endl<< "+-----------------"<<std::endl;
-  for ( std::list<sotTaskAbstract*>::const_iterator it=this->stack.begin();
+  for ( std::list<TaskAbstract*>::const_iterator it=this->stack.begin();
 	this->stack.end()!=it;++it )
     {
       os << "| " << (*it)->getName() <<std::endl;
@@ -979,7 +979,7 @@ display( std::ostream& os ) const
 }
 
 std::ostream&
-operator<< ( std::ostream& os,const sotSOTQr& sot )
+operator<< ( std::ostream& os,const SotQr& sot )
 {
   sot.display(os);
   return os;
@@ -989,7 +989,7 @@ operator<< ( std::ostream& os,const sotSOTQr& sot )
 /* --- COMMAND --------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-void sotSOTQr::
+void SotQr::
 commandLine( const std::string& cmdLine,std::istringstream& cmdArgs,
 	     std::ostream& os )
 {
@@ -1021,7 +1021,7 @@ commandLine( const std::string& cmdLine,std::istringstream& cmdArgs,
   else if( cmdLine == "push")
     {
       std::string tname; cmdArgs >> tname;
-      sotTaskAbstract & task = sotPool.getTask( tname );
+      TaskAbstract & task = sotPool.getTask( tname );
       push(task);
     }
   else if( cmdLine == "gradient")
@@ -1034,7 +1034,7 @@ commandLine( const std::string& cmdLine,std::istringstream& cmdArgs,
 	    { taskGradient = 0; }
 	  else
 	    {
-	      sotTaskAbstract & task = sotPool.getTask( tname );
+	      TaskAbstract & task = sotPool.getTask( tname );
 	      taskGradient = &task;
 	    }
 	}
@@ -1049,24 +1049,24 @@ commandLine( const std::string& cmdLine,std::istringstream& cmdArgs,
   else if( cmdLine == "up")
     {
       std::string tname; cmdArgs >> tname;
-      sotTaskAbstract & task = sotPool.getTask( tname );
+      TaskAbstract & task = sotPool.getTask( tname );
       up(task);
     }
   else if( cmdLine == "down")
     {
       std::string tname; cmdArgs >> tname;
-      sotTaskAbstract & task = sotPool.getTask( tname );
+      TaskAbstract & task = sotPool.getTask( tname );
       down(task);
     }
   else if( cmdLine == "rm")
     {
       std::string tname; cmdArgs >> tname;
-      sotTaskAbstract & task = sotPool.getTask( tname );
+      TaskAbstract & task = sotPool.getTask( tname );
       remove(task);
     }
   else if( cmdLine == "pop")
     {
-      sotTaskAbstract& task = pop();
+      TaskAbstract& task = pop();
       os << "Remove : "<< task << std::endl;
     }
 
@@ -1117,19 +1117,19 @@ commandLine( const std::string& cmdLine,std::istringstream& cmdArgs,
   sotDEBUGOUT(15);
 }
 
-std::ostream& sotSOTQr::
+std::ostream& SotQr::
 writeGraph( std::ostream& os ) const
 {
-  std::list<sotTaskAbstract *>::const_iterator iter;
+  std::list<TaskAbstract *>::const_iterator iter;
   for(  iter = stack.begin(); iter!=stack.end();++iter )
     {
-      const sotTaskAbstract & task = **iter;
-      std::list<sotTaskAbstract *>::const_iterator nextiter =iter;
+      const TaskAbstract & task = **iter;
+      std::list<TaskAbstract *>::const_iterator nextiter =iter;
       nextiter++;
 
       if (nextiter!=stack.end())
 	{
-	  sotTaskAbstract & nexttask = **nextiter;
+	  TaskAbstract & nexttask = **nextiter;
 	  os << "\t\t\t" << task.getName() << " -> " << nexttask.getName() << " [color=red]" << endl;
 	}
 
@@ -1140,7 +1140,7 @@ writeGraph( std::ostream& os ) const
   os << "\t\t\t\tcolor=lightsteelblue1; label=\"" << getName() <<"\"; style=filled;" << std::endl;
   for(  iter = stack.begin(); iter!=stack.end();++iter )
     {
-      const sotTaskAbstract & task = **iter;
+      const TaskAbstract & task = **iter;
       os << "\t\t\t\t" << task.getName()
 		<<" [ label = \"" << task.getName() << "\" ," << std::endl
 		<<"\t\t\t\t   fontcolor = black, color = black, fillcolor = magenta, style=filled, shape=box ]" << std::endl;
diff --git a/src/sot/sot.cpp b/src/sot/sot.cpp
index 9d0f15af..2884a086 100644
--- a/src/sot/sot.cpp
+++ b/src/sot/sot.cpp
@@ -49,17 +49,17 @@ using namespace sot;
 /* --------------------------------------------------------------------- */
 
 
-SOT_FACTORY_ENTITY_PLUGIN(sotSOT,"SOT");
+SOT_FACTORY_ENTITY_PLUGIN(Sot,"SOT");
 
 
-const double sotSOT::INVERSION_THRESHOLD_DEFAULT = 1e-4;
-const unsigned int sotSOT::NB_JOINTS_DEFAULT = 46;
+const double Sot::INVERSION_THRESHOLD_DEFAULT = 1e-4;
+const unsigned int Sot::NB_JOINTS_DEFAULT = 46;
 
 /* --------------------------------------------------------------------- */
 /* --- CONSTRUCTION ---------------------------------------------------- */
 /* --------------------------------------------------------------------- */
-sotSOT::
-sotSOT( const std::string& name )
+Sot::
+Sot( const std::string& name )
   :Entity(name)
   ,stack()
   ,constraintList()
@@ -71,10 +71,10 @@ sotSOT( const std::string& name )
   ,recomputeEachTime(true)
   ,q0SIN( NULL,"sotSOT("+name+")::input(double)::q0" )
    ,inversionThresholdSIN( NULL,"sotSOT("+name+")::input(double)::damping" )
-   ,constraintSOUT( boost::bind(&sotSOT::computeConstraintProjector,this,_1,_2),
+   ,constraintSOUT( boost::bind(&Sot::computeConstraintProjector,this,_1,_2),
 		   sotNOSIGNAL,
 		    "sotSOT("+name+")::output(matrix)::constraint" )
-  ,controlSOUT( boost::bind(&sotSOT::computeControlLaw,this,_1,_2),
+  ,controlSOUT( boost::bind(&Sot::computeControlLaw,this,_1,_2),
 		constraintSOUT<<inversionThresholdSIN<<q0SIN,
 		"sotSOT("+name+")::output(vector)::control" )
 {
@@ -86,8 +86,8 @@ sotSOT( const std::string& name )
 /* --------------------------------------------------------------------- */
 /* --- STACK MANIPULATION --- */
 /* --------------------------------------------------------------------- */
-void sotSOT::
-push( sotTaskAbstract& task )
+void Sot::
+push( TaskAbstract& task )
 {
   stack.push_back( &task );
   controlSOUT.addDependancy( task.taskSOUT );
@@ -95,10 +95,10 @@ push( sotTaskAbstract& task )
   //controlSOUT.addDependancy( task.featureActivationSOUT );
   controlSOUT.setReady();
 }
-sotTaskAbstract& sotSOT::
+TaskAbstract& Sot::
 pop( void )
 {
-  sotTaskAbstract* res = stack.back();
+  TaskAbstract* res = stack.back();
   stack.pop_back();
   controlSOUT.removeDependancy( res->taskSOUT );
   controlSOUT.removeDependancy( res->jacobianSOUT );
@@ -106,20 +106,20 @@ pop( void )
   controlSOUT.setReady();
   return *res;
 }
-bool sotSOT::
-exist( const sotTaskAbstract& key )
+bool Sot::
+exist( const TaskAbstract& key )
 {
-  std::list<sotTaskAbstract*>::iterator it;
+  std::list<TaskAbstract*>::iterator it;
   for ( it=stack.begin();stack.end()!=it;++it )
     {
       if( *it == &key ) { return true; }
     }
   return false;
 }
-void sotSOT::
-remove( const sotTaskAbstract& key )
+void Sot::
+remove( const TaskAbstract& key )
 {
-  bool find =false; std::list<sotTaskAbstract*>::iterator it;
+  bool find =false; std::list<TaskAbstract*>::iterator it;
   for ( it=stack.begin();stack.end()!=it;++it )
     {
       if( *it == &key ) { find=true; break; }
@@ -130,8 +130,8 @@ remove( const sotTaskAbstract& key )
   removeDependancy( key );
 }
 
-void sotSOT::
-removeDependancy( const sotTaskAbstract& key )
+void Sot::
+removeDependancy( const TaskAbstract& key )
 {
   controlSOUT.removeDependancy( key.taskSOUT );
   controlSOUT.removeDependancy( key.jacobianSOUT );
@@ -139,10 +139,10 @@ removeDependancy( const sotTaskAbstract& key )
   controlSOUT.setReady();
 }
 
-void sotSOT::
-up( const sotTaskAbstract& key )
+void Sot::
+up( const TaskAbstract& key )
 {
-  bool find =false; std::list<sotTaskAbstract*>::iterator it;
+  bool find =false; std::list<TaskAbstract*>::iterator it;
   for ( it=stack.begin();stack.end()!=it;++it )
     {
       if( *it == &key ) { find=true; break; }
@@ -150,16 +150,16 @@ up( const sotTaskAbstract& key )
   if( stack.begin()==it ) { return; }
   if(! find ){ return; }
 
-  std::list<sotTaskAbstract*>::iterator pos=it; pos--;
-  sotTaskAbstract * task = *it;
+  std::list<TaskAbstract*>::iterator pos=it; pos--;
+  TaskAbstract * task = *it;
   stack.erase( it );
   stack.insert( pos,task );
   controlSOUT.setReady();
 }
-void sotSOT::
-down( const sotTaskAbstract& key )
+void Sot::
+down( const TaskAbstract& key )
 {
-  bool find =false; std::list<sotTaskAbstract*>::iterator it;
+  bool find =false; std::list<TaskAbstract*>::iterator it;
   for ( it=stack.begin();stack.end()!=it;++it )
     {
       if( *it == &key ) { find=true; break; }
@@ -167,8 +167,8 @@ down( const sotTaskAbstract& key )
   if( stack.end()==it ) { return; }
   if(! find ){ return; }
 
-  std::list<sotTaskAbstract*>::iterator pos=it; pos++;
-  sotTaskAbstract* task=*it;
+  std::list<TaskAbstract*>::iterator pos=it; pos++;
+  TaskAbstract* task=*it;
   stack.erase( it );
   if( stack.end()==pos ){ stack.push_back(task); }
   else
@@ -179,10 +179,10 @@ down( const sotTaskAbstract& key )
   controlSOUT.setReady();
 }
 
-void sotSOT::
+void Sot::
 clear( void )
 {
-  for (  std::list<sotTaskAbstract*>::iterator it=stack.begin();stack.end()!=it;++it )
+  for (  std::list<TaskAbstract*>::iterator it=stack.begin();stack.end()!=it;++it )
     {
       removeDependancy( **it );
     }
@@ -194,14 +194,14 @@ clear( void )
 /* --- CONSTRAINTS ----------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-void sotSOT::
+void Sot::
 addConstraint( Constraint& constraint )
 {
   constraintList.push_back( &constraint );
   constraintSOUT.addDependancy( constraint.jacobianSOUT );
 }
 
-void sotSOT::
+void Sot::
 removeConstraint( const Constraint& key )
 {
   bool find =false; ConstraintListType::iterator it;
@@ -215,7 +215,7 @@ removeConstraint( const Constraint& key )
 
   constraintSOUT.removeDependancy( key.jacobianSOUT );
 }
-void sotSOT::
+void Sot::
 clearConstraint( void )
 {
   for (  ConstraintListType::iterator it=constraintList.begin();
@@ -226,7 +226,7 @@ clearConstraint( void )
   constraintList.clear();
 }
 
-void sotSOT::
+void Sot::
 defineFreeFloatingJoints( const unsigned int& first,const unsigned int& last )
 {
   ffJointIdFirst = first ;
@@ -234,7 +234,7 @@ defineFreeFloatingJoints( const unsigned int& first,const unsigned int& last )
   else ffJointIdLast=ffJointIdFirst+6;
 }
 
-void sotSOT::
+void Sot::
 defineNbDof( const unsigned int& nbDof )
 {
   nbJoints = nbDof;
@@ -246,7 +246,7 @@ defineNbDof( const unsigned int& nbDof )
 /* --------------------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-ml::Matrix & sotSOT::
+ml::Matrix & Sot::
 computeJacobianConstrained( const ml::Matrix& Jac,
                             const ml::Matrix& K,
                             ml::Matrix& JK,
@@ -270,12 +270,12 @@ computeJacobianConstrained( const ml::Matrix& Jac,
 }
 
 
-ml::Matrix & sotSOT::
-computeJacobianConstrained( const sotTaskAbstract& task,
+ml::Matrix & Sot::
+computeJacobianConstrained( const TaskAbstract& task,
                             const ml::Matrix& K )
 {
   const ml::Matrix &Jac = task.jacobianSOUT;
-  sotMemoryTaskSOT * mem = dynamic_cast<sotMemoryTaskSOT *>( task.memoryInternal );
+  MemoryTaskSOT * mem = dynamic_cast<MemoryTaskSOT *>( task.memoryInternal );
   if( NULL==mem ) throw; // TODO
   ml::Matrix &Jff = mem->Jff;
   ml::Matrix &Jact = mem->Jact;
@@ -283,13 +283,13 @@ computeJacobianConstrained( const sotTaskAbstract& task,
   return computeJacobianConstrained(Jac,K,JK,Jff,Jact);
 }
 
-static void computeJacobianActivated( sotTask* taskSpec,
+static void computeJacobianActivated( Task* taskSpec,
 				      ml::Matrix& Jt,
 				      const int& iterTime )
 {
   if( NULL!=taskSpec )
     {
-      const sotFlags& controlSelec = taskSpec->controlSelectionSIN( iterTime );
+      const Flags& controlSelec = taskSpec->controlSelectionSIN( iterTime );
       sotDEBUG(25) << "Control selection = " << controlSelec <<endl;
       if( controlSelec )
 	{
@@ -365,7 +365,7 @@ static void computeJacobianActivated( sotTask* taskSpec,
 #   define sotPRINTCOUNTER(nbc1)
 #endif // #ifdef  WITH_CHRONO
 
-ml::Vector sotSOT::
+ml::Vector Sot::
 taskVectorToMlVector( const sotVectorMultiBound& taskVector )
 {
   ml::Vector res(taskVector.size()); unsigned int i=0;
@@ -377,7 +377,7 @@ taskVectorToMlVector( const sotVectorMultiBound& taskVector )
   return res;
 }
 
-ml::Vector& sotSOT::
+ml::Vector& Sot::
 computeControlLaw( ml::Vector& control,const int& iterTime )
 {
   sotDEBUGIN(15);
@@ -410,7 +410,7 @@ computeControlLaw( ml::Vector& control,const int& iterTime )
   for( StackType::iterator iter = stack.begin(); iter!=stack.end();++iter )
     {
       sotDEBUGF(5,"Rank %d.",iterTask);
-      sotTaskAbstract & task = **iter;
+      TaskAbstract & task = **iter;
       sotDEBUG(15) << "Task: e_" << task.getName() << std::endl;
       const ml::Matrix &Jac = task.jacobianSOUT(iterTime);
       const ml::Vector err = taskVectorToMlVector(task.taskSOUT(iterTime));
@@ -420,11 +420,11 @@ computeControlLaw( ml::Vector& control,const int& iterTime )
       const unsigned int nJ = Jac.nbRows();
 
       /* Init memory. */
-      sotMemoryTaskSOT * mem = dynamic_cast<sotMemoryTaskSOT *>( task.memoryInternal );
+      MemoryTaskSOT * mem = dynamic_cast<MemoryTaskSOT *>( task.memoryInternal );
       if( NULL==mem )
         {
           if( NULL!=task.memoryInternal ) delete task.memoryInternal;
-          mem = new sotMemoryTaskSOT( task.getName()+"_memSOT",nJ,mJ );
+          mem = new MemoryTaskSOT( task.getName()+"_memSOT",nJ,mJ );
           task.memoryInternal = mem;
         }
 
@@ -477,7 +477,7 @@ sotDEBUG(1) << std::endl;
 	/***/sotCOUNTER(3,4); // compute Jt
 	
 	/* --- COMPUTE S --- */
-	computeJacobianActivated( dynamic_cast<sotTask*>( &task ),Jt,iterTime );
+	computeJacobianActivated( dynamic_cast<Task*>( &task ),Jt,iterTime );
 	/***/sotCOUNTER(4,5); // Jt*S
 	
 	/* --- PINV --- */
@@ -627,13 +627,13 @@ sotDEBUG(1) << std::endl;
 
       const unsigned int nJ = Jac.nbRows();
 
-      sotMemoryTaskSOT * mem
-        = dynamic_cast<sotMemoryTaskSOT *>( taskGradient->memoryInternal );
+      MemoryTaskSOT * mem
+        = dynamic_cast<MemoryTaskSOT *>( taskGradient->memoryInternal );
       if( NULL==mem )
         {
           if( NULL!=taskGradient->memoryInternal )
             { delete taskGradient->memoryInternal; }
-          mem = new sotMemoryTaskSOT( taskGradient->getName()+"_memSOT",nJ,mJ );
+          mem = new MemoryTaskSOT( taskGradient->getName()+"_memSOT",nJ,mJ );
           taskGradient->memoryInternal = mem;
         }
 
@@ -689,7 +689,7 @@ sotDEBUG(1) << std::endl;
 
 
 
-ml::Matrix& sotSOT::
+ml::Matrix& Sot::
 computeConstraintProjector( ml::Matrix& ProjK, const int& time )
 {
   sotDEBUGIN(15);
@@ -705,7 +705,7 @@ computeConstraintProjector( ml::Matrix& ProjK, const int& time )
     { Jptr = &(*constraintList.begin())->jacobianSOUT(time); }
   else
     {
-      SOT_THROW sotExceptionTask( sotExceptionTask::EMPTY_LIST,
+      SOT_THROW ExceptionTask( ExceptionTask::EMPTY_LIST,
 				  "Not implemented yet." );
     }
 
@@ -746,13 +746,13 @@ computeConstraintProjector( ml::Matrix& ProjK, const int& time )
 /* --------------------------------------------------------------------- */
 /* --- DISPLAY --------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
-void sotSOT::
+void Sot::
 display( std::ostream& os ) const
 {
 
   os << "+-----------------"<<std::endl<<"+   SOT     "
      << std::endl<< "+-----------------"<<std::endl;
-  for ( std::list<sotTaskAbstract*>::const_iterator it=this->stack.begin();
+  for ( std::list<TaskAbstract*>::const_iterator it=this->stack.begin();
 	this->stack.end()!=it;++it )
     {
       os << "| " << (*it)->getName() <<std::endl;
@@ -771,7 +771,7 @@ display( std::ostream& os ) const
 }
 
 std::ostream&
-operator<< ( std::ostream& os,const sotSOT& sot )
+operator<< ( std::ostream& os,const Sot& sot )
 {
   sot.display(os);
   return os;
@@ -781,7 +781,7 @@ operator<< ( std::ostream& os,const sotSOT& sot )
 /* --- COMMAND --------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-void sotSOT::
+void Sot::
 commandLine( const std::string& cmdLine,std::istringstream& cmdArgs,
 	     std::ostream& os )
 {
@@ -820,7 +820,7 @@ commandLine( const std::string& cmdLine,std::istringstream& cmdArgs,
   else if( cmdLine == "push")
     {
       std::string tname; cmdArgs >> tname;
-      sotTaskAbstract & task = sotPool.getTask( tname );
+      TaskAbstract & task = sotPool.getTask( tname );
       push(task);
     }
   else if( cmdLine == "gradient")
@@ -833,7 +833,7 @@ commandLine( const std::string& cmdLine,std::istringstream& cmdArgs,
 	    { taskGradient = 0; }
 	  else
 	    {
-	      sotTaskAbstract & task = sotPool.getTask( tname );
+	      TaskAbstract & task = sotPool.getTask( tname );
 	      taskGradient = &task;
 	    }
 	}
@@ -848,24 +848,24 @@ commandLine( const std::string& cmdLine,std::istringstream& cmdArgs,
   else if( cmdLine == "up")
     {
       std::string tname; cmdArgs >> tname;
-      sotTaskAbstract & task = sotPool.getTask( tname );
+      TaskAbstract & task = sotPool.getTask( tname );
       up(task);
     }
   else if( cmdLine == "down")
     {
       std::string tname; cmdArgs >> tname;
-      sotTaskAbstract & task = sotPool.getTask( tname );
+      TaskAbstract & task = sotPool.getTask( tname );
       down(task);
     }
   else if( cmdLine == "rm")
     {
       std::string tname; cmdArgs >> tname;
-      sotTaskAbstract & task = sotPool.getTask( tname );
+      TaskAbstract & task = sotPool.getTask( tname );
       remove(task);
     }
   else if( cmdLine == "pop")
     {
-      sotTaskAbstract& task = pop();
+      TaskAbstract& task = pop();
       os << "Remove : "<< task << std::endl;
     }
 
@@ -916,19 +916,19 @@ commandLine( const std::string& cmdLine,std::istringstream& cmdArgs,
   sotDEBUGOUT(15);
 }
 
-std::ostream& sotSOT::
+std::ostream& Sot::
 writeGraph( std::ostream& os ) const
 {
-  std::list<sotTaskAbstract *>::const_iterator iter;
+  std::list<TaskAbstract *>::const_iterator iter;
   for(  iter = stack.begin(); iter!=stack.end();++iter )
     {
-      const sotTaskAbstract & task = **iter;
-      std::list<sotTaskAbstract *>::const_iterator nextiter =iter;
+      const TaskAbstract & task = **iter;
+      std::list<TaskAbstract *>::const_iterator nextiter =iter;
       nextiter++;
 
       if (nextiter!=stack.end())
 	{
-	  sotTaskAbstract & nexttask = **nextiter;
+	  TaskAbstract & nexttask = **nextiter;
 	  os << "\t\t\t" << task.getName() << " -> " << nexttask.getName() << " [color=red]" << endl;
 	}
 
@@ -939,7 +939,7 @@ writeGraph( std::ostream& os ) const
   os << "\t\t\t\tcolor=lightsteelblue1; label=\"" << getName() <<"\"; style=filled;" << std::endl;
   for(  iter = stack.begin(); iter!=stack.end();++iter )
     {
-      const sotTaskAbstract & task = **iter;
+      const TaskAbstract & task = **iter;
       os << "\t\t\t\t" << task.getName()
 		<<" [ label = \"" << task.getName() << "\" ," << std::endl
 		<<"\t\t\t\t   fontcolor = black, color = black, fillcolor = magenta, style=filled, shape=box ]" << std::endl;
diff --git a/src/sot/weighted-sot.cpp b/src/sot/weighted-sot.cpp
index 02a3de6a..21bc5f7b 100644
--- a/src/sot/weighted-sot.cpp
+++ b/src/sot/weighted-sot.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotWeightedSOT.cpp
+ * File:      WeightedSot.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -38,21 +38,21 @@ using namespace sot;
 
 
 #include <sot-core/factory.h>
-SOT_FACTORY_ENTITY_PLUGIN(sotWeightedSOT,"WSOT");
+SOT_FACTORY_ENTITY_PLUGIN(WeightedSot,"WSOT");
 
 /* --------------------------------------------------------------------- */
 /* --- CONSTRUCTION ---------------------------------------------------- */
 /* --------------------------------------------------------------------- */
-sotWeightedSOT::
-sotWeightedSOT( const std::string& name )
-  :sotSOT(name)
+WeightedSot::
+WeightedSot( const std::string& name )
+  :Sot(name)
    ,weightSIN( NULL,"sotWeightedSOT("+name+")::input(matrix)::weight" )
-   ,constrainedWeightSOUT( boost::bind(&sotWeightedSOT::computeConstrainedWeight,
+   ,constrainedWeightSOUT( boost::bind(&WeightedSot::computeConstrainedWeight,
 				       this,_1,_2),
 			   weightSIN<<constraintSOUT,
 			   "sotWeightedSOT("+name+")::input(matrix)::KweightOUT" )
    ,constrainedWeightSIN( NULL,"sotWeightedSOT("+name+")::input(matrix)::Kweight" )
-   ,squareRootInvWeightSOUT( boost::bind(&sotWeightedSOT::computeSquareRootInvWeight,this,_1,_2),
+   ,squareRootInvWeightSOUT( boost::bind(&WeightedSot::computeSquareRootInvWeight,this,_1,_2),
 			     weightSIN<<constrainedWeightSIN,
 			     "sotWeightedSOT("+name+")::output(matrix)::sqweight" )
    ,squareRootInvWeightSIN( &squareRootInvWeightSOUT,
@@ -62,7 +62,7 @@ sotWeightedSOT( const std::string& name )
   signalRegistration( weightSIN<<constrainedWeightSIN<<squareRootInvWeightSOUT
 		      << squareRootInvWeightSIN );
 
-  controlSOUT.setFunction( boost::bind(&sotWeightedSOT::computeWeightedControlLaw,
+  controlSOUT.setFunction( boost::bind(&WeightedSot::computeWeightedControlLaw,
 				       this,_1,_2) );
   controlSOUT.addDependancy( squareRootInvWeightSIN );
 
@@ -77,7 +77,7 @@ sotWeightedSOT( const std::string& name )
 
 #include <MatrixAbstractLayer/boostspecific.h>
 
-ml::Matrix& sotWeightedSOT::
+ml::Matrix& WeightedSot::
 computeSquareRootInvWeight( ml::Matrix& S5i,const int& time )
 {
   sotDEBUGIN(15);
@@ -85,7 +85,7 @@ computeSquareRootInvWeight( ml::Matrix& S5i,const int& time )
   const ml::Matrix& A = constrainedWeightSIN( time );
   if( A.nbCols()!= A.nbRows() )
     {
-      SOT_THROW sotExceptionTask( sotExceptionTask::MATRIX_SIZE,
+      SOT_THROW ExceptionTask( ExceptionTask::MATRIX_SIZE,
 				  "Weight matrix should be square.","" );
     }
   sotDEBUG(25) << "KA = " << A << endl;
@@ -151,7 +151,7 @@ computeSquareRootInvWeight( ml::Matrix& S5i,const int& time )
 /* --- CONTROL --------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-ml::Matrix& sotWeightedSOT::
+ml::Matrix& WeightedSot::
 computeConstrainedWeight( ml::Matrix& KAK,const int& iterTime )
 {
   sotDEBUGIN(15);
@@ -235,7 +235,7 @@ computeConstrainedWeight( ml::Matrix& KAK,const int& iterTime )
 
 
 
-ml::Vector& sotWeightedSOT::
+ml::Vector& WeightedSot::
 computeWeightedControlLaw( ml::Vector& control,const int& iterTime )
 {
   sotDEBUGIN(15);
@@ -283,18 +283,18 @@ computeWeightedControlLaw( ml::Vector& control,const int& iterTime )
     {
       sotCOUNTER(0,0b); // Direct Dynamic
       sotDEBUGF(5,"Rank %d.",iterTask);
-      sotTaskAbstract & task = **iter;
+      TaskAbstract & task = **iter;
       const ml::Matrix &JacRO = task.jacobianSOUT(iterTime);
-      const ml::Vector err = sotSOT::taskVectorToMlVector(task.taskSOUT(iterTime));
+      const ml::Vector err = Sot::taskVectorToMlVector(task.taskSOUT(iterTime));
       const unsigned int nJ = JacRO.nbRows();
       sotCOUNTER(0b,1); // Direct Dynamic
 
       /* Init memory. */
-      sotMemoryTaskSOT * mem = dynamic_cast<sotMemoryTaskSOT *>( task.memoryInternal );
+      MemoryTaskSOT * mem = dynamic_cast<MemoryTaskSOT *>( task.memoryInternal );
       if( NULL==mem )
         {
           if( NULL!=task.memoryInternal ) delete task.memoryInternal;
-          mem = new sotMemoryTaskSOT( task.getName()+"_memSOT",nJ,mJ );
+          mem = new MemoryTaskSOT( task.getName()+"_memSOT",nJ,mJ );
           task.memoryInternal = mem;
         }
 
@@ -336,10 +336,10 @@ computeWeightedControlLaw( ml::Vector& control,const int& iterTime )
 	
 	/* --- COMPUTE S --- */	
 	ml::Matrix Kact(mJ,mJ); Kact=S5i;
-	sotTask* taskSpec = dynamic_cast<sotTask*>( &task );
+	Task* taskSpec = dynamic_cast<Task*>( &task );
 	if( NULL!=taskSpec )
 	  {
-	    const sotFlags& controlSelec = taskSpec->controlSelectionSIN( iterTime );
+	    const Flags& controlSelec = taskSpec->controlSelectionSIN( iterTime );
 	    sotDEBUG(25) << "Control selection = " << controlSelec <<endl;
 	    if( controlSelec )
 	      {
diff --git a/src/task/constraint.cpp b/src/task/constraint.cpp
index 84381e9a..01c7fce8 100644
--- a/src/task/constraint.cpp
+++ b/src/task/constraint.cpp
@@ -40,7 +40,7 @@ SOT_FACTORY_TASK_PLUGIN(Constraint,"Constraint");
 
 Constraint::
 Constraint( const std::string& n )
-  :sotTaskAbstract(n)
+  :TaskAbstract(n)
 {
   jacobianSOUT.setFunction( boost::bind(&Constraint::computeJacobian,this,_1,_2) );
   
@@ -83,7 +83,7 @@ computeJacobian( ml::Matrix& J,int time )
 
   if( jacobianList.empty())
     { J.resize(0,0); }
-//    { throw( sotExceptionTask(sotExceptionTask::EMPTY_LIST,
+//    { throw( ExceptionTask(ExceptionTask::EMPTY_LIST,
 // 			      "Empty feature list") ) ; }
 
   try {
@@ -105,7 +105,7 @@ computeJacobian( ml::Matrix& J,int time )
 	
 	if( 0==nbc ) { nbc = partialJacobian.nbCols(); J.resize(nbc,dimJ); }
 	else if( partialJacobian.nbCols() != nbc )
-	  {SOT_THROW sotExceptionTask(sotExceptionTask::NON_ADEQUATE_FEATURES,
+	  {SOT_THROW ExceptionTask(ExceptionTask::NON_ADEQUATE_FEATURES,
 				      "Features from the list don't "
 				      "have compatible-size jacobians.");}
 	sotDEBUG(25) << "Jp =" <<endl<< partialJacobian<<endl;
@@ -152,7 +152,7 @@ commandLine( const std::string& cmdLine
       os << "Constraint: "<<endl
 	 << "  - add <obj.signal>"<<endl
 	 << "  - clear"<<endl;
-      //sotTaskAbstract
+      //TaskAbstract
       Entity::commandLine( cmdLine,cmdArgs,os );
     }
   else if( cmdLine=="add" )
@@ -163,12 +163,12 @@ commandLine( const std::string& cmdLine
       if(! sig ) 
 	{
     	  if ( sigA )
-			  SOT_THROW sotExceptionSignal( sotExceptionSignal::BAD_CAST,
+			  SOT_THROW ExceptionSignal( ExceptionSignal::BAD_CAST,
 							"Not a Matrix signal",
 							": while casting signal <%s> (signal type is %s).",
 							sigA->getName().c_str(), typeid(*sigA).name() );
     	  else
-    		  SOT_THROW sotExceptionSignal( sotExceptionSignal::NOT_INITIALIZED,
+    		  SOT_THROW ExceptionSignal( ExceptionSignal::NOT_INITIALIZED,
     				  "Could not get a reference to requested signal");
 	}
       addJacobian( *sig );
@@ -179,6 +179,6 @@ commandLine( const std::string& cmdLine
       jacobianSOUT.setReady();
     }
   else 
-    sotTaskAbstract::commandLine( cmdLine,cmdArgs,os );
+    TaskAbstract::commandLine( cmdLine,cmdArgs,os );
 
 }
diff --git a/src/task/gain-adaptative.cpp b/src/task/gain-adaptative.cpp
index 5f3bece0..b3849620 100644
--- a/src/task/gain-adaptative.cpp
+++ b/src/task/gain-adaptative.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotGainAdaptative.cpp
+ * File:      GainAdaptative.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -31,13 +31,13 @@
 
 using namespace sot;
 
-SOT_FACTORY_ENTITY_PLUGIN(sotGainAdaptative,"GainAdaptative");
+SOT_FACTORY_ENTITY_PLUGIN(GainAdaptative,"GainAdaptative");
 
-const double sotGainAdaptative::
+const double GainAdaptative::
 ZERO_DEFAULT = .1;
-const double sotGainAdaptative::
+const double GainAdaptative::
 INFTY_DEFAULT = .1;
-const double sotGainAdaptative::
+const double GainAdaptative::
 TAN_DEFAULT = 1;
 
 /* --------------------------------------------------------------------- */
@@ -51,13 +51,13 @@ Entity(name) \
 ,coeff_b(0) \
 ,coeff_c(0) \
 ,errorSIN(NULL,"sotGainAdaptative("+name+")::input(vector)::error") \
-,gainSOUT( boost::bind(&sotGainAdaptative::computeGain,this,_1,_2), \
+,gainSOUT( boost::bind(&GainAdaptative::computeGain,this,_1,_2), \
 	   errorSIN,"sotGainAdaptative("+name+")::output(double)::gain" )
 
 
 
-sotGainAdaptative::
-sotGainAdaptative( const std::string & name )
+GainAdaptative::
+GainAdaptative( const std::string & name )
   :__SOT_GAIN_ADAPTATIVE_INIT
 {
   sotDEBUG(15) << "New gain <"<<name<<">"<<std::endl;
@@ -66,16 +66,16 @@ sotGainAdaptative( const std::string & name )
 }
 
 
-sotGainAdaptative::
-sotGainAdaptative( const std::string & name,const double& lambda )
+GainAdaptative::
+GainAdaptative( const std::string & name,const double& lambda )
   :__SOT_GAIN_ADAPTATIVE_INIT
 {
   init(lambda);
   Entity::signalRegistration( gainSOUT );
 }
 
-sotGainAdaptative::
-sotGainAdaptative( const std::string & name,
+GainAdaptative::
+GainAdaptative( const std::string & name,
 		   const double& valueAt0,
 		   const double& valueAtInfty,
 		   const double& tanAt0 )
@@ -86,7 +86,7 @@ sotGainAdaptative( const std::string & name,
 }
 
 
-void sotGainAdaptative::
+void GainAdaptative::
 init( const double& valueAt0,
       const double& valueAtInfty,
       const double& tanAt0 )
@@ -99,7 +99,7 @@ init( const double& valueAt0,
   return;
 }
 
-void sotGainAdaptative::
+void GainAdaptative::
 forceConstant( void )
 {
   coeff_a = 0;
@@ -109,16 +109,16 @@ forceConstant( void )
 /* --------------------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-void sotGainAdaptative::
+void GainAdaptative::
 display( std::ostream& os ) const
 {
   os << "Gain Adaptative "<<getName();
-  try{ os <<" = "<<double(gainSOUT); } catch (sotExceptionSignal e) {}
+  try{ os <<" = "<<double(gainSOUT); } catch (ExceptionSignal e) {}
   os <<" ("<<coeff_a<<";"<<coeff_b<<";"<<coeff_c<<") ";
 }
 
 #include <sot-core/exception-task.h>
-void sotGainAdaptative::
+void GainAdaptative::
 commandLine( const std::string& cmdLine,
 	     std::istringstream& cmdArgs,
 	     std::ostream& os )
@@ -153,7 +153,7 @@ commandLine( const std::string& cmdLine,
 /* --------------------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
-double& sotGainAdaptative::
+double& GainAdaptative::
 computeGain( double&res, int t )
 {
   sotDEBUGIN(15);
diff --git a/src/task/gain-hyperbolic.cpp b/src/task/gain-hyperbolic.cpp
index 7db40dac..9203380a 100644
--- a/src/task/gain-hyperbolic.cpp
+++ b/src/task/gain-hyperbolic.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotGainHyperbolic.cpp
+ * File:      GainHyperbolic.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -31,13 +31,13 @@
 
 using namespace sot;
 
-SOT_FACTORY_ENTITY_PLUGIN(sotGainHyperbolic,"GainHyperbolic");
+SOT_FACTORY_ENTITY_PLUGIN(GainHyperbolic,"GainHyperbolic");
 
-const double sotGainHyperbolic::
+const double GainHyperbolic::
 ZERO_DEFAULT = .1;
-const double sotGainHyperbolic::
+const double GainHyperbolic::
 INFTY_DEFAULT = .1;
-const double sotGainHyperbolic::
+const double GainHyperbolic::
 TAN_DEFAULT = 1;
 
 /* --------------------------------------------------------------------- */
@@ -52,13 +52,13 @@ Entity(name) \
 ,coeff_c(0) \
 ,coeff_d(0) \
 ,errorSIN(NULL,"sotGainHyperbolic("+name+")::input(vector)::error") \
-,gainSOUT( boost::bind(&sotGainHyperbolic::computeGain,this,_1,_2), \
+,gainSOUT( boost::bind(&GainHyperbolic::computeGain,this,_1,_2), \
 	   errorSIN,"sotGainHyperbolic("+name+")::output(double)::gain" ) 
 
 
 
-sotGainHyperbolic::
-sotGainHyperbolic( const std::string & name )
+GainHyperbolic::
+GainHyperbolic( const std::string & name )
   :__SOT_GAIN_HYPERBOLIC_INIT
 {
   sotDEBUG(15) << "New gain <"<<name<<">"<<std::endl;
@@ -67,16 +67,16 @@ sotGainHyperbolic( const std::string & name )
 }
 
 
-sotGainHyperbolic::
-sotGainHyperbolic( const std::string & name,const double& lambda )
+GainHyperbolic::
+GainHyperbolic( const std::string & name,const double& lambda )
   :__SOT_GAIN_HYPERBOLIC_INIT
 {
   init(lambda);
   Entity::signalRegistration( gainSOUT );
 }
 
-sotGainHyperbolic::
-sotGainHyperbolic( const std::string & name,
+GainHyperbolic::
+GainHyperbolic( const std::string & name,
 		   const double& valueAt0, 
 		   const double& valueAtInfty,
 		   const double& tanAt0,
@@ -88,7 +88,7 @@ sotGainHyperbolic( const std::string & name,
 }
 
 
-void sotGainHyperbolic::
+void GainHyperbolic::
 init( const double& valueAt0, 
       const double& valueAtInfty,
       const double& tanAt0,
@@ -103,7 +103,7 @@ init( const double& valueAt0,
   return;
 }
 
-void sotGainHyperbolic::
+void GainHyperbolic::
 forceConstant( void )
 {
   coeff_a = 0;
@@ -113,17 +113,17 @@ forceConstant( void )
 /* --------------------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-void sotGainHyperbolic::
+void GainHyperbolic::
 display( std::ostream& os ) const
 {
   os << "Gain Hyperbolic "<<getName();
-  try{ os <<" = "<<double(gainSOUT); } catch (sotExceptionSignal e) {}
+  try{ os <<" = "<<double(gainSOUT); } catch (ExceptionSignal e) {}
   //os <<" ("<<coeff_a<<";"<<coeff_b<<";"<<coeff_c<<coeff_d<<") ";
   os <<" ("<<coeff_a<<".exp(-"<<coeff_b<<"(x-" << coeff_d << "))+" <<coeff_c;
 }
 
 #include <sot-core/exception-task.h>
-void sotGainHyperbolic::
+void GainHyperbolic::
 commandLine( const std::string& cmdLine,
 	     std::istringstream& cmdArgs,
 	     std::ostream& os )
@@ -156,7 +156,7 @@ commandLine( const std::string& cmdLine,
 /* --------------------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
-double& sotGainHyperbolic::
+double& GainHyperbolic::
 computeGain( double&res, int t ) 
 {
   sotDEBUGIN(15);
diff --git a/src/task/multi-bound.cpp b/src/task/multi-bound.cpp
index ab0865fe..1250d915 100644
--- a/src/task/multi-bound.cpp
+++ b/src/task/multi-bound.cpp
@@ -26,47 +26,47 @@
 using namespace sot;
 
 
-sotMultiBound::
-sotMultiBound( const double x )
+MultiBound::
+MultiBound( const double x )
   : mode(MODE_SINGLE),boundSingle(x)
   ,boundSup(0),boundInf(0),boundSupSetup(false),boundInfSetup(false) {}
 
-sotMultiBound::
-sotMultiBound( const double xi,const double xs )
+MultiBound::
+MultiBound( const double xi,const double xs )
   : mode(MODE_DOUBLE),boundSingle(0)
   ,boundSup(xs),boundInf(xi),boundSupSetup(true),boundInfSetup(true) {}
 
-sotMultiBound::
-sotMultiBound( const double x,const sotMultiBound::SupInfType bound )
+MultiBound::
+MultiBound( const double x,const MultiBound::SupInfType bound )
   : mode(MODE_DOUBLE),boundSingle(0)
   ,boundSup((bound==BOUND_SUP)?x:0),boundInf((bound==BOUND_INF)?x:0)
   ,boundSupSetup(bound==BOUND_SUP),boundInfSetup(bound==BOUND_INF) {}
 
-sotMultiBound::
-sotMultiBound( const sotMultiBound& clone )
+MultiBound::
+MultiBound( const MultiBound& clone )
 :mode(clone.mode),boundSingle(clone.boundSingle)
 ,boundSup(clone.boundSup),boundInf(clone.boundInf)
 ,boundSupSetup(clone.boundSupSetup),boundInfSetup(clone.boundInfSetup) {}
 
-sotMultiBound::MultiBoundModeType sotMultiBound::
+MultiBound::MultiBoundModeType MultiBound::
 getMode( void ) const
 { return mode; }
-double sotMultiBound::
+double MultiBound::
 getSingleBound( void ) const
 {
   if( MODE_SINGLE!=mode )
     {
-      SOT_THROW sotExceptionTask( sotExceptionTask::BOUND_TYPE,
+      SOT_THROW ExceptionTask( ExceptionTask::BOUND_TYPE,
                                   "Accessing single bound of a non-single type.");
     }
   return boundSingle;
 }
-double sotMultiBound::
-getDoubleBound( const sotMultiBound::SupInfType bound ) const
+double MultiBound::
+getDoubleBound( const MultiBound::SupInfType bound ) const
 {
   if( MODE_DOUBLE!=mode )
     {
-      SOT_THROW sotExceptionTask( sotExceptionTask::BOUND_TYPE,
+      SOT_THROW ExceptionTask( ExceptionTask::BOUND_TYPE,
                                   "Accessing double bound of a non-double type.");
     }
   switch(bound)
@@ -74,26 +74,26 @@ getDoubleBound( const sotMultiBound::SupInfType bound ) const
     case BOUND_SUP:
       {
         if(! boundSupSetup)
-          {SOT_THROW sotExceptionTask( sotExceptionTask::BOUND_TYPE,
+          {SOT_THROW ExceptionTask( ExceptionTask::BOUND_TYPE,
                                        "Accessing un-setup sup bound.");}
         return boundSup;
       }
     case BOUND_INF:
       {
         if(! boundInfSetup)
-          {SOT_THROW sotExceptionTask( sotExceptionTask::BOUND_TYPE,
+          {SOT_THROW ExceptionTask( ExceptionTask::BOUND_TYPE,
                                        "Accessing un-setup inf bound");}
         return boundInf;
       }
     }
   return 0;
 }
-bool sotMultiBound::
-getDoubleBoundSetup( const sotMultiBound::SupInfType bound ) const
+bool MultiBound::
+getDoubleBoundSetup( const MultiBound::SupInfType bound ) const
 {
   if( MODE_DOUBLE!=mode )
     {
-      SOT_THROW sotExceptionTask( sotExceptionTask::BOUND_TYPE,
+      SOT_THROW ExceptionTask( ExceptionTask::BOUND_TYPE,
                                   "Accessing double bound of a non-double type.");
     }
   switch(bound)
@@ -105,7 +105,7 @@ getDoubleBoundSetup( const sotMultiBound::SupInfType bound ) const
     }
   return false;
 }
-void sotMultiBound::
+void MultiBound::
 setDoubleBound( SupInfType boundType,double boundValue )
 {
   if(MODE_DOUBLE!=mode)
@@ -120,7 +120,7 @@ setDoubleBound( SupInfType boundType,double boundValue )
       break;
     }
 }
-void sotMultiBound::
+void MultiBound::
 unsetDoubleBound( SupInfType boundType )
 {
   if(MODE_DOUBLE!=mode)
@@ -138,7 +138,7 @@ unsetDoubleBound( SupInfType boundType )
         }
     }
 }
-void sotMultiBound::
+void MultiBound::
 setSingleBound( double boundValue )
 {
   mode=MODE_SINGLE;
@@ -156,23 +156,23 @@ inline static void SOT_MULTI_BOUND_CHECK_C(std::istream& is,
       v.resize(0);
       sotERROR << "Error while parsing vector multi-bound. Waiting for a '" << check
                << "'. Get '" << c << "' instead. " << std::endl;
-      SOT_THROW sotExceptionTask(sotExceptionTask::PARSER_MULTI_BOUND,
+      SOT_THROW ExceptionTask(ExceptionTask::PARSER_MULTI_BOUND,
                                  "Error parsing vector multi-bound.");
     }
 }
 
 namespace sot {
 
-std::ostream& operator<< ( std::ostream& os, const sotMultiBound & m  )
+std::ostream& operator<< ( std::ostream& os, const MultiBound & m  )
 {
   switch( m.mode )
     {
-    case sotMultiBound::MODE_SINGLE:
+    case MultiBound::MODE_SINGLE:
       {
         os << m.boundSingle;
         break;
       }
-    case sotMultiBound::MODE_DOUBLE:
+    case MultiBound::MODE_DOUBLE:
       {
         os << "(";
         if( m.boundInfSetup )  os << m.boundInf; else os << "--"; os<<",";
@@ -183,7 +183,7 @@ std::ostream& operator<< ( std::ostream& os, const sotMultiBound & m  )
   return os;
 }
 
-std::istream& operator>> ( std::istream& is, sotMultiBound & m  )
+std::istream& operator>> ( std::istream& is, MultiBound & m  )
 {
   sotDEBUGIN(15);
   char c; double val;
@@ -199,14 +199,14 @@ std::istream& operator>> ( std::istream& is, sotMultiBound & m  )
           //{char strbuf[256]; is.getline(strbuf,256); sotDEBUG(1) << "#"<<strbuf<<"#"<<std::endl;}
           is>>val;
           sotDEBUG(15) << "First val = " << val << std::endl;
-          m.setDoubleBound(sotMultiBound::BOUND_INF,val);
-        } else { m.unsetDoubleBound(sotMultiBound::BOUND_INF); }
+          m.setDoubleBound(MultiBound::BOUND_INF,val);
+        } else { m.unsetDoubleBound(MultiBound::BOUND_INF); }
       is.get(c);
       if( c!=',' )
         {
           sotERROR << "Error while parsing multi-bound. Waiting for a ','. Get '"
                    << c << "' instead. " << std::endl;
-          SOT_THROW sotExceptionTask(sotExceptionTask::PARSER_MULTI_BOUND,
+          SOT_THROW ExceptionTask(ExceptionTask::PARSER_MULTI_BOUND,
                                      "Error parsing multi-bound, while waiting for a ','.");
         }
 
@@ -216,14 +216,14 @@ std::istream& operator>> ( std::istream& is, sotMultiBound & m  )
           is.putback(c2[1]); is.putback(c2[0]);
           is>>val;
           sotDEBUG(15) << "Second val = " << val << std::endl;
-          m.setDoubleBound(sotMultiBound::BOUND_SUP,val);
-        } else { m.unsetDoubleBound(sotMultiBound::BOUND_SUP); }
+          m.setDoubleBound(MultiBound::BOUND_SUP,val);
+        } else { m.unsetDoubleBound(MultiBound::BOUND_SUP); }
       is.get(c);
       if( c!=')' )
         {
           sotERROR << "Error while parsing multi-bound. Waiting for a ')'. Get '"
                    << c << "' instead. " << std::endl;
-          SOT_THROW sotExceptionTask(sotExceptionTask::PARSER_MULTI_BOUND,
+          SOT_THROW ExceptionTask(ExceptionTask::PARSER_MULTI_BOUND,
                                      "Error parsing multi-bound, while waiting for a ')'.");
         }
     }
diff --git a/src/task/task-abstract.cpp b/src/task/task-abstract.cpp
index 4ce0dfa4..15dd7220 100644
--- a/src/task/task-abstract.cpp
+++ b/src/task/task-abstract.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotTaskAbstract.cpp
+ * File:      TaskAbstract.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -33,8 +33,8 @@ using namespace sot;
 /* --------------------------------------------------------------------- */
 
 
-sotTaskAbstract::
-sotTaskAbstract( const std::string& n )
+TaskAbstract::
+TaskAbstract( const std::string& n )
   :Entity(n)
   ,memoryInternal(NULL)
   ,taskSOUT( "sotTaskAbstract("+n+")::output(vector)::task" )
@@ -47,14 +47,14 @@ sotTaskAbstract( const std::string& n )
 }
 
 
-void sotTaskAbstract::
+void TaskAbstract::
 taskRegistration( void )
 {
   sotPool.registerTask(name,this);
 }
 
 
-void sotTaskAbstract::
+void TaskAbstract::
 commandLine( const std::string& cmdLine,std::istringstream& cmdArgs,
 	     std::ostream& os )
 {
diff --git a/src/task/task-conti.cpp b/src/task/task-conti.cpp
index 3b3c3629..ecce5700 100644
--- a/src/task/task-conti.cpp
+++ b/src/task/task-conti.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotTaskConti.cpp
+ * File:      TaskConti.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -31,7 +31,7 @@
 using namespace std;
 using namespace sot;
 
-SOT_FACTORY_TASK_PLUGIN(sotTaskConti,"TaskConti");
+SOT_FACTORY_TASK_PLUGIN(TaskConti,"TaskConti");
 
 
 /* --------------------------------------------------------------------- */
@@ -39,19 +39,19 @@ SOT_FACTORY_TASK_PLUGIN(sotTaskConti,"TaskConti");
 /* --------------------------------------------------------------------- */
 
 
-sotTaskConti::
-sotTaskConti( const std::string& n )
-  :sotTask(n)
+TaskConti::
+TaskConti( const std::string& n )
+  :Task(n)
    ,timeRef( TIME_REF_UNSIGNIFICANT )
    ,mu(0)
    ,controlPrevSIN( NULL,"sotTaskConti("+n+")::input(double)::q0" )
 {
-  taskSOUT.setFunction( boost::bind(&sotTaskConti::computeContiDesiredVelocity,this,_1,_2) );
+  taskSOUT.setFunction( boost::bind(&TaskConti::computeContiDesiredVelocity,this,_1,_2) );
   signalRegistration( controlPrevSIN );
 }
 
 
-sotVectorMultiBound& sotTaskConti::
+sotVectorMultiBound& TaskConti::
 computeContiDesiredVelocity( sotVectorMultiBound& desvel2b,const int & timecurr )
 {
   sotDEBUG(15) << "# In {" << endl;
@@ -118,7 +118,7 @@ computeContiDesiredVelocity( sotVectorMultiBound& desvel2b,const int & timecurr
 /* --- DISPLAY ------------------------------------------------------------ */
 /* --- DISPLAY ------------------------------------------------------------ */
 
-void sotTaskConti::
+void TaskConti::
 display( std::ostream& os ) const
 {
   os << "TaskConti " << name
@@ -126,7 +126,7 @@ display( std::ostream& os ) const
      << ": " << endl;
   os << "--- LIST ---  " << std::endl;
 
-  for(   std::list< sotFeatureAbstract* >::const_iterator iter = featureList.begin();
+  for(   std::list< FeatureAbstract* >::const_iterator iter = featureList.begin();
 	 iter!=featureList.end(); ++iter )
     {
       os << "-> " << (*iter)->getName() <<endl;
@@ -142,7 +142,7 @@ display( std::ostream& os ) const
 
 #include <dynamic-graph/pool.h>
 
-void sotTaskConti::
+void TaskConti::
 commandLine( const std::string& cmdLine
 	     ,std::istringstream& cmdArgs
 	     ,std::ostream& os )
@@ -154,7 +154,7 @@ commandLine( const std::string& cmdLine
 	 << "  - timeRef" << endl
 	 << "  - mu [<val>]" << endl;
 
-      sotTask::commandLine( cmdLine,cmdArgs,os );
+      Task::commandLine( cmdLine,cmdArgs,os );
     }
   else if( cmdLine=="touch" )
     {
@@ -176,6 +176,6 @@ commandLine( const std::string& cmdLine
       cmdArgs >> std::ws; if(! cmdArgs.good() ) os << "mu = " << mu << std::endl;
       else { cmdArgs >> mu; }
     }
-  else  sotTask::commandLine( cmdLine,cmdArgs,os );
+  else  Task::commandLine( cmdLine,cmdArgs,os );
 
 }
diff --git a/src/task/task-pd.cpp b/src/task/task-pd.cpp
index 70bc9b85..761c96c0 100644
--- a/src/task/task-pd.cpp
+++ b/src/task/task-pd.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotTaskPD.cpp
+ * File:      TaskPD.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -34,7 +34,7 @@ using namespace sot;
 
 #include <sot-core/factory.h>
 
-SOT_FACTORY_TASK_PLUGIN(sotTaskPD,"TaskPD");
+SOT_FACTORY_TASK_PLUGIN(TaskPD,"TaskPD");
 
 
 /* --------------------------------------------------------------------- */
@@ -42,18 +42,18 @@ SOT_FACTORY_TASK_PLUGIN(sotTaskPD,"TaskPD");
 /* --------------------------------------------------------------------- */
 
 
-sotTaskPD::
-sotTaskPD( const std::string& n )
-  :sotTask(n)
+TaskPD::
+TaskPD( const std::string& n )
+  :Task(n)
    ,previousError()
    ,beta(1)
-   ,errorDotSOUT( boost::bind(&sotTaskPD::computeErrorDot,this,_1,_2),
+   ,errorDotSOUT( boost::bind(&TaskPD::computeErrorDot,this,_1,_2),
 		  errorSOUT,
 		  "sotTaskPD("+n+")::output(vector)::errorDotOUT" )
    ,errorDotSIN(  NULL,
 		  "sotTaskPD("+n+")::input(vector)::errorDot" )
 {
-  taskSOUT.setFunction( boost::bind(&sotTaskPD::computeTaskModif,this,_1,_2) );
+  taskSOUT.setFunction( boost::bind(&TaskPD::computeTaskModif,this,_1,_2) );
   taskSOUT.addDependancy( errorDotSOUT );
 
   signalRegistration( errorDotSOUT<<errorDotSIN );
@@ -65,7 +65,7 @@ sotTaskPD( const std::string& n )
 /* --- COMPUTATION ---------------------------------------------------------- */
 /* --- COMPUTATION ---------------------------------------------------------- */
 
-ml::Vector& sotTaskPD::
+ml::Vector& TaskPD::
 computeErrorDot( ml::Vector& errorDot,int time )
 {
   sotDEBUG(15) << "# In {" << endl;
@@ -87,13 +87,13 @@ computeErrorDot( ml::Vector& errorDot,int time )
   return errorDot;
 }
 
-sotVectorMultiBound& sotTaskPD::
+sotVectorMultiBound& TaskPD::
 computeTaskModif( sotVectorMultiBound& task,int time )
 {
   sotDEBUG(15) << "# In {" << endl;
 
   const ml::Vector & errorDot = errorDotSIN(time);
-  sotTask::computeTaskExponentialDecrease(task,time);
+  Task::computeTaskExponentialDecrease(task,time);
 
   sotDEBUG(25) << " Task = " << task;
   sotDEBUG(25) << " edot = " << errorDot;
@@ -113,7 +113,7 @@ computeTaskModif( sotVectorMultiBound& task,int time )
 /* --- PARAMS --------------------------------------------------------------- */
 #include <sot-core/pool.h>
 
-void sotTaskPD::
+void TaskPD::
 commandLine( const std::string& cmdLine
 	     ,std::istringstream& cmdArgs
 	     ,std::ostream& os )
@@ -130,6 +130,6 @@ commandLine( const std::string& cmdLine
 	{ cmdArgs >> beta; } else { os << beta; }
     }
   else  //sotTaskPDAbstract::
-    sotTask::commandLine( cmdLine,cmdArgs,os );
+    Task::commandLine( cmdLine,cmdArgs,os );
 
 }
diff --git a/src/task/task-unilateral.cpp b/src/task/task-unilateral.cpp
index 5d555884..c8acc999 100644
--- a/src/task/task-unilateral.cpp
+++ b/src/task/task-unilateral.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotTaskUnilateral.cpp
+ * File:      TaskUnilateral.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -35,7 +35,7 @@ using namespace sot;
 
 
 #include <sot-core/factory.h>
-SOT_FACTORY_TASK_PLUGIN(sotTaskUnilateral,"TaskUnilateral");
+SOT_FACTORY_TASK_PLUGIN(TaskUnilateral,"TaskUnilateral");
 
 
 /* --------------------------------------------------------------------- */
@@ -43,16 +43,16 @@ SOT_FACTORY_TASK_PLUGIN(sotTaskUnilateral,"TaskUnilateral");
 /* --------------------------------------------------------------------- */
 
 
-sotTaskUnilateral::
-sotTaskUnilateral( const std::string& n )
-  :sotTask(n)
+TaskUnilateral::
+TaskUnilateral( const std::string& n )
+  :Task(n)
   ,featureList()
   ,positionSIN( NULL,"sotTaskUnilateral("+n+")::input(vector)::position" )
   ,referenceInfSIN( NULL,"sotTaskUnilateral("+n+")::input(vector)::referenceInf" )
   ,referenceSupSIN( NULL,"sotTaskUnilateral("+n+")::input(vector)::referenceSup" )
   ,dtSIN( NULL,"sotTaskUnilateral("+n+")::input(double)::dt" )
 {
-  taskSOUT.setFunction( boost::bind(&sotTaskUnilateral::computeTaskUnilateral,this,_1,_2) );
+  taskSOUT.setFunction( boost::bind(&TaskUnilateral::computeTaskUnilateral,this,_1,_2) );
   taskSOUT.clearDependancies();
   taskSOUT.addDependancy( referenceSupSIN );
   taskSOUT.addDependancy( referenceInfSIN );
@@ -67,7 +67,7 @@ sotTaskUnilateral( const std::string& n )
 /* --- COMPUTATION ---------------------------------------------------------- */
 /* --- COMPUTATION ---------------------------------------------------------- */
 
-sotVectorMultiBound& sotTaskUnilateral::
+sotVectorMultiBound& TaskUnilateral::
 computeTaskUnilateral( sotVectorMultiBound& res,int time )
 {
   sotDEBUG(45) << "# In " << getName() << " {" << endl;
@@ -79,7 +79,7 @@ computeTaskUnilateral( sotVectorMultiBound& res,int time )
   res.resize(position.size());
   for( unsigned int i=0;i<res.size();++i )
     {
-      sotMultiBound toto((refInf(i)-position(i))/dt,(refSup(i)-position(i))/dt);
+      MultiBound toto((refInf(i)-position(i))/dt,(refSup(i)-position(i))/dt);
       res[i] = toto;
     }
 
@@ -92,7 +92,7 @@ computeTaskUnilateral( sotVectorMultiBound& res,int time )
 /* --- DISPLAY ------------------------------------------------------------ */
 /* --- DISPLAY ------------------------------------------------------------ */
 
-void sotTaskUnilateral::
+void TaskUnilateral::
 display( std::ostream& os ) const
 {
   os << "TaskUnilateral " << name << ": " << endl;
diff --git a/src/task/task.cpp b/src/task/task.cpp
index 3d43b1f1..5c8a3cdc 100644
--- a/src/task/task.cpp
+++ b/src/task/task.cpp
@@ -2,7 +2,7 @@
  * Copyright Projet JRL-Japan, 2007
  *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  *
- * File:      sotTask.cpp
+ * File:      Task.cpp
  * Project:   SOT
  * Author:    Nicolas Mansard
  *
@@ -32,7 +32,7 @@ using namespace sot;
 
 
 #include <sot-core/factory.h>
-SOT_FACTORY_TASK_PLUGIN(sotTask,"Task");
+SOT_FACTORY_TASK_PLUGIN(Task,"Task");
 
 
 /* --------------------------------------------------------------------- */
@@ -40,20 +40,20 @@ SOT_FACTORY_TASK_PLUGIN(sotTask,"Task");
 /* --------------------------------------------------------------------- */
 
 
-sotTask::
-sotTask( const std::string& n )
-  :sotTaskAbstract(n)
+Task::
+Task( const std::string& n )
+  :TaskAbstract(n)
    ,featureList()
    ,controlGainSIN( NULL,"sotTask("+n+")::input(double)::controlGain" )
    ,dampingGainSINOUT( NULL,"sotTask("+n+")::in/output(double)::damping" )
    ,controlSelectionSIN( NULL,"sotTask("+n+")::input(flag)::controlSelec" )
-   ,errorSOUT( boost::bind(&sotTask::computeError,this,_1,_2),
+   ,errorSOUT( boost::bind(&Task::computeError,this,_1,_2),
 	       sotNOSIGNAL,
 	       "sotTask("+n+")::output(vector)::error" )
 {
-  taskSOUT.setFunction( boost::bind(&sotTask::computeTaskExponentialDecrease,this,_1,_2) );
-  jacobianSOUT.setFunction( boost::bind(&sotTask::computeJacobian,this,_1,_2) );
-  featureActivationSOUT.setFunction( boost::bind(&sotTask::computeFeatureActivation,this,_1,_2) );
+  taskSOUT.setFunction( boost::bind(&Task::computeTaskExponentialDecrease,this,_1,_2) );
+  jacobianSOUT.setFunction( boost::bind(&Task::computeJacobian,this,_1,_2) );
+  featureActivationSOUT.setFunction( boost::bind(&Task::computeFeatureActivation,this,_1,_2) );
 
   taskSOUT.addDependancy( controlGainSIN );
   taskSOUT.addDependancy( errorSOUT );
@@ -68,22 +68,22 @@ sotTask( const std::string& n )
 
 
 
-void sotTask::
-addFeature( sotFeatureAbstract& s )
+void Task::
+addFeature( FeatureAbstract& s )
 {
   featureList.push_back(&s);
   jacobianSOUT.addDependancy( s.jacobianSOUT );
   errorSOUT.addDependancy( s.errorSOUT );
   featureActivationSOUT.addDependancy( s.activationSOUT );
 }
-void sotTask::
+void Task::
 clearFeatureList( void )
 {
 
-  for(   std::list< sotFeatureAbstract* >::iterator iter = featureList.begin();
+  for(   std::list< FeatureAbstract* >::iterator iter = featureList.begin();
 	 iter!=featureList.end(); ++iter )
     {
-      sotFeatureAbstract & s = **iter;
+      FeatureAbstract & s = **iter;
       jacobianSOUT.removeDependancy( s.jacobianSOUT );
       errorSOUT.removeDependancy( s.errorSOUT );
       featureActivationSOUT.removeDependancy( s.activationSOUT );
@@ -92,35 +92,35 @@ clearFeatureList( void )
   featureList.clear();
 }
 
-void sotTask::
-setControlSelection( const sotFlags& act )
+void Task::
+setControlSelection( const Flags& act )
 {
   controlSelectionSIN = act;
 }
-void sotTask::
-addControlSelection( const sotFlags& act )
+void Task::
+addControlSelection( const Flags& act )
 {
-  sotFlags fl = controlSelectionSIN.accessCopy();
+  Flags fl = controlSelectionSIN.accessCopy();
   fl &= act;
   controlSelectionSIN = fl;
 }
-void sotTask::
+void Task::
 clearControlSelection( void )
 {
-  controlSelectionSIN = sotFlags(false);
+  controlSelectionSIN = Flags(false);
 }
 
 /* --- COMPUTATION ---------------------------------------------------------- */
 /* --- COMPUTATION ---------------------------------------------------------- */
 /* --- COMPUTATION ---------------------------------------------------------- */
 
-ml::Vector& sotTask::
+ml::Vector& Task::
 computeError( ml::Vector& error,int time )
 {
   sotDEBUG(15) << "# In " << getName() << " {" << endl;
 
   if( featureList.empty())
-    { throw( sotExceptionTask(sotExceptionTask::EMPTY_LIST,
+    { throw( ExceptionTask(ExceptionTask::EMPTY_LIST,
 			      "Empty feature list") ) ; }
 
   try {
@@ -145,10 +145,10 @@ computeError( ml::Vector& error,int time )
     int cursorError = 0;
 
     /* For each cell of the list, recopy value of s, s_star and error. */
-    for(   std::list< sotFeatureAbstract* >::iterator iter = featureList.begin();
+    for(   std::list< FeatureAbstract* >::iterator iter = featureList.begin();
 	   iter!=featureList.end(); ++iter )
       {
-	sotFeatureAbstract &feature = **iter;
+	FeatureAbstract &feature = **iter;
 
 	/* Get s, and store it in the s vector. */
 	sotDEBUG(45) << "Feature <" << feature.getName() << ">." << std::endl;
@@ -172,7 +172,7 @@ computeError( ml::Vector& error,int time )
   return error;
 }
 
-sotVectorMultiBound& sotTask::
+sotVectorMultiBound& Task::
 computeTaskExponentialDecrease( sotVectorMultiBound& errorRef,int time )
 {
   sotDEBUG(15) << "# In {" << endl;
@@ -187,13 +187,13 @@ computeTaskExponentialDecrease( sotVectorMultiBound& errorRef,int time )
   return errorRef;
 }
 
-ml::Matrix& sotTask::
+ml::Matrix& Task::
 computeJacobian( ml::Matrix& J,int time )
 {
   sotDEBUG(15) << "# In {" << endl;
 
   if( featureList.empty())
-    { throw( sotExceptionTask(sotExceptionTask::EMPTY_LIST,
+    { throw( ExceptionTask(ExceptionTask::EMPTY_LIST,
 			      "Empty feature list") ) ; }
 
   try {
@@ -202,13 +202,13 @@ computeJacobian( ml::Matrix& J,int time )
     if( 0==dimJ ){ dimJ = 1; J.resize(dimJ,nbc); }
 
     int cursorJ = 0;
-    //const sotFlags& selection = controlSelectionSIN(time);
+    //const Flags& selection = controlSelectionSIN(time);
 
     /* For each cell of the list, recopy value of s, s_star and error. */
-    for(   std::list< sotFeatureAbstract* >::iterator iter = featureList.begin();
+    for(   std::list< FeatureAbstract* >::iterator iter = featureList.begin();
 	   iter!=featureList.end(); ++iter )
       {
-	sotFeatureAbstract &feature = ** iter;
+	FeatureAbstract &feature = ** iter;
 	sotDEBUG(25) << "Feature <" << feature.getName() <<">"<< endl;
 
 	/* Get s, and store it in the s vector. */
@@ -218,7 +218,7 @@ computeJacobian( ml::Matrix& J,int time )
 
 	if( 0==nbc ) { nbc = partialJacobian.nbCols(); J.resize(nbc,dimJ); }
 	else if( partialJacobian.nbCols() != nbc )
-	  throw sotExceptionTask(sotExceptionTask::NON_ADEQUATE_FEATURES,
+	  throw ExceptionTask(ExceptionTask::NON_ADEQUATE_FEATURES,
 				 "Features from the list don't have compatible-size jacobians.");
 
 	while( cursorJ+nbr>=dimJ )
@@ -245,12 +245,12 @@ computeJacobian( ml::Matrix& J,int time )
 
 
 
-ml::Vector& sotTask::
+ml::Vector& Task::
 computeFeatureActivation( ml::Vector& activation,int time )
 {
   sotDEBUG(15) << "# In {" << endl;
   if( featureList.empty())
-    { throw( sotExceptionTask(sotExceptionTask::EMPTY_LIST,
+    { throw( ExceptionTask(ExceptionTask::EMPTY_LIST,
 			      "Empty feature list") ) ; }
 
   try {
@@ -260,10 +260,10 @@ computeFeatureActivation( ml::Vector& activation,int time )
     int cursorH = 0;
 
     /* For each cell of the list, recopy value of s, s_star and error. */
-    for(   std::list< sotFeatureAbstract* >::iterator iter = featureList.begin();
+    for(   std::list< FeatureAbstract* >::iterator iter = featureList.begin();
 	   iter!=featureList.end(); ++iter )
       {
-	sotFeatureAbstract &feature = ** iter;
+	FeatureAbstract &feature = ** iter;
 
 	/* Get s, and store it in the s vector. */
 	const ml::Vector& partialActivation = feature.activationSOUT(time);
@@ -289,13 +289,13 @@ computeFeatureActivation( ml::Vector& activation,int time )
 /* --- DISPLAY ------------------------------------------------------------ */
 /* --- DISPLAY ------------------------------------------------------------ */
 
-void sotTask::
+void Task::
 display( std::ostream& os ) const
 {
   os << "Task " << name << ": " << endl;
   os << "--- LIST ---  " << std::endl;
 
-  for(   std::list< sotFeatureAbstract* >::const_iterator iter = featureList.begin();
+  for(   std::list< FeatureAbstract* >::const_iterator iter = featureList.begin();
 	 iter!=featureList.end(); ++iter )
     {
       os << "-> " << (*iter)->getName() <<endl;
@@ -338,7 +338,7 @@ static void readListIdx( std::istringstream& cmdArgs,
 	       << "(" << no_end <<")"<<endl;
 }
 
-void sotTask::
+void Task::
 commandLine( const std::string& cmdLine
 	     ,std::istringstream& cmdArgs
 	     ,std::ostream& os )
@@ -350,12 +350,12 @@ commandLine( const std::string& cmdLine
 	 << "  - [un]selec [init] : [end] :"<<endl
 	 << "modify the default value of the controlSelec signal"<<endl
 	 << "  - clear"<<endl;
-      sotTaskAbstract::commandLine( cmdLine,cmdArgs,os );
+      TaskAbstract::commandLine( cmdLine,cmdArgs,os );
     }
   else if( cmdLine=="add" )
     {
       std::string f; cmdArgs >> f;
-      sotFeatureAbstract& feat = sotPool.getFeature( f );
+      FeatureAbstract& feat = sotPool.getFeature( f );
       addFeature( feat );
     }
   else if( cmdLine=="selec" )
@@ -364,7 +364,7 @@ commandLine( const std::string& cmdLine
       bool base;
       readListIdx( cmdArgs,idx_beg,idx_end,base );
 
-      sotFlags newFlag( base );
+      Flags newFlag( base );
       if(base)
 	{
 	  for( unsigned int i=0;i<idx_beg;++i)
@@ -386,7 +386,7 @@ commandLine( const std::string& cmdLine
       unsigned int idx_beg,idx_end; bool base;
       readListIdx( cmdArgs,idx_beg,idx_end,base );
 
-      sotFlags newFlag(! base );
+      Flags newFlag(! base );
       if(base)
 	{
 	  for( unsigned int i=0;i<idx_beg;++i)
@@ -407,7 +407,7 @@ commandLine( const std::string& cmdLine
       unsigned int idx_beg,idx_end; bool base;
       readListIdx( cmdArgs,idx_beg,idx_end,base );
 
-      sotFlags newFlag(! base );
+      Flags newFlag(! base );
       if(base)
 	{
 	  for( unsigned int i=0;i<idx_beg;++i)
@@ -427,13 +427,13 @@ commandLine( const std::string& cmdLine
     {
       clearFeatureList();
     }
-  else  { sotTaskAbstract::commandLine( cmdLine,cmdArgs,os ); }
+  else  { TaskAbstract::commandLine( cmdLine,cmdArgs,os ); }
 
 }
-std::ostream & sotTask::
+std::ostream & Task::
 writeGraph(std::ostream &os) const
 {
-  std::list< sotFeatureAbstract * >::const_iterator itFeatureAbstract;
+  std::list< FeatureAbstract * >::const_iterator itFeatureAbstract;
   itFeatureAbstract = featureList.begin();
   while(itFeatureAbstract!=featureList.end())
     {
-- 
GitLab