diff --git a/CMakeLists.txt b/CMakeLists.txt
index 070e7c2c49ced2e730557189bf63ffd390be9711..6d53a686b105ac53840e0806fd30232a83ae0cbc 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -16,7 +16,6 @@ find_package(catkin REQUIRED COMPONENTS iri_base_algorithm sensor_msgs image_tra
 # ******************************************************************** 
 # find_package(<dependency> REQUIRED)
 find_package(OpenCV REQUIRED)
-find_package(iriutils REQUIRED)
 
 # ******************************************************************** 
 #           Add topic, service and action definition here
@@ -80,7 +79,6 @@ catkin_package(
 include_directories(include)
 include_directories(${catkin_INCLUDE_DIRS})
 include_directories(${OpenCV_INCLUDE_DIRS})
-include_directories(${iriutils_INCLUDE_DIR})
 
 ## Declare a cpp library
 # add_library(${PROJECT_NAME} <list of source files>)
@@ -95,10 +93,8 @@ add_library(${PROJECT_NAME}_nodelet src/blob_detector_alg.cpp src/blob_detector_
 # ******************************************************************** 
 target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})
 target_link_libraries(${PROJECT_NAME} ${OpenCV_LIBS})
-target_link_libraries(${PROJECT_NAME} ${iriutils_LIBRARY})
 target_link_libraries(${PROJECT_NAME}_nodelet ${catkin_LIBRARIES})
 target_link_libraries(${PROJECT_NAME}_nodelet ${OpenCV_LIBS})
-target_link_libraries(${PROJECT_NAME}_nodelet ${iriutils_LIBRARY})
 
 # ******************************************************************** 
 #               Add message headers dependencies 
diff --git a/include/blob_detector_alg_nodelet.h b/include/blob_detector_alg_nodelet.h
index 2646b862c8a347ec4ebec52a1b3fb5f244369ffd..fdcb6e908e8675b6058374d45a8ce2c6756a648b 100644
--- a/include/blob_detector_alg_nodelet.h
+++ b/include/blob_detector_alg_nodelet.h
@@ -28,18 +28,13 @@
 #include "nodelet/nodelet.h"
 #include "blob_detector_alg_node.h"
 
-#include "threadserver.h"
-
 class BlobDetectorNodelet : public nodelet::Nodelet
 {
   private:
     virtual void onInit();// initialization function
     BlobDetectorAlgNode *dev;
-    // thread attributes
-    CThreadServer *thread_server;
-    std::string spin_thread_id;
   protected:
-    static void *spin_thread(void *param);
+    void spin_thread(void);
   public:
     BlobDetectorNodelet();
     ~BlobDetectorNodelet();
diff --git a/launch/blob_detector.launch b/launch/blob_detector.launch
index f1685fd3c69428b98b3d48abf1214ca5d64d99ef..4256e66790d9fb1351b425573f56959fb8caee47 100644
--- a/launch/blob_detector.launch
+++ b/launch/blob_detector.launch
@@ -7,8 +7,8 @@
     <node pkg="libuvc_camera" type="camera_node" name="mycam">
       <!-- Parameters used to find the camera -->
       <param name="vendor" value="0x046d"/>
-      <param name="product" value="0x0805"/>
-      <param name="serial" value="AB659260"/>
+      <param name="product" value="0x0802"/>
+      <param name="serial" value="BEE76360"/>
       <!-- If the above parameters aren't unique, choose the first match: -->
       <param name="index" value="0"/>
 
diff --git a/src/blob_detector_alg_nodelet.cpp b/src/blob_detector_alg_nodelet.cpp
index e4220b04df8882588b487263edcc57f50f3d9e78..5c4f2a1c91bd2941fb7992d30f9f2f1a2d1d23a5 100644
--- a/src/blob_detector_alg_nodelet.cpp
+++ b/src/blob_detector_alg_nodelet.cpp
@@ -10,32 +10,17 @@ void BlobDetectorNodelet::onInit()
 {
   this->dev=new BlobDetectorAlgNode(this->getPrivateNodeHandle());
   // initialize the thread
-  std::cout << this->getName() << "," << this->getPrivateNodeHandle().getNamespace() << std::endl;
-  this->thread_server=CThreadServer::instance();
-  this->spin_thread_id=getName() + "_blob_detector_nodelet_spin";
-  std::cout << this->spin_thread_id << std::endl;
-  this->thread_server->create_thread(this->spin_thread_id);
-  this->thread_server->attach_thread(this->spin_thread_id,this->spin_thread,this);
-  // start the spin thread
-  this->thread_server->start_thread(this->spin_thread_id);
+  boost::bind(&BlobDetectorNodelet::spin_thread,this);
 }
 
-void *BlobDetectorNodelet::spin_thread(void *param)
+void BlobDetectorNodelet::spin_thread(void)
 {
-  BlobDetectorNodelet *nodelet=(BlobDetectorNodelet *)param;
-
-  nodelet->dev->spin();
-
-  pthread_exit(NULL);
+  this->dev->spin();
 }
 
 BlobDetectorNodelet::~BlobDetectorNodelet()
 {
   // kill the thread
-  this->thread_server->kill_thread(this->spin_thread_id);
-  this->thread_server->detach_thread(this->spin_thread_id);
-  this->thread_server->delete_thread(this->spin_thread_id);
-  this->spin_thread_id="";
   if(this->dev!=NULL)
     delete this->dev;
 }