From 3e1929c0a8dee302237b6e8a1aff60a918cd53dc Mon Sep 17 00:00:00 2001
From: Olivier Stasse <olivier.stasse@laas.fr>
Date: Sat, 2 Dec 2023 03:39:24 +0100
Subject: [PATCH] [pre-commit] Beautification

---
 include/dynamic_graph_bridge/ros.hpp          |   1 -
 include/dynamic_graph_bridge/sot_loader.hh    |   2 +-
 .../dynamic_graph_bridge/sot_loader_basic.hh  |   6 +-
 scripts/remote_python_client.py               |   2 +-
 src/ros.cpp                                   |   4 +-
 src/ros_python_interpreter_server.cpp         |  11 +-
 src/sot_loader.cpp                            |   6 +-
 src/sot_loader_basic.cpp                      |  37 +++----
 tests/CMakeLists.txt                          |   7 +-
 tests/impl_test_sot_external_interface.cpp    |   3 +-
 tests/test_ros_interpreter.cpp                |   1 -
 tests/test_sot_loader.cpp                     | 100 ++++++++----------
 12 files changed, 84 insertions(+), 96 deletions(-)

diff --git a/include/dynamic_graph_bridge/ros.hpp b/include/dynamic_graph_bridge/ros.hpp
index 5340598..b11acb3 100644
--- a/include/dynamic_graph_bridge/ros.hpp
+++ b/include/dynamic_graph_bridge/ros.hpp
@@ -67,7 +67,6 @@ typedef std_srvs::srv::Empty EmptyServiceType;
  */
 RosNodePtr get_ros_node(std::string node_name);
 
-
 size_t ros_executor_get_nb_threads();
 
 void ros_display_list_of_nodes();
diff --git a/include/dynamic_graph_bridge/sot_loader.hh b/include/dynamic_graph_bridge/sot_loader.hh
index 9d4070a..f844ba6 100644
--- a/include/dynamic_graph_bridge/sot_loader.hh
+++ b/include/dynamic_graph_bridge/sot_loader.hh
@@ -80,7 +80,7 @@ class SotLoader : public SotLoaderBasic {
   geometry_msgs::msg::TransformStamped freeFlyerPose_;
 
  public:
-  SotLoader(const std::string &aNodeName=std::string("sot_loader"));
+  SotLoader(const std::string &aNodeName = std::string("sot_loader"));
   virtual ~SotLoader();
 
   // \brief Create a thread for ROS and start the control loop.
diff --git a/include/dynamic_graph_bridge/sot_loader_basic.hh b/include/dynamic_graph_bridge/sot_loader_basic.hh
index 8be36bf..76187f7 100644
--- a/include/dynamic_graph_bridge/sot_loader_basic.hh
+++ b/include/dynamic_graph_bridge/sot_loader_basic.hh
@@ -38,7 +38,7 @@
 namespace po = boost::program_options;
 namespace dgs = dynamicgraph::sot;
 
-class SotLoaderBasic  {
+class SotLoaderBasic {
  protected:
   // RosNode
   dynamic_graph_bridge::RosNodePtr ros_node_;
@@ -83,9 +83,9 @@ class SotLoaderBasic  {
   // Ordered list of joint names describing the robot state.
   std::vector<std::string> stateVectorMap_;
 
-
  public:
-  SotLoaderBasic(const std::string& aNodeName = std::string("sot_loader_basic"));
+  SotLoaderBasic(
+      const std::string& aNodeName = std::string("sot_loader_basic"));
   virtual ~SotLoaderBasic();
 
   // \brief Read user input to extract the path of the SoT dynamic library.
diff --git a/scripts/remote_python_client.py b/scripts/remote_python_client.py
index 2fb0432..e3c7023 100755
--- a/scripts/remote_python_client.py
+++ b/scripts/remote_python_client.py
@@ -24,10 +24,10 @@ import sys
 from pathlib import Path
 
 import rclpy
+from dynamic_graph_bridge_cpp_bindings import RosPythonInterpreterClient
 
 # Used to connect to ROS services
 from dynamic_graph_bridge.ros.dgcompleter import DGCompleter
-from dynamic_graph_bridge_cpp_bindings import RosPythonInterpreterClient
 
 
 def signal_handler(sig, frame):
diff --git a/src/ros.cpp b/src/ros.cpp
index dd07121..0f8f215 100644
--- a/src/ros.cpp
+++ b/src/ros.cpp
@@ -211,7 +211,6 @@ std::string executable_name() {
 #endif
 }
 
-
 /**
  * @brief Private function that allow us to initialize ROS only once.
  */
@@ -288,14 +287,13 @@ size_t ros_executor_get_nb_threads() {
 void ros_display_list_of_nodes() {
   GlobalListOfRosNodeType::iterator ros_node_it =
       GLOBAL_LIST_OF_ROS_NODE.begin();
-  while(ros_node_it!=GLOBAL_LIST_OF_ROS_NODE.end()) {
+  while (ros_node_it != GLOBAL_LIST_OF_ROS_NODE.end()) {
     RCLCPP_INFO(rclcpp::get_logger("dynamic_graph_bridge"),
                 "ros_display_list_of_nodes: %s/%s",
                 ros_node_it->second->get_namespace(),
                 ros_node_it->second->get_name());
     ros_node_it++;
   }
-
 }
 
 void ros_clean() {
diff --git a/src/ros_python_interpreter_server.cpp b/src/ros_python_interpreter_server.cpp
index 9f93ada..ce92f7d 100644
--- a/src/ros_python_interpreter_server.cpp
+++ b/src/ros_python_interpreter_server.cpp
@@ -31,8 +31,9 @@ void RosPythonInterpreterServer::start_ros_service() {
                 std::placeholders::_1, std::placeholders::_2);
   run_python_command_srv_ = ros_node_->create_service<RunPythonCommandSrvType>(
       "/dynamic_graph_bridge/run_python_command", runCommandCb);
-  RCLCPP_INFO(rclcpp::get_logger("dynamic_graph_bridge"),
-              "RosPythonInterpreterServer::start_ros_service - run_python_command...");
+  RCLCPP_INFO(
+      rclcpp::get_logger("dynamic_graph_bridge"),
+      "RosPythonInterpreterServer::start_ros_service - run_python_command...");
 
   run_python_file_callback_t runPythonFileCb =
       std::bind(&RosPythonInterpreterServer::runPythonFileCallback, this,
@@ -40,9 +41,9 @@ void RosPythonInterpreterServer::start_ros_service() {
   run_python_file_srv_ = ros_node_->create_service<RunPythonFileSrvType>(
       "/dynamic_graph_bridge/run_python_file", runPythonFileCb);
 
-  RCLCPP_INFO(rclcpp::get_logger("dynamic_graph_bridge"),
-              "RosPythonInterpreterServer::start_ros_service - run_python_file...");
-
+  RCLCPP_INFO(
+      rclcpp::get_logger("dynamic_graph_bridge"),
+      "RosPythonInterpreterServer::start_ros_service - run_python_file...");
 }
 
 void RosPythonInterpreterServer::runCommandCallback(
diff --git a/src/sot_loader.cpp b/src/sot_loader.cpp
index 9db6ded..ae0f363 100644
--- a/src/sot_loader.cpp
+++ b/src/sot_loader.cpp
@@ -226,8 +226,10 @@ void SotLoader::workThreadLoader() {
   double periodd;
 
   /// Declare parameters
-  if (not ros_node_->has_parameter("dt")) ros_node_->declare_parameter<double>("dt", 0.01);
-  if (not ros_node_->has_parameter("paused")) ros_node_->declare_parameter<bool>("paused", false);
+  if (not ros_node_->has_parameter("dt"))
+    ros_node_->declare_parameter<double>("dt", 0.01);
+  if (not ros_node_->has_parameter("paused"))
+    ros_node_->declare_parameter<bool>("paused", false);
 
   //
   ros_node_->get_parameter_or("dt", periodd, 0.001);
diff --git a/src/sot_loader_basic.cpp b/src/sot_loader_basic.cpp
index 26ecf1c..a8f3593 100644
--- a/src/sot_loader_basic.cpp
+++ b/src/sot_loader_basic.cpp
@@ -31,7 +31,6 @@ SotLoaderBasic::SotLoaderBasic(const std::string& aNodeName)
       dynamic_graph_stopped_(true),
       sotController_(NULL),
       sotRobotControllerLibrary_(0) {
-
   ros_node_ = dynamic_graph_bridge::get_ros_node(aNodeName);
 
   RCLCPP_INFO(rclcpp::get_logger("dynamic_graph_bridge::"),
@@ -51,8 +50,8 @@ int SotLoaderBasic::initPublication() {
   RCLCPP_INFO(rclcpp::get_logger("dynamic_graph_bridge"),
               "SotLoaderBasic::initPublication - create joint_pub");
 
-  joint_pub_ = ros_node_->
-      create_publisher<sensor_msgs::msg::JointState>("joint_states", 1);
+  joint_pub_ = ros_node_->create_publisher<sensor_msgs::msg::JointState>(
+      "joint_states", 1);
 
   RCLCPP_INFO(rclcpp::get_logger("dynamic_graph_bridge"),
               "SotLoaderBasic::initPublication - after create joint_pub");
@@ -65,19 +64,17 @@ void SotLoaderBasic::initializeServices() {
       "SotLoaderBasic::initializeServices - Ready to start dynamic graph.");
 
   using namespace std::placeholders;
-  service_start_ = ros_node_->
-      create_service<std_srvs::srv::Empty>(
-          "start_dynamic_graph",
-          std::bind(&SotLoaderBasic::start_dg, this, std::placeholders::_1,
-                    std::placeholders::_2));
+  service_start_ = ros_node_->create_service<std_srvs::srv::Empty>(
+      "start_dynamic_graph",
+      std::bind(&SotLoaderBasic::start_dg, this, std::placeholders::_1,
+                std::placeholders::_2));
   RCLCPP_INFO(rclcpp::get_logger("dynamic_graph_bridge"),
               "SotLoaderBasic::initializeServices - start_dynamic_graph.");
 
-  service_stop_ = ros_node_->
-      create_service<std_srvs::srv::Empty>(
-          "stop_dynamic_graph",
-          std::bind(&SotLoaderBasic::stop_dg, this, std::placeholders::_1,
-                    std::placeholders::_2));
+  service_stop_ = ros_node_->create_service<std_srvs::srv::Empty>(
+      "stop_dynamic_graph",
+      std::bind(&SotLoaderBasic::stop_dg, this, std::placeholders::_1,
+                std::placeholders::_2));
   RCLCPP_INFO(rclcpp::get_logger("dynamic_graph_bridge"),
               "SotLoaderBasic::initializeServices - stop_dynamic_graph.");
 
@@ -95,9 +92,11 @@ int SotLoaderBasic::readSotVectorStateParam() {
   // It is necessary to declare parameters first
   // before trying to access them.
   if (not ros_node_->has_parameter("state_vector_map"))
-    ros_node_->declare_parameter("state_vector_map", std::vector<std::string>{});
+    ros_node_->declare_parameter("state_vector_map",
+                                 std::vector<std::string>{});
   if (not ros_node_->has_parameter("joint_state_parallel"))
-    ros_node_->declare_parameter("joint_state_parallel", std::vector<std::string>{});
+    ros_node_->declare_parameter("joint_state_parallel",
+                                 std::vector<std::string>{});
 
   // Read the state vector of the robot
   // Defines the order in which the actuators are ordered
@@ -208,8 +207,7 @@ void SotLoaderBasic::loadController() {
       dlopen(dynamicLibraryName_.c_str(), RTLD_LAZY | RTLD_GLOBAL);
   if (!sotRobotControllerLibrary_) {
     RCLCPP_ERROR(rclcpp::get_logger("dynamic_graph_bridge"),
-                 "Cannot load library: %s",
-                 dlerror());
+                 "Cannot load library: %s", dlerror());
     return;
   }
 
@@ -223,9 +221,8 @@ void SotLoaderBasic::loadController() {
   const char* dlsym_error = dlerror();
   if (dlsym_error) {
     RCLCPP_ERROR(rclcpp::get_logger("dynamic_graph_bridge"),
-                 "Cannot load symbol create: %s from %s",
-                 dlsym_error,
-                 dynamicLibraryName_.c_str() );
+                 "Cannot load symbol create: %s from %s", dlsym_error,
+                 dynamicLibraryName_.c_str());
     return;
   }
 
diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt
index 184907b..aab0fcf 100644
--- a/tests/CMakeLists.txt
+++ b/tests/CMakeLists.txt
@@ -67,8 +67,8 @@ if(BUILD_TESTING)
     PUBLIC include "${GMOCK_INCLUDE_DIRS}"
     PRIVATE ${PROJECT_SOURCE_DIR}/include)
   target_compile_definitions(
-      test_sot_loader
-      PUBLIC TEST_CONFIG_PATH="${CMAKE_CURRENT_LIST_DIR}/python_scripts/")
+    test_sot_loader
+    PUBLIC TEST_CONFIG_PATH="${CMAKE_CURRENT_LIST_DIR}/python_scripts/")
   target_link_libraries(test_sot_loader sot_loader "${GMOCK_LIBRARIES}")
 
   add_launch_test(launch/launching_test_sot_loader.py)
@@ -116,8 +116,7 @@ if(BUILD_TESTING)
                               rclcpp rcl_interfaces std_srvs)
 
     # Install tests
-    install(TARGETS test_${test_name}
-      DESTINATION lib/${PROJECT_NAME})
+    install(TARGETS test_${test_name} DESTINATION lib/${PROJECT_NAME})
 
   endmacro(create_ros_bridge_unittest test_name)
 
diff --git a/tests/impl_test_sot_external_interface.cpp b/tests/impl_test_sot_external_interface.cpp
index 34b0100..c285411 100644
--- a/tests/impl_test_sot_external_interface.cpp
+++ b/tests/impl_test_sot_external_interface.cpp
@@ -79,7 +79,8 @@ void ImplTestSotExternalInterface::setupSetSensors(
 
 void ImplTestSotExternalInterface::nominalSetSensors(
     std::map<std::string, dynamicgraph::sot::SensorValues> &) {
-  //  std::cout << "ImplTestSotExternalInterface::nominalSetSensors" << std::endl;
+  //  std::cout << "ImplTestSotExternalInterface::nominalSetSensors" <<
+  //  std::endl;
 }
 
 void ImplTestSotExternalInterface::cleanupSetSensors(
diff --git a/tests/test_ros_interpreter.cpp b/tests/test_ros_interpreter.cpp
index 1129125..10091b3 100644
--- a/tests/test_ros_interpreter.cpp
+++ b/tests/test_ros_interpreter.cpp
@@ -286,5 +286,4 @@ TEST_F(TestRosInterpreter, test_call_run_script_ros_publish) {
 
   /* Tests the result. */
   ASSERT_EQ(result, "");
-
 }
diff --git a/tests/test_sot_loader.cpp b/tests/test_sot_loader.cpp
index 12b32e1..3170c6d 100644
--- a/tests/test_sot_loader.cpp
+++ b/tests/test_sot_loader.cpp
@@ -8,14 +8,14 @@ using namespace std::chrono_literals;
 #include <rclcpp/rclcpp.hpp>
 
 #include "dynamic_graph_bridge/ros.hpp"
+#include "dynamic_graph_bridge/ros_python_interpreter_server.hpp"
 #include "dynamic_graph_bridge/sot_loader.hh"
 #include "dynamic_graph_bridge_msgs/msg/vector.hpp"
-#include "dynamic_graph_bridge/ros_python_interpreter_server.hpp"
 
 namespace test_sot_loader {
 int l_argc;
 char** l_argv;
-}
+}  // namespace test_sot_loader
 
 namespace dg = dynamicgraph;
 
@@ -24,42 +24,45 @@ class MockSotLoaderTest : public ::testing::Test {
   class MockSotLoader : public SotLoader {
    public:
     rclcpp::Subscription<dynamic_graph_bridge_msgs::msg::Vector>::SharedPtr
-    subscription_;
+        subscription_;
     bool service_done_;
     std::string node_name_;
     std::string response_dg_python_result_;
 
-    MockSotLoader():
-        node_name_("unittest_sot_loader") {}
+    MockSotLoader() : node_name_("unittest_sot_loader") {}
 
     ~MockSotLoader() {
       service_done_ = false;
       response_dg_python_result_ = "";
     }
 
-    void topic_callback(const dynamic_graph_bridge_msgs::msg::Vector::SharedPtr msg) const {
-      bool ok=true;
-      for(std::vector<double>::size_type idx=0;idx<msg->data.size();idx++) {
-        if (msg->data[idx]!=0.0)
-          ok=false;
+    void topic_callback(
+        const dynamic_graph_bridge_msgs::msg::Vector::SharedPtr msg) const {
+      bool ok = true;
+      for (std::vector<double>::size_type idx = 0; idx < msg->data.size();
+           idx++) {
+        if (msg->data[idx] != 0.0) ok = false;
       }
       ASSERT_TRUE(ok);
     }
-    // This method is to listen to publication from the control signal (dg world)
-    // to the control_ros topic (ros world).
+    // This method is to listen to publication from the control signal (dg
+    // world) to the control_ros topic (ros world).
     void subscribe_to_a_topic() {
-      subscription_ = dynamic_graph_bridge::get_ros_node(node_name_)->
-          create_subscription<dynamic_graph_bridge_msgs::msg::Vector>(
-              "control_ros", 1, std::bind(&MockSotLoader::topic_callback, this,
-                                          std::placeholders::_1));
+      subscription_ =
+          dynamic_graph_bridge::get_ros_node(node_name_)
+              ->create_subscription<dynamic_graph_bridge_msgs::msg::Vector>(
+                  "control_ros", 1,
+                  std::bind(&MockSotLoader::topic_callback, this,
+                            std::placeholders::_1));
     }
 
     // This method is to receive the result of client request to run_python_file
     //
     void response_dg_python(
-        const rclcpp::Client<dynamic_graph_bridge_msgs::srv::RunPythonFile>::SharedFuture
-        future) {
-      RCLCPP_INFO(rclcpp::get_logger("dynamic_graph_bridge"), "response_dg_python:");
+        const rclcpp::Client<dynamic_graph_bridge_msgs::srv::RunPythonFile>::
+            SharedFuture future) {
+      RCLCPP_INFO(rclcpp::get_logger("dynamic_graph_bridge"),
+                  "response_dg_python:");
       auto status = future.wait_for(500ms);
       if (status == std::future_status::ready) {
         // uncomment below line if using Empty() message
@@ -80,34 +83,30 @@ class MockSotLoaderTest : public ::testing::Test {
       // Service name.
       std::string service_name = "/dynamic_graph_bridge/run_python_file";
       // Create a client from a temporary node.
-      auto client = dynamic_graph_bridge::get_ros_node(node_name_)->
-          create_client<dynamic_graph_bridge_msgs::srv::RunPythonFile>(
-              service_name);
+      auto client =
+          dynamic_graph_bridge::get_ros_node(node_name_)
+              ->create_client<dynamic_graph_bridge_msgs::srv::RunPythonFile>(
+                  service_name);
       ASSERT_TRUE(client->wait_for_service(1s));
 
       // Fill the command message.
-      dynamic_graph_bridge_msgs::srv::RunPythonFile::Request::SharedPtr request =
-          std::make_shared<
-            dynamic_graph_bridge_msgs::srv::RunPythonFile::Request>();
+      dynamic_graph_bridge_msgs::srv::RunPythonFile::Request::SharedPtr
+          request = std::make_shared<
+              dynamic_graph_bridge_msgs::srv::RunPythonFile::Request>();
       request->input = file_name;
       // Call the service.
-      auto response =
-          client->async_send_request(request,
-                                     std::bind(&MockSotLoader::response_dg_python,
-                                               this,
-                                               std::placeholders::_1));
+      auto response = client->async_send_request(
+          request, std::bind(&MockSotLoader::response_dg_python, this,
+                             std::placeholders::_1));
       RCLCPP_INFO(rclcpp::get_logger("dynamic_graph_bridge"),
-                  "Send request to service %s - Waiting",
-                  service_name.c_str());
+                  "Send request to service %s - Waiting", service_name.c_str());
       response.wait();
-      RCLCPP_INFO(rclcpp::get_logger("dynamic_graph_bridge"),
-                  "Get the answer");
-
+      RCLCPP_INFO(rclcpp::get_logger("dynamic_graph_bridge"), "Get the answer");
     }
 
-    void display_services(
-        std::map<std::string, std::vector<std::string> >& list_service_and_types) {
-      for (std::map<std::string, std::vector<std::string> >::const_iterator
+    void display_services(std::map<std::string, std::vector<std::string>>&
+                              list_service_and_types) {
+      for (std::map<std::string, std::vector<std::string>>::const_iterator
                const_it = list_service_and_types.begin();
            const_it != list_service_and_types.end(); ++const_it) {
         std::cerr << const_it->first << "\t\t\t";
@@ -119,8 +118,7 @@ class MockSotLoaderTest : public ::testing::Test {
     }
 
     void local_ros_spin() {
-      RCLCPP_INFO(rclcpp::get_logger("dynamic_graph_bridge"),
-                  "local_ros_spin");
+      RCLCPP_INFO(rclcpp::get_logger("dynamic_graph_bridge"), "local_ros_spin");
       dynamic_graph_bridge::ros_spin();
     }
 
@@ -137,23 +135,22 @@ class MockSotLoaderTest : public ::testing::Test {
       std::string standard_error = "";
       start_run_python_script_ros_service(file_name);
 
-
       usleep(100000);
       std::map<std::string, std::vector<std::string>> list_service_and_types;
-      dynamic_graph_bridge::RosNodePtr ros_node = dynamic_graph_bridge::get_ros_node(node_name_);
+      dynamic_graph_bridge::RosNodePtr ros_node =
+          dynamic_graph_bridge::get_ros_node(node_name_);
       bool simple_service_exists = false;
 
-      usleep(30720000); // Wait 30s
+      usleep(30720000);  // Wait 30s
       RCLCPP_INFO(rclcpp::get_logger("dynamic_graph_bridge"),
                   "Stop Dynamic Graph ");
       dynamic_graph_stopped_ = true;
     }
 
-
     void testLoadController() {
       // Set input  call
       int argc = 2;
-      char *argv[2];
+      char* argv[2];
       char argv1[30] = "mocktest";
       argv[0] = argv1;
       char argv2[60] = "--input-file=libimpl_test_library.so";
@@ -195,19 +192,15 @@ class MockSotLoaderTest : public ::testing::Test {
   };
 
  public:
-  MockSotLoader *mockSotLoader_ptr_;
+  MockSotLoader* mockSotLoader_ptr_;
 
   // For the set of tests coded in this file.
   static void SetUpTestCase() {
-
-    rclcpp::init(test_sot_loader::l_argc,
-                 test_sot_loader::l_argv);
+    rclcpp::init(test_sot_loader::l_argc, test_sot_loader::l_argv);
   }
 
   // For each test specified in this file
-  static void TearDownTestCase() {
-    rclcpp::shutdown();
-  }
+  static void TearDownTestCase() { rclcpp::shutdown(); }
 
   void SetUp() {
     mockSotLoader_ptr_ = new MockSotLoader();
@@ -226,13 +219,12 @@ TEST_F(MockSotLoaderTest, TestLoadController) {
   mockSotLoader_ptr_->testLoadController();
 }
 
-int main(int argc, char **argv) {
+int main(int argc, char** argv) {
   ::testing::InitGoogleTest(&argc, argv);
 
   test_sot_loader::l_argc = argc;
   test_sot_loader::l_argv = argv;
 
-
   int r = RUN_ALL_TESTS();
 
   return r;
-- 
GitLab