Update 'src/pubsub/pubsub/pubsub_library_v4.py'
Added the possibility to input a certain amount of allowed overflows until watchdog is triggered and reset overflow to false every time its called to reevaluate.
This commit is contained in:
parent
ae20df933b
commit
7d27ff3eba
@ -123,15 +123,16 @@ class MinimalSubscriber(Node):
|
||||
def return_msg(self):
|
||||
return self.msg
|
||||
|
||||
def timer_overflow(self, time_limit=0):
|
||||
def timer_overflow(self, time_limit=0, numer_of_timer_overflows=10):
|
||||
"""Watchdog for Topic Publisher Messages\n
|
||||
ture = timer_overflow >> error
|
||||
false = no timer_overflow >> no error"""
|
||||
self.overflow = False
|
||||
if time_limit > 0:
|
||||
if time.time() > self.last_msg_time + time_limit:
|
||||
self.watchdog += 1
|
||||
self.get_logger().warn(f"Message-Watchdog triggered {self.watchdog} times")
|
||||
if self.watchdog > 10:
|
||||
if self.watchdog > numer_of_timer_overflows:
|
||||
self.overflow = True
|
||||
return self.overflow
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user