From 3fb3b43baa0e4d462a52599a74905450ae564eb3 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Sergi=20Hern=C3=A0ndez=20Juan?= <shernand@iri.upc.edu>
Date: Thu, 5 Dec 2013 14:05:08 +0000
Subject: [PATCH] Removed the dependencies on the iriutils library from the
 iri_base_algorithm

---
 CMakeLists.txt                                |  4 +-
 .../iri_base_algorithm/iri_base_algorithm.h   | 50 +++++--------------
 2 files changed, 14 insertions(+), 40 deletions(-)

diff --git a/CMakeLists.txt b/CMakeLists.txt
index 87a9622..6ce13fd 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -23,9 +23,7 @@ set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
 # edit the following line to add all the header files of the library
 # SET(headers ./include/iri_base_algorithm.h)
 
-# FIND_PACKAGE(iriutils REQUIRED)
-
-# INCLUDE_DIRECTORIES(${iriutils_INCLUDE_DIR} ${headers})
+# INCLUDE_DIRECTORIES(${headers})
 
 #common commands for building c++ executables and libraries
 # rosbuild_add_library(${PROJECT_NAME} SHARED ${sources})
diff --git a/include/iri_base_algorithm/iri_base_algorithm.h b/include/iri_base_algorithm/iri_base_algorithm.h
index 012fb8c..e0d3026 100644
--- a/include/iri_base_algorithm/iri_base_algorithm.h
+++ b/include/iri_base_algorithm/iri_base_algorithm.h
@@ -22,11 +22,6 @@
 #include <ros/ros.h>
 #include <signal.h>
 
-// iri-utils thread server
-#include "threadserver.h"
-#include "exceptions.h"
-#include "mutex.h"
-
 // boost thread includes for ROS::spin thread
 #include <boost/thread.hpp>
 #include <boost/bind.hpp>
@@ -98,24 +93,15 @@ class IriBaseAlgorithm : public AbstractAlgorithmNode
     typedef typename Algorithm::Config Config;
 
   protected:
-   /**
-    * \brief Reference to the unique thread handler
-    *
-    * This reference to the unique thread handler is initialized when an object 
-    * of this class is first created. It is used to create and handle all the
-    * IriBaseNodeDriver threads. The object pointed by this reference is shared 
-    * by all objects in any application.
-    */
-    CThreadServer *thread_server_;
-
-   /**
-    * \brief identifier of the node main thread
-    *
-    * This string has the identifier of the main IriBaseNodeDriver thread.  
-    * This string is initialized at contruction time. This thread is only used 
-    * internally to the class, so it is not possible to get its identifier out.
-    */
-    std::string main_thread_id_;
+    /**
+     * \brief Thread information structure
+     *
+     * This structure hold system level information of the thread and it is 
+     * initialized when the thread is first created. This information can not 
+     * be modified at any time and it is not accessible from outside the class.
+     *
+     */
+    pthread_t thread;
 
    /**
     * \brief template algorithm class
@@ -299,15 +285,9 @@ IriBaseAlgorithm<Algorithm>::IriBaseAlgorithm() :
   dsrv_(private_node_handle_)
 {
   ROS_DEBUG("IriBaseAlgorithm::Constructor");
-  // create thread server instance
-  this->thread_server_  = CThreadServer::instance();
-
-  // identify main thread
-  this->main_thread_id_ = "main_thread";
 
-  // create main thread and attach to server
-  this->thread_server_->create_thread(this->main_thread_id_);
-  this->thread_server_->attach_thread(this->main_thread_id_, this->mainThread, this);
+  // create the status thread
+  pthread_create(&this->thread,NULL,this->mainThread,this);
 
 //   // assign callback to dynamic reconfigure server
 //   dsrv_.setCallback(boost::bind(&IriBaseAlgorithm<Algorithm>::reconfigureCallback, this, _1, _2));
@@ -318,9 +298,8 @@ template <class Algorithm>
 IriBaseAlgorithm<Algorithm>::~IriBaseAlgorithm()
 {
   ROS_DEBUG("IriBaseAlgorithm::Destructor");
-
-  this->thread_server_->kill_thread(this->main_thread_id_);
-  this->thread_server_->delete_thread(this->main_thread_id_);
+  pthread_cancel(this->thread);
+  pthread_join(this->thread,NULL);
 }
 
 template <class Algorithm>
@@ -375,9 +354,6 @@ int IriBaseAlgorithm<Algorithm>::spin(void)
   // assign callback to dynamic reconfigure server
   this->dsrv_.setCallback(boost::bind(&IriBaseAlgorithm<Algorithm>::reconfigureCallback, this, _1, _2));
 
-  // launch node thread
-  this->thread_server_->start_thread( this->main_thread_id_);
-  
   while(ros::ok() && !ctrl_c_hit_count_)
   {
     // update diagnostics
-- 
GitLab