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 import roslib
00039 roslib.load_manifest('lwr_dashboard')
00040 import rospy
00041
00042 import wx
00043
00044 from os import path
00045 import std_msgs
00046
00047 class FRIControl(wx.Window):
00048 def __init__(self, parent, id, icons_path):
00049 wx.Window.__init__(self, parent, id, wx.DefaultPosition, wx.Size(60, 40))
00050
00051 bitmap = wx.Bitmap(path.join(icons_path, "long_buttons.png"), wx.BITMAP_TYPE_PNG)
00052 self._screen_bitmap = (bitmap.GetSubBitmap(wx.Rect(0, 0, 80, 40)),
00053 bitmap.GetSubBitmap(wx.Rect( 80, 0, 80, 40)),
00054 bitmap.GetSubBitmap(wx.Rect( 80, 40, 80, 40)),
00055 bitmap.GetSubBitmap(wx.Rect( 0, 40, 80, 40)))
00056
00057 self._status = {}
00058 self._stale = True
00059
00060 self.SetSize(wx.Size(80, 40))
00061
00062 self.Bind(wx.EVT_PAINT, self.on_paint)
00063
00064 def on_paint(self, evt):
00065 dc = wx.BufferedPaintDC(self)
00066
00067 dc.SetBackground(wx.Brush(self.GetBackgroundColour()))
00068 dc.Clear()
00069
00070 w = self.GetSize().GetWidth()
00071 h = self.GetSize().GetHeight()
00072
00073 qual = "?"
00074 rate = "?"
00075
00076 if (self._stale):
00077
00078 dc.DrawBitmap(self._screen_bitmap[3], 0, 0, True)
00079 else:
00080 qual = self._status["Quality"]
00081 rate = "%.0f" % (1000*float(self._status["Desired Command Sample Time"]))
00082
00083
00084
00085
00086
00087
00088 if (qual == "PERFECT" or qual == "OK"):
00089 dc.DrawBitmap(self._screen_bitmap[0], 0, 0, True)
00090 if (qual == "BAD"):
00091 dc.DrawBitmap(self._screen_bitmap[1], 0, 0, True)
00092 if (qual == "UNACCEPTABLE"):
00093 dc.DrawBitmap(self._screen_bitmap[2], 0, 0, True)
00094
00095
00096
00097
00098 fnt = dc.GetFont()
00099 fnt.SetPointSize(7)
00100 dc.SetFont(fnt)
00101 dc.DrawLabel("Rate [ms]", wx.Rect(5, 5, 70, 32), wx.ALIGN_LEFT|wx.ALIGN_TOP)
00102
00103 fnt.SetPointSize(14)
00104 fnt.SetWeight(wx.FONTWEIGHT_BOLD)
00105 dc.SetFont(fnt)
00106 dc.DrawLabel("%s" % rate, wx.Rect(5, 5, 70, 32), wx.ALIGN_RIGHT|wx.ALIGN_BOTTOM)
00107
00108 def set_state(self, msg):
00109 self._stale = False
00110 self._status = msg;
00111 tooltip = ""
00112
00113 for key, value in msg.items():
00114 tooltip = tooltip + "%s: %s\n" % (key, value)
00115
00116 tool = wx.ToolTip(tooltip)
00117 tool.SetDelay(1)
00118 self.SetToolTip(tool)
00119
00120 self.Refresh()
00121
00122 def set_stale(self):
00123 self.SetToolTip(wx.ToolTip("FRI: Stale"))
00124 self._stale = True
00125 self.Refresh()
00126