HObs.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 ##
00003 ##
00004 # HObs.py is a Hardware 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 # The Hardware Observer observers the status of the hardware channels
00024 # and publishes the state of the channels wehether ON or OFF.
00025 # It publishes this trned of the vaule overs /observations topic compatible for our Model Based Diagnosis.
00026 
00027 import roslib.message; 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 thread
00034 import time
00035 import traceback
00036 
00037 class Hardware_Observer(object):
00038 
00039     def __init__(self):
00040                                         rospy.init_node('HObs', anonymous=True)
00041                                         self.caller_id = '/script'
00042                                         self.m = xmlrpclib.ServerProxy(os.environ['ROS_MASTER_URI'])
00043                                         self.topic = ""
00044                                         self.topic_type = ""
00045                                         self.pub = rospy.Publisher('/observations', Observations)
00046                                         self.top = rospy.get_param('~topic', '/board_measurments')
00047                                         thread.start_new_thread(self.check_topic,(self.top,2))
00048          
00049     def start(self):
00050                                 pubcode, statusMessage, topicList = self.m.getPublishedTopics(self.caller_id, "")
00051                                 top_found = False
00052                                 for item in topicList:
00053                                         if item[0] == self.top:
00054                                                 self.topic = item[0]
00055                                                 self.topic_type = item[1]
00056                                                 top_found = True
00057                                 if top_found == True:
00058                                         msg_class = roslib.message.get_message_class(self.topic_type)
00059                                 else:
00060                                         self.report_error()
00061                                 print "HObs is up...."
00062                                 rospy.Subscriber(self.topic, msg_class, self.access_data)
00063                                 rospy.spin()
00064 
00065     def access_data(self,data):
00066                         temp_data = data
00067                         for f in temp_data.__slots__:
00068                                         if f == "channel":
00069                                                 att = getattr(temp_data, f)
00070                                                 j=0
00071                                                 obs_msg = []
00072                                                 while (j<len(att)):
00073                                                         if att[j].status == 1:
00074                                                                         obs_msg.append('on('+att[j].dev_connected+')')
00075                                                         else:
00076                                                                         obs_msg.append('~on('+att[j].dev_connected+')')
00077                                                         j = j + 1
00078                                                 self.pub.publish(Observations(time.time(),obs_msg))
00079                                                 
00080 
00081     def check_topic(self,top,sleeptime,*args):
00082                         try:
00083                                         while True:
00084                                                 t = 0
00085                                                 m = xmlrpclib.ServerProxy(os.environ['ROS_MASTER_URI'])
00086                                                 pubcode, statusMessage, topicList = m.getPublishedTopics(self.caller_id, "")
00087                                                 for item in topicList:
00088                                                         if item[0] == top:
00089                                                                         self.Topic = True
00090                                                                         t = 1
00091                                                                         break
00092                                                 if t == 0:
00093                                                                 t = 1
00094                                                                 print "Topic:[" +top+ "] does not exist."
00095                                                 time.sleep(sleeptime) #sleep for a specified amount of time.
00096                         except:
00097                                                 print "An unhandled exception occured, here's the traceback!"
00098                                                 traceback.print_exc()
00099 
00100                                                 
00101 
00102                                         
00103     def report_error(self):
00104                         print 'Incorrect Command:'
00105                         print 'use [rosrun tug_ist_diagnosis_observers HObs.py]'
00106                         sys.exit(os.EX_USAGE)
00107 
00108     def throws():
00109                                                                 raise RuntimeError('this is the error message')
00110 
00111 if __name__ == '__main__':
00112                         hObs = Hardware_Observer()
00113                         hObs.start()


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