tactile_data_gui.py
Go to the documentation of this file.
00001 #!/usr/bin/python
00002 
00003 import pygtk
00004 pygtk.require('2.0')
00005 import gtk, gobject, cairo
00006 import threading
00007 
00008 #Initializing the gtk's thread engine
00009 gtk.gdk.threads_init()
00010 
00011 import rospy
00012 from schunk_sdh.msg import TactileMatrix, TactileSensor
00013 
00014 class Screen(gtk.DrawingArea):
00015 
00016     # Draw in response to an expose-event
00017     __gsignals__ = { "expose-event": "override" }
00018     sizex = 3
00019     sizey = 1
00020     def __init__(self):
00021         gtk.DrawingArea.__init__(self)
00022         self.tactile_array = (0,0,0)
00023 
00024     # Handle the expose-event by drawing
00025     def do_expose_event(self, event):
00026         # Create the cairo context
00027         cr = self.window.cairo_create()
00028         #print "Width: ", self.allocation.width
00029         #print "Height: ", self.allocation.height
00030         # Restrict Cairo to the exposed area; avoid extra work
00031         cr.rectangle(event.area.x, event.area.y, event.area.width, event.area.height)
00032         cr.clip()
00033         self.draw(cr, self.allocation.width,self.allocation.height )
00034 
00035     def getColorCode(self, value):
00036         if(value < 0):
00037             #schwarz
00038             return [1,1,1]
00039         if(value > 4000):
00040             #rot
00041             return [1,0,0]
00042         elif (value > 3429):
00043             #orange
00044             return [248./256,171./256,21./256]
00045         elif (value > 2857):
00046             #gelb
00047             return [248./256,245./256,21./256]
00048         elif (value > 2286):
00049             #gruen
00050             return [1./256,181./256,22./256.]
00051         elif (value > 1714):
00052             #gruen hell
00053             return [118./256,255./256,86./256]
00054         elif (value > 1143):
00055             #tuerkis
00056             return [85./256.,249./256.,251./256.]
00057         elif (value > 571):
00058             #blauig
00059             return [39./256.,126./256.,167./256.]
00060         else:
00061             #blau
00062             return [1./256.,7./256.,255./256.]
00063 
00064     def draw(self, cr, width, height):
00065         # Fill the background with gray
00066         color = 0.5
00067         xw = width/(self.sizex)
00068         yw = height/(self.sizey)
00069         #print "SIZE+++++ ", len(self.tactile_array)
00070         for j in range(0,self.sizey):
00071             for i in range(0,self.sizex):
00072                 #print (i+1)*(j+1)
00073                 [colorr, colorg, colorb] = self.getColorCode(self.tactile_array[self.sizex*j+i])
00074                 #print colorr, colorg, colorb
00075                 cr.set_source_rgb(colorr, colorg, colorb)
00076                 cr.rectangle((i)*xw, (j)*yw, xw, yw)
00077                 cr.fill()
00078 
00079     def setMatrixSize(self, matrixx, matrixy):
00080         self.sizex = matrixx
00081         self.sizey = matrixy
00082 
00083     def updateTactileMatrix(self, array):
00084         #print "Got something: ", array
00085         self.tactile_array = array
00086         self.queue_draw()
00087 
00088 def roscb(data):
00089     global sc1
00090     global sc2
00091     global sc3
00092     global sc4
00093     global sc5
00094     global sc6
00095     global testv
00096     matrices = data.tactile_matrix
00097     gtk.gdk.threads_enter()
00098     for mat in matrices:
00099         if(mat.matrix_id == 1):
00100             sc1.setMatrixSize(mat.cells_x,mat.cells_y)
00101             sc1.updateTactileMatrix(mat.tactile_array)
00102         if(mat.matrix_id == 3):
00103             sc2.setMatrixSize(mat.cells_x,mat.cells_y)
00104             sc2.updateTactileMatrix(mat.tactile_array)
00105         if(mat.matrix_id == 5):
00106             sc3.setMatrixSize(mat.cells_x,mat.cells_y)
00107             sc3.updateTactileMatrix(mat.tactile_array)
00108         if(mat.matrix_id == 0):
00109             sc4.setMatrixSize(mat.cells_x,mat.cells_y)
00110             sc4.updateTactileMatrix(mat.tactile_array)
00111         if(mat.matrix_id == 2):
00112             sc5.setMatrixSize(mat.cells_x,mat.cells_y)
00113             sc5.updateTactileMatrix(mat.tactile_array)
00114         if(mat.matrix_id == 4):
00115             sc6.setMatrixSize(mat.cells_x,mat.cells_y)
00116             sc6.updateTactileMatrix(mat.tactile_array)
00117     gtk.gdk.threads_leave()
00118 
00119 
00120 # GTK mumbo-jumbo to show the widget in a window and quit when it's closed
00121 def main_quit(obh, obb):
00122     #Stopping the thread and the gtk's main loop
00123     gtk.main_quit()
00124 
00125 try:
00126     window = gtk.Window()
00127     winwidth = 200
00128     winheight = 300
00129     window.set_size_request(winwidth,winheight)
00130     window.set_title("TactileSensorData")
00131     testv = 0
00132     sc1 = Screen()
00133     sc1.set_size_request((winwidth/3)-10, (winheight/2)-5)
00134     sc2 = Screen()
00135     sc2.set_size_request((winwidth/3)-10, (winheight/2)-5)
00136     sc3 = Screen()
00137     sc3.set_size_request((winwidth/3)-10, (winheight/2)-5)
00138     sc4 = Screen()
00139     sc4.set_size_request((winwidth/3)-10, (winheight/2)-5)
00140     sc5 = Screen()
00141     sc5.set_size_request((winwidth/3)-10, (winheight/2)-5)
00142     sc6 = Screen()
00143     sc6.set_size_request((winwidth/3)-10, (winheight/2)-5)
00144     hbox1=gtk.HBox(False ,1 )
00145     hbox1.pack_start(sc1,False, True, 0)
00146     hbox1.pack_start(sc2,False, True, 0)
00147     hbox1.pack_start(sc3,False, True, 0)
00148     hbox2=gtk.HBox(False,1)
00149     hbox2.pack_start(sc4,False, True, 0)
00150     hbox2.pack_start(sc5,False, True, 0)
00151     hbox2.pack_start(sc6,False, True, 0)
00152     vbox=gtk.VBox(True,0)
00153     vbox.pack_start(hbox1,False, False, 0)
00154     vbox.pack_start(hbox2,False, False, 0)
00155     window.add(vbox)
00156     window.show_all()
00157     window.connect("delete-event", main_quit)
00158     window.present()
00159     #ROS Subscribes
00160     rospy.init_node('TactileSensorView', anonymous=True)
00161     rospy.Subscriber("/gripper_controller/tactile_data", TactileSensor, roscb)
00162     gtk.main()
00163 except KeyboardInterrupt:
00164     main_quit("tut", "tut")


cob_tactiletools
Author(s): Alexander Bubeck
autogenerated on Mon Apr 4 2016 12:02:03