$search
00001 #!/usr/bin/env python 00002 # Software License Agreement (BSD License) 00003 # 00004 # Copyright (c) 2009, Willow Garage, Inc. 00005 # All rights reserved. 00006 # 00007 # Redistribution and use in source and binary forms, with or without 00008 # modification, are permitted provided that the following conditions 00009 # are met: 00010 # 00011 # * Redistributions of source code must retain the above copyright 00012 # notice, this list of conditions and the following disclaimer. 00013 # * Redistributions in binary form must reproduce the above 00014 # copyright notice, this list of conditions and the following 00015 # disclaimer in the documentation and/or other materials provided 00016 # with the distribution. 00017 # * Neither the name of the Willow Garage nor the names of its 00018 # contributors may be used to endorse or promote products derived 00019 # from this software without specific prior written permission. 00020 # 00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 # POSSIBILITY OF SUCH DAMAGE. 00033 # 00034 00035 ##\author Josh Faust 00036 00037 PKG = "robot_monitor" 00038 00039 from collections import deque 00040 import rospy 00041 import roslib 00042 00043 import wx 00044 import os 00045 import os.path 00046 00047 def clamp(val, min, max): 00048 if (val < min): 00049 return min 00050 if (val > max): 00051 return max 00052 00053 return val 00054 00055 class ColoredTimeline(wx.Control): 00056 def __init__(self, parent, min_val, max_val, val, color_callback): 00057 wx.Control.__init__(self, parent, wx.ID_ANY) 00058 00059 self._min = min_val 00060 self._max = max_val 00061 self._val = val 00062 self._color_callback = color_callback 00063 00064 self.SetMinSize(wx.Size(-1, 16)) 00065 self.SetMaxSize(wx.Size(-1, 16)) 00066 00067 self._timeline_marker_bitmap = wx.Bitmap(os.path.join(roslib.packages.get_pkg_dir(PKG), 'icons/timeline_marker.png'), wx.BITMAP_TYPE_PNG) 00068 00069 self.Bind(wx.EVT_PAINT, self.on_paint) 00070 self.Bind(wx.EVT_SIZE, self.on_size) 00071 self.Bind(wx.EVT_MOUSE_EVENTS, self.on_mouse) 00072 00073 self._left_down = False 00074 00075 self.SetToolTip(wx.ToolTip("Drag to rewind messages")) 00076 00077 def SetValue(self, val): 00078 self._val = clamp(int(val), self._min, self._max) 00079 self.Refresh() 00080 00081 def GetValue(self): 00082 return self._val 00083 00084 def SetRange(self, min_val, max_val): 00085 self._min = min_val 00086 self._max = max_val 00087 self._val = clamp(self._val, min, max) 00088 self.Refresh() 00089 00090 def on_size(self, event): 00091 self.Refresh() 00092 00093 def on_paint(self, event): 00094 dc = wx.PaintDC(self) 00095 dc.Clear() 00096 00097 is_enabled = self.IsEnabled() 00098 00099 (width, height) = self.GetSizeTuple() 00100 length = self._max + 1 - self._min 00101 value_size = width / float(length) 00102 for i in xrange(0, length): 00103 if (is_enabled): 00104 color = self._color_callback(i + self._min) 00105 else: 00106 color = wx.LIGHT_GREY 00107 end_color = wx.Colour(0.6 * color.Red(), 0.6 * color.Green(), 0.6 * color.Blue()) 00108 dc.SetPen(wx.Pen(color)) 00109 dc.SetBrush(wx.Brush(color)) 00110 start = i * value_size 00111 end = (i + 1) * value_size 00112 dc.GradientFillLinear(wx.Rect(start, 0, end, height), color, end_color, wx.SOUTH) 00113 00114 if (i > 0): 00115 dc.SetPen(wx.BLACK_PEN) 00116 dc.DrawLine(start, 0, start, height) 00117 00118 marker_x = (self._val - 1) * value_size + (value_size / 2.0) - (self._timeline_marker_bitmap.GetWidth() / 2.0) 00119 dc.DrawBitmap(self._timeline_marker_bitmap, marker_x, 0, True) 00120 00121 def _set_val_from_x(self, x): 00122 (width, height) = self.GetSizeTuple() 00123 # determine value from mouse click 00124 length = self._max + 1 - self._min 00125 value_size = width / float(length) 00126 self.SetValue(x / value_size + 1) 00127 00128 def on_mouse(self, event): 00129 if (event.LeftDown()): 00130 self._left_down = True 00131 elif (event.LeftUp()): 00132 self._left_down = False 00133 self._set_val_from_x(event.GetX()) 00134 wx.PostEvent(self.GetEventHandler(), wx.PyCommandEvent(wx.EVT_COMMAND_SCROLL_CHANGED.typeId, self.GetId())) 00135 00136 if (self._left_down): 00137 self._set_val_from_x(event.GetX()) 00138 wx.PostEvent(self.GetEventHandler(), wx.PyCommandEvent(wx.EVT_COMMAND_SCROLL_THUMBTRACK.typeId, self.GetId())) 00139 00140 class MessageTimeline(wx.Panel): 00141 def __init__(self, parent, count, topic, type, message_callback, color_callback, pause_callback): 00142 wx.Panel.__init__(self, parent, wx.ID_ANY) 00143 00144 self._count = count 00145 self._message_callback = message_callback 00146 self._color_callback = color_callback 00147 self._pause_callback = pause_callback 00148 self._queue = deque() 00149 00150 sizer = wx.BoxSizer(wx.HORIZONTAL) 00151 self._timeline = ColoredTimeline(self, 1, 1, 1, self._get_color_for_value) 00152 sizer.Add(self._timeline, 1, wx.ALIGN_CENTER_VERTICAL|wx.ALL, 5) 00153 self._pause_button = wx.ToggleButton(self, wx.ID_ANY, "Pause") 00154 self._pause_button.SetToolTip(wx.ToolTip("Pause message updates")) 00155 sizer.Add(self._pause_button, 0, wx.ALIGN_CENTER_VERTICAL|wx.ALL, 5) 00156 self.SetSizer(sizer) 00157 00158 self._pause_button.Bind(wx.EVT_TOGGLEBUTTON, self.on_pause) 00159 self._paused = False 00160 self._last_msg = None 00161 00162 self._tracking_latest = True 00163 self.Layout() 00164 00165 self._last_val = 2 00166 00167 self._timeline.Bind(wx.EVT_COMMAND_SCROLL_THUMBTRACK, self.on_slider_scroll) 00168 self._timeline.Bind(wx.EVT_COMMAND_SCROLL_CHANGED, self.on_slider_scroll) 00169 00170 self._subscriber = None 00171 if (topic is not None): 00172 self._subscriber = rospy.Subscriber(topic, type, self.callback) 00173 00174 self._message_receipt_callback = None 00175 00176 def set_message_receipt_callback(self, cb): 00177 self._message_receipt_callback = cb 00178 00179 def Close(self): 00180 if (self._subscriber is not None): 00181 self._subscriber.unregister() 00182 self._subscriber = None 00183 wx.Panel.Close(self) 00184 00185 def __del__(self): 00186 if (self._subscriber is not None): 00187 self._subscriber.unregister() 00188 00189 def enable(self): 00190 wx.Panel.Enable(self) 00191 self._timeline.Enable() 00192 self._pause_button.Enable() 00193 00194 def disable(self): 00195 wx.Panel.Disable(self) 00196 self._timeline.Disable() 00197 self._pause_button.Disable() 00198 self.unpause() 00199 00200 def clear(self): 00201 self._queue.clear() 00202 self._timeline.SetRange(1, 1) 00203 self._timeline.SetValue(1) 00204 00205 def is_paused(self): 00206 return self._paused 00207 00208 def pause(self): 00209 self._paused = True 00210 self._pause_button.SetBackgroundColour(wx.Colour(123, 193, 255)) 00211 self._pause_button.SetToolTip(wx.ToolTip("Resume message updates")) 00212 00213 if (self._pause_callback is not None): 00214 self._pause_callback(True) 00215 00216 self._pause_button.SetValue(True) 00217 00218 def unpause(self): 00219 if (self._pause_callback is not None): 00220 self._pause_callback(False) 00221 00222 self._pause_button.SetBackgroundColour(wx.NullColour) 00223 self._pause_button.SetToolTip(wx.ToolTip("Pause message updates")) 00224 self._paused = False 00225 if (self._last_msg is not None): 00226 self._tracking_latest = True 00227 self._new_msg(self._last_msg) 00228 00229 self._pause_button.SetValue(False) 00230 00231 def on_pause(self, event): 00232 if (event.IsChecked()): 00233 self.pause() 00234 else: 00235 self.unpause() 00236 00237 def on_slider_scroll(self, event): 00238 val = self._timeline.GetValue() - 1 00239 if (val == self._last_val): 00240 return 00241 00242 if (val >= len(self._queue)): 00243 return 00244 00245 self._last_val = val 00246 00247 if (not self._paused and self._pause_callback is not None): 00248 self._pause_callback(True) 00249 00250 self._pause_button.SetValue(True) 00251 self._pause_button.SetBackgroundColour(wx.Colour(123, 193, 255)) 00252 self._paused = True 00253 self._tracking_latest = False 00254 00255 msg = self._queue[val] 00256 00257 self._message_callback(msg) 00258 00259 def callback(self, msg): 00260 wx.CallAfter(self._new_msg, msg) 00261 00262 def add_msg(self, msg): 00263 self._new_msg(msg) 00264 00265 def _new_msg(self, msg): 00266 self._last_msg = msg 00267 if (self._message_receipt_callback is not None): 00268 self._message_receipt_callback(msg) 00269 if (self._paused): 00270 return 00271 00272 self._queue.append(msg) 00273 if (len(self._queue) > self._count): 00274 self._queue.popleft() 00275 00276 new_len = len(self._queue) 00277 00278 self._timeline.SetRange(1, new_len) 00279 00280 if (self._tracking_latest): 00281 self._timeline.SetValue(new_len) 00282 self._message_callback(msg) 00283 00284 def _get_color_for_value(self, val): 00285 if (val == 1 and len(self._queue) == 0): 00286 return wx.LIGHT_GREY 00287 00288 return self._color_callback(self._queue[val - 1]) 00289 00290 def get_messages(self): 00291 return self._queue 00292