diff --git a/include/sot/core/clamp-workspace.hh b/include/sot/core/clamp-workspace.hh
index 7b53a11d710756d8a284b50670c38311d2235283..d1c2544c72642f77627653f459fc4c114c284f8a 100644
--- a/include/sot/core/clamp-workspace.hh
+++ b/include/sot/core/clamp-workspace.hh
@@ -62,8 +62,10 @@ public:
 
   void update(int time);
 
-  virtual dynamicgraph::Matrix &computeOutput(dynamicgraph::Matrix &res, int time);
-  virtual dynamicgraph::Matrix &computeOutputBar(dynamicgraph::Matrix &res, int time);
+  virtual dynamicgraph::Matrix &computeOutput(dynamicgraph::Matrix &res,
+                                              int time);
+  virtual dynamicgraph::Matrix &computeOutputBar(dynamicgraph::Matrix &res,
+                                                 int time);
   virtual MatrixHomogeneous &computeRef(MatrixHomogeneous &res, int time);
 
   virtual void display(std::ostream &) const;
diff --git a/include/sot/core/com-freezer.hh b/include/sot/core/com-freezer.hh
index 4621f6e25d94e0c13e447d30363ca7cb99f01447..ab58d8ddcea578f8863bd53e895128bbd4a022bb 100644
--- a/include/sot/core/com-freezer.hh
+++ b/include/sot/core/com-freezer.hh
@@ -62,7 +62,8 @@ public: /* --- SIGNAL --- */
   dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> freezedCoMSOUT;
 
 public: /* --- FUNCTION --- */
-  dynamicgraph::Vector &computeFreezedCoM(dynamicgraph::Vector &freezedCoM, const int &time);
+  dynamicgraph::Vector &computeFreezedCoM(dynamicgraph::Vector &freezedCoM,
+                                          const int &time);
 
 public: /* --- PARAMS --- */
   virtual void display(std::ostream &os) const;
diff --git a/include/sot/core/control-gr.hh b/include/sot/core/control-gr.hh
index c0ac928f600e21942f7c012d44745d78d59fa7da..9a8f14092fbfa14f34914dd9b5f4a9bf9a7a9ef3 100644
--- a/include/sot/core/control-gr.hh
+++ b/include/sot/core/control-gr.hh
@@ -39,7 +39,6 @@
 namespace dynamicgraph {
 namespace sot {
 
-
 /* --------------------------------------------------------------------- */
 /* --- CLASS ----------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
diff --git a/include/sot/core/control-pd.hh b/include/sot/core/control-pd.hh
index 293300f518fda79ecf836607e51685283cc736c3..31ad8056bde29b55ff00d8b73180b71ab3416677 100644
--- a/include/sot/core/control-pd.hh
+++ b/include/sot/core/control-pd.hh
@@ -80,8 +80,10 @@ protected:
   dynamicgraph::Vector &computeControl(dynamicgraph::Vector &tau, int t);
   dynamicgraph::Vector position_error_;
   dynamicgraph::Vector velocity_error_;
-  dynamicgraph::Vector &getPositionError(dynamicgraph::Vector &position_error, int t);
-  dynamicgraph::Vector &getVelocityError(dynamicgraph::Vector &velocity_error, int t);
+  dynamicgraph::Vector &getPositionError(dynamicgraph::Vector &position_error,
+                                         int t);
+  dynamicgraph::Vector &getVelocityError(dynamicgraph::Vector &velocity_error,
+                                         int t);
 };
 
 } // namespace sot
diff --git a/include/sot/core/device.hh b/include/sot/core/device.hh
index 9cb5c266cf3e8938791d36476bdb975063785c53..0b835dc3f3707d13e281eede49634e9e8fd3ab80 100644
--- a/include/sot/core/device.hh
+++ b/include/sot/core/device.hh
@@ -141,8 +141,8 @@ public: /* --- SIGNALS --- */
 
 protected:
   /// Compute roll pitch yaw angles of freeflyer joint.
-  void integrateRollPitchYaw(dynamicgraph::Vector &state, const dynamicgraph::Vector &control,
-                             double dt);
+  void integrateRollPitchYaw(dynamicgraph::Vector &state,
+                             const dynamicgraph::Vector &control, double dt);
   /// Store Position of free flyer joint
   MatrixHomogeneous ffPose_;
   /// Compute the new position, from the current control.
diff --git a/include/sot/core/exp-moving-avg.hh b/include/sot/core/exp-moving-avg.hh
index 2ed1d42528e874041412611f85588a624a042660..de48d5f38693df23cd11a177189f9937df337924 100644
--- a/include/sot/core/exp-moving-avg.hh
+++ b/include/sot/core/exp-moving-avg.hh
@@ -18,7 +18,6 @@
 #include <dynamic-graph/signal-time-dependent.h>
 #include <sot/core/config.hh>
 
-
 namespace dynamicgraph {
 namespace sot {
 
diff --git a/include/sot/core/feature-1d.hh b/include/sot/core/feature-1d.hh
index 23705f190b10a3b82e8ab91b9c126f4db273b89f..ee7808d978844f6fc240557eb251d07fb3c495f9 100644
--- a/include/sot/core/feature-1d.hh
+++ b/include/sot/core/feature-1d.hh
@@ -98,10 +98,12 @@ public:
 
   /*! \brief Compute the error between the desired value and the value itself.
    */
-  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time);
+  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res,
+                                             int time);
 
   /*! \brief Compute the Jacobian of the value according to the robot state.. */
-  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time);
+  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res,
+                                                int time);
 
   /*! @} */
 
diff --git a/include/sot/core/feature-abstract.hh b/include/sot/core/feature-abstract.hh
index 282ae07fbe7d11780ce6f76adc23e424b22a8397..06ca928df9812a7dc5318962cb8f10bc2b892acf 100644
--- a/include/sot/core/feature-abstract.hh
+++ b/include/sot/core/feature-abstract.hh
@@ -136,20 +136,23 @@ public:
     \par[in] time: The time at which the error is computed.
     \return The vector res with the appropriate value.
   */
-  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time) = 0;
+  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res,
+                                             int time) = 0;
 
   /*! \brief Compute the Jacobian of the error according the robot state.
 
     \par[out] res: The matrix in which the error will be written.
     \return The matrix res with the appropriate values.
   */
-  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time) = 0;
+  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res,
+                                                int time) = 0;
 
   /// Callback for signal errordotSOUT
   ///
   /// Copy components of the input signal errordotSIN defined by selection
   /// flag selectionSIN.
-  virtual dynamicgraph::Vector &computeErrorDot(dynamicgraph::Vector &res, int time);
+  virtual dynamicgraph::Vector &computeErrorDot(dynamicgraph::Vector &res,
+                                                int time);
 
   /*! @} */
 
diff --git a/include/sot/core/feature-generic.hh b/include/sot/core/feature-generic.hh
index 2d0e9e18964d136fdbb3aabb78efd28933baebb8..2f1d00672e2c95d4f2155e3455068e277fec2a3f 100644
--- a/include/sot/core/feature-generic.hh
+++ b/include/sot/core/feature-generic.hh
@@ -109,10 +109,12 @@ public:
 
   /*! \brief Compute the error between the desired value and the value itself.
    */
-  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time);
+  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res,
+                                             int time);
 
   /*! \brief Compute the Jacobian of the value according to the robot state.. */
-  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time);
+  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res,
+                                                int time);
 
   /*! @} */
 
diff --git a/include/sot/core/feature-joint-limits.hh b/include/sot/core/feature-joint-limits.hh
index 8a11cb1ed320d842ed797dafab4c4c3b5e4db1e2..7c670d61cc19473b5c02e0e5beeccb06c55a9a7a 100644
--- a/include/sot/core/feature-joint-limits.hh
+++ b/include/sot/core/feature-joint-limits.hh
@@ -83,9 +83,12 @@ public:
 
   virtual unsigned int &getDimension(unsigned int &dim, int time);
 
-  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time);
-  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time);
-  dynamicgraph::Vector &computeWidthJl(dynamicgraph::Vector &res, const int &time);
+  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res,
+                                             int time);
+  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res,
+                                                int time);
+  dynamicgraph::Vector &computeWidthJl(dynamicgraph::Vector &res,
+                                       const int &time);
 
   /** Static Feature selection. */
   inline static Flags selectActuated(void);
diff --git a/include/sot/core/feature-line-distance.hh b/include/sot/core/feature-line-distance.hh
index c618cd9e9d0de169d46f5fb26aef3507fb7ae150..6aa7002f1d880b0771c28efeba8c7be8e7cfc6f1 100644
--- a/include/sot/core/feature-line-distance.hh
+++ b/include/sot/core/feature-line-distance.hh
@@ -75,9 +75,12 @@ public:
 
   virtual unsigned int &getDimension(unsigned int &dim, int time);
 
-  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time);
-  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time);
-  dynamicgraph::Vector &computeLineCoordinates(dynamicgraph::Vector &cood, int time);
+  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res,
+                                             int time);
+  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res,
+                                                int time);
+  dynamicgraph::Vector &computeLineCoordinates(dynamicgraph::Vector &cood,
+                                               int time);
 
   virtual void display(std::ostream &os) const;
 };
diff --git a/include/sot/core/feature-point6d-relative.hh b/include/sot/core/feature-point6d-relative.hh
index e1d0730705e536e71a3d74dbfe17605ec9866b2b..997ad917b04f4f19368931a048769e2216536813 100644
--- a/include/sot/core/feature-point6d-relative.hh
+++ b/include/sot/core/feature-point6d-relative.hh
@@ -60,7 +60,8 @@ protected:
   /* --- SIGNALS ------------------------------------------------------------ */
 public:
   dynamicgraph::SignalPtr<MatrixHomogeneous, int> positionReferenceSIN;
-  dynamicgraph::SignalPtr<dynamicgraph::Matrix, int> articularJacobianReferenceSIN;
+  dynamicgraph::SignalPtr<dynamicgraph::Matrix, int>
+      articularJacobianReferenceSIN;
 
   /*! dynamicgraph::Signals related to the computation of the derivative of
     the error
@@ -80,9 +81,12 @@ public:
   FeaturePoint6dRelative(const std::string &name);
   virtual ~FeaturePoint6dRelative(void) {}
 
-  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time);
-  virtual dynamicgraph::Vector &computeErrorDot(dynamicgraph::Vector &res, int time);
-  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time);
+  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res,
+                                             int time);
+  virtual dynamicgraph::Vector &computeErrorDot(dynamicgraph::Vector &res,
+                                                int time);
+  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res,
+                                                int time);
 
   virtual void display(std::ostream &os) const;
 
diff --git a/include/sot/core/feature-point6d.hh b/include/sot/core/feature-point6d.hh
index e2624f0712e26558451cbadfd1368097ac5ac8d2..5df8c4efa148f005a1ff86bc17706ba88d56cb11 100644
--- a/include/sot/core/feature-point6d.hh
+++ b/include/sot/core/feature-point6d.hh
@@ -89,9 +89,12 @@ public:
 
   virtual unsigned int &getDimension(unsigned int &dim, int time);
 
-  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time);
-  virtual dynamicgraph::Vector &computeErrordot(dynamicgraph::Vector &res, int time);
-  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time);
+  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res,
+                                             int time);
+  virtual dynamicgraph::Vector &computeErrordot(dynamicgraph::Vector &res,
+                                                int time);
+  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res,
+                                                int time);
 
   /** Static Feature selection. */
   inline static Flags selectX(void) { return FLAG_LINE_1; }
diff --git a/include/sot/core/feature-pose.hh b/include/sot/core/feature-pose.hh
index a55d842083d067abf2febb0593260e483011cf1a..23b5a366bf8525d65589c922ed7e3da7468c33eb 100644
--- a/include/sot/core/feature-pose.hh
+++ b/include/sot/core/feature-pose.hh
@@ -120,21 +120,24 @@ public:
   virtual unsigned int &getDimension(unsigned int &dim, int time);
 
   /// Computes \f$ {}^oM^{-1}_{fa} {}^oM_{fb} \ominus {}^{fa}M^*_{fb} \f$
-  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time);
+  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res,
+                                             int time);
   /// Computes \f$ \frac{\partial\ominus}{\partial b} X {}^{fa}\nu^*_{fafb} \f$.
   /// There are two different cases, depending on the representation:
   /// - R3xSO3Representation: \f$ X = \left( \begin{array}{cc} I_3 & [
   /// {}^{fa}t_{fb} ] \\ 0_3 & {{}^{fa}R^*_{fb}}^T \end{array} \right) \f$
   /// - SE3Representation: \f$ X = {{}^{fa}X^*_{fb}}^{-1} \f$ (see
   /// pinocchio::SE3Base<Scalar,Options>::toActionMatrix)
-  virtual dynamicgraph::Vector &computeErrorDot(dynamicgraph::Vector &res, int time);
+  virtual dynamicgraph::Vector &computeErrorDot(dynamicgraph::Vector &res,
+                                                int time);
   /// Computes \f$ \frac{\partial\ominus}{\partial b} Y \left( {{}^{fb}X_{jb}}
   /// {}^{jb}J_{jb} - {{}^{fb}X_{ja}} {}^{ja}J_{ja} \right) \f$. There are two
   /// different cases, depending on the representation:
   /// - R3xSO3Representation: \f$ Y = \left( \begin{array}{cc} {{}^{fa}R_{fb}} &
   /// 0_3 \\ 0_3 & I_3 \end{array} \right) \f$
   /// - SE3Representation: \f$ Y = I_6 \f$
-  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time);
+  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res,
+                                                int time);
 
   /** Static Feature selection. */
   inline static Flags selectX(void) { return FLAG_LINE_1; }
@@ -160,10 +163,10 @@ private:
   /// \todo Intermediate variables for internal computations
 };
 
-template < typename T >
+template <typename T>
 Vector6d convertVelocity(const MatrixHomogeneous &M,
-                                const MatrixHomogeneous &Mdes,
-                                const Vector &faNufafbDes);
+                         const MatrixHomogeneous &Mdes,
+                         const Vector &faNufafbDes);
 #if __cplusplus >= 201103L
 extern template class SOT_CORE_DLLAPI FeaturePose<SE3Representation>;
 extern template class SOT_CORE_DLLAPI FeaturePose<R3xSO3Representation>;
diff --git a/include/sot/core/feature-pose.hxx b/include/sot/core/feature-pose.hxx
index 500dd4ecd2c663487a24f555c711217dbc11b0ee..7ba9f507052cb9596488fffc52691e9e6106d321 100644
--- a/include/sot/core/feature-pose.hxx
+++ b/include/sot/core/feature-pose.hxx
@@ -41,7 +41,7 @@ template <Representation_t representation> struct LG_t {
   typedef typename boost::mpl::if_c<representation == SE3Representation, SE3_t,
                                     R3xSO3_t>::type type;
 };
-}
+} // namespace internal
 
 /* --------------------------------------------------------------------- */
 /* --- CLASS ----------------------------------------------------------- */
@@ -104,11 +104,7 @@ FeaturePose<representation>::FeaturePose(const std::string &pointName)
 }
 
 template <Representation_t representation>
-FeaturePose<representation>::~FeaturePose()
-{
-}
-
-
+FeaturePose<representation>::~FeaturePose() {}
 
 /* --------------------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
@@ -261,8 +257,8 @@ Vector &FeaturePose<representation>::computeError(Vector &error, int time) {
 // feature (R^3xSO(3) or SE(3)), in the right frame.
 template <>
 Vector6d convertVelocity<SE3_t>(const MatrixHomogeneous &M,
-                         const MatrixHomogeneous &Mdes,
-                         const Vector &faNufafbDes) {
+                                const MatrixHomogeneous &Mdes,
+                                const Vector &faNufafbDes) {
   (void)M;
   MatrixTwist X;
   buildFrom(Mdes.inverse(Eigen::Affine), X);
@@ -351,6 +347,5 @@ void FeaturePose<representation>::display(std::ostream &os) const {
   }
 }
 
-
-}
-}
+} // namespace sot
+} // namespace dynamicgraph
diff --git a/include/sot/core/feature-posture.hh b/include/sot/core/feature-posture.hh
index dede94104c98979468e2cb0f128515db316a3831..fe78576d5ffb607e12df764ff8315e1ed598b12a 100644
--- a/include/sot/core/feature-posture.hh
+++ b/include/sot/core/feature-posture.hh
@@ -53,7 +53,8 @@ class SOTFEATUREPOSTURE_EXPORT FeaturePosture : public FeatureAbstract {
 
 public:
   typedef dynamicgraph::SignalPtr<dynamicgraph::Vector, int> signalIn_t;
-  typedef dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> signalOut_t;
+  typedef dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int>
+      signalOut_t;
 
   DECLARE_NO_REFERENCE;
 
@@ -65,7 +66,8 @@ public:
 protected:
   virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int);
   virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int);
-  virtual dynamicgraph::Vector &computeErrorDot(dynamicgraph::Vector &res, int time);
+  virtual dynamicgraph::Vector &computeErrorDot(dynamicgraph::Vector &res,
+                                                int time);
 
   signalIn_t state_;
   signalIn_t posture_;
diff --git a/include/sot/core/feature-task.hh b/include/sot/core/feature-task.hh
index d1f33f40a0d66c73cb94d601f33bb3cdde3e69f8..d4f1912cdd25c0fe397571f462b28a570a574a0d 100644
--- a/include/sot/core/feature-task.hh
+++ b/include/sot/core/feature-task.hh
@@ -40,7 +40,6 @@
 namespace dynamicgraph {
 namespace sot {
 
-
 class SOTFEATURETASK_EXPORT FeatureTask : public FeatureGeneric {
 
 public:
diff --git a/include/sot/core/feature-vector3.hh b/include/sot/core/feature-vector3.hh
index 43402f531c45b40728577d106fe6b25db108d579..7ed5e5e75eb3001e2dbca06e2bb72503297568dc 100644
--- a/include/sot/core/feature-vector3.hh
+++ b/include/sot/core/feature-vector3.hh
@@ -70,8 +70,10 @@ public:
 
   virtual unsigned int &getDimension(unsigned int &dim, int time);
 
-  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time);
-  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time);
+  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res,
+                                             int time);
+  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res,
+                                                int time);
 
   virtual void display(std::ostream &os) const;
 };
diff --git a/include/sot/core/feature-visual-point.hh b/include/sot/core/feature-visual-point.hh
index ffdc37c5f6041608957d9bf2b23fe42883c95b55..9212bf149f44cb0717bf815366bcc5885b16e4cb 100644
--- a/include/sot/core/feature-visual-point.hh
+++ b/include/sot/core/feature-visual-point.hh
@@ -74,8 +74,10 @@ public:
 
   virtual unsigned int &getDimension(unsigned int &dim, int time);
 
-  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res, int time);
-  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res, int time);
+  virtual dynamicgraph::Vector &computeError(dynamicgraph::Vector &res,
+                                             int time);
+  virtual dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &res,
+                                                int time);
 
   /** Static Feature selection. */
   inline static Flags selectX(void) { return FLAG_LINE_1; }
diff --git a/include/sot/core/fir-filter.hh b/include/sot/core/fir-filter.hh
index 3e563b36e747aa8e4833f5c3b2e865d1bcb84e87..4dc9db35b1e5822bac7800a4455239823e34e29b 100644
--- a/include/sot/core/fir-filter.hh
+++ b/include/sot/core/fir-filter.hh
@@ -21,7 +21,6 @@
 #include <dynamic-graph/command-setter.h>
 #include <dynamic-graph/entity.h>
 
-
 namespace dynamicgraph {
 namespace sot {
 
diff --git a/include/sot/core/gradient-ascent.hh b/include/sot/core/gradient-ascent.hh
index 8eff01ba5acaf21bbeeb901ee479077695520e02..40df988a4333a6133330ffe227b9e91d38e533a8 100644
--- a/include/sot/core/gradient-ascent.hh
+++ b/include/sot/core/gradient-ascent.hh
@@ -18,7 +18,6 @@
 #include <dynamic-graph/signal-time-dependent.h>
 #include <sot/core/config.hh>
 
-
 namespace dynamicgraph {
 namespace sot {
 
diff --git a/include/sot/core/gripper-control.hh b/include/sot/core/gripper-control.hh
index 61189295a809e6c0b7f2fe19f1b292ee44cc6b60..75fef519d73fdc1fbc33159a696b403d42231537 100644
--- a/include/sot/core/gripper-control.hh
+++ b/include/sot/core/gripper-control.hh
@@ -46,7 +46,6 @@
 namespace dynamicgraph {
 namespace sot {
 
-
 /*! \brief The goal of this entity is to ensure that the maximal torque will not
  * be exceeded during a grasping task.
  * If the maximal torque is reached, then the current position of the gripper is
@@ -71,26 +70,29 @@ public:
                         const dynamicgraph::Vector &currentNormVel);
 
   //! \brief
-  dynamicgraph::Vector &computeDesiredPosition(const dynamicgraph::Vector &currentPos,
-                                     const dynamicgraph::Vector &desiredPos,
-                                     const dynamicgraph::Vector &torques,
-                                     const dynamicgraph::Vector &torqueLimits,
-                                     dynamicgraph::Vector &referencePos);
+  dynamicgraph::Vector &
+  computeDesiredPosition(const dynamicgraph::Vector &currentPos,
+                         const dynamicgraph::Vector &desiredPos,
+                         const dynamicgraph::Vector &torques,
+                         const dynamicgraph::Vector &torqueLimits,
+                         dynamicgraph::Vector &referencePos);
 
   /*! \brief select only some of the values of the vector fullsize,
    *   based on the Flags vector.
    */
 
-  static dynamicgraph::Vector &selector(const dynamicgraph::Vector &fullsize, const Flags &selec,
-                              dynamicgraph::Vector &desPos);
+  static dynamicgraph::Vector &selector(const dynamicgraph::Vector &fullsize,
+                                        const Flags &selec,
+                                        dynamicgraph::Vector &desPos);
 };
 
 /* --------------------------------------------------------------------- */
 /* --- PLUGIN ---------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
 
-class SOTGRIPPERCONTROL_EXPORT GripperControlPlugin : public dynamicgraph::Entity,
-                                                      public GripperControl {
+class SOTGRIPPERCONTROL_EXPORT GripperControlPlugin
+    : public dynamicgraph::Entity,
+      public GripperControl {
   DYNAMIC_GRAPH_ENTITY_DECL();
 
 public:
@@ -113,14 +115,17 @@ public: /* --- SIGNAL --- */
 
   /* --- INTERMEDIARY --- */
   dynamicgraph::SignalPtr<dynamicgraph::Vector, int> positionFullSizeSIN;
-  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> positionReduceSOUT;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int>
+      positionReduceSOUT;
   dynamicgraph::SignalPtr<dynamicgraph::Vector, int> torqueFullSizeSIN;
   dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> torqueReduceSOUT;
   dynamicgraph::SignalPtr<dynamicgraph::Vector, int> torqueLimitFullSizeSIN;
-  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> torqueLimitReduceSOUT;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int>
+      torqueLimitReduceSOUT;
 
   /* --- OUTPUTS --- */
-  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> desiredPositionSOUT;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int>
+      desiredPositionSOUT;
 
 public: /* --- COMMANDLINE --- */
   void initCommands();
diff --git a/include/sot/core/integrator-abstract-impl.hh b/include/sot/core/integrator-abstract-impl.hh
index 25df9ee43fef2e0347b7392612fab7d5b7a22dbb..9054fecbe2740ce01f9fc3750d1c26fcd02c6384 100644
--- a/include/sot/core/integrator-abstract-impl.hh
+++ b/include/sot/core/integrator-abstract-impl.hh
@@ -46,7 +46,8 @@
 namespace dynamicgraph {
 namespace sot {
 DECLARE_SPECIFICATION(IntegratorAbstractDouble, double, double)
-DECLARE_SPECIFICATION(IntegratorAbstractVector, dynamicgraph::Vector, dynamicgraph::Matrix)
+DECLARE_SPECIFICATION(IntegratorAbstractVector, dynamicgraph::Vector,
+                      dynamicgraph::Matrix)
 } // namespace sot
 } // namespace dynamicgraph
 #endif // #ifndef  __SOT_MAILBOX_HH
diff --git a/include/sot/core/integrator-euler.hh b/include/sot/core/integrator-euler.hh
index e808c9b3123c4ad5880641c3e7afcd4552bb1b63..3b55fdf2401b4b2e32411b67c9b02aa83654704a 100644
--- a/include/sot/core/integrator-euler.hh
+++ b/include/sot/core/integrator-euler.hh
@@ -151,8 +151,9 @@ public:
 
   sigT &derivative(sigT &res, int time) {
     if (outputMemory.size() < 2)
-      throw dynamicgraph::ExceptionSignal(dynamicgraph::ExceptionSignal::GENERIC,
-                                "Integrator does not compute the derivative.");
+      throw dynamicgraph::ExceptionSignal(
+          dynamicgraph::ExceptionSignal::GENERIC,
+          "Integrator does not compute the derivative.");
 
     SOUT.recompute(time);
     res = outputMemory[1];
diff --git a/include/sot/core/joint-limitator.hh b/include/sot/core/joint-limitator.hh
index e3cce324402049073f8c808d3b4d97531ca93d5a..efb1e91475e0d991380e5b6f3d184abb771b67ce 100644
--- a/include/sot/core/joint-limitator.hh
+++ b/include/sot/core/joint-limitator.hh
@@ -41,8 +41,10 @@ public:
   JointLimitator(const std::string &name);
   virtual ~JointLimitator() {}
 
-  virtual dynamicgraph::Vector &computeControl(dynamicgraph::Vector &res, int time);
-  dynamicgraph::Vector &computeWidthJl(dynamicgraph::Vector &res, const int &time);
+  virtual dynamicgraph::Vector &computeControl(dynamicgraph::Vector &res,
+                                               int time);
+  dynamicgraph::Vector &computeWidthJl(dynamicgraph::Vector &res,
+                                       const int &time);
 
   virtual void display(std::ostream &os) const;
 
diff --git a/include/sot/core/joint-trajectory-entity.hh b/include/sot/core/joint-trajectory-entity.hh
index 91a7aa75555d5e48599c50c439cb68727b642662..d674e1322a5fb4a20522043b442ab3779285e54a 100644
--- a/include/sot/core/joint-trajectory-entity.hh
+++ b/include/sot/core/joint-trajectory-entity.hh
@@ -57,7 +57,8 @@ public:
   void loadFile(const std::string &name);
 
   /// \brief Return the next pose for the legs.
-  dynamicgraph::Vector &getNextPosition(dynamicgraph::Vector &pos, const int &time);
+  dynamicgraph::Vector &getNextPosition(dynamicgraph::Vector &pos,
+                                        const int &time);
 
   /// \brief Return the next com.
   dynamicgraph::Vector &getNextCoM(dynamicgraph::Vector &com, const int &time);
diff --git a/include/sot/core/mailbox.hh b/include/sot/core/mailbox.hh
index 0aab925afb83ab1108ba251ac4b4224ba60ad5b5..998ff45b21fbee6b01694625d423d8b26754edc5 100644
--- a/include/sot/core/mailbox.hh
+++ b/include/sot/core/mailbox.hh
@@ -31,7 +31,6 @@
 namespace dynamicgraph {
 namespace sot {
 
-
 template <class Object> class Mailbox : public dynamicgraph::Entity {
 public:
   static const std::string CLASS_NAME;
diff --git a/include/sot/core/motion-period.hh b/include/sot/core/motion-period.hh
index 25ff16cd28870ba2257293b20d832ebed3877e1c..4adbf274cb6f4c7574d64e3f42d9783d44082c99 100644
--- a/include/sot/core/motion-period.hh
+++ b/include/sot/core/motion-period.hh
@@ -46,7 +46,6 @@
 namespace dynamicgraph {
 namespace sot {
 
-
 class SOTMOTIONPERIOD_EXPORT MotionPeriod : public dynamicgraph::Entity {
 
 public:
@@ -77,7 +76,8 @@ public:
   MotionPeriod(const std::string &name);
   virtual ~MotionPeriod(void) {}
 
-  dynamicgraph::Vector &computeMotion(dynamicgraph::Vector &res, const int &time);
+  dynamicgraph::Vector &computeMotion(dynamicgraph::Vector &res,
+                                      const int &time);
 
   virtual void display(std::ostream &os) const;
 };
diff --git a/include/sot/core/neck-limitation.hh b/include/sot/core/neck-limitation.hh
index 23c593229a97469297b11a6768b86762ec98d6fd..3d0a1abf9ffd6d274a82bac4f6db32e43074e0d6 100644
--- a/include/sot/core/neck-limitation.hh
+++ b/include/sot/core/neck-limitation.hh
@@ -48,7 +48,6 @@
 namespace dynamicgraph {
 namespace sot {
 
-
 class NeckLimitation_EXPORT NeckLimitation : public dynamicgraph::Entity {
 public:
   static const std::string CLASS_NAME;
@@ -76,8 +75,9 @@ public: /* --- SIGNAL --- */
   dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> jointSOUT;
 
 public: /* --- FUNCTIONS --- */
-  dynamicgraph::Vector &computeJointLimitation(dynamicgraph::Vector &jointLimited,
-                                     const int &timeSpec);
+  dynamicgraph::Vector &
+  computeJointLimitation(dynamicgraph::Vector &jointLimited,
+                         const int &timeSpec);
 
 public: /* --- PARAMS --- */
   virtual void display(std::ostream &os) const;
diff --git a/include/sot/core/op-point-modifier.hh b/include/sot/core/op-point-modifier.hh
index 809c0dfd3378deec5fd1be8f6a434f6a4ec51be8..d0de4871d7b65295b0a3462489273335b853ad75 100644
--- a/include/sot/core/op-point-modifier.hh
+++ b/include/sot/core/op-point-modifier.hh
@@ -61,7 +61,8 @@ public:
   OpPointModifier(const std::string &name);
   virtual ~OpPointModifier(void) {}
 
-  dynamicgraph::Matrix &jacobianSOUT_function(dynamicgraph::Matrix &res, const int &time);
+  dynamicgraph::Matrix &jacobianSOUT_function(dynamicgraph::Matrix &res,
+                                              const int &time);
   MatrixHomogeneous &positionSOUT_function(MatrixHomogeneous &res,
                                            const int &time);
   void setTransformation(const Eigen::Matrix4d &tr);
diff --git a/include/sot/core/parameter-server.hh b/include/sot/core/parameter-server.hh
index c6e858a52da6b7c133630e157b47cbe0c82d34dd..1275f0eafdabd76b955234a793d637425ea2cdc3 100644
--- a/include/sot/core/parameter-server.hh
+++ b/include/sot/core/parameter-server.hh
@@ -60,7 +60,7 @@ public:
   /* --- CONSTRUCTOR ---- */
   ParameterServer(const std::string &name);
 
-  ~ParameterServer() {};
+  ~ParameterServer(){};
 
   /// Initialize
   /// @param dt: control interval
diff --git a/include/sot/core/reader.hh b/include/sot/core/reader.hh
index 7c216aea5ddb33278313be31687101de8559f02d..fee84b2254579d287d9816286ed61dc65d199a4b 100644
--- a/include/sot/core/reader.hh
+++ b/include/sot/core/reader.hh
@@ -17,7 +17,6 @@
 /* Matrix */
 #include <dynamic-graph/linear-algebra.h>
 
-
 /* STD */
 #include <boost/function.hpp>
 #include <fstream>
@@ -80,8 +79,10 @@ protected:
 
   int rows, cols;
 
-  dynamicgraph::Vector &getNextData(dynamicgraph::Vector &res, const unsigned int time);
-  dynamicgraph::Matrix &getNextMatrix(dynamicgraph::Matrix &res, const unsigned int time);
+  dynamicgraph::Vector &getNextData(dynamicgraph::Vector &res,
+                                    const unsigned int time);
+  dynamicgraph::Matrix &getNextMatrix(dynamicgraph::Matrix &res,
+                                      const unsigned int time);
   void resize(const int &nbRow, const int &nbCol);
 
 public:
diff --git a/include/sot/core/robot-utils.hh b/include/sot/core/robot-utils.hh
index 6ddaafba9f1fd93a9c215879d89af5444026a986..7f0e1737d50c1ae89accafcc3d42d2854a2145b3 100644
--- a/include/sot/core/robot-utils.hh
+++ b/include/sot/core/robot-utils.hh
@@ -18,7 +18,6 @@
 #include <map>
 #include <sot/core/matrix-geometry.hh>
 
-
 namespace dynamicgraph {
 namespace sot {
 
@@ -55,7 +54,8 @@ struct SOT_CORE_EXPORT ForceUtil {
 
   void set_name_to_force_id(const std::string &name, const Index &force_id);
 
-  void set_force_id_to_limits(const Index &force_id, const dynamicgraph::Vector &lf,
+  void set_force_id_to_limits(const Index &force_id,
+                              const dynamicgraph::Vector &lf,
                               const dynamicgraph::Vector &uf);
 
   void create_force_id_to_name_map();
@@ -244,7 +244,7 @@ RobotUtilShrPtr RefVoidRobotUtil();
 RobotUtilShrPtr getRobotUtil(std::string &robotName);
 bool isNameInRobotUtil(std::string &robotName);
 RobotUtilShrPtr createRobotUtil(std::string &robotName);
-std::shared_ptr< std::vector<std::string> > getListOfRobots();
+std::shared_ptr<std::vector<std::string> > getListOfRobots();
 
 bool base_se3_to_sot(ConstRefVector pos, ConstRefMatrix R, RefVector q_sot);
 
diff --git a/include/sot/core/seq-play.hh b/include/sot/core/seq-play.hh
index 6be8ca4e30324d8fe714cde0df4eb8adfcc245bd..fb7dd5ef988d3666ee40a82ef050af6d1ad74ab8 100644
--- a/include/sot/core/seq-play.hh
+++ b/include/sot/core/seq-play.hh
@@ -64,7 +64,8 @@ public:
 
   void loadFile(const std::string &name);
 
-  dynamicgraph::Vector &getNextPosition(dynamicgraph::Vector &pos, const int &time);
+  dynamicgraph::Vector &getNextPosition(dynamicgraph::Vector &pos,
+                                        const int &time);
 
 public: /* --- DISPLAY --- */
   virtual void display(std::ostream &os) const;
diff --git a/include/sot/core/seqplay.hh b/include/sot/core/seqplay.hh
index 6be8ca4e30324d8fe714cde0df4eb8adfcc245bd..fb7dd5ef988d3666ee40a82ef050af6d1ad74ab8 100644
--- a/include/sot/core/seqplay.hh
+++ b/include/sot/core/seqplay.hh
@@ -64,7 +64,8 @@ public:
 
   void loadFile(const std::string &name);
 
-  dynamicgraph::Vector &getNextPosition(dynamicgraph::Vector &pos, const int &time);
+  dynamicgraph::Vector &getNextPosition(dynamicgraph::Vector &pos,
+                                        const int &time);
 
 public: /* --- DISPLAY --- */
   virtual void display(std::ostream &os) const;
diff --git a/include/sot/core/smooth-reach.hh b/include/sot/core/smooth-reach.hh
index 5848bb190396726d9b5eb9b70325bd85890dc1ed..3f64dbc5e805cf72d898e826a275161ae4eb133c 100644
--- a/include/sot/core/smooth-reach.hh
+++ b/include/sot/core/smooth-reach.hh
@@ -38,7 +38,6 @@
 namespace dynamicgraph {
 namespace sot {
 
-
 /* --------------------------------------------------------------------- */
 /* --- CLASS ----------------------------------------------------------- */
 /* --------------------------------------------------------------------- */
@@ -66,7 +65,8 @@ public: /* --- SIGNAL --- */
   dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> goalSOUT;
 
 public: /* --- FUNCTION --- */
-  dynamicgraph::Vector &goalSOUT_function(dynamicgraph::Vector &goal, const int &time);
+  dynamicgraph::Vector &goalSOUT_function(dynamicgraph::Vector &goal,
+                                          const int &time);
 
   void set(const dynamicgraph::Vector &goal, const int &length);
   const dynamicgraph::Vector &getGoal(void);
diff --git a/include/sot/core/sot.hh b/include/sot/core/sot.hh
index 0675735714fe93e40139305a053746d17e81144b..30d3ba0c2ff30eb6bd43b75bceea1da7db367397 100644
--- a/include/sot/core/sot.hh
+++ b/include/sot/core/sot.hh
@@ -158,7 +158,8 @@ public: /* --- CONTROL --- */
   */
 
   /*! \brief Compute the control law. */
-  virtual dynamicgraph::Vector &computeControlLaw(dynamicgraph::Vector &control, const int &time);
+  virtual dynamicgraph::Vector &computeControlLaw(dynamicgraph::Vector &control,
+                                                  const int &time);
 
   /*! @} */
 
diff --git a/include/sot/core/task.hh b/include/sot/core/task.hh
index 7417a0342be22b0656b9daa1a7aaafde19d2bfe2..53bbfb9b5d27a5bccdebd67e9fdc7851ff378e72 100644
--- a/include/sot/core/task.hh
+++ b/include/sot/core/task.hh
@@ -101,7 +101,8 @@ public:
   VectorMultiBound &computeTaskExponentialDecrease(VectorMultiBound &errorRef,
                                                    int time);
   dynamicgraph::Matrix &computeJacobian(dynamicgraph::Matrix &J, int time);
-  dynamicgraph::Vector &computeErrorTimeDerivative(dynamicgraph::Vector &res, int time);
+  dynamicgraph::Vector &computeErrorTimeDerivative(dynamicgraph::Vector &res,
+                                                   int time);
 
   /* --- SIGNALS ------------------------------------------------------------ */
 public:
@@ -109,7 +110,8 @@ public:
   dynamicgraph::SignalPtr<double, int> dampingGainSINOUT;
   dynamicgraph::SignalPtr<Flags, int> controlSelectionSIN;
   dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> errorSOUT;
-  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int> errorTimeDerivativeSOUT;
+  dynamicgraph::SignalTimeDependent<dynamicgraph::Vector, int>
+      errorTimeDerivativeSOUT;
 
   /* --- DISPLAY ------------------------------------------------------------ */
   void display(std::ostream &os) const;
diff --git a/include/sot/core/time-stamp.hh b/include/sot/core/time-stamp.hh
index 93b3d9918fd21dfff98aee577289f36d8433f4f6..ceb6c6967962d2df0b19de6d8eae41a29058f059 100644
--- a/include/sot/core/time-stamp.hh
+++ b/include/sot/core/time-stamp.hh
@@ -79,7 +79,8 @@ public: /* --- SIGNALS --- */
   dynamicgraph::SignalTimeDependent<double, int> timeOnceDoubleSOUT;
 
 protected: /* --- SIGNAL FUNCTIONS --- */
-  dynamicgraph::Vector &getTimeStamp(dynamicgraph::Vector &res, const int &time);
+  dynamicgraph::Vector &getTimeStamp(dynamicgraph::Vector &res,
+                                     const int &time);
   double &getTimeStampDouble(const dynamicgraph::Vector &vect, double &res);
 };
 
diff --git a/include/sot/core/trajectory.hh b/include/sot/core/trajectory.hh
index b6957f8e17c2dc95f7fa11c7d223acf9fcf6ae03..6f05c6e2f58c458f903f8dc1ebd96a31ed02f5c2 100644
--- a/include/sot/core/trajectory.hh
+++ b/include/sot/core/trajectory.hh
@@ -17,7 +17,6 @@
 #include <boost/assign/list_of.hpp>
 #include <boost/regex.hpp>
 
-
 namespace dynamicgraph {
 namespace sot {
 
@@ -121,8 +120,8 @@ public:
   typedef std::vector<double> vec_ref;
 
   void display(std::ostream &os) const {
-    boost::array<std::string, 4> names =
-        boost::assign::list_of("Positions")("Velocities")("Accelerations")("Effort");
+    boost::array<std::string, 4> names = boost::assign::list_of("Positions")(
+        "Velocities")("Accelerations")("Effort");
 
     const std::vector<double> *points = 0;
 
diff --git a/include/sot/core/vector-to-rotation.hh b/include/sot/core/vector-to-rotation.hh
index 9a4bb2aeb5ef73d9c9f5fb2933240f02ff3174df..bfe22e70c729796320fec6c0cea253cd5b5bc215 100644
--- a/include/sot/core/vector-to-rotation.hh
+++ b/include/sot/core/vector-to-rotation.hh
@@ -40,7 +40,8 @@
 namespace dynamicgraph {
 namespace sot {
 
-class SOTVECTORTOROTATION_EXPORT VectorToRotation : public dynamicgraph::Entity {
+class SOTVECTORTOROTATION_EXPORT VectorToRotation
+    : public dynamicgraph::Entity {
   static const std::string CLASS_NAME;
   virtual const std::string &getClassName(void) const { return CLASS_NAME; }
 
diff --git a/src/feature/feature-pose.cpp b/src/feature/feature-pose.cpp
index f328281c41ce40c886d2ebe0639585d51d9c717b..d76605e53d624ed9648ac720997fc72d4df9dd69 100644
--- a/src/feature/feature-pose.cpp
+++ b/src/feature/feature-pose.cpp
@@ -41,5 +41,5 @@ namespace dynamicgraph {
 namespace sot {
 template class FeaturePose<R3xSO3Representation>;
 template class FeaturePose<SE3Representation>;
-}
-}
+} // namespace sot
+} // namespace dynamicgraph
diff --git a/src/sot/sot.cpp b/src/sot/sot.cpp
index 817b50f08007e6103932481f3a2599bdf84d0f35..01a5c8a4a300f97d03bba22ece5d76f96bc2c063 100644
--- a/src/sot/sot.cpp
+++ b/src/sot/sot.cpp
@@ -505,8 +505,9 @@ dynamicgraph::Vector &Sot::computeControlLaw(dynamicgraph::Vector &control,
       makeMap(kernel, K);
       has_kernel = true;
     } else {
-      DYNAMIC_GRAPH_ENTITY_ERROR_STREAM(*this) << "Projector of " << getName()
-        << " has " << K.rows() << " rows while " << nbJoints << " expected.\n";
+      DYNAMIC_GRAPH_ENTITY_ERROR_STREAM(*this)
+          << "Projector of " << getName() << " has " << K.rows()
+          << " rows while " << nbJoints << " expected.\n";
     }
   }
   for (StackType::iterator iter = stack.begin(); iter != stack.end(); ++iter) {
diff --git a/src/tools/parameter-server.cpp b/src/tools/parameter-server.cpp
index 4370130899aee0f9212a6de28c4dec41a41306b4..1ac3b080730eeaa20b67e473f14621ea755e5ebc 100644
--- a/src/tools/parameter-server.cpp
+++ b/src/tools/parameter-server.cpp
@@ -61,11 +61,11 @@ ParameterServer::ParameterServer(const std::string &name)
                                               "Time period in seconds (double)",
                                               "URDF file path (string)",
                                               "Robot reference (string)")));
-  addCommand("init_simple",
-             makeCommandVoid1(*this, &ParameterServer::init_simple,
-                              docCommandVoid1("Initialize the entity.",
-                                              "Time period in seconds (double)"
-                                              )));
+  addCommand(
+      "init_simple",
+      makeCommandVoid1(*this, &ParameterServer::init_simple,
+                       docCommandVoid1("Initialize the entity.",
+                                       "Time period in seconds (double)")));
 
   addCommand("setNameToId",
              makeCommandVoid2(*this, &ParameterServer::setNameToId,
@@ -144,7 +144,7 @@ ParameterServer::ParameterServer(const std::string &name)
                                      "(string) ParameterName")));
 }
 
-void ParameterServer::init_simple(const double & dt) {
+void ParameterServer::init_simple(const double &dt) {
 
   if (dt <= 0.0)
     return SEND_MSG("Timestep must be positive", MSG_TYPE_ERROR);
@@ -155,10 +155,10 @@ void ParameterServer::init_simple(const double & dt) {
   m_initSucceeded = true;
 
   std::string localName("robot");
-  std::shared_ptr< std::vector<std::string> >
-      listOfRobots = sot::getListOfRobots();
+  std::shared_ptr<std::vector<std::string> > listOfRobots =
+      sot::getListOfRobots();
 
-  if (listOfRobots->size()==1)
+  if (listOfRobots->size() == 1)
     localName = (*listOfRobots)[0];
   else {
     throw ExceptionTools(ExceptionTools::ErrorCodeEnum::PARAMETER_SERVER,
@@ -176,7 +176,6 @@ void ParameterServer::init_simple(const double & dt) {
       makeDirectGetter(*this, &m_robot_util->m_dgv_urdf_to_sot,
                        docDirectSetter("Display map Joints From URDF to SoT.",
                                        "Vector of integer for mapping")));
-
 }
 
 void ParameterServer::init(const double &dt, const std::string &urdfFile,
@@ -195,7 +194,6 @@ void ParameterServer::init(const double &dt, const std::string &urdfFile,
   }
 
   m_robot_util->m_urdf_filename = urdfFile;
-
 }
 
 /* ------------------------------------------------------------------- */
diff --git a/src/tools/robot-utils.cpp b/src/tools/robot-utils.cpp
index fbc545825b0c0395b62dc1718e5d58ac03f11ec9..565b8d8c3f335a7c0f526c9d4a6025d440808a00 100644
--- a/src/tools/robot-utils.cpp
+++ b/src/tools/robot-utils.cpp
@@ -438,18 +438,17 @@ bool base_sot_to_urdf(ConstRefVector q_sot, RefVector q_urdf) {
 
 std::map<std::string, RobotUtilShrPtr> sgl_map_name_to_robot_util;
 
-std::shared_ptr<std::vector<std::string> >  getListOfRobots() {
+std::shared_ptr<std::vector<std::string> > getListOfRobots() {
   std::shared_ptr<std::vector<std::string> > res =
       std::make_shared<std::vector<std::string> >();
-  
+
   std::map<std::string, RobotUtilShrPtr>::iterator it =
       sgl_map_name_to_robot_util.begin();
-  while (it != sgl_map_name_to_robot_util.end())
-  {
+  while (it != sgl_map_name_to_robot_util.end()) {
     res->push_back(it->first);
     it++;
   }
-  
+
   return res;
 }
 
diff --git a/tests/features/test_feature_generic.cpp b/tests/features/test_feature_generic.cpp
index 18ad6645b5989db5695cad062a8f7f5ba4a90596..87651211ba44d56affea052ab7e056e984a21e34 100644
--- a/tests/features/test_feature_generic.cpp
+++ b/tests/features/test_feature_generic.cpp
@@ -26,8 +26,8 @@
 #include <boost/test/unit_test.hpp>
 
 #include <Eigen/SVD>
-#include <dynamic-graph/linear-algebra.h>
 #include <dynamic-graph/factory.h>
+#include <dynamic-graph/linear-algebra.h>
 #include <sot/core/debug.hh>
 #include <sot/core/feature-abstract.hh>
 #include <sot/core/feature-generic.hh>
@@ -51,9 +51,9 @@ template <Representation_t representation> struct LG_t {
   typedef typename boost::mpl::if_c<representation == SE3Representation, SE3_t,
                                     R3xSO3_t>::type type;
 };
-}
-}
-}
+} // namespace internal
+} // namespace sot
+} // namespace dynamicgraph
 
 using namespace std;
 using namespace dynamicgraph::sot;
@@ -345,7 +345,6 @@ public:
     setJointFrame();
   }
 
-
   void _setFrame() {
     setSignal(
         feature_.jaMfa,