00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 
00039 
00040 from __future__ import with_statement
00041 
00042 import roslib; roslib.load_manifest('application_manager')
00043 import rospy
00044 import threading
00045 import actionlib
00046 from actionlib_msgs.msg import GoalStatus
00047 from application_msgs.msg import *
00048 
00049 
00050 
00051 class ApplicationMonitor(threading.Thread):
00052     def __init__(self, app_cb):
00053         threading.Thread.__init__(self)
00054         self.lock = threading.RLock()
00055         self.app_cb = app_cb
00056         self.state = {}
00057         rospy.loginfo("Connecting to the application manager.")
00058         self.list_client = actionlib.SimpleActionClient(rospy.remap_name('application_manager') + '/list_applications', 
00059                                                        ListApplicationsAction)
00060         self.list_client.wait_for_server()
00061         rospy.loginfo("Connected to the application manager.")
00062         self.get_state()  
00063         self.start()  
00064 
00065 
00066     def monitor_app(self, app_name):
00067         with self.lock:
00068             self.state[app_name] = None
00069             self.get_state()
00070     
00071 
00072     def get_state(self):
00073         
00074         self.list_client.send_goal_and_wait(ListApplicationsGoal(), rospy.Duration(20.0), rospy.Duration(2.0))
00075         res = self.list_client.get_result()
00076         last_state = {}
00077         for app, state in zip(res.application_name, res.application_status):
00078             last_state[app] = state
00079 
00080         
00081         with self.lock:
00082             for a in self.state:  
00083                 if a in last_state:  
00084                     if not self.state[a]:
00085                         self.state[a] = last_state[a]  
00086                     elif last_state[a] != self.state[a]:  
00087                         self.state[a] = last_state[a]
00088                         self.app_cb(a, self.state[a])  
00089                     
00090 
00091     def run(self):
00092         rospy.loginfo('Running battery callbacks')
00093         while not rospy.is_shutdown():
00094             rospy.sleep(5.0)
00095             self.get_state()