diff --git a/CMakeLists.txt b/CMakeLists.txt
index 66272b2e35e02ec5ccb33605800eb3f3b8bd4e27..73f91c747c10eec4cf8343242ef65279fecaf7f7 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -23,9 +23,7 @@ SET(sources ./src/iri_base_driver.cpp)
 # edit the following line to add all the header files of the library
 SET(headers ./include/iri_base_driver.h ./include/iri_base_driver_node.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_driver/iri_base_driver.h b/include/iri_base_driver/iri_base_driver.h
index 51ade143ccd9e55a5d6f8ab1b1b57980b31e108b..90d5cac9a19a3240932fe71af64f580ee45f14d1 100644
--- a/include/iri_base_driver/iri_base_driver.h
+++ b/include/iri_base_driver/iri_base_driver.h
@@ -22,7 +22,6 @@
 // ros base driver class
 #include "driver_base/driver.h"
 #include "ros/ros.h"
-#include "mutex.h"
 
 namespace iri_base_driver
 {
@@ -60,14 +59,15 @@ class IriBaseDriver : public driver_base::Driver
     */
     std::string driver_id_;
 
-   /**
-    * \brief driver mutex
-    *
-    * This variable is used to block access to the driver resource. Public
-    * methods such as lock, unlock and try_enter provide an interface to
-    * avoid multiple concurrent access.
-    */
-    CMutex access_;
+    /**
+     * \brief  variable to handle the mutual exclusion mechanism
+     *
+     * this variable is automatically initialized when an object of this class
+     * or any inherited class is created and holds all the necessary information 
+     * to handle any shared resource.
+     *
+     */
+    pthread_mutex_t access_;
 
    /**
     * \brief Set Driver Id
diff --git a/include/iri_base_driver/iri_base_driver_node.h b/include/iri_base_driver/iri_base_driver_node.h
index 7eb719d3bb4b8b28aed9d16d776dcdf266cb486e..cdbee840ac9b6f4debd347d564575d98843f0b4a 100644
--- a/include/iri_base_driver/iri_base_driver_node.h
+++ b/include/iri_base_driver/iri_base_driver_node.h
@@ -24,10 +24,6 @@
 #include <diagnostic_updater/diagnostic_updater.h>
 #include "iri_base_driver.h"
 
-// iri-utils thread server
-#include "threadserver.h"
-#include "exceptions.h"
-
 namespace iri_base_driver
 {
 
@@ -65,24 +61,15 @@ template <class Driver>
 class IriBaseNodeDriver : public driver_base::DriverNode<Driver>
 {
   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 main node post open hook
@@ -275,12 +262,7 @@ IriBaseNodeDriver<Driver>::IriBaseNodeDriver(ros::NodeHandle &nh) :
   this->driver_.setPreCloseHook(boost::bind(&IriBaseNodeDriver::preNodeCloseHook, this));
 
   // create the status thread
-  this->thread_server_=CThreadServer::instance();
-  this->main_thread_id_="main_thread";
-
-  this->thread_server_->create_thread(this->main_thread_id_);
-  this->thread_server_->attach_thread(this->main_thread_id_, this->mainThread, this);
-  this->thread_server_->start_thread( this->main_thread_id_);
+  pthread_create(&this->thread,NULL,this->mainThread,this);
   
   // initialize class attributes
 }
@@ -300,8 +282,9 @@ void *IriBaseNodeDriver<Driver>::mainThread(void *param)
       iriNode->mainNodeThread();
 
 //       ros::spinOnce();
-      iriNode->loop_rate_.sleep();
     }
+    iriNode->loop_rate_.sleep();
+
   }
 
   pthread_exit(NULL);
@@ -369,20 +352,14 @@ template <class Driver>
 IriBaseNodeDriver<Driver>::~IriBaseNodeDriver()
 {
   ROS_DEBUG("IriBaseNodeDriver::Destrcutor");
-  try
-  {
-    //try access to driver to assert it is
-    //unlock before its destruction
-    this->driver_.try_enter();
-    this->driver_.unlock();
-  }
-  catch(CException e)
-  {
-    std::cout << e.what() << std::endl;
-  }
+  //try access to driver to assert it is
+  //unlock before its destruction
+  this->driver_.try_enter();
+  this->driver_.unlock();
   
   this->driver_.close();
-  this->thread_server_->kill_thread(this->main_thread_id_);
+  pthread_cancel(this->thread);
+  pthread_join(this->thread,NULL);
 }
 
 }
diff --git a/manifest.xml b/manifest.xml
index ec77159f9233eb3c6b2527b87d2ea0527c05e9a5..0c40aa86d16d6562b297445bb410952003c3f25d 100644
--- a/manifest.xml
+++ b/manifest.xml
@@ -4,8 +4,8 @@
      iri_base_driver
 
   </description>
-  <author></author>
-  <license>BSD</license>
+  <author>Joan Perez, jnperez at iri.upc.edu</author>
+  <license>LGPL</license>
   <review status="unreviewed" notes=""/>
   <url>http://ros.org/wiki/iri_base_driver</url>
 
diff --git a/src/iri_base_driver.cpp b/src/iri_base_driver.cpp
index 8cd74c139cefc8503938469aa1d1f3bb99a2b003..984f667e0f70e6cb852336486b0f0c4cb1933d31 100644
--- a/src/iri_base_driver.cpp
+++ b/src/iri_base_driver.cpp
@@ -5,21 +5,25 @@ namespace iri_base_driver
 
 IriBaseDriver::IriBaseDriver() : driver_id_("none")
 {
+  pthread_mutex_init(&this->access_,NULL);
 }
 
 void IriBaseDriver::lock(void)
 {
-  this->access_.enter();
+  pthread_mutex_lock(&this->access_);
 }
 
 void IriBaseDriver::unlock(void)
 {
-  this->access_.exit();
+  pthread_mutex_unlock(&this->access_);
 }
 
 bool IriBaseDriver::try_enter(void)
 {
-  return this->access_.try_enter();
+  if(pthread_mutex_trylock(&this->access_)==0)
+    return true;
+  else
+    return false;
 }
 
 void IriBaseDriver::setDriverId(const std::string & id)
@@ -60,6 +64,7 @@ void IriBaseDriver::setPreCloseHook(hookFunction f)
 
 IriBaseDriver::~IriBaseDriver()
 {
+  pthread_mutex_destroy(&this->access_);
 }
 
 }