diff --git a/.yapfignore b/.yapfignore
index 9ae923eec4431e88586b7f66c9df321120d0d215..b0370c811f1446fca215104406a41de0cce35cf9 100644
--- a/.yapfignore
+++ b/.yapfignore
@@ -1 +1 @@
-unitTesting/test_python-syntax_error.py
+tests/test_python-syntax_error.py
diff --git a/cmake b/cmake
index c333a88decb3e4c0a86947bc6c7f072dc5c5df20..fb4c22c319ec5320f9a85527eb1a4130954846f5 160000
--- a/cmake
+++ b/cmake
@@ -1 +1 @@
-Subproject commit c333a88decb3e4c0a86947bc6c7f072dc5c5df20
+Subproject commit fb4c22c319ec5320f9a85527eb1a4130954846f5
diff --git a/package.xml b/package.xml
index df7b292b25b6fee87ff9ce61ce236baad9ded96d..9b2850de6a66d1889e9169925983878d16fb2d5d 100644
--- a/package.xml
+++ b/package.xml
@@ -1,7 +1,7 @@
 <?xml version="1.0"?>
 <package format="3">
   <name>dynamic-graph-python</name>
-  <version>3.5.2</version>
+  <version>3.5.3</version>
   <description>
     Dynamic graph library Python bindings
   </description>
diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt
index 489c9322d9638bc3265ab9bbdc3e3d4cc587999e..b8cf40d3eedd630f6dbe398e3772f5ed366a9e0f 100644
--- a/src/CMakeLists.txt
+++ b/src/CMakeLists.txt
@@ -16,7 +16,6 @@ FOREACH(source ${PYTHON_SOURCES})
 ENDFOREACH(source)
 
 # --- ADD the wrap on the dg modules
-LINK_DIRECTORIES(${DYNAMIC_GRAPH_PLUGINDIR})
 DYNAMIC_GRAPH_PYTHON_MODULE("tracer" dynamic-graph::tracer tracer-wrap)
 DYNAMIC_GRAPH_PYTHON_MODULE("tracer_real_time" dynamic-graph::tracer-real-time
   tracer_real_time-wrap)
diff --git a/src/dynamic_graph/debug-py.cc b/src/dynamic_graph/debug-py.cc
index 503fb4177632ad813a3bd8977594f3c7513e6c92..e612f0d2858bb1527749968d2e66e1c0d24c9f8d 100644
--- a/src/dynamic_graph/debug-py.cc
+++ b/src/dynamic_graph/debug-py.cc
@@ -22,8 +22,8 @@ namespace dynamicgraph {
 namespace python {
 
 #if PY_MAJOR_VERSION == 2
-  extern PyObject* dgpyError;
-# endif
+extern PyObject* dgpyError;
+#endif
 
 namespace debug {
 
@@ -35,7 +35,7 @@ PyObject* addLoggerFileOutputStream(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   char* filename;
   if (!PyArg_ParseTuple(args, "s", &filename)) return NULL;
   std::string sfilename(filename);
@@ -58,7 +58,7 @@ PyObject* closeLoggerFileOutputStream(
 #else
     PyObject*, PyObject*
 #endif
-    ) {
+) {
   try {
     for (std::map<std::string, ofstreamShrPtr>::iterator it = mapOfFiles_.begin(); it != mapOfFiles_.end(); ++it) {
       it->second->close();
@@ -74,7 +74,7 @@ PyObject* addLoggerCoutOutputStream(
 #else
     PyObject*, PyObject*
 #endif
-    ) {
+) {
   try {
     dgADD_OSTREAM_TO_RTLOG(std::cout);
   }
@@ -88,7 +88,7 @@ PyObject* realTimeLoggerDestroy(
 #else
     PyObject*, PyObject*
 #endif
-    ) {
+) {
   try {
     RealTimeLogger::destroy();
   }
@@ -102,7 +102,7 @@ PyObject* realTimeLoggerSpinOnce(
 #else
     PyObject*, PyObject*
 #endif
-    ) {
+) {
   try {
     RealTimeLogger::instance().spinOnce();
   }
@@ -116,7 +116,7 @@ PyObject* realTimeLoggerInstance(
 #else
     PyObject*, PyObject*
 #endif
-    ) {
+) {
   try {
     RealTimeLogger::instance();
   }
diff --git a/src/dynamic_graph/dynamic-graph-py.cc b/src/dynamic_graph/dynamic-graph-py.cc
index 6a9d26cc6420e7f4b33628c5df61de9bdf55e22a..e26b8bdc1abeb337f8462c900de1bc8f968e0c87 100644
--- a/src/dynamic_graph/dynamic-graph-py.cc
+++ b/src/dynamic_graph/dynamic-graph-py.cc
@@ -15,8 +15,8 @@ namespace dynamicgraph {
 namespace python {
 
 #if PY_MAJOR_VERSION == 2
-  PyObject* dgpyError;
-# endif
+PyObject* dgpyError;
+#endif
 
 /**
    \brief plug a signal into another one.
@@ -27,7 +27,7 @@ PyObject* plug(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   PyObject* objOut = NULL;
   PyObject* objIn = NULL;
   void* pObjOut;
@@ -51,20 +51,20 @@ PyObject* plug(
   pObjIn = PyCapsule_GetPointer(objIn, "dynamic_graph.Signal");
   SignalBase<int>* signalIn = (SignalBase<int>*)pObjIn;
   if (signalIn == NULL) {
-      std::ostringstream oss;
-      oss << "dynamic_graph.plug(a, b): Argument 'b' must be of type 'dynamic_graph.Signal', but got "
-          << PyCapsule_GetName(objIn);
-      PyErr_SetString(PyExc_TypeError, oss.str().c_str());
-      return NULL;
+    std::ostringstream oss;
+    oss << "dynamic_graph.plug(a, b): Argument 'b' must be of type 'dynamic_graph.Signal', but got "
+        << PyCapsule_GetName(objIn);
+    PyErr_SetString(PyExc_TypeError, oss.str().c_str());
+    return NULL;
   }
   pObjOut = PyCapsule_GetPointer(objOut, "dynamic_graph.Signal");
   SignalBase<int>* signalOut = (SignalBase<int>*)pObjOut;
   if (signalOut == NULL) {
-      std::ostringstream oss;
-      oss << "dynamic_graph.plug(a, b): Argument 'a' must be of type 'dynamic_graph.Signal', but got "
-          << PyCapsule_GetName(objOut);
-      PyErr_SetString(PyExc_TypeError, oss.str().c_str());
-      return NULL;
+    std::ostringstream oss;
+    oss << "dynamic_graph.plug(a, b): Argument 'a' must be of type 'dynamic_graph.Signal', but got "
+        << PyCapsule_GetName(objOut);
+    PyErr_SetString(PyExc_TypeError, oss.str().c_str());
+    return NULL;
   }
   std::ostringstream os;
 
@@ -81,7 +81,7 @@ PyObject* enableTrace(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   PyObject* boolean;
   char* filename = NULL;
 
diff --git a/src/dynamic_graph/entity-py.cc b/src/dynamic_graph/entity-py.cc
index 41c4cad69fe1fc545a2301123fc4a02ce620e711..b8f2c2441d91929ae2a27dbc904f72622045efd5 100644
--- a/src/dynamic_graph/entity-py.cc
+++ b/src/dynamic_graph/entity-py.cc
@@ -33,8 +33,8 @@ namespace python {
 using namespace convert;
 
 #if PY_MAJOR_VERSION == 2
-  extern PyObject* dgpyError;
-# endif
+extern PyObject* dgpyError;
+#endif
 
 namespace entity {
 
@@ -47,7 +47,7 @@ PyObject* create(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   char* className = NULL;
   char* instanceName = NULL;
 
@@ -85,7 +85,7 @@ PyObject* getName(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   PyObject* object = NULL;
   void* pointer = NULL;
   std::string name;
@@ -115,7 +115,7 @@ PyObject* getClassName(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   PyObject* object = NULL;
   void* pointer = NULL;
   std::string name;
@@ -145,7 +145,7 @@ PyObject* hasSignal(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   char* name = NULL;
   PyObject* object = NULL;
   void* pointer = NULL;
@@ -181,7 +181,7 @@ PyObject* getSignal(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   char* name = NULL;
   PyObject* object = NULL;
   void* pointer = NULL;
@@ -213,7 +213,7 @@ PyObject* listSignals(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   void* pointer = NULL;
   PyObject* object = NULL;
 
@@ -246,9 +246,9 @@ PyObject* executeCommand(
 #if PY_MAJOR_VERSION >= 3
     PyObject* m, PyObject* args
 #else
-    PyObject* , PyObject* args
+    PyObject*, PyObject* args
 #endif
-    ) {
+) {
   PyObject* object = NULL;
   PyObject* argTuple = NULL;
   char* commandName = NULL;
@@ -344,7 +344,7 @@ PyObject* getCommandDocstring(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   PyObject* object = NULL;
   char* commandName;
   if (!PyArg_ParseTuple(args, "Os", &object, &commandName)) {
@@ -380,7 +380,7 @@ PyObject* getDocString(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   PyObject* object = NULL;
   if (!PyArg_ParseTuple(args, "O", &object)) {
     return NULL;
@@ -411,7 +411,7 @@ PyObject* display(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   /* Retrieve the entity instance. */
   PyObject* object = NULL;
   if (!PyArg_ParseTuple(args, "O", &object) || (!PyCapsule_CheckExact(object))) {
@@ -438,7 +438,7 @@ PyObject* setLoggerVerbosityLevel(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   PyObject* object = NULL;
   PyObject* objectVerbosityLevel = NULL;
   if (!PyArg_ParseTuple(args, "OO", &object, &objectVerbosityLevel)) return NULL;
@@ -500,7 +500,7 @@ PyObject* getLoggerVerbosityLevel(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   PyObject* object = NULL;
   if (!PyArg_ParseTuple(args, "O", &object)) return NULL;
 
@@ -532,7 +532,7 @@ PyObject* getStreamPrintPeriod(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   PyObject* object = NULL;
   if (!PyArg_ParseTuple(args, "O", &object)) return NULL;
 
@@ -563,7 +563,7 @@ PyObject* setStreamPrintPeriod(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   PyObject* object = NULL;
   double streamPrintPeriod = 0;
   if (!PyArg_ParseTuple(args, "Od", &object, &streamPrintPeriod)) return NULL;
@@ -603,7 +603,7 @@ PyObject* getTimeSample(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   PyObject* object = NULL;
   if (!PyArg_ParseTuple(args, "O", &object)) return NULL;
 
@@ -634,7 +634,7 @@ PyObject* setTimeSample(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   PyObject* object = NULL;
   double timeSample;
   if (!PyArg_ParseTuple(args, "Od", &object, &timeSample)) return NULL;
diff --git a/src/dynamic_graph/pool-py.cc b/src/dynamic_graph/pool-py.cc
index aecb0a8432afa55f9fcc694363096cb5b8b6f3d6..68f0ce698f3f3c9811d5b40b4642a4dcea913e8b 100644
--- a/src/dynamic_graph/pool-py.cc
+++ b/src/dynamic_graph/pool-py.cc
@@ -11,8 +11,8 @@ namespace dynamicgraph {
 namespace python {
 
 #if PY_MAJOR_VERSION == 2
-  extern PyObject* dgpyError;
-# endif
+extern PyObject* dgpyError;
+#endif
 
 namespace pool {
 
@@ -22,7 +22,7 @@ PyObject* writeGraph(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   char* filename;
   if (!PyArg_ParseTuple(args, "s", &filename)) return NULL;
   try {
@@ -41,7 +41,7 @@ PyObject* getEntityList(
 #else
     PyObject*, PyObject* args
 #endif
-  ) {
+) {
   if (!PyArg_ParseTuple(args, "")) return NULL;
 
   std::vector<std::string> entityNames;
diff --git a/src/dynamic_graph/signal-base-py.cc b/src/dynamic_graph/signal-base-py.cc
index ca11e8e71345b1a8f979f4ddb51605aed1c5d18e..743cb1f7aba7274142510503df6b4ccdc2049fc3 100644
--- a/src/dynamic_graph/signal-base-py.cc
+++ b/src/dynamic_graph/signal-base-py.cc
@@ -22,8 +22,8 @@ namespace dynamicgraph {
 namespace python {
 
 #if PY_MAJOR_VERSION == 2
-  extern PyObject* dgpyError;
-# endif
+extern PyObject* dgpyError;
+#endif
 
 using namespace convert;
 
@@ -96,7 +96,7 @@ PyObject* createSignalWrapper(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   PythonSignalContainer* psc = getPythonSignalContainer();
   if (psc == NULL) return NULL;
 
@@ -159,7 +159,7 @@ PyObject* setTime(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   void* pointer = NULL;
   PyObject* object = NULL;
   int time;
@@ -182,7 +182,7 @@ PyObject* display(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   void* pointer = NULL;
   PyObject* object = NULL;
   if (!PyArg_ParseTuple(args, "O", &object)) return NULL;
@@ -206,7 +206,7 @@ PyObject* displayDependencies(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   void* pointer = NULL;
   PyObject* object = NULL;
   int time;
@@ -230,7 +230,7 @@ PyObject* getValue(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   void* pointer = NULL;
   PyObject* object = NULL;
   if (!PyArg_ParseTuple(args, "O", &object)) return NULL;
@@ -330,7 +330,7 @@ PyObject* getName(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   void* pointer = NULL;
   PyObject* object = NULL;
   if (!PyArg_ParseTuple(args, "O", &object)) return NULL;
@@ -354,7 +354,7 @@ PyObject* getClassName(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   void* pointer = NULL;
   PyObject* object = NULL;
   if (!PyArg_ParseTuple(args, "O", &object)) return NULL;
@@ -378,7 +378,7 @@ PyObject* setValue(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   void* pointer = NULL;
   PyObject* object = NULL;
   char* valueString = NULL;
@@ -405,7 +405,7 @@ PyObject* recompute(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   void* pointer = NULL;
   PyObject* object = NULL;
   unsigned int time;
@@ -427,7 +427,7 @@ PyObject* unplug(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   void* pointer = NULL;
   PyObject* object = NULL;
   if (!PyArg_ParseTuple(args, "O", &object)) return NULL;
@@ -448,7 +448,7 @@ PyObject* isPlugged(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   void* pointer = NULL;
   PyObject* object = NULL;
   if (!PyArg_ParseTuple(args, "O", &object)) return NULL;
@@ -473,7 +473,7 @@ PyObject* getPlugged(
 #else
     PyObject*, PyObject* args
 #endif
-    ) {
+) {
   void* pointer = NULL;
   PyObject* object = NULL;
   if (!PyArg_ParseTuple(args, "O", &object)) return NULL;
diff --git a/tests/custom_entity.cpp b/tests/custom_entity.cpp
index 8df5d46465ab9203bb44208081fa76e9944538e0..90632d7ada1ad224e7466faf335c87fd39f5bdf6 100644
--- a/tests/custom_entity.cpp
+++ b/tests/custom_entity.cpp
@@ -34,8 +34,7 @@ class CustomEntity : public Entity {
 
     using namespace dynamicgraph::command;
 
-    this->addCommand("act", makeCommandVoid0( *this, &CustomEntity::act,
-          docCommandVoid0( "act on input signal")));
+    this->addCommand("act", makeCommandVoid0(*this, &CustomEntity::act, docCommandVoid0("act on input signal")));
   }
 
   void addSignal() { signalRegistration(m_sigdSIN << m_sigdTimeDepSOUT); }
@@ -49,21 +48,19 @@ class CustomEntity : public Entity {
     const double &aDouble = m_sigdSIN(inTime);
     res = aDouble;
     logger().stream(MSG_TYPE_ERROR) << "start update " << res << '\n';
-    DYNAMIC_GRAPH_ENTITY_DEBUG   (*this) << "This is a message of level MSG_TYPE_DEBUG\n";
-    DYNAMIC_GRAPH_ENTITY_INFO    (*this) << "This is a message of level MSG_TYPE_INFO\n";
-    DYNAMIC_GRAPH_ENTITY_WARNING (*this) << "This is a message of level MSG_TYPE_WARNING\n";
-    DYNAMIC_GRAPH_ENTITY_ERROR   (*this) << "This is a message of level MSG_TYPE_ERROR\n";
-    DYNAMIC_GRAPH_ENTITY_DEBUG_STREAM   (*this) << "This is a message of level MSG_TYPE_DEBUG_STREAM\n";
-    DYNAMIC_GRAPH_ENTITY_INFO_STREAM    (*this) << "This is a message of level MSG_TYPE_INFO_STREAM\n";
-    DYNAMIC_GRAPH_ENTITY_WARNING_STREAM (*this) << "This is a message of level MSG_TYPE_WARNING_STREAM\n";
-    DYNAMIC_GRAPH_ENTITY_ERROR_STREAM   (*this) << "This is a message of level MSG_TYPE_ERROR_STREAM\n";
+    DYNAMIC_GRAPH_ENTITY_DEBUG(*this) << "This is a message of level MSG_TYPE_DEBUG\n";
+    DYNAMIC_GRAPH_ENTITY_INFO(*this) << "This is a message of level MSG_TYPE_INFO\n";
+    DYNAMIC_GRAPH_ENTITY_WARNING(*this) << "This is a message of level MSG_TYPE_WARNING\n";
+    DYNAMIC_GRAPH_ENTITY_ERROR(*this) << "This is a message of level MSG_TYPE_ERROR\n";
+    DYNAMIC_GRAPH_ENTITY_DEBUG_STREAM(*this) << "This is a message of level MSG_TYPE_DEBUG_STREAM\n";
+    DYNAMIC_GRAPH_ENTITY_INFO_STREAM(*this) << "This is a message of level MSG_TYPE_INFO_STREAM\n";
+    DYNAMIC_GRAPH_ENTITY_WARNING_STREAM(*this) << "This is a message of level MSG_TYPE_WARNING_STREAM\n";
+    DYNAMIC_GRAPH_ENTITY_ERROR_STREAM(*this) << "This is a message of level MSG_TYPE_ERROR_STREAM\n";
     logger().stream(MSG_TYPE_ERROR) << "end update\n";
     return res;
   }
 
-  void act() {
-    m_sigdSIN.accessCopy();
-  }
+  void act() { m_sigdSIN.accessCopy(); }
 };
 DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(CustomEntity, "CustomEntity");
 }  // namespace dynamicgraph