From ab1fda1ac874121f72627821344d510e079ee9ab Mon Sep 17 00:00:00 2001 From: Kevin Allen Date: Thu, 16 May 2019 14:54:50 -0400 Subject: [PATCH] HANDLERS: call raised/cleared handler functions for initial alarm --- nodes/alarm_server.py | 20 +++++++------------- 1 file changed, 7 insertions(+), 13 deletions(-) diff --git a/nodes/alarm_server.py b/nodes/alarm_server.py index 8438014..8f1b605 100755 --- a/nodes/alarm_server.py +++ b/nodes/alarm_server.py @@ -37,7 +37,7 @@ def set_alarm(self, alarm): Updating the alarm triggers all of the alarms callbacks ''' if alarm.alarm_name in self.handlers: - res = self.handlers[alarm.alarm_name].on_set(alarm) + res = self.handlers[alarm.alarm_name].on_set(Alarm.from_msg(alarm)) if res is False: return False @@ -123,23 +123,17 @@ def _create_alarm_handlers(self): h = handler() alarm_name = handler.alarm_name - - # Set initial state if necessary (could have already been added while creating metas) - if hasattr(h, 'initial_alarm'): - if alarm_name in self.alarms: - self.alarms[alarm_name].update(h.initial_alarm) - else: - self.alarms[alarm_name] = h.initial_alarm # Update even if already added to server - elif alarm_name not in self.alarms: # Add default initial if not there already - self.alarms[alarm_name] = self.make_tagged_alarm(alarm_name) - else: - pass + self.handlers[alarm_name] = h # If a handler exists for a meta alarm, we need to save the predicate if alarm_name in self.meta_alarms: self.meta_alarms[alarm_name] = h.meta_predicate - self.handlers[alarm_name] = h + # Set initial state if necessary (could have already been added while creating metas) + if hasattr(h, 'initial_alarm'): + self.set_alarm(h.initial_alarm.as_msg()) + else: + self.set_alarm(self.make_tagged_alarm(alarm_name).as_msg()) rospy.loginfo("Loaded handler: {}".format(h.alarm_name))