diff --git a/include/iri_base_algorithm/iri_base_algorithm.h b/include/iri_base_algorithm/iri_base_algorithm.h
index b41f0a4df12dac6fcee2b0f795b2b6b64c688334..492edfe9476a56f8deb9ae8cc5e08da3f8c3f200 100644
--- a/include/iri_base_algorithm/iri_base_algorithm.h
+++ b/include/iri_base_algorithm/iri_base_algorithm.h
@@ -42,17 +42,12 @@ namespace algorithm_base
 class AbstractAlgorithmNode
 {
   protected:
-    static int ctrl_c_hit_count_;
     
     static void hupCalled(int sig)
     {
       ROS_WARN("Unexpected SIGHUP caught. Ignoring it.");
     }
     
-    static void sigCalled(int sig)
-    {
-      ctrl_c_hit_count_++;
-    }
 };
 
 /**
@@ -322,7 +317,7 @@ void *IriBaseAlgorithm<Algorithm>::mainThread(void *param)
   // retrieve base algorithm class
   IriBaseAlgorithm *iriNode = (IriBaseAlgorithm *)param;
 
-  while(ros::ok() && !ctrl_c_hit_count_)
+  while(ros::ok())
   {
     // run node stuff
     iriNode->mainNodeThread();
@@ -354,7 +349,7 @@ int IriBaseAlgorithm<Algorithm>::spin(void)
   // create the status thread
   pthread_create(&this->thread,NULL,this->mainThread,this);
 
-  while(ros::ok() && !ctrl_c_hit_count_)
+  while(ros::ok())
   {
     // update diagnostics
     this->diagnostic_.update();
@@ -372,7 +367,6 @@ int IriBaseAlgorithm<Algorithm>::spin(void)
 }
 
 // definition of the static Ctrl+C counter
-int AbstractAlgorithmNode::ctrl_c_hit_count_ = 0;
 
 /**
  * \brief base main