From fa0185f2fbb04555cc8637f46025fa9f7c7e3c83 Mon Sep 17 00:00:00 2001
From: Sergi Hernandez Juan <shernand@iri.upc.edu>
Date: Tue, 4 Feb 2020 08:29:51 +0100
Subject: [PATCH] Solved a bug: the main node thread was launched twice. This
 exaplins that the output rate of drivers doubled the desired one.

---
 include/iri_base_driver/iri_base_driver_node.h | 3 ---
 1 file changed, 3 deletions(-)

diff --git a/include/iri_base_driver/iri_base_driver_node.h b/include/iri_base_driver/iri_base_driver_node.h
index ca06777..0bc5be8 100644
--- a/include/iri_base_driver/iri_base_driver_node.h
+++ b/include/iri_base_driver/iri_base_driver_node.h
@@ -347,9 +347,6 @@ IriBaseNodeDriver<Driver>::IriBaseNodeDriver(const ros::NodeHandle &nh) :
   this->driver_.setPreCloseHook(boost::bind(&IriBaseNodeDriver::preCloseHook, this));
   this->driver_.setPostStartHook(boost::bind(&IriBaseNodeDriver::postStartHook, this));
   this->driver_.setPreStopHook(boost::bind(&IriBaseNodeDriver::preStopHook, this));
-
-  // create the status thread
-  pthread_create(&this->main_thread,NULL,this->mainThread,this);
   
   // initialize class attributes
   // allow Ctrl+C management
-- 
GitLab