NObs.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 ##
00004 # NObs.py is a Node Observer.
00005 # It needs three parameters Required frequency, frequency deviation and window size.
00006 # Copyright (c).2012. OWNER: Institute for Software Technology, TU Graz Austria.
00007 # Authors: Safdar Zaman, Gerald Steinbauer. (szaman@ist.tugraz.at, steinbauer@ist.tugraz.at)
00008 # All rights reserved.
00009 #    This program is free software: you can redistribute it and/or modify
00010 #    it under the terms of the GNU General Public License as published by
00011 #    the Free Software Foundation, either version 3 of the License, or
00012 #    (at your option) any later version.
00013 #
00014 #    This program is distributed in the hope that it will be useful,
00015 #    but WITHOUT ANY WARRANTY; without even the implied warranty of
00016 #    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00017 #    GNU General Public License for more details.
00018 #
00019 #    You should have received a copy of the GNU General Public License
00020 #    along with this program.  If not, see <http://www.gnu.org/licenses/>.
00021 ##
00022 
00023 
00024 # The Node Observer (NObs) observers the given node 
00025 # and publishes the state of this not either running or not running.
00026 
00027 import roslib; roslib.load_manifest('tug_ist_diagnosis_observers')
00028 import rospy
00029 import sys
00030 import xmlrpclib
00031 import os
00032 from tug_ist_diagnosis_msgs.msg import Observations
00033 import time
00034 
00035 class Node_Observer(object):
00036 
00037     def __init__(self):
00038                                         rospy.init_node('NObs', anonymous=True)
00039                                         self.caller_id = '/script'
00040                                         self.m = xmlrpclib.ServerProxy(os.environ['ROS_MASTER_URI'])
00041                                         self.msg = ""
00042                                         self.pub = rospy.Publisher('/observations', Observations)
00043                                         self.param_node_name = rospy.get_param('~node', '/NoNode')
00044 
00045          
00046     def start(self):
00047                         print "NObs is up...."
00048                         if self.param_node_name[0] != '/':
00049                                 self.param_node_name = "/%s" % (self.param_node_name)
00050                         r = rospy.Rate(10) # 10hz
00051                         while not rospy.is_shutdown():
00052                                 found = False
00053                                 code, statusMessage, sysState = self.m.getSystemState(self.caller_id)
00054                                 for lst in sysState:
00055                                         for row in lst:
00056                                                 for node in row[1]:
00057                                                                 if node == self.param_node_name:
00058                                                                         found = True
00059                                                                         break
00060                                 obs_msg = []
00061                                 if found == True:
00062                                         self.msg = 'running('+self.param_node_name[1:len(self.param_node_name)]+')'
00063                                         rospy.loginfo('running('+self.param_node_name[1:len(self.param_node_name)]+')')
00064                                         obs_msg.append(self.msg)
00065                                         self.pub.publish(Observations(time.time(),obs_msg))
00066                                 else:
00067                                         self.msg = '~running('+self.param_node_name[1:len(self.param_node_name)]+')'
00068                                         rospy.loginfo('~running('+self.param_node_name[1:len(self.param_node_name)]+')')
00069                                         obs_msg.append(self.msg)
00070                                         self.pub.publish(Observations(time.time(),obs_msg))
00071                                 r.sleep()
00072 
00073 
00074 if __name__ == '__main__':
00075                         nObs = Node_Observer()
00076                         nObs.start()


tug_ist_diagnosis_observers
Author(s): Safdar Zaman, Gerald Steinbauer
autogenerated on Mon Jan 6 2014 11:51:27