From 6a22f43e6fa7d80d22648708cc71455be6fb66dd Mon Sep 17 00:00:00 2001 From: Fernando Herrero Cotarelo <fherrero@iri.upc.edu> Date: Thu, 17 Nov 2016 17:29:34 +0000 Subject: [PATCH] iri_ros_tools: watchdog: changed start_time from static to class member. --- include/iri_ros_tools/watchdog.h | 1 + src/watchdog.cpp | 6 +++--- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/include/iri_ros_tools/watchdog.h b/include/iri_ros_tools/watchdog.h index f910997..3cf8660 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 11507a0..bfb1a66 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_); -- GitLab