Update 'src/pubsub/pubsub/pubsub_library_v4.py'
Changed the order so that the time is not overflowing while checking
This commit is contained in:
parent
61ebd7ca68
commit
e17c718d0b
@ -130,17 +130,17 @@ class MinimalSubscriber(Node):
|
|||||||
false = no timer_overflow >> no error"""
|
false = no timer_overflow >> no error"""
|
||||||
self.overflow = False
|
self.overflow = False
|
||||||
if time_limit > 0 and self.has_msg():
|
if time_limit > 0 and self.has_msg():
|
||||||
|
if time.time() <= self.last_msg_time + time_limit:
|
||||||
|
if self.watchdog > 0:
|
||||||
|
self.trust += 1
|
||||||
|
if self.trust > number_of_timer_overflows * trust_factor:
|
||||||
|
self.watchdog = 0
|
||||||
if time.time() > self.last_msg_time + time_limit:
|
if time.time() > self.last_msg_time + time_limit:
|
||||||
self.watchdog += 1
|
self.watchdog += 1
|
||||||
self.trust = 0
|
self.trust = 0
|
||||||
self.get_logger().warn(f"Message-Watchdog triggered {self.watchdog} times")
|
self.get_logger().warn(f"Message-Watchdog triggered {self.watchdog} times")
|
||||||
if self.watchdog > number_of_timer_overflows:
|
if self.watchdog > number_of_timer_overflows:
|
||||||
self.overflow = True
|
self.overflow = True
|
||||||
if self.watchdog > 0:
|
|
||||||
if time.time() < self.last_msg_time + time_limit:
|
|
||||||
self.trust += 1
|
|
||||||
if self.trust > number_of_timer_overflows * trust_factor:
|
|
||||||
self.watchdog = 0
|
|
||||||
return self.overflow
|
return self.overflow
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user