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
00039
00040
00041
00042 PKG = 'rxtools'
00043 import collections
00044 import os
00045 import string
00046 import sys
00047 import wx
00048
00049 import roslib.names
00050 import roslib.packages
00051
00052 import rospy
00053
00054 import rxtools.vizutil
00055 rxtools.vizutil.check_matplotlib_deps()
00056
00057
00058
00059 import matplotlib
00060 matplotlib.use('WXAgg')
00061 from matplotlib.figure import Figure
00062 from matplotlib.backends.backend_wxagg import \
00063 FigureCanvasWxAgg as FigCanvas, \
00064 NavigationToolbar2WxAgg as NavigationToolbar
00065
00066 import numpy as np
00067 import pylab
00068
00069 from rxtools.rosplot import ROSData, is_ros_pause, is_ros_stop, toggle_ros_pause, set_ros_stop
00070 import mpl_toolkits.mplot3d.art3d as art3d
00071
00072
00073
00074 COLORS = (1, 0, 0), (0, 0, 1), (0, 1, 0), (1, 0, 1), (0, 1, 1), (0.5, 0.24, 0), (0, 0.5, 0.24), (1, 0.5, 0),
00075
00076
00077
00078 class RxPlotToolbar(NavigationToolbar):
00079 ON_PAUSE = wx.NewId()
00080 ON_STOP = wx.NewId()
00081 def __init__(self, canvas):
00082 NavigationToolbar.__init__(self, canvas)
00083
00084 self.play_bm = wx.Bitmap(roslib.packages.get_pkg_dir(PKG) + '/icons/play-16.png')
00085 self.pause_bm = wx.Bitmap(roslib.packages.get_pkg_dir(PKG) + '/icons/pause-16.png')
00086 self.AddSimpleTool(self.ON_PAUSE, self.pause_bm, 'Pause', 'Activate pause')
00087 wx.EVT_TOOL(self, self.ON_PAUSE, self._on_pause)
00088
00089 self.AddSimpleTool(self.ON_STOP, wx.Bitmap(roslib.packages.get_pkg_dir(PKG) + '/icons/stop-16.png'), 'Stop', 'Activate stop')
00090
00091 wx.EVT_TOOL(self, self.ON_STOP, self._on_stop)
00092 self._set_tb_enable()
00093
00094
00095 def _set_tb_enable(self):
00096
00097
00098
00099 tb_enabled = is_ros_pause() or is_ros_stop()
00100 for b in [self._NTB2_BACK, self._NTB2_FORWARD, self._NTB2_PAN, self._NTB2_ZOOM]:
00101 self.EnableTool(b, tb_enabled)
00102
00103 def _on_pause(self, evt):
00104 toggle_ros_pause()
00105 self._set_tb_enable()
00106 if is_ros_pause():
00107 self.SetToolNormalBitmap(self.ON_PAUSE, self.play_bm)
00108 else:
00109 self.SetToolNormalBitmap(self.ON_PAUSE, self.pause_bm)
00110
00111 self.ToggleTool(self._NTB2_PAN, False)
00112 self.ToggleTool(self._NTB2_ZOOM, False)
00113 self._active = 'ZOOM'
00114 self.zoom(tuple())
00115
00116 def _on_stop(self, evt):
00117 set_ros_stop()
00118 self._set_tb_enable()
00119
00120 self.EnableTool(self.ON_PAUSE, False)
00121 self.EnableTool(self.ON_STOP, False)
00122
00123
00124 class RxPlotFrame(wx.Frame):
00125 def __init__(self, topics, options):
00126 self.title = options.title
00127 self.legend = options.legend
00128 self.mode = options.mode
00129 if self.mode == '2d':
00130 self.draw_plot = self.draw_plot_2d
00131 self.init_plot = self.init_plot_2d
00132 elif self.mode in ['3d', 'scatter']:
00133 self.draw_plot = self.draw_plot_3d
00134 self.init_plot = self.init_plot_3d
00135 else:
00136 raise ValueError("Mode must be one of [2d, 3d, scatter], not [%s]"%(options.mode))
00137
00138 wx.Frame.__init__(self, None, -1, self.title)
00139
00140
00141
00142
00143
00144
00145
00146
00147
00148
00149
00150
00151
00152
00153
00154
00155 self.axes = []
00156 self.topics = topics
00157 self.period = options.period
00158 self.marker = options.marker
00159
00160
00161
00162 self.datagen = []
00163 self.datax = []
00164 self.datay = []
00165 self.buffer_size = options.buffer
00166
00167 self.start_time = rospy.get_time()
00168 for topic_list in topics:
00169 for t in topic_list:
00170 dg = ROSData(t, self.start_time)
00171 self.datagen.append(dg)
00172 datax, datay = dg.next()
00173 self.datax.append(collections.deque(datax))
00174 self.datay.append(collections.deque(datay))
00175
00176 self.create_menu()
00177 self.statusbar = self.CreateStatusBar()
00178 self.create_main_canvas()
00179
00180 self.redraw_timer = wx.Timer(self)
00181 self.Bind(wx.EVT_TIMER, self.on_redraw_timer, self.redraw_timer)
00182
00183
00184 self.redraw_timer.Start(500)
00185
00186 def create_menu(self):
00187 self.menubar = wx.MenuBar()
00188
00189 menu_file = wx.Menu()
00190 m_expt = menu_file.Append(-1, "&Save plot\tCtrl-S", "Save plot to file")
00191 self.Bind(wx.EVT_MENU, self.on_save_plot, m_expt)
00192 menu_file.AppendSeparator()
00193 m_exit = menu_file.Append(-1, "E&xit\tCtrl-X", "Exit")
00194 self.Bind(wx.EVT_MENU, self.on_exit, m_exit)
00195
00196 self.menubar.Append(menu_file, "&File")
00197 self.SetMenuBar(self.menubar)
00198
00199 def onpick(self, event):
00200 thisline = event.artist
00201 xdata, ydata = thisline.get_data()
00202 ind = event.ind
00203 self.statusbar.SetStatusText("%s, %s" % (xdata[ind][len(xdata[ind])/2], ydata[ind][len(ydata[ind])/2]))
00204
00205 def create_main_canvas(self):
00206
00207 self.dpi = 100
00208 params = matplotlib.figure.SubplotParams(left=0.125, bottom=0.12, right=0.99, top=0.99, wspace=0.001, hspace=0.1)
00209 self.fig = Figure((3.0, 3.0), dpi=self.dpi, subplotpars=params)
00210
00211 self.canvas = FigCanvas(self, -1, self.fig)
00212 self.canvas.mpl_connect('pick_event', self.onpick)
00213
00214 self.init_plot()
00215
00216 self.sizer = wx.BoxSizer(wx.VERTICAL)
00217 self.sizer.Add(self.canvas, 1, flag=wx.LEFT | wx.TOP | wx.GROW)
00218 self.SetSizer(self.sizer)
00219
00220 self.add_toolbar()
00221
00222 self.SetSize(wx.Size(500, 700))
00223 self.Layout()
00224
00225 def init_plot_2d(self):
00226 self.plot_data = []
00227 flat_topics = []
00228
00229 axes_index = 0
00230 plot_index = 0
00231
00232 for topic_list in self.topics:
00233 axes = self.fig.add_subplot(string.atoi('%d1%d'%(len(self.topics), axes_index+1)))
00234 axes.set_axis_bgcolor('white')
00235
00236 pylab.setp(axes.get_xticklabels(), fontsize=6)
00237 pylab.setp(axes.get_yticklabels(), fontsize=8)
00238
00239 self.axes.append(axes)
00240 axes_index += 1
00241
00242 for topic in topic_list:
00243 flat_topics.append(topic)
00244 plot_data = \
00245 axes.plot(self.datax[plot_index],
00246 self.datay[plot_index],
00247 marker=self.marker,
00248 linewidth=1,
00249 picker=5,
00250 color=COLORS[plot_index],
00251 )[0]
00252
00253 self.plot_data.append(plot_data)
00254 plot_index += 1
00255
00256
00257 for ax in self.axes:
00258 ax.grid(True, color='gray')
00259 pylab.setp(ax.get_xticklabels(), visible=True)
00260
00261
00262 fp = matplotlib.font_manager.FontProperties(size=8)
00263 legends = self.legend.split(",") if self.legend else []
00264 if legends:
00265 if len(legends) != len(flat_topics):
00266 raise "Number of legend strings does not match the number of topics"
00267 self.fig.legend(self.plot_data, legends, 'lower right', prop=fp)
00268 elif len(flat_topics) > 1:
00269 self.fig.legend(self.plot_data, flat_topics, 'lower right', prop=fp)
00270
00271 def init_plot_3d(self):
00272
00273 self.plot_data = []
00274
00275 import random
00276 self.color = COLORS[random.randint(0, len(COLORS))]
00277
00278
00279 import mpl_toolkits.mplot3d.axes3d
00280 self.ax = mpl_toolkits.mplot3d.axes3d.Axes3D(self.fig)
00281
00282 flat_topics = []
00283 for topic_list in self.topics:
00284 for topic in topic_list:
00285 flat_topics.append(topic)
00286
00287 ntopics = len(flat_topics)
00288 if ntopics <= 3:
00289 self.ax.set_xlabel(flat_topics[0])
00290 self.ax.set_ylabel(flat_topics[1])
00291 if ntopics == 2:
00292 self.ax.set_zlabel("time")
00293 elif ntopics == 3:
00294 self.ax.set_zlabel(flat_topics[2])
00295 else:
00296 raise Exception("Expected 2 or 3 topics, but got %d" % (ntopics))
00297
00298
00299 self.ax.mouse_init()
00300
00301 def draw_plot_2d(self, relimit=False):
00302 if not self.plot_data:
00303 return
00304
00305
00306 if relimit and self.datax[0]:
00307 axes_index = 0
00308 plot_index = 0
00309
00310 for topic_list in self.topics:
00311 axes = self.axes[axes_index]
00312 axes_index += 1
00313 ymin = ymax = None
00314 for t in topic_list:
00315 datax = self.datax[plot_index]
00316 datay = self.datay[plot_index]
00317 plot_index += 1
00318
00319 xmax = datax[-1]
00320 xmin = xmax - self.period
00321 if ymin is None:
00322 ymin = min(datay)
00323 ymax = max(datay)
00324 else:
00325 ymin = min(min(datay), ymin)
00326 ymax = max(max(datay), ymax)
00327
00328
00329 delta = ymax - ymin
00330 ymin -= .05*delta
00331 ymax += .05*delta
00332
00333 axes.set_xbound(lower=xmin, upper=xmax)
00334 axes.set_ybound(lower=ymin, upper=ymax)
00335
00336
00337 for plot_index in xrange(0, len(self.plot_data)):
00338 datax = self.datax[plot_index]
00339 datay = self.datay[plot_index]
00340
00341 plot_data = self.plot_data[plot_index]
00342 plot_data.set_data(np.array(datax), np.array(datay))
00343
00344 self.canvas.draw()
00345
00346 def draw_plot_3d(self, relimit=False):
00347
00348 if self.datax[0] and self.datay[0] and self.datay[1]:
00349
00350 ndata = len(self.datay)
00351 if ndata >=2:
00352 datax = np.array(self.datay[0])
00353 datay = np.array(self.datay[1])
00354
00355
00356 if ndata == 2:
00357 dataz = np.array(self.datax[0])
00358 elif ndata == 3 and self.datay[2]:
00359 dataz = np.array(self.datay[2])
00360 else:
00361 print "unexpected input data dimensions for 3d plotting (%d)" % ndata
00362
00363 if self.mode == '3d':
00364 if not self.plot_data:
00365 self.plot_data = self.ax.plot(datax, datay, dataz)
00366
00367 self.plot_data[0].set_data(datax, datay)
00368 art3d.line_2d_to_3d(self.plot_data[0], zs=dataz, zdir='z')
00369 self.ax.auto_scale_xyz(datax, datay, dataz, True)
00370 else:
00371
00372
00373
00374
00375
00376
00377 self.plot_data = self.ax.scatter(datax, datay, dataz, color=self.color)
00378
00379 self.canvas.draw()
00380
00381 def on_save_plot(self, event):
00382 file_choices = "PNG (*.png)|*.png"
00383
00384 dlg = wx.FileDialog(
00385 self,
00386 message="Save plot as...",
00387 defaultDir=os.getcwd(),
00388 defaultFile="plot.png",
00389 wildcard=file_choices,
00390 style=wx.SAVE)
00391
00392 if dlg.ShowModal() == wx.ID_OK:
00393 path = dlg.GetPath()
00394 self.canvas.print_figure(path, dpi=self.dpi)
00395 self.flash_status_message("Saved to %s" % path)
00396
00397 def on_redraw_timer(self, event):
00398
00399
00400
00401 if is_ros_stop():
00402 for dg in self.datagen:
00403 dg.close()
00404 self.datagen = []
00405
00406 if not is_ros_pause():
00407 for plot_index in xrange(0, len(self.datagen)):
00408 try:
00409 datax, datay = self.datagen[plot_index].next()
00410 except Exception, e:
00411 print >> sys.stderr, str(e)
00412 wx.GetApp().Exit()
00413 return
00414
00415 plot_datax, plot_datay = self.datax[plot_index], self.datay[plot_index]
00416 plot_datax.extend(datax)
00417 plot_datay.extend(datay)
00418
00419 if len(plot_datax) > 0 and self.buffer_size > 0:
00420 xcutoff = plot_datax[-1] - self.buffer_size
00421 while len(plot_datax) > 0 and plot_datax[0] < xcutoff:
00422 plot_datax.popleft()
00423 plot_datay.popleft()
00424
00425 self.draw_plot(relimit=True)
00426
00427 def on_exit(self, event):
00428 self.Destroy()
00429
00430 def flash_status_message(self, msg, flash_len_ms=1500):
00431 self.statusbar.SetStatusText(msg)
00432 self.timeroff = wx.Timer(self)
00433 self.Bind(
00434 wx.EVT_TIMER,
00435 self.on_flash_status_off,
00436 self.timeroff)
00437 self.timeroff.Start(flash_len_ms, oneShot=True)
00438
00439 def on_flash_status_off(self, event):
00440 self.statusbar.SetStatusText('')
00441
00442 def add_toolbar(self):
00443 self.toolbar = RxPlotToolbar(self.canvas)
00444 self.toolbar.Realize()
00445 self.SetToolBar(self.toolbar)
00446 if 0:
00447 if wx.Platform == '__WXMAC__':
00448
00449
00450
00451 self.SetToolBar(self.toolbar)
00452 else:
00453
00454
00455 tw, th = self.toolbar.GetSizeTuple()
00456 fw, fh = self.canvas.GetSizeTuple()
00457
00458
00459
00460 self.toolbar.SetSize(wx.Size(fw, th))
00461 self.sizer.Add(self.toolbar, 0, wx.LEFT | wx.EXPAND)
00462
00463 self.toolbar.update()
00464
00465
00466
00467 def rxplot_app(topic_list, options):
00468 rospy.init_node('rxplot', anonymous=True)
00469
00470 try:
00471 app = wx.PySimpleApp()
00472 app.frame = rxtools.rxplot.RxPlotFrame(topic_list, options)
00473 app.frame.Show()
00474 app.MainLoop()
00475 except Exception, e:
00476 rospy.logerr(e)
00477 print >> sys.stderr, str(e)
00478 wx.GetApp().Exit()
00479
00480 rospy.signal_shutdown('GUI shutdown')
00481