From c573696d94b4eec3731cb4372d4fc51791e031de Mon Sep 17 00:00:00 2001
From: Guilhem Saurel <guilhem.saurel@laas.fr>
Date: Mon, 24 Aug 2020 10:58:55 +0200
Subject: [PATCH] Format

---
 .../dynamic-graph/python/dynamic-graph-py.hh  |  18 +-
 include/dynamic-graph/python/module.hh        |  35 +-
 .../dynamic-graph/python/signal-wrapper.hh    |   2 +-
 src/dynamic_graph/convert-dg-to-py.cc         |  12 +-
 src/dynamic_graph/debug-py.cc                 |  29 +-
 src/dynamic_graph/dynamic-graph-py.cc         | 358 ++++++++----------
 src/dynamic_graph/entity-py.cc                |  18 +-
 src/dynamic_graph/pool-py.cc                  |  19 +-
 src/dynamic_graph/signal-base-py.cc           | 140 ++++---
 src/dynamic_graph/tracer/wrap.cc              |   7 +-
 src/dynamic_graph/tracer_real_time/wrap.cc    |   7 +-
 tests/custom_entity.cpp                       |  35 +-
 12 files changed, 292 insertions(+), 388 deletions(-)

diff --git a/include/dynamic-graph/python/dynamic-graph-py.hh b/include/dynamic-graph/python/dynamic-graph-py.hh
index d5ac7bd..df7eb66 100644
--- a/include/dynamic-graph/python/dynamic-graph-py.hh
+++ b/include/dynamic-graph/python/dynamic-graph-py.hh
@@ -17,24 +17,22 @@ namespace bp = boost::python;
 namespace dynamicgraph {
 namespace python {
 
-template <typename Iterator> inline
-bp::list to_py_list(Iterator begin, Iterator end) {
+template <typename Iterator>
+inline bp::list to_py_list(Iterator begin, Iterator end) {
   typedef typename Iterator::value_type T;
   bp::list lst;
   std::for_each(begin, end, [&](const T& t) { lst.append(t); });
   return lst;
 }
 
-template <typename Iterator> inline
-bp::tuple to_py_tuple(Iterator begin, Iterator end) {
+template <typename Iterator>
+inline bp::tuple to_py_tuple(Iterator begin, Iterator end) {
   return bp::tuple(to_py_list(begin, end));
 }
 
-template<typename T> inline
-std::vector< T > to_std_vector( const bp::object& iterable )
-{
-    return std::vector< T >( bp::stl_input_iterator< T >( iterable ),
-                             bp::stl_input_iterator< T >( ) );
+template <typename T>
+inline std::vector<T> to_std_vector(const bp::object& iterable) {
+  return std::vector<T>(bp::stl_input_iterator<T>(iterable), bp::stl_input_iterator<T>());
 }
 
 void exposeSignals();
@@ -50,7 +48,7 @@ void addCommands(boost::python::object obj);
 void addSignals(boost::python::object obj);
 
 Entity* create(const char* type, const char* name);
-bp::object executeCmd (bp::tuple args, bp::dict);
+bp::object executeCmd(bp::tuple args, bp::dict);
 }  // namespace entity
 
 namespace factory {
diff --git a/include/dynamic-graph/python/module.hh b/include/dynamic-graph/python/module.hh
index 2403d5e..7933e47 100644
--- a/include/dynamic-graph/python/module.hh
+++ b/include/dynamic-graph/python/module.hh
@@ -10,41 +10,40 @@
 namespace dynamicgraph {
 namespace python {
 
-constexpr int AddSignals  = 1;
+constexpr int AddSignals = 1;
 constexpr int AddCommands = 2;
 
 namespace internal {
 
-template<typename T, int Options = AddCommands | AddSignals>
+template <typename T, int Options = AddCommands | AddSignals>
 bp::object makeEntity1(const char* name) {
   Entity* ent = entity::create(T::CLASS_NAME.c_str(), name);
   assert(dynamic_cast<T*>(ent) != NULL);
   bp::object obj(bp::ptr(static_cast<T*>(ent)));
   if (Options & AddCommands) entity::addCommands(obj);
-  if (Options & AddSignals)  entity::addSignals(obj);
+  if (Options & AddSignals) entity::addSignals(obj);
   return obj;
 }
-template<typename T, int Options = AddCommands | AddSignals>
-bp::object makeEntity2() { return makeEntity1<T, Options>(""); }
-
+template <typename T, int Options = AddCommands | AddSignals>
+bp::object makeEntity2() {
+  return makeEntity1<T, Options>("");
 }
 
+}  // namespace internal
+
 /// \tparam Options by default, all the signals and commands are added as
 ///         attribute to the Python object. This behaviour works fine for
 ///         entities that have static commands and signals.
 ///         If some commands or signals are added or removed dynamiccally, then
 ///         it is better to disable the default behaviour and handle it
 ///         specifically.
-template<typename T,
-  typename bases = boost::python::bases<dynamicgraph::Entity>,
-  int Options = AddCommands | AddSignals>
-inline auto exposeEntity ()
-{
-  //std::string hiddenClassName ("_" + T::CLASS_NAME);
-  std::string hiddenClassName (T::CLASS_NAME);
+template <typename T, typename bases = boost::python::bases<dynamicgraph::Entity>,
+          int Options = AddCommands | AddSignals>
+inline auto exposeEntity() {
+  // std::string hiddenClassName ("_" + T::CLASS_NAME);
+  std::string hiddenClassName(T::CLASS_NAME);
   namespace bp = boost::python;
-  bp::class_<T, bases, boost::noncopyable > obj (hiddenClassName.c_str(),
-      bp::init<std::string>());
+  bp::class_<T, bases, boost::noncopyable> obj(hiddenClassName.c_str(), bp::init<std::string>());
   /* TODO at the moment, I couldn't easily find a way to define a Python constructor
    * that would create the entity via the factory and then populate the
    * python object with its commands.
@@ -69,7 +68,7 @@ inline auto exposeEntity ()
   return obj;
 }
 
-} // namespace python
-} // namespace dynamicgraph
+}  // namespace python
+}  // namespace dynamicgraph
 
-#endif // DYNAMIC_GRAPH_PYTHON_MODULE_HH
+#endif  // DYNAMIC_GRAPH_PYTHON_MODULE_HH
diff --git a/include/dynamic-graph/python/signal-wrapper.hh b/include/dynamic-graph/python/signal-wrapper.hh
index cceec78..941ca97 100644
--- a/include/dynamic-graph/python/signal-wrapper.hh
+++ b/include/dynamic-graph/python/signal-wrapper.hh
@@ -39,7 +39,7 @@ class SignalWrapper : public Signal<T, Time> {
     this->setFunction(f);
   }
 
-  virtual ~SignalWrapper() {};
+  virtual ~SignalWrapper(){};
 
  private:
   T& call(T& value, Time t) {
diff --git a/src/dynamic_graph/convert-dg-to-py.cc b/src/dynamic_graph/convert-dg-to-py.cc
index f684906..b9ff9e9 100644
--- a/src/dynamic_graph/convert-dg-to-py.cc
+++ b/src/dynamic_graph/convert-dg-to-py.cc
@@ -80,13 +80,11 @@ bp::object fromValue(const command::Value& value) {
       return bp::object(value.matrixXdValue());
     case (Value::MATRIX4D):
       return bp::object(value.matrix4dValue());
-    case (Value::VALUES):
-      {
-        bp::list list;
-        for(const Value& v : value.constValuesValue())
-          list.append(fromValue(v));
-        return list;
-      }
+    case (Value::VALUES): {
+      bp::list list;
+      for (const Value& v : value.constValuesValue()) list.append(fromValue(v));
+      return list;
+    }
     case (Value::NONE):
     default:
       return bp::object();
diff --git a/src/dynamic_graph/debug-py.cc b/src/dynamic_graph/debug-py.cc
index 812ee94..dc72df8 100644
--- a/src/dynamic_graph/debug-py.cc
+++ b/src/dynamic_graph/debug-py.cc
@@ -24,8 +24,7 @@ namespace debug {
 
 std::map<std::string, ofstreamShrPtr> mapOfFiles_;
 
-void addLoggerFileOutputStream(const char* filename)
-{
+void addLoggerFileOutputStream(const char* filename) {
   std::ofstream* aofs = new std::ofstream;
   ofstreamShrPtr ofs_shrptr = boost::shared_ptr<std::ofstream>(aofs);
   aofs->open(filename, std::ofstream::out);
@@ -35,31 +34,17 @@ void addLoggerFileOutputStream(const char* filename)
   mapOfFiles_[filename] = ofs_shrptr;
 }
 
-void closeLoggerFileOutputStream()
-{
-  for (const auto& el : mapOfFiles_)
-    el.second->close();
+void closeLoggerFileOutputStream() {
+  for (const auto& el : mapOfFiles_) el.second->close();
 }
 
-void addLoggerCoutOutputStream()
-{
-  dgADD_OSTREAM_TO_RTLOG(std::cout);
-}
+void addLoggerCoutOutputStream() { dgADD_OSTREAM_TO_RTLOG(std::cout); }
 
-void realTimeLoggerDestroy()
-{
-  RealTimeLogger::destroy();
-}
+void realTimeLoggerDestroy() { RealTimeLogger::destroy(); }
 
-void realTimeLoggerSpinOnce()
-{
-  RealTimeLogger::instance().spinOnce();
-}
+void realTimeLoggerSpinOnce() { RealTimeLogger::instance().spinOnce(); }
 
-void realTimeLoggerInstance()
-{
-  RealTimeLogger::instance();
-}
+void realTimeLoggerInstance() { RealTimeLogger::instance(); }
 
 }  // namespace debug
 }  // namespace python
diff --git a/src/dynamic_graph/dynamic-graph-py.cc b/src/dynamic_graph/dynamic-graph-py.cc
index 8f0f48a..7a6f0f6 100644
--- a/src/dynamic_graph/dynamic-graph-py.cc
+++ b/src/dynamic_graph/dynamic-graph-py.cc
@@ -33,13 +33,9 @@ namespace python {
 /**
    \brief plug a signal into another one.
 */
-void plug(SignalBase<int>* signalOut, SignalBase<int>* signalIn)
-{
-  signalIn->plug(signalOut);
-}
+void plug(SignalBase<int>* signalOut, SignalBase<int>* signalIn) { signalIn->plug(signalOut); }
 
-void enableTrace(bool enable, const char* filename)
-{
+void enableTrace(bool enable, const char* filename) {
   if (enable)
     DebugTrace::openFile(filename);
   else
@@ -63,200 +59,175 @@ struct MapOfEntitiesPairToPythonConverter {
   }
 };
 
-MapOfEntities* getEntityMap() {
-  return const_cast<MapOfEntities*>(&dg::PoolStorage::getInstance()->getEntityMap());
-}
+MapOfEntities* getEntityMap() { return const_cast<MapOfEntities*>(&dg::PoolStorage::getInstance()->getEntityMap()); }
 
-dg::SignalBase<int>* getSignal(dg::Entity& e, const std::string& name) {
-  return &e.getSignal(name);
-}
+dg::SignalBase<int>* getSignal(dg::Entity& e, const std::string& name) { return &e.getSignal(name); }
 
-class PythonEntity : public dg::Entity
-{
-DYNAMIC_GRAPH_ENTITY_DECL();
-public:
+class PythonEntity : public dg::Entity {
+  DYNAMIC_GRAPH_ENTITY_DECL();
+
+ public:
   using dg::Entity::Entity;
 
-  void signalRegistration(dg::SignalBase<int> &signal)
-  {
-    dg::Entity::signalRegistration(signal);
-  }
-  void signalDeregistration(const std::string &name)
-  {
-    dg::Entity::signalDeregistration(name);
-  }
+  void signalRegistration(dg::SignalBase<int>& signal) { dg::Entity::signalRegistration(signal); }
+  void signalDeregistration(const std::string& name) { dg::Entity::signalDeregistration(name); }
 };
 
 DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(PythonEntity, "PythonEntity");
 
-void exposeEntityBase()
-{
+void exposeEntityBase() {
   using namespace dynamicgraph;
-  bp::enum_<LoggerVerbosity> ("LoggerVerbosity")
-    .value("VERBOSITY_ALL"               , VERBOSITY_ALL)
-    .value("VERBOSITY_INFO_WARNING_ERROR", VERBOSITY_INFO_WARNING_ERROR)
-    .value("VERBOSITY_WARNING_ERROR"     , VERBOSITY_WARNING_ERROR)
-    .value("VERBOSITY_ERROR"             , VERBOSITY_ERROR)
-    .value("VERBOSITY_NONE"              , VERBOSITY_NONE)
-    .export_values();
-
+  bp::enum_<LoggerVerbosity>("LoggerVerbosity")
+      .value("VERBOSITY_ALL", VERBOSITY_ALL)
+      .value("VERBOSITY_INFO_WARNING_ERROR", VERBOSITY_INFO_WARNING_ERROR)
+      .value("VERBOSITY_WARNING_ERROR", VERBOSITY_WARNING_ERROR)
+      .value("VERBOSITY_ERROR", VERBOSITY_ERROR)
+      .value("VERBOSITY_NONE", VERBOSITY_NONE)
+      .export_values();
 
   bp::class_<Entity, boost::noncopyable>("Entity", bp::no_init)
-    .add_property ("name",
-        bp::make_function(&Entity::getName, bp::return_value_policy<bp::copy_const_reference>()))
-    .add_property ("className",
-        bp::make_function(&Entity::getClassName, bp::return_value_policy<bp::copy_const_reference>()),
-        "the class name of the Entity")
-    .add_property ("__doc__", &Entity::getDocString)
-
-    .def("setLoggerVerbosityLevel", &Entity::setLoggerVerbosityLevel)
-    .def("getLoggerVerbosityLevel", &Entity::getLoggerVerbosityLevel)
-    .add_property("loggerVerbosityLevel", &Entity::setLoggerVerbosityLevel,
-        &Entity::getLoggerVerbosityLevel, "the verbosity level of the entity")
-    .def("setTimeSample", &Entity::setTimeSample)
-    .def("getTimeSample", &Entity::getTimeSample)
-    .add_property("timeSample", &Entity::getTimeSample, &Entity::setTimeSample,
-        "the time sample for printing debugging information")
-    .def("setStreamPrintPeriod", &Entity::setStreamPrintPeriod)
-    .def("getStreamPrintPeriod", &Entity::getStreamPrintPeriod)
-    .add_property("streamPrintPeriod", &Entity::getStreamPrintPeriod,
-        &Entity::setStreamPrintPeriod,
-        "set the period at which debugging information are printed")
-
-    .def("__str__", +[](const Entity& e) -> std::string {
-          std::ostringstream os;
-          e.display(os);
-          return os.str();
-        })
-    .def("signals", +[](const Entity& e) -> bp::list {
-          bp::list ret;
-          for (auto& el : e.getSignalMap())
-            ret.append(bp::ptr(el.second));
-          return ret;
-        }, "Return the list of signals.")
-    //.def("signal", +[](Entity& e, const std::string &name) { return &e.getSignal(name); },
-        //reference_existing_object())
-    .def("signal", &getSignal, reference_existing_object(),
-        "get signal by name from an Entity", bp::arg("name"))
-    .def("hasSignal", &Entity::hasSignal,
-        "return True if the entity has a signal with the given name")
-
-    .def("displaySignals", +[](const Entity& e) {
-          Entity::SignalMap signals (e.getSignalMap());
-          std::cout << "--- <" << e.getName();
-          if (signals.empty())
-            std::cout << "> has no signal\n";
-          else
-            std::cout << "> signal list:\n";
-          for(const auto& el : signals)
-            el.second->display(std::cout << "    |-- <") << '\n';
-        },
-        "Print the list of signals into standard output: temporary.")
-
-    /*
-    .def("__getattr__", +[](Entity& e, const std::string &name) -> SignalBase<int>* { return &e.getSignal(name); },
-        reference_existing_object())
-    def __getattr__(self, name):
-        try:
-            return self.signal(name)
-        except Exception:
-            try:
-                object.__getattr__(self, name)
-            except AttributeError:
-                raise AttributeError("'%s' entity has no attribute %s\n" % (self.name, name) +
-                                     '  entity attributes are usually either\n' + '    - commands,\n' +
-                                     '    - signals or,\n' + '    - user defined attributes')
-                                     */
-    /*
-    .def("__setattr__", +[](bp::object self, const std::string &name, bp::object value) {
-          Entity& e = bp::extract<Entity&> (self);
-          if (e.hasSignal(name))
-            throw std::invalid_argument(name + " already designates a signal. "
-                "It is not advised to set a new attribute of the same name.");
-          // TODO How do you do that ? I am sure it is possible.
-          //object.__setattr__(self, name, value)
-        })
-        */
-
-    /* TODO ?
-    def boundNewCommand(self, cmdName):
-        """
-        At construction, all existing commands are bound directly in the class.
-        This method enables to bound new commands dynamically. These new bounds
-        are not made with the class, but directly with the object instance.
-        """
-    def boundAllNewCommands(self):
-        """
-        For all commands that are not attribute of the object instance nor of the
-        class, a new attribute of the instance is created to bound the command.
-        """
-        */
-
-    // For backward compat
-    .add_static_property ("entities", bp::make_function(&getEntityMap, reference_existing_object()))
-    ;
-
-    python::exposeEntity<PythonEntity, bp::bases<Entity>, 0>()
+      .add_property("name", bp::make_function(&Entity::getName, bp::return_value_policy<bp::copy_const_reference>()))
+      .add_property("className",
+                    bp::make_function(&Entity::getClassName, bp::return_value_policy<bp::copy_const_reference>()),
+                    "the class name of the Entity")
+      .add_property("__doc__", &Entity::getDocString)
+
+      .def("setLoggerVerbosityLevel", &Entity::setLoggerVerbosityLevel)
+      .def("getLoggerVerbosityLevel", &Entity::getLoggerVerbosityLevel)
+      .add_property("loggerVerbosityLevel", &Entity::setLoggerVerbosityLevel, &Entity::getLoggerVerbosityLevel,
+                    "the verbosity level of the entity")
+      .def("setTimeSample", &Entity::setTimeSample)
+      .def("getTimeSample", &Entity::getTimeSample)
+      .add_property("timeSample", &Entity::getTimeSample, &Entity::setTimeSample,
+                    "the time sample for printing debugging information")
+      .def("setStreamPrintPeriod", &Entity::setStreamPrintPeriod)
+      .def("getStreamPrintPeriod", &Entity::getStreamPrintPeriod)
+      .add_property("streamPrintPeriod", &Entity::getStreamPrintPeriod, &Entity::setStreamPrintPeriod,
+                    "set the period at which debugging information are printed")
+
+      .def("__str__",
+           +[](const Entity& e) -> std::string {
+             std::ostringstream os;
+             e.display(os);
+             return os.str();
+           })
+      .def("signals",
+           +[](const Entity& e) -> bp::list {
+             bp::list ret;
+             for (auto& el : e.getSignalMap()) ret.append(bp::ptr(el.second));
+             return ret;
+           },
+           "Return the list of signals.")
+      //.def("signal", +[](Entity& e, const std::string &name) { return &e.getSignal(name); },
+      // reference_existing_object())
+      .def("signal", &getSignal, reference_existing_object(), "get signal by name from an Entity", bp::arg("name"))
+      .def("hasSignal", &Entity::hasSignal, "return True if the entity has a signal with the given name")
+
+      .def("displaySignals",
+           +[](const Entity& e) {
+             Entity::SignalMap signals(e.getSignalMap());
+             std::cout << "--- <" << e.getName();
+             if (signals.empty())
+               std::cout << "> has no signal\n";
+             else
+               std::cout << "> signal list:\n";
+             for (const auto& el : signals) el.second->display(std::cout << "    |-- <") << '\n';
+           },
+           "Print the list of signals into standard output: temporary.")
+
+      /*
+      .def("__getattr__", +[](Entity& e, const std::string &name) -> SignalBase<int>* { return &e.getSignal(name); },
+          reference_existing_object())
+      def __getattr__(self, name):
+          try:
+              return self.signal(name)
+          except Exception:
+              try:
+                  object.__getattr__(self, name)
+              except AttributeError:
+                  raise AttributeError("'%s' entity has no attribute %s\n" % (self.name, name) +
+                                       '  entity attributes are usually either\n' + '    - commands,\n' +
+                                       '    - signals or,\n' + '    - user defined attributes')
+                                       */
+      /*
+      .def("__setattr__", +[](bp::object self, const std::string &name, bp::object value) {
+            Entity& e = bp::extract<Entity&> (self);
+            if (e.hasSignal(name))
+              throw std::invalid_argument(name + " already designates a signal. "
+                  "It is not advised to set a new attribute of the same name.");
+            // TODO How do you do that ? I am sure it is possible.
+            //object.__setattr__(self, name, value)
+          })
+          */
+
+      /* TODO ?
+      def boundNewCommand(self, cmdName):
+          """
+          At construction, all existing commands are bound directly in the class.
+          This method enables to bound new commands dynamically. These new bounds
+          are not made with the class, but directly with the object instance.
+          """
+      def boundAllNewCommands(self):
+          """
+          For all commands that are not attribute of the object instance nor of the
+          class, a new attribute of the instance is created to bound the command.
+          """
+          */
+
+      // For backward compat
+      .add_static_property("entities", bp::make_function(&getEntityMap, reference_existing_object()));
+
+  python::exposeEntity<PythonEntity, bp::bases<Entity>, 0>()
       .def("signalRegistration", &PythonEntity::signalRegistration)
-      .def("signalDeregistration", &PythonEntity::signalDeregistration)
-      ;
+      .def("signalDeregistration", &PythonEntity::signalDeregistration);
 
-
-    python::exposeEntity<python::PythonSignalContainer, bp::bases<Entity>, 0>()
-      .def("rmSignal", &python::PythonSignalContainer::rmSignal, "Remove a signal", bp::arg("signal_name"))
-      ;
+  python::exposeEntity<python::PythonSignalContainer, bp::bases<Entity>, 0>().def(
+      "rmSignal", &python::PythonSignalContainer::rmSignal, "Remove a signal", bp::arg("signal_name"));
 }
 
-void exposeCommand()
-{
+void exposeCommand() {
   using dg::command::Command;
-  bp::class_<Command, boost::noncopyable> ("Command", bp::no_init)
-    .def ("__call__", bp::raw_function(dg::python::entity::executeCmd, 1), "execute the command")
-    .add_property ("__doc__", &Command::getDocstring)
-    ;
+  bp::class_<Command, boost::noncopyable>("Command", bp::no_init)
+      .def("__call__", bp::raw_function(dg::python::entity::executeCmd, 1), "execute the command")
+      .add_property("__doc__", &Command::getDocstring);
 }
 
-void exposeOldAPI()
-{
-  bp::def ("plug", dynamicgraph::python::plug, "plug an output signal into an input signal", (bp::arg("signalOut"), "signalIn"));
-  bp::def ("enableTrace", dynamicgraph::python::enableTrace, "Enable or disable tracing debug info in a file");
+void exposeOldAPI() {
+  bp::def("plug", dynamicgraph::python::plug, "plug an output signal into an input signal",
+          (bp::arg("signalOut"), "signalIn"));
+  bp::def("enableTrace", dynamicgraph::python::enableTrace, "Enable or disable tracing debug info in a file");
   // Signals
-  bp::def ("create_signal_wrapper", dynamicgraph::python::signalBase::createSignalWrapper,
-      reference_existing_object(), "create a SignalWrapper C++ object");
-    // Entity
-  bp::def ("factory_get_entity_class_list", dynamicgraph::python::factory::getEntityClassList,
-     "return the list of entity classes");
-  bp::def ("writeGraph", dynamicgraph::python::pool::writeGraph, "Write the graph of entities in a filename.");
-    bp::def ("get_entity_list", dynamicgraph::python::pool::getEntityList,
-     "return the list of instanciated entities");
-  bp::def ("addLoggerFileOutputStream", dynamicgraph::python::debug::addLoggerFileOutputStream,
-     "add a output file stream to the logger by filename");
-  bp::def ("addLoggerCoutOutputStream", dynamicgraph::python::debug::addLoggerCoutOutputStream,
-     "add std::cout as output stream to the logger");
-  bp::def ("closeLoggerFileOutputStream", dynamicgraph::python::debug::closeLoggerFileOutputStream,
-     "close all the loggers file output streams.");
-  bp::def ("real_time_logger_destroy", dynamicgraph::python::debug::realTimeLoggerDestroy,
-     "Destroy the real time logger.");
-  bp::def ("real_time_logger_spin_once", dynamicgraph::python::debug::realTimeLoggerSpinOnce,
-     "Destroy the real time logger.");
-  bp::def ("real_time_logger_instance", dynamicgraph::python::debug::realTimeLoggerInstance,
-     "Starts the real time logger.");
+  bp::def("create_signal_wrapper", dynamicgraph::python::signalBase::createSignalWrapper, reference_existing_object(),
+          "create a SignalWrapper C++ object");
+  // Entity
+  bp::def("factory_get_entity_class_list", dynamicgraph::python::factory::getEntityClassList,
+          "return the list of entity classes");
+  bp::def("writeGraph", dynamicgraph::python::pool::writeGraph, "Write the graph of entities in a filename.");
+  bp::def("get_entity_list", dynamicgraph::python::pool::getEntityList, "return the list of instanciated entities");
+  bp::def("addLoggerFileOutputStream", dynamicgraph::python::debug::addLoggerFileOutputStream,
+          "add a output file stream to the logger by filename");
+  bp::def("addLoggerCoutOutputStream", dynamicgraph::python::debug::addLoggerCoutOutputStream,
+          "add std::cout as output stream to the logger");
+  bp::def("closeLoggerFileOutputStream", dynamicgraph::python::debug::closeLoggerFileOutputStream,
+          "close all the loggers file output streams.");
+  bp::def("real_time_logger_destroy", dynamicgraph::python::debug::realTimeLoggerDestroy,
+          "Destroy the real time logger.");
+  bp::def("real_time_logger_spin_once", dynamicgraph::python::debug::realTimeLoggerSpinOnce,
+          "Destroy the real time logger.");
+  bp::def("real_time_logger_instance", dynamicgraph::python::debug::realTimeLoggerInstance,
+          "Starts the real time logger.");
 }
 
-void enableEigenPy()
-{
+void enableEigenPy() {
   eigenpy::enableEigenPy();
-  
-  if(!eigenpy::register_symbolic_link_to_registered_type<Eigen::Quaterniond>())
-    eigenpy::exposeQuaternion();
-  if(!eigenpy::register_symbolic_link_to_registered_type<Eigen::AngleAxisd>())
-    eigenpy::exposeAngleAxis();
+
+  if (!eigenpy::register_symbolic_link_to_registered_type<Eigen::Quaterniond>()) eigenpy::exposeQuaternion();
+  if (!eigenpy::register_symbolic_link_to_registered_type<Eigen::AngleAxisd>()) eigenpy::exposeAngleAxis();
 
   eigenpy::enableEigenPySpecific<Eigen::Matrix4d>();
 }
 
-BOOST_PYTHON_MODULE(wrap)
-{
+BOOST_PYTHON_MODULE(wrap) {
   enableEigenPy();
 
   exposeOldAPI();
@@ -267,24 +238,23 @@ BOOST_PYTHON_MODULE(wrap)
 
   typedef dg::PoolStorage::Entities MapOfEntities;
   bp::class_<MapOfEntities>("MapOfEntities")
-    .def("__len__", &MapOfEntities::size)
-    .def("keys", +[](const MapOfEntities& m) -> bp::tuple {
-          bp::list res;
-          for (const auto& el : m) res.append(el.first);
-          return bp::tuple(res);
-        })
-    .def("values", +[](const MapOfEntities& m) -> bp::tuple {
-          bp::list res;
-          for (const auto& el : m) res.append(bp::ptr(el.second));
-          return bp::tuple(res);
-        })
-    .def("__getitem__",
-        static_cast<dg::Entity*& (MapOfEntities::*) (const std::string& k)> (&MapOfEntities::at),
-        reference_existing_object())
-    .def("__setitem__", +[](MapOfEntities& m, const std::string& n, dg::Entity* e)
-        { m.emplace(n, e); })
-    .def("__iter__", bp::iterator<MapOfEntities>())
-    .def("__contains__", +[](const MapOfEntities& m, const std::string& n) -> bool { return m.count(n); })
-    ;
-  bp::to_python_converter<MapOfEntities::value_type, MapOfEntitiesPairToPythonConverter >();
+      .def("__len__", &MapOfEntities::size)
+      .def("keys",
+           +[](const MapOfEntities& m) -> bp::tuple {
+             bp::list res;
+             for (const auto& el : m) res.append(el.first);
+             return bp::tuple(res);
+           })
+      .def("values",
+           +[](const MapOfEntities& m) -> bp::tuple {
+             bp::list res;
+             for (const auto& el : m) res.append(bp::ptr(el.second));
+             return bp::tuple(res);
+           })
+      .def("__getitem__", static_cast<dg::Entity*& (MapOfEntities::*)(const std::string& k)>(&MapOfEntities::at),
+           reference_existing_object())
+      .def("__setitem__", +[](MapOfEntities& m, const std::string& n, dg::Entity* e) { m.emplace(n, e); })
+      .def("__iter__", bp::iterator<MapOfEntities>())
+      .def("__contains__", +[](const MapOfEntities& m, const std::string& n) -> bool { return m.count(n); });
+  bp::to_python_converter<MapOfEntities::value_type, MapOfEntitiesPairToPythonConverter>();
 }
diff --git a/src/dynamic_graph/entity-py.cc b/src/dynamic_graph/entity-py.cc
index 79b64e9..f5993fd 100644
--- a/src/dynamic_graph/entity-py.cc
+++ b/src/dynamic_graph/entity-py.cc
@@ -38,8 +38,7 @@ namespace entity {
 /// \param obj an Entity object
 void addCommands(bp::object obj) {
   Entity& entity = bp::extract<Entity&>(obj);
-  for (const auto& el : entity.getNewStyleCommandMap())
-    obj.attr(el.first.c_str()) = bp::object(bp::ptr(el.second));
+  for (const auto& el : entity.getNewStyleCommandMap()) obj.attr(el.first.c_str()) = bp::object(bp::ptr(el.second));
 }
 
 /// \param obj an Entity object
@@ -58,20 +57,16 @@ void addSignals(bp::object obj) {
 Entity* create(const char* className, const char* instanceName) {
   Entity* obj = NULL;
   /* Try to find if the corresponding object already exists. */
-  if (dynamicgraph::PoolStorage::getInstance()->existEntity(instanceName,
-                                                            obj)) {
+  if (dynamicgraph::PoolStorage::getInstance()->existEntity(instanceName, obj)) {
     if (obj->getClassName() != className) {
-      throw std::invalid_argument("Found an object named " +
-                                  std::string(instanceName) +
+      throw std::invalid_argument("Found an object named " + std::string(instanceName) +
                                   ",\n"
                                   "but this object is of type " +
-                                  std::string(obj->getClassName()) +
-                                  " and not " + std::string(className));
+                                  std::string(obj->getClassName()) + " and not " + std::string(className));
     }
   } else /* If not, create a new object. */
   {
-    obj = dynamicgraph::FactoryStorage::getInstance()->newEntity(
-        std::string(className), std::string(instanceName));
+    obj = dynamicgraph::FactoryStorage::getInstance()->newEntity(std::string(className), std::string(instanceName));
   }
 
   return obj;
@@ -84,8 +79,7 @@ bp::object executeCmd(bp::tuple args, bp::dict) {
     throw std::out_of_range("Wrong number of arguments");
   std::vector<Value> values;
   values.reserve(command.valueTypes().size());
-  for (int i = 1; i < bp::len(args); ++i)
-    values.push_back(convert::toValue(args[i], command.valueTypes()[i - 1]));
+  for (int i = 1; i < bp::len(args); ++i) values.push_back(convert::toValue(args[i], command.valueTypes()[i - 1]));
   command.setParameterValues(values);
   return convert::fromValue(command.execute());
 }
diff --git a/src/dynamic_graph/pool-py.cc b/src/dynamic_graph/pool-py.cc
index 7fc6294..2c1659d 100644
--- a/src/dynamic_graph/pool-py.cc
+++ b/src/dynamic_graph/pool-py.cc
@@ -11,28 +11,19 @@ namespace python {
 
 namespace pool {
 
-void writeGraph(const char* filename)
-{
-  PoolStorage::getInstance()->writeGraph(filename);
-}
+void writeGraph(const char* filename) { PoolStorage::getInstance()->writeGraph(filename); }
 
-const std::map<std::string, Entity*>* getEntityMap()
-{
-  return &PoolStorage::getInstance()->getEntityMap();
-}
+const std::map<std::string, Entity*>* getEntityMap() { return &PoolStorage::getInstance()->getEntityMap(); }
 
 /**
    \brief Get list of entities
 */
-bp::list getEntityList()
-{
+bp::list getEntityList() {
   std::vector<std::string> entityNames;
   bp::list res;
-  const PoolStorage::Entities& listOfEntities =
-    PoolStorage::getInstance()->getEntityMap();
+  const PoolStorage::Entities& listOfEntities = PoolStorage::getInstance()->getEntityMap();
 
-  for (const auto& el : listOfEntities)
-    res.append(el.second->getName());
+  for (const auto& el : listOfEntities) res.append(el.second->getName());
   return res;
 }
 
diff --git a/src/dynamic_graph/signal-base-py.cc b/src/dynamic_graph/signal-base-py.cc
index 2e77dbb..50a80ad 100644
--- a/src/dynamic_graph/signal-base-py.cc
+++ b/src/dynamic_graph/signal-base-py.cc
@@ -43,110 +43,100 @@ typedef Eigen::Matrix<double, 4, 4> Matrix4;
 typedef Eigen::Transform<double, 3, Eigen::Affine> MatrixHomogeneous;
 typedef Eigen::Matrix<double, 6, 6> MatrixTwist;
 
-template<typename Time> void exposeSignalBase (const char* name)
-{
+template <typename Time>
+void exposeSignalBase(const char* name) {
   typedef SignalBase<Time> S_t;
   bp::class_<S_t, boost::noncopyable>(name, bp::no_init)
-    .add_property ("time",
-        bp::make_function(&S_t::getTime, bp::return_value_policy<bp::copy_const_reference>()),
-        &S_t::setTime)
-    .add_property ("name",
-        bp::make_function(&S_t::getName, bp::return_value_policy<bp::copy_const_reference>()))
-
-    .def("getName", &S_t::getName, bp::return_value_policy<bp::copy_const_reference>())
-    .def("getClassName", +[](const S_t& s) -> std::string {
-          std::string ret;
-          s.getClassName(ret);
-          return ret;
-        })
-
-    .def("plug", &S_t::plug, "Plug the signal to another signal")
-    .def("unplug", &S_t::unplug, "Unplug the signal")
-    .def("isPlugged", &S_t::isPlugged, "Whether the signal is plugged")
-    .def("getPlugged", &S_t::getPluged,
-        bp::return_value_policy<bp::reference_existing_object>(),
-        "To which signal the signal is plugged")
-
-    .def("recompute", &S_t::recompute, "Recompute the signal at given time")
-
-    .def("__str__", +[](const S_t& s) -> std::string {
-          std::ostringstream oss;
-          s.display(oss);
-          return oss.str();
-        })
-    .def("displayDependencies", +[](const S_t& s, int time) -> std::string {
-          std::ostringstream oss;
-          s.displayDependencies(oss, time);
-          return oss.str();
-        }, "Print the signal dependencies in a string")
-    ;
+      .add_property("time", bp::make_function(&S_t::getTime, bp::return_value_policy<bp::copy_const_reference>()),
+                    &S_t::setTime)
+      .add_property("name", bp::make_function(&S_t::getName, bp::return_value_policy<bp::copy_const_reference>()))
+
+      .def("getName", &S_t::getName, bp::return_value_policy<bp::copy_const_reference>())
+      .def("getClassName",
+           +[](const S_t& s) -> std::string {
+             std::string ret;
+             s.getClassName(ret);
+             return ret;
+           })
+
+      .def("plug", &S_t::plug, "Plug the signal to another signal")
+      .def("unplug", &S_t::unplug, "Unplug the signal")
+      .def("isPlugged", &S_t::isPlugged, "Whether the signal is plugged")
+      .def("getPlugged", &S_t::getPluged, bp::return_value_policy<bp::reference_existing_object>(),
+           "To which signal the signal is plugged")
+
+      .def("recompute", &S_t::recompute, "Recompute the signal at given time")
+
+      .def("__str__",
+           +[](const S_t& s) -> std::string {
+             std::ostringstream oss;
+             s.display(oss);
+             return oss.str();
+           })
+      .def("displayDependencies",
+           +[](const S_t& s, int time) -> std::string {
+             std::ostringstream oss;
+             s.displayDependencies(oss, time);
+             return oss.str();
+           },
+           "Print the signal dependencies in a string");
 }
 
-template<typename T, typename Time> auto exposeSignal (const std::string& name)
-{
+template <typename T, typename Time>
+auto exposeSignal(const std::string& name) {
   typedef Signal<T, Time> S_t;
   bp::class_<S_t, bp::bases<SignalBase<Time> >, boost::noncopyable> obj(name.c_str(), bp::init<std::string>());
-  obj
-    .add_property("value",
-        bp::make_function(&S_t::accessCopy, bp::return_value_policy<bp::copy_const_reference>()),
-        &S_t::setConstant, // TODO check the setter
-        "the signal value.\n"
-        "warning: for Eigen objects, sig.value[0] = 1. may not work).")
-    ;
+  obj.add_property("value", bp::make_function(&S_t::accessCopy, bp::return_value_policy<bp::copy_const_reference>()),
+                   &S_t::setConstant,  // TODO check the setter
+                   "the signal value.\n"
+                   "warning: for Eigen objects, sig.value[0] = 1. may not work).");
   return obj;
 }
 
-template<> auto exposeSignal<MatrixHomogeneous, time_type> (const std::string& name)
-{
+template <>
+auto exposeSignal<MatrixHomogeneous, time_type>(const std::string& name) {
   typedef Signal<MatrixHomogeneous, time_type> S_t;
   bp::class_<S_t, bp::bases<SignalBase<time_type> >, boost::noncopyable> obj(name.c_str(), bp::init<std::string>());
-  obj
-    .add_property("value",
-        +[](const S_t& signal) -> Matrix4 { return signal.accessCopy().matrix(); },
-        +[](S_t& signal, const Matrix4& v) {
-          // TODO it isn't hard to support pinocchio::SE3 type here.
-          // However, this adds a dependency to pinocchio.
-          signal.setConstant (MatrixHomogeneous(v));
-        }, "the signal value.")
-    ;
+  obj.add_property("value", +[](const S_t& signal) -> Matrix4 { return signal.accessCopy().matrix(); },
+                   +[](S_t& signal, const Matrix4& v) {
+                     // TODO it isn't hard to support pinocchio::SE3 type here.
+                     // However, this adds a dependency to pinocchio.
+                     signal.setConstant(MatrixHomogeneous(v));
+                   },
+                   "the signal value.");
   return obj;
 }
 
-template<typename T, typename Time> auto exposeSignalWrapper (const std::string& name)
-{
+template <typename T, typename Time>
+auto exposeSignalWrapper(const std::string& name) {
   typedef SignalWrapper<T, Time> S_t;
   bp::class_<S_t, bp::bases<Signal<T, Time> >, boost::noncopyable> obj(name.c_str(), bp::no_init);
   return obj;
 }
 
-template<typename T, typename Time> auto exposeSignalPtr (const std::string& name)
-{
+template <typename T, typename Time>
+auto exposeSignalPtr(const std::string& name) {
   typedef SignalPtr<T, Time> S_t;
-  bp::class_<S_t, bp::bases<Signal<T, Time> >, boost::noncopyable> obj(name.c_str(), bp::no_init)
-    ;
+  bp::class_<S_t, bp::bases<Signal<T, Time> >, boost::noncopyable> obj(name.c_str(), bp::no_init);
   return obj;
 }
 
-template<typename T, typename Time> auto exposeSignalTimeDependent (const std::string& name)
-{
+template <typename T, typename Time>
+auto exposeSignalTimeDependent(const std::string& name) {
   typedef SignalTimeDependent<T, Time> S_t;
-  bp::class_<S_t, bp::bases<Signal<T, Time> >, boost::noncopyable> obj(name.c_str(),
-      bp::no_init)
-    ;
+  bp::class_<S_t, bp::bases<Signal<T, Time> >, boost::noncopyable> obj(name.c_str(), bp::no_init);
   return obj;
 }
 
-template<typename T, typename Time>
-void exposeSignalsOfType(const std::string& name)
-{
+template <typename T, typename Time>
+void exposeSignalsOfType(const std::string& name) {
   exposeSignal<T, Time>("Signal" + name);
   exposeSignalPtr<T, Time>("SignalPtr" + name);
   exposeSignalWrapper<T, Time>("SignalWrapper" + name);
   exposeSignalTimeDependent<T, Time>("SignalTimeDependent" + name);
 }
 
-void exposeSignals()
-{
+void exposeSignals() {
   exposeSignalBase<time_type>("SignalBase");
 
   exposeSignalsOfType<bool, time_type>("Bool");
@@ -180,7 +170,7 @@ SignalWrapper<T, int>* createSignalWrapperTpl(const char* name, bp::object o, st
 }
 
 PythonSignalContainer* getPythonSignalContainer() {
-  Entity* obj = entity::create ("PythonSignalContainer", "python_signals");
+  Entity* obj = entity::create("PythonSignalContainer", "python_signals");
   return dynamic_cast<PythonSignalContainer*>(obj);
 }
 
@@ -192,8 +182,7 @@ PythonSignalContainer* getPythonSignalContainer() {
 /**
    \brief Create an instance of SignalWrapper
 */
-SignalBase<int>* createSignalWrapper(const char* name, const char* type, bp::object object)
-{
+SignalBase<int>* createSignalWrapper(const char* name, const char* type, bp::object object) {
   PythonSignalContainer* psc = getPythonSignalContainer();
   if (psc == NULL) return NULL;
 
@@ -212,8 +201,7 @@ SignalBase<int>* createSignalWrapper(const char* name, const char* type, bp::obj
     error = "Type not understood";
   }
 
-  if (obj == NULL)
-    throw std::runtime_error(error);
+  if (obj == NULL) throw std::runtime_error(error);
   // Register signal into the python signal container
   psc->signalRegistration(*obj);
 
diff --git a/src/dynamic_graph/tracer/wrap.cc b/src/dynamic_graph/tracer/wrap.cc
index 33da78e..a790c98 100644
--- a/src/dynamic_graph/tracer/wrap.cc
+++ b/src/dynamic_graph/tracer/wrap.cc
@@ -2,12 +2,9 @@
 
 #include <dynamic-graph/tracer.h>
 
-BOOST_PYTHON_MODULE(wrap)
-{
+BOOST_PYTHON_MODULE(wrap) {
   using dynamicgraph::Tracer;
 
   bp::import("dynamic_graph");
-  dynamicgraph::python::exposeEntity<Tracer>()
-    .def("addSignal", &Tracer::addSignalToTrace)
-    ;
+  dynamicgraph::python::exposeEntity<Tracer>().def("addSignal", &Tracer::addSignalToTrace);
 }
diff --git a/src/dynamic_graph/tracer_real_time/wrap.cc b/src/dynamic_graph/tracer_real_time/wrap.cc
index b644508..9fb24ec 100644
--- a/src/dynamic_graph/tracer_real_time/wrap.cc
+++ b/src/dynamic_graph/tracer_real_time/wrap.cc
@@ -2,13 +2,10 @@
 
 #include <dynamic-graph/tracer-real-time.h>
 
-BOOST_PYTHON_MODULE(wrap)
-{
+BOOST_PYTHON_MODULE(wrap) {
   using dynamicgraph::Tracer;
   using dynamicgraph::TracerRealTime;
 
   bp::import("dynamic_graph.tracer");
-  dynamicgraph::python::exposeEntity<TracerRealTime,
-    bp::bases<Tracer> >()
-    ;
+  dynamicgraph::python::exposeEntity<TracerRealTime, bp::bases<Tracer> >();
 }
diff --git a/tests/custom_entity.cpp b/tests/custom_entity.cpp
index cfc9197..1d4bf52 100644
--- a/tests/custom_entity.cpp
+++ b/tests/custom_entity.cpp
@@ -21,8 +21,7 @@ namespace dynamicgraph {
 CustomEntity::CustomEntity(const std::string n)
     : Entity(n),
       m_sigdSIN(NULL, "CustomEntity(" + name + ")::input(double)::in_double"),
-      m_sigdTimeDepSOUT(boost::bind(&CustomEntity::update, this, _1, _2),
-                        m_sigdSIN,
+      m_sigdTimeDepSOUT(boost::bind(&CustomEntity::update, this, _1, _2), m_sigdSIN,
                         "CustomEntity(" + name + ")::input(double)::out_double")
 
 {
@@ -30,14 +29,10 @@ CustomEntity::CustomEntity(const std::string n)
 
   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 CustomEntity::addSignal() {
-  signalRegistration(m_sigdSIN << m_sigdTimeDepSOUT);
-}
+void CustomEntity::addSignal() { signalRegistration(m_sigdSIN << m_sigdTimeDepSOUT); }
 
 void CustomEntity::rmValidSignal() {
   signalDeregistration("in_double");
@@ -48,22 +43,14 @@ double &CustomEntity::update(double &res, const int &inTime) {
   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;
 }
-- 
GitLab