From 354d5cf1c4d77ee81e1bf58b61aaa0984cd8ecb3 Mon Sep 17 00:00:00 2001
From: Steve Tonneau <stonneau@laas.fr>
Date: Wed, 8 Mar 2017 14:35:34 +0100
Subject: [PATCH] finished renaming

---
 .gitignore                                    | 22 ++++++++++
 CMakeLists.txt                                |  2 +-
 ..._equilibrium.hh => centroidal_dynamics.hh} | 28 ++++++------
 include/centroidal-dynamics-lib/config.hh     | 44 +++++++++----------
 include/centroidal-dynamics-lib/logger.hh     |  6 +--
 .../solver_LP_abstract.hh                     | 12 ++---
 .../centroidal-dynamics-lib/solver_LP_clp.hh  |  8 ++--
 .../solver_LP_qpoases.hh                      |  8 ++--
 include/centroidal-dynamics-lib/util.hh       |  6 +--
 src/CMakeLists.txt                            |  4 +-
 ...quilibrium.cpp => centroidal_dynamics.cpp} | 24 +++++-----
 src/util.cpp                                  |  6 +--
 test/test_static_equilibrium.cpp              | 30 ++++++-------
 13 files changed, 111 insertions(+), 89 deletions(-)
 create mode 100644 .gitignore
 rename include/centroidal-dynamics-lib/{static_equilibrium.hh => centroidal_dynamics.hh} (93%)
 rename src/{static_equilibrium.cpp => centroidal_dynamics.cpp} (97%)

diff --git a/.gitignore b/.gitignore
new file mode 100644
index 0000000..c2f28d4
--- /dev/null
+++ b/.gitignore
@@ -0,0 +1,22 @@
+# Compiled Object files
+*.slo
+*.lo
+*.o
+*.obj
+# Compiled Dynamic libraries
+*.so
+*.dylib
+*.dll
+# Compiled Static libraries
+*.lai
+*.la
+*.a
+*.lib
+# Executables
+*.exe
+*.out
+*.app
+*.user
+build/
+build-rel/
+bin/
diff --git a/CMakeLists.txt b/CMakeLists.txt
index e4cfe82..6ed03a9 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -39,7 +39,7 @@ SET(${PROJECT_NAME}_HEADERS
 		include/centroidal-dynamics-lib/solver_LP_abstract.hh
 		include/centroidal-dynamics-lib/solver_LP_qpoases.hh
 		include/centroidal-dynamics-lib/solver_LP_clp.hh
-		include/centroidal-dynamics-lib/static_equilibrium.hh
+		include/centroidal-dynamics-lib/centroidal_dynamics.hh
 		include/centroidal-dynamics-lib/stop-watch.hh
   )
 
diff --git a/include/centroidal-dynamics-lib/static_equilibrium.hh b/include/centroidal-dynamics-lib/centroidal_dynamics.hh
similarity index 93%
rename from include/centroidal-dynamics-lib/static_equilibrium.hh
rename to include/centroidal-dynamics-lib/centroidal_dynamics.hh
index dcdab41..7d423b8 100644
--- a/include/centroidal-dynamics-lib/static_equilibrium.hh
+++ b/include/centroidal-dynamics-lib/centroidal_dynamics.hh
@@ -3,8 +3,8 @@
  * Author: Andrea Del Prete
  */
 
-#ifndef ROBUST_EQUILIBRIUM_LIB_STATIC_EQUILIBRIUM_H
-#define ROBUST_EQUILIBRIUM_LIB_STATIC_EQUILIBRIUM_H
+#ifndef CENTROIDAL_DYNAMICS_LIB_STATIC_EQUILIBRIUM_H
+#define CENTROIDAL_DYNAMICS_LIB_STATIC_EQUILIBRIUM_H
 
 #include <Eigen/Dense>
 #include <centroidal-dynamics-lib/config.hh>
@@ -14,23 +14,23 @@
 namespace robust_equilibrium
 {
 
-enum ROBUST_EQUILIBRIUM_DLLAPI StaticEquilibriumAlgorithm
+enum CENTROIDAL_DYNAMICS_DLLAPI EquilibriumAlgorithm
 {
-  STATIC_EQUILIBRIUM_ALGORITHM_LP,  /// primal LP formulation
-  STATIC_EQUILIBRIUM_ALGORITHM_LP2, /// another primal LP formulation
-  STATIC_EQUILIBRIUM_ALGORITHM_DLP, /// dual LP formulation
-  STATIC_EQUILIBRIUM_ALGORITHM_PP,  /// polytope projection algorithm
-  STATIC_EQUILIBRIUM_ALGORITHM_IP,  /// incremental projection algorithm based on primal LP formulation
-  STATIC_EQUILIBRIUM_ALGORITHM_DIP  /// incremental projection algorithm based on dual LP formulation
+  EQUILIBRIUM_ALGORITHM_LP,  /// primal LP formulation
+  EQUILIBRIUM_ALGORITHM_LP2, /// another primal LP formulation
+  EQUILIBRIUM_ALGORITHM_DLP, /// dual LP formulation
+  EQUILIBRIUM_ALGORITHM_PP,  /// polytope projection algorithm
+  EQUILIBRIUM_ALGORITHM_IP,  /// incremental projection algorithm based on primal LP formulation
+  EQUILIBRIUM_ALGORITHM_DIP  /// incremental projection algorithm based on dual LP formulation
 };
 
-class ROBUST_EQUILIBRIUM_DLLAPI StaticEquilibrium
+class CENTROIDAL_DYNAMICS_DLLAPI StaticEquilibrium
 {
 private:
   static bool m_is_cdd_initialized;   /// true if cdd lib has been initialized, false otherwise
 
   std::string                 m_name;         /// name of this object
-  StaticEquilibriumAlgorithm  m_algorithm;    /// current algorithm used
+  EquilibriumAlgorithm  m_algorithm;    /// current algorithm used
   Solver_LP_abstract*         m_solver;       /// LP solver
   SolverLP                    m_solver_type;  /// type of LP solver
 
@@ -46,7 +46,7 @@ private:
   VectorX m_h;
   /** False if a numerical instability appeared in the computation H and h*/
   bool m_is_cdd_stable;
-  /** STATIC_EQUILIBRIUM_ALGORITHM_PP: If double description fails,
+  /** EQUILIBRIUM_ALGORITHM_PP: If double description fails,
     * indicate the max number of attempts to compute the cone by introducing
     * a small pertubation of the system */
   const unsigned max_num_cdd_trials;
@@ -115,7 +115,7 @@ public:
    */
   std::string getName(){ return m_name; }
 
-  StaticEquilibriumAlgorithm getAlgorithm(){ return m_algorithm; }
+  EquilibriumAlgorithm getAlgorithm(){ return m_algorithm; }
 
   /**
    * @brief Specify a new set of contacts.
@@ -128,7 +128,7 @@ public:
    * @return True if the operation succeeded, false otherwise.
    */
   bool setNewContacts(Cref_matrixX3 contactPoints, Cref_matrixX3 contactNormals,
-                      double frictionCoefficient, StaticEquilibriumAlgorithm alg);
+                      double frictionCoefficient, EquilibriumAlgorithm alg);
 
   /**
    * @brief Compute a measure of the robustness of the equilibrium of the specified com position.
diff --git a/include/centroidal-dynamics-lib/config.hh b/include/centroidal-dynamics-lib/config.hh
index 6f042ad..8d60cbe 100644
--- a/include/centroidal-dynamics-lib/config.hh
+++ b/include/centroidal-dynamics-lib/config.hh
@@ -3,11 +3,11 @@
  * Author: Andrea Del Prete
  */
 
-#ifndef _ROBUST_EQUILIBRIUM_LIB_CONFIG_HH
-#define _ROBUST_EQUILIBRIUM_LIB_CONFIG_HH
+#ifndef _CENTROIDAL_DYNAMICS_LIB_CONFIG_HH
+#define _CENTROIDAL_DYNAMICS_LIB_CONFIG_HH
 
 // Package version (header).
-# define ROBUST_EQUILIBRIUM_VERSION "UNKNOWN"
+# define CENTROIDAL_DYNAMICS_VERSION "UNKNOWN"
 
 // Handle portable symbol export.
 // Defining manually which symbol should be exported is required
@@ -21,37 +21,37 @@
 // is handled by the compiler, see: http://gcc.gnu.org/wiki/Visibility
 # if defined _WIN32 || defined __CYGWIN__
 // On Microsoft Windows, use dllimport and dllexport to tag symbols.
-#  define ROBUST_EQUILIBRIUM_DLLIMPORT __declspec(dllimport)
-#  define ROBUST_EQUILIBRIUM_DLLEXPORT __declspec(dllexport)
-#  define ROBUST_EQUILIBRIUM_DLLLOCAL
+#  define CENTROIDAL_DYNAMICS_DLLIMPORT __declspec(dllimport)
+#  define CENTROIDAL_DYNAMICS_DLLEXPORT __declspec(dllexport)
+#  define CENTROIDAL_DYNAMICS_DLLLOCAL
 # else
 // On Linux, for GCC >= 4, tag symbols using GCC extension.
 #  if __GNUC__ >= 4
-#   define ROBUST_EQUILIBRIUM_DLLIMPORT __attribute__ ((visibility("default")))
-#   define ROBUST_EQUILIBRIUM_DLLEXPORT __attribute__ ((visibility("default")))
-#   define ROBUST_EQUILIBRIUM_DLLLOCAL  __attribute__ ((visibility("hidden")))
+#   define CENTROIDAL_DYNAMICS_DLLIMPORT __attribute__ ((visibility("default")))
+#   define CENTROIDAL_DYNAMICS_DLLEXPORT __attribute__ ((visibility("default")))
+#   define CENTROIDAL_DYNAMICS_DLLLOCAL  __attribute__ ((visibility("hidden")))
 #  else
 // Otherwise (GCC < 4 or another compiler is used), export everything.
-#   define ROBUST_EQUILIBRIUM_DLLIMPORT
-#   define ROBUST_EQUILIBRIUM_DLLEXPORT
-#   define ROBUST_EQUILIBRIUM_DLLLOCAL
+#   define CENTROIDAL_DYNAMICS_DLLIMPORT
+#   define CENTROIDAL_DYNAMICS_DLLEXPORT
+#   define CENTROIDAL_DYNAMICS_DLLLOCAL
 #  endif // __GNUC__ >= 4
 # endif // defined _WIN32 || defined __CYGWIN__
 
-# ifdef ROBUST_EQUILIBRIUM_STATIC
+# ifdef CENTROIDAL_DYNAMICS_STATIC
 // If one is using the library statically, get rid of
 // extra information.
-#  define ROBUST_EQUILIBRIUM_DLLAPI
-#  define ROBUST_EQUILIBRIUM_LOCAL
+#  define CENTROIDAL_DYNAMICS_DLLAPI
+#  define CENTROIDAL_DYNAMICS_LOCAL
 # else
 // Depending on whether one is building or using the
 // library define DLLAPI to import or export.
-#  ifdef ROBUST_EQUILIBRIUM_EXPORTS
-#   define ROBUST_EQUILIBRIUM_DLLAPI ROBUST_EQUILIBRIUM_DLLEXPORT
+#  ifdef CENTROIDAL_DYNAMICS_EXPORTS
+#   define CENTROIDAL_DYNAMICS_DLLAPI CENTROIDAL_DYNAMICS_DLLEXPORT
 #  else
-#   define ROBUST_EQUILIBRIUM_DLLAPI ROBUST_EQUILIBRIUM_DLLIMPORT
-#  endif // ROBUST_EQUILIBRIUM_EXPORTS
-#  define ROBUST_EQUILIBRIUM_LOCAL ROBUST_EQUILIBRIUM_DLLLOCAL
-# endif // ROBUST_EQUILIBRIUM_STATIC
+#   define CENTROIDAL_DYNAMICS_DLLAPI CENTROIDAL_DYNAMICS_DLLIMPORT
+#  endif // CENTROIDAL_DYNAMICS_EXPORTS
+#  define CENTROIDAL_DYNAMICS_LOCAL CENTROIDAL_DYNAMICS_DLLLOCAL
+# endif // CENTROIDAL_DYNAMICS_STATIC
 
-#endif //_ROBUST_EQUILIBRIUM_LIB_CONFIG_HH
+#endif //_CENTROIDAL_DYNAMICS_LIB_CONFIG_HH
diff --git a/include/centroidal-dynamics-lib/logger.hh b/include/centroidal-dynamics-lib/logger.hh
index c83ac52..9015d15 100644
--- a/include/centroidal-dynamics-lib/logger.hh
+++ b/include/centroidal-dynamics-lib/logger.hh
@@ -73,7 +73,7 @@ namespace robust_equilibrium
 
   /** Enum representing the different kind of messages.
        */
-  enum ROBUST_EQUILIBRIUM_DLLAPI MsgType
+  enum CENTROIDAL_DYNAMICS_DLLAPI MsgType
   {
     MSG_TYPE_DEBUG          =0,
     MSG_TYPE_INFO           =1,
@@ -113,7 +113,7 @@ namespace robust_equilibrium
     return ss.str();
   }
 
-  enum ROBUST_EQUILIBRIUM_DLLAPI LoggerVerbosity
+  enum CENTROIDAL_DYNAMICS_DLLAPI LoggerVerbosity
   {
     VERBOSITY_ALL,
     VERBOSITY_INFO_WARNING_ERROR,
@@ -124,7 +124,7 @@ namespace robust_equilibrium
 
   /** A simple class for logging messages
       */
-  class ROBUST_EQUILIBRIUM_DLLAPI Logger
+  class CENTROIDAL_DYNAMICS_DLLAPI Logger
   {
   public:
 
diff --git a/include/centroidal-dynamics-lib/solver_LP_abstract.hh b/include/centroidal-dynamics-lib/solver_LP_abstract.hh
index b28cbd4..43ccb29 100644
--- a/include/centroidal-dynamics-lib/solver_LP_abstract.hh
+++ b/include/centroidal-dynamics-lib/solver_LP_abstract.hh
@@ -3,8 +3,8 @@
  * Author: Andrea Del Prete
  */
 
-#ifndef ROBUST_EQUILIBRIUM_LIB_SOLVER_LP_ABSTRACT_HH
-#define ROBUST_EQUILIBRIUM_LIB_SOLVER_LP_ABSTRACT_HH
+#ifndef CENTROIDAL_DYNAMICS_LIB_SOLVER_LP_ABSTRACT_HH
+#define CENTROIDAL_DYNAMICS_LIB_SOLVER_LP_ABSTRACT_HH
 
 #include <Eigen/Dense>
 #include <centroidal-dynamics-lib/config.hh>
@@ -16,7 +16,7 @@ namespace robust_equilibrium
 /**
   * Available LP solvers.
   */
-enum ROBUST_EQUILIBRIUM_DLLAPI SolverLP
+enum CENTROIDAL_DYNAMICS_DLLAPI SolverLP
 {
   SOLVER_LP_QPOASES = 0
 #ifdef CLP_FOUND
@@ -28,7 +28,7 @@ enum ROBUST_EQUILIBRIUM_DLLAPI SolverLP
 /**
   * Possible states of an LP solver.
   */
-enum ROBUST_EQUILIBRIUM_DLLAPI LP_status
+enum CENTROIDAL_DYNAMICS_DLLAPI LP_status
 {
   LP_STATUS_UNKNOWN=-1,
   LP_STATUS_OPTIMAL=0,
@@ -42,7 +42,7 @@ enum ROBUST_EQUILIBRIUM_DLLAPI LP_status
 /**
  * @brief Abstract interface for a Linear Program (LP) solver.
  */
-class ROBUST_EQUILIBRIUM_DLLAPI Solver_LP_abstract
+class CENTROIDAL_DYNAMICS_DLLAPI Solver_LP_abstract
 {
 protected:
   bool                  m_useWarmStart;   // true if the solver is allowed to warm start
@@ -149,4 +149,4 @@ public:
 
 } // end namespace robust_equilibrium
 
-#endif //ROBUST_EQUILIBRIUM_LIB_SOLVER_LP_ABSTRACT_HH
+#endif //CENTROIDAL_DYNAMICS_LIB_SOLVER_LP_ABSTRACT_HH
diff --git a/include/centroidal-dynamics-lib/solver_LP_clp.hh b/include/centroidal-dynamics-lib/solver_LP_clp.hh
index a4729ce..6d0c2ee 100644
--- a/include/centroidal-dynamics-lib/solver_LP_clp.hh
+++ b/include/centroidal-dynamics-lib/solver_LP_clp.hh
@@ -5,8 +5,8 @@
 
 #ifdef CLP_FOUND
 
-#ifndef ROBUST_EQUILIBRIUM_LIB_SOLVER_LP_CLP_HH
-#define ROBUST_EQUILIBRIUM_LIB_SOLVER_LP_CLP_HH
+#ifndef CENTROIDAL_DYNAMICS_LIB_SOLVER_LP_CLP_HH
+#define CENTROIDAL_DYNAMICS_LIB_SOLVER_LP_CLP_HH
 
 #include <centroidal-dynamics-lib/config.hh>
 #include <centroidal-dynamics-lib/util.hh>
@@ -16,7 +16,7 @@
 namespace robust_equilibrium
 {
 
-class ROBUST_EQUILIBRIUM_DLLAPI Solver_LP_clp: public Solver_LP_abstract
+class CENTROIDAL_DYNAMICS_DLLAPI Solver_LP_clp: public Solver_LP_abstract
 {
 private:
   ClpSimplex m_model;
@@ -52,6 +52,6 @@ public:
 
 } // end namespace robust_equilibrium
 
-#endif //ROBUST_EQUILIBRIUM_LIB_SOLVER_LP_CLP_HH
+#endif //CENTROIDAL_DYNAMICS_LIB_SOLVER_LP_CLP_HH
 
 #endif // CLP_FOUND
diff --git a/include/centroidal-dynamics-lib/solver_LP_qpoases.hh b/include/centroidal-dynamics-lib/solver_LP_qpoases.hh
index 5b46c70..62bd5e9 100644
--- a/include/centroidal-dynamics-lib/solver_LP_qpoases.hh
+++ b/include/centroidal-dynamics-lib/solver_LP_qpoases.hh
@@ -3,8 +3,8 @@
  * Author: Andrea Del Prete
  */
 
-#ifndef ROBUST_EQUILIBRIUM_LIB_SOLVER_QPOASES_HH
-#define ROBUST_EQUILIBRIUM_LIB_SOLVER_QPOASES_HH
+#ifndef CENTROIDAL_DYNAMICS_LIB_SOLVER_QPOASES_HH
+#define CENTROIDAL_DYNAMICS_LIB_SOLVER_QPOASES_HH
 
 #include <centroidal-dynamics-lib/config.hh>
 #include <centroidal-dynamics-lib/util.hh>
@@ -14,7 +14,7 @@
 namespace robust_equilibrium
 {
 
-class ROBUST_EQUILIBRIUM_DLLAPI Solver_LP_qpoases: public Solver_LP_abstract
+class CENTROIDAL_DYNAMICS_DLLAPI Solver_LP_qpoases: public Solver_LP_abstract
 {
 private:
   qpOASES::Options    m_options;  // solver options
@@ -49,4 +49,4 @@ public:
 
 } // end namespace robust_equilibrium
 
-#endif //ROBUST_EQUILIBRIUM_LIB_SOLVER_QPOASES_HH
+#endif //CENTROIDAL_DYNAMICS_LIB_SOLVER_QPOASES_HH
diff --git a/include/centroidal-dynamics-lib/util.hh b/include/centroidal-dynamics-lib/util.hh
index d735325..43ea244 100644
--- a/include/centroidal-dynamics-lib/util.hh
+++ b/include/centroidal-dynamics-lib/util.hh
@@ -2,8 +2,8 @@
  * Copyright 2015, LAAS-CNRS
  * Author: Andrea Del Prete
  */
-#ifndef _ROBUST_EQUILIBRIUM_LIB_UTIL_HH
-#define _ROBUST_EQUILIBRIUM_LIB_UTIL_HH
+#ifndef _CENTROIDAL_DYNAMICS_LIB_UTIL_HH
+#define _CENTROIDAL_DYNAMICS_LIB_UTIL_HH
 
 #include <iostream>
 #include <fstream>
@@ -131,4 +131,4 @@ namespace robust_equilibrium
 
 } //namespace robust_equilibrium
 
-#endif //_ROBUST_EQUILIBRIUM_LIB_UTIL_HH
+#endif //_CENTROIDAL_DYNAMICS_LIB_UTIL_HH
diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt
index e06587b..ac902ed 100644
--- a/src/CMakeLists.txt
+++ b/src/CMakeLists.txt
@@ -19,8 +19,8 @@ SET(${LIBRARY_NAME}_SOURCES
 		${INCLUDE_DIR}/centroidal-dynamics-lib/solver_LP_abstract.hh
 		${INCLUDE_DIR}/centroidal-dynamics-lib/solver_LP_qpoases.hh
 		${INCLUDE_DIR}/centroidal-dynamics-lib/solver_LP_clp.hh
-		${INCLUDE_DIR}/centroidal-dynamics-lib/static_equilibrium.hh
-    static_equilibrium.cpp
+		${INCLUDE_DIR}/centroidal-dynamics-lib/centroidal_dynamics.hh
+		centroidal_dynamics.cpp
     solver_LP_abstract.cpp
     solver_LP_qpoases.cpp
     solver_LP_clp.cpp
diff --git a/src/static_equilibrium.cpp b/src/centroidal_dynamics.cpp
similarity index 97%
rename from src/static_equilibrium.cpp
rename to src/centroidal_dynamics.cpp
index 6787847..9cc69b2 100644
--- a/src/static_equilibrium.cpp
+++ b/src/centroidal_dynamics.cpp
@@ -3,7 +3,7 @@
  * Author: Andrea Del Prete
  */
 
-#include <centroidal-dynamics-lib/static_equilibrium.hh>
+#include <centroidal-dynamics-lib/centroidal_dynamics.hh>
 #include <centroidal-dynamics-lib/logger.hh>
 #include <centroidal-dynamics-lib/stop-watch.hh>
 #include <iostream>
@@ -130,16 +130,16 @@ bool StaticEquilibrium::computeGenerators(Cref_matrixX3 contactPoints, Cref_matr
 }
 
 bool StaticEquilibrium::setNewContacts(Cref_matrixX3 contactPoints, Cref_matrixX3 contactNormals,
-                                       double frictionCoefficient, StaticEquilibriumAlgorithm alg)
+                                       double frictionCoefficient, EquilibriumAlgorithm alg)
 {
   assert(contactPoints.rows()==contactNormals.rows());
 
-  if(alg==STATIC_EQUILIBRIUM_ALGORITHM_IP)
+  if(alg==EQUILIBRIUM_ALGORITHM_IP)
   {
     SEND_ERROR_MSG("Algorithm IP not implemented yet");
     return false;
   }
-  if(alg==STATIC_EQUILIBRIUM_ALGORITHM_DIP)
+  if(alg==EQUILIBRIUM_ALGORITHM_DIP)
   {
     SEND_ERROR_MSG("Algorithm DIP not implemented yet");
     return false;
@@ -155,7 +155,7 @@ bool StaticEquilibrium::setNewContacts(Cref_matrixX3 contactPoints, Cref_matrixX
     return false;
   }
 
-  if(m_algorithm==STATIC_EQUILIBRIUM_ALGORITHM_PP)
+  if(m_algorithm==EQUILIBRIUM_ALGORITHM_PP)
   {
     unsigned int attempts = max_num_cdd_trials;
     while(!computePolytopeProjection(m_G_centr) && attempts>0)
@@ -181,7 +181,7 @@ LP_status StaticEquilibrium::computeEquilibriumRobustness(Cref_vector3 com, doub
   if(m==0)
     return LP_STATUS_INFEASIBLE;
 
-  if(m_algorithm==STATIC_EQUILIBRIUM_ALGORITHM_LP)
+  if(m_algorithm==EQUILIBRIUM_ALGORITHM_LP)
   {
     /* Compute the robustness measure of the equilibrium of a specified CoM position
      * by solving the following LP:
@@ -220,7 +220,7 @@ LP_status StaticEquilibrium::computeEquilibriumRobustness(Cref_vector3 com, doub
     return lpStatus;
   }
 
-  if(m_algorithm==STATIC_EQUILIBRIUM_ALGORITHM_LP2)
+  if(m_algorithm==EQUILIBRIUM_ALGORITHM_LP2)
   {
     /* Compute the robustness measure of the equilibrium of a specified CoM position
      * by solving the following LP:
@@ -257,7 +257,7 @@ LP_status StaticEquilibrium::computeEquilibriumRobustness(Cref_vector3 com, doub
     return lpStatus_primal;
   }
 
-  if(m_algorithm==STATIC_EQUILIBRIUM_ALGORITHM_DLP)
+  if(m_algorithm==EQUILIBRIUM_ALGORITHM_DLP)
   {
     /*Compute the robustness measure of the equilibrium of a specified CoM position
       by solving the following dual LP:
@@ -336,7 +336,7 @@ LP_status StaticEquilibrium::checkRobustEquilibrium(Cref_vector3 com, bool &equi
     SEND_ERROR_MSG("checkRobustEquilibrium with e_max!=0 not implemented yet");
     return LP_STATUS_ERROR;
   }
-  if(m_algorithm!=STATIC_EQUILIBRIUM_ALGORITHM_PP)
+  if(m_algorithm!=EQUILIBRIUM_ALGORITHM_PP)
   {
     SEND_ERROR_MSG("checkRobustEquilibrium is only implemented for the PP algorithm");
     return LP_STATUS_ERROR;
@@ -357,7 +357,7 @@ LP_status StaticEquilibrium::checkRobustEquilibrium(Cref_vector3 com, bool &equi
 
 LP_status StaticEquilibrium::getPolytopeInequalities(MatrixXX& H, VectorX& h) const
 {
-    if(m_algorithm!=STATIC_EQUILIBRIUM_ALGORITHM_PP)
+    if(m_algorithm!=EQUILIBRIUM_ALGORITHM_PP)
     {
       SEND_ERROR_MSG("getPolytopeInequalities is only implemented for the PP algorithm");
       return LP_STATUS_ERROR;
@@ -384,7 +384,7 @@ LP_status StaticEquilibrium::findExtremumOverLine(Cref_vector3 a, Cref_vector3 a
 
   double b0 = convert_emax_to_b0(e_max);
 
-  if(m_algorithm==STATIC_EQUILIBRIUM_ALGORITHM_LP)
+  if(m_algorithm==EQUILIBRIUM_ALGORITHM_LP)
   {
     /* Compute the extremum CoM position over the line a*p + a0 that is in robust equilibrium
      * by solving the following LP:
@@ -436,7 +436,7 @@ LP_status StaticEquilibrium::findExtremumOverLine(Cref_vector3 a, Cref_vector3 a
     return lpStatus_primal;
   }
 
-  if(m_algorithm==STATIC_EQUILIBRIUM_ALGORITHM_DLP)
+  if(m_algorithm==EQUILIBRIUM_ALGORITHM_DLP)
   {
     /* Compute the extremum CoM position over the line a*x + a0 that is in robust equilibrium
      * by solving the following dual LP:
diff --git a/src/util.cpp b/src/util.cpp
index e10ac96..243fd2b 100644
--- a/src/util.cpp
+++ b/src/util.cpp
@@ -3,8 +3,8 @@
  * Author: Andrea Del Prete
  */
 
-#ifndef _ROBUST_EQUILIBRIUM_LIB_CONFIG_HH
-#define _ROBUST_EQUILIBRIUM_LIB_CONFIG_HH
+#ifndef _CENTROIDAL_DYNAMICS_LIB_CONFIG_HH
+#define _CENTROIDAL_DYNAMICS_LIB_CONFIG_HH
 
 #include <centroidal-dynamics-lib/util.hh>
 #include <ctime>
@@ -168,4 +168,4 @@ std::string getDateAndTimeAsString()
 
 } //namespace robust_equilibrium
 
-#endif //_ROBUST_EQUILIBRIUM_LIB_CONFIG_HH
+#endif //_CENTROIDAL_DYNAMICS_LIB_CONFIG_HH
diff --git a/test/test_static_equilibrium.cpp b/test/test_static_equilibrium.cpp
index 7c90550..a25f65d 100644
--- a/test/test_static_equilibrium.cpp
+++ b/test/test_static_equilibrium.cpp
@@ -5,7 +5,7 @@
 
 #include <vector>
 #include <iostream>
-#include <centroidal-dynamics-lib/static_equilibrium.hh>
+#include <centroidal-dynamics-lib/centroidal_dynamics.hh>
 #include <centroidal-dynamics-lib/logger.hh>
 #include <centroidal-dynamics-lib/stop-watch.hh>
 
@@ -359,9 +359,9 @@ void testWithLoadedData()
 
   const int N_SOLVERS = 3;
   string solverNames[] = {"LP oases", "LP2 oases", "DLP oases"};
-  StaticEquilibriumAlgorithm algorithms[] = {STATIC_EQUILIBRIUM_ALGORITHM_LP,
-                                             STATIC_EQUILIBRIUM_ALGORITHM_LP2,
-                                             STATIC_EQUILIBRIUM_ALGORITHM_DLP};
+  EquilibriumAlgorithm algorithms[] = {EQUILIBRIUM_ALGORITHM_LP,
+                                             EQUILIBRIUM_ALGORITHM_LP2,
+                                             EQUILIBRIUM_ALGORITHM_DLP};
 
   MatrixXX contactPoints, contactNormals;
   Vector3 com;
@@ -440,20 +440,20 @@ int main()
   const int N_SOLVERS = 6;
   string solverNames[] = {"LP oases", "LP2 oases", "DLP oases",
                           "LP coin", "LP2 coin", "DLP coin"};
-  StaticEquilibriumAlgorithm algorithms[] = {STATIC_EQUILIBRIUM_ALGORITHM_LP,
-                                             STATIC_EQUILIBRIUM_ALGORITHM_LP2,
-                                             STATIC_EQUILIBRIUM_ALGORITHM_DLP,
-                                             STATIC_EQUILIBRIUM_ALGORITHM_LP,
-                                             STATIC_EQUILIBRIUM_ALGORITHM_LP2,
-                                             STATIC_EQUILIBRIUM_ALGORITHM_DLP};
+  EquilibriumAlgorithm algorithms[] = {EQUILIBRIUM_ALGORITHM_LP,
+                                             EQUILIBRIUM_ALGORITHM_LP2,
+                                             EQUILIBRIUM_ALGORITHM_DLP,
+                                             EQUILIBRIUM_ALGORITHM_LP,
+                                             EQUILIBRIUM_ALGORITHM_LP2,
+                                             EQUILIBRIUM_ALGORITHM_DLP};
   SolverLP lp_solver_types[] = {SOLVER_LP_QPOASES, SOLVER_LP_QPOASES, SOLVER_LP_QPOASES,
                         SOLVER_LP_CLP, SOLVER_LP_CLP, SOLVER_LP_CLP};
 #else
   const int N_SOLVERS = 3;
   string solverNames[] = {"LP oases", "LP2 oases", "DLP oases"};
-  StaticEquilibriumAlgorithm algorithms[] = {STATIC_EQUILIBRIUM_ALGORITHM_LP,
-                                             STATIC_EQUILIBRIUM_ALGORITHM_LP2,
-                                             STATIC_EQUILIBRIUM_ALGORITHM_DLP};
+  EquilibriumAlgorithm algorithms[] = {EQUILIBRIUM_ALGORITHM_LP,
+                                             EQUILIBRIUM_ALGORITHM_LP2,
+                                             EQUILIBRIUM_ALGORITHM_DLP};
   SolverLP lp_solver_types[] = {SOLVER_LP_QPOASES, SOLVER_LP_QPOASES, SOLVER_LP_QPOASES};
 #endif
 
@@ -487,7 +487,7 @@ int main()
       getProfiler().stop(PERF_LP_PREPARATION);
     }
     getProfiler().start(PERF_PP);
-    if(!solver_PP->setNewContacts(p, N, mu, STATIC_EQUILIBRIUM_ALGORITHM_PP))
+    if(!solver_PP->setNewContacts(p, N, mu, EQUILIBRIUM_ALGORITHM_PP))
     {
       SEND_ERROR_MSG("Error while setting new contacts for solver "+solver_PP->getName());
       return -1;
@@ -544,7 +544,7 @@ int main()
       string test_name2 = "Compute equilibrium robustness ";
       for(int s=1; s<N_SOLVERS; s++)
       {
-        if(solvers[s]->getAlgorithm()!=STATIC_EQUILIBRIUM_ALGORITHM_LP2)
+        if(solvers[s]->getAlgorithm()!=EQUILIBRIUM_ALGORITHM_LP2)
           test_findExtremumOverLine(solvers[s], solvers[0], a0, N_TESTS_EXTREMUM, e_max, test_name+solvers[s]->getName(),
               test_name2+solvers[0]->getName(), 1);
       }
-- 
GitLab