diff --git a/include/iri_ros_tools/watchdog.h b/include/iri_ros_tools/watchdog.h
index f9109976ac97267a3a7938bc00ead270a72a401f..3cf86606d335bc06f19108ed16bba0d91ce40d82 100644
--- a/include/iri_ros_tools/watchdog.h
+++ b/include/iri_ros_tools/watchdog.h
@@ -6,6 +6,7 @@
 class CROSWatchdog
 {
   private:
+    ros::Time start_time;
     ros::Duration max_time;
     pthread_mutex_t access_;
   public:
diff --git a/src/watchdog.cpp b/src/watchdog.cpp
index 11507a0eb8adeb49d1537eea24a6c7238ef75e50..bfb1a66e36532fe35f786653e94dd65e241a5536 100644
--- a/src/watchdog.cpp
+++ b/src/watchdog.cpp
@@ -15,12 +15,12 @@ void CROSWatchdog::reset(ros::Duration time)
 
 bool CROSWatchdog::is_active(void)
 {
-  static ros::Time start_time=ros::Time::now();
+  this->start_time=ros::Time::now();
   ros::Time current_time=ros::Time::now();
 
   pthread_mutex_lock(&this->access_);
-  this->max_time-=(current_time-start_time);
-  start_time=current_time;
+  this->max_time-=(current_time-this->start_time);
+  this->start_time=current_time;
   if(this->max_time.toSec()<=0.0)
   {
     pthread_mutex_unlock(&this->access_);