PObs.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 ##
00004 # PObs.py is a Property Observer.
00005 # It needs five parameters node name, property(either cpu or mem), maximum value, mismatch threshold 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 # The Property Observer observers a specific hardware/software property related to a node. 
00024 # A property could be CPU usage , Memory usage or any other resourse.
00025 # It publishes this property over /observations topic compatible for our Model Based Diagnosis.
00026 
00027 
00028 import roslib; roslib.load_manifest('tug_ist_diagnosis_observers')
00029 import commands
00030 import rospy
00031 import subprocess
00032 import sys
00033 import os
00034 import shlex
00035 from tug_ist_diagnosis_msgs.msg import Observations
00036 import time
00037 import numpy
00038 class Property_Observer(object):
00039 
00040                 def __init__(self, argv):
00041                         rospy.init_node('PObs', anonymous=True)
00042                         self.pub = rospy.Publisher('/observations', Observations)
00043                         self.param_node = rospy.get_param('~node', 'Node')
00044                         self.param_property = rospy.get_param('~property', 'MEM')
00045                         self.param_max = rospy.get_param('~max_val', 0.2)
00046                         self.param_mis_th = rospy.get_param('~mismatch_thr', 5)
00047                         self.param_ws = rospy.get_param('~ws', 10)
00048                         self.circular_queu = [0 for i in xrange(self.param_ws)]
00049                         self.mismatch_counter = 0
00050                         self.args = argv
00051                         self.sum = 0
00052                         if self.param_node[0] == '/':
00053                                 self.node = self.node[1:len(self.node)]
00054          
00055                 def start(self):
00056                         print 'PObs is up and has started publishsing observations.......'
00057                         a = subprocess.Popen("rosnode info " + self.param_node , shell=True,stdout=subprocess.PIPE)
00058                         parts = shlex.split(a.communicate()[0])
00059                         indx = parts.index("Pid:")
00060                         pid = parts[indx+1]
00061                         p = subprocess.Popen("top -b -n 1 | grep -i %s" %pid, shell=True,stdout=subprocess.PIPE)
00062                         self.out = p.communicate()[0]
00063                         self.out1 = shlex.split(self.out)
00064                         if (self.param_property == 'CPU') | (self.param_property == 'cpu') :
00065                                 indx = 8
00066                         else:
00067                                 indx = 9
00068                         while not rospy.is_shutdown():
00069                                 self.circular_queu.pop(0)
00070                                 p = subprocess.Popen("top -b -n 1 | grep -i %s" %pid, shell=True,stdout=subprocess.PIPE)
00071                                 self.out = p.communicate()[0]
00072                                 print self.out
00073                                 self.out1 = shlex.split(self.out)
00074                                 self.circular_queu.append(float(self.out1[indx]))
00075                                 avg_val = numpy.mean(self.circular_queu)
00076                                 self.publish_output(avg_val)
00077                                 time.sleep(0.1);
00078 
00079                                 
00080                 def publish_output(self,obtained_val):
00081                         obs_msg = []
00082                         if (obtained_val <= float(self.param_max)):
00083                                 if self.mismatch_counter > 0:
00084                                         self.mismatch_counter = self.mismatch_counter - 1       
00085                                 print 'ok('+self.param_node+','+self.param_property+')'
00086                                 obs_msg.append('ok('+self.param_node+','+self.param_property+')')
00087                                 self.pub.publish(Observations(time.time(),obs_msg))
00088                         else:
00089                                 self.mismatch_counter = self.mismatch_counter + 1
00090                                 if self.mismatch_counter < self.param_mis_th:
00091                                         print 'ok('+self.param_node+','+self.param_property+')'
00092                                         obs_msg.append('ok('+self.param_node+','+self.param_property+')')
00093                                         self.pub.publish(Observations(time.time(),obs_msg))
00094                                 else:
00095                                         print '~ok('+self.param_node+','+self.param_property+')'
00096                                         obs_msg.append('~ok('+self.param_node+','+self.param_property+')')
00097                                         self.pub.publish(Observations(time.time(),obs_msg))
00098                         
00099 
00100 def report_error():
00101         print """
00102 rosrun tug_ist_diagnosis_observers PObs.py _node:=<Node_name> _property:=<Mem/Cpu> _max_value:=<maximumLimit> _mismatch_thr:=<mistmachthr> _ws:=<windowsize>
00103 e.g rosrun tug_ist_diagnosis_observers PObs.py _node:=openni_camera _property:=CPU _max_value:=0.2 _mismatch_thr:=5'
00104 """
00105         sys.exit(os.EX_USAGE)        
00106     
00107 if __name__ == '__main__':
00108                         print len(sys.argv)
00109                         if len(sys.argv) < 2: 
00110                                 report_error()
00111                         pObs = Property_Observer(sys.argv)
00112                         pObs.start()
00113 


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