Update 'src/pubsub/pubsub/pubsub_library_v4.py'
Added trust to reset the watchdog
This commit is contained in:
parent
7d27ff3eba
commit
95276b75da
@ -98,6 +98,7 @@ class MinimalSubscriber(Node):
|
||||
self.topic_received = False
|
||||
self.overflow = False
|
||||
self.watchdog = 0
|
||||
self.trust = 0
|
||||
self.msg = None
|
||||
super().__init__(self.NODE_NAME)
|
||||
self.subscription = self.create_subscription(
|
||||
@ -123,7 +124,7 @@ class MinimalSubscriber(Node):
|
||||
def return_msg(self):
|
||||
return self.msg
|
||||
|
||||
def timer_overflow(self, time_limit=0, numer_of_timer_overflows=10):
|
||||
def timer_overflow(self, time_limit=0, number_of_timer_overflows=10, trust_factor=1):
|
||||
"""Watchdog for Topic Publisher Messages\n
|
||||
ture = timer_overflow >> error
|
||||
false = no timer_overflow >> no error"""
|
||||
@ -131,9 +132,15 @@ class MinimalSubscriber(Node):
|
||||
if time_limit > 0:
|
||||
if time.time() > self.last_msg_time + time_limit:
|
||||
self.watchdog += 1
|
||||
self.trust = 0
|
||||
self.get_logger().warn(f"Message-Watchdog triggered {self.watchdog} times")
|
||||
if self.watchdog > numer_of_timer_overflows:
|
||||
if self.watchdog > number_of_timer_overflows:
|
||||
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
|
||||
|
||||
|
||||
|
Loading…
x
Reference in New Issue
Block a user