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 import roslib; roslib.load_manifest('smach_viewer')
00033 import rospy
00034
00035 from smach_msgs.msg import SmachContainerStatus,SmachContainerInitialStatusCmd,SmachContainerStructure
00036
00037 import sys
00038 import os
00039 import threading
00040 import pickle
00041 import pprint
00042 import copy
00043 import StringIO
00044 import colorsys
00045
00046 import wxversion
00047 wxversion.select("2.8")
00048 import wx
00049 import wx.richtext
00050
00051 import xdot
00052 import smach
00053 import smach_ros
00054
00055 def graph_attr_string(attrs):
00056 attrs_strs = ['"'+str(k)+'"="'+str(v)+'"' for k,v in attrs.iteritems()]
00057 return ';\n'.join(attrs_strs)+';\n'
00058
00059 def attr_string(attrs):
00060 attrs_strs = ['"'+str(k)+'"="'+str(v)+'"' for k,v in attrs.iteritems()]
00061 return ' ['+(', '.join(attrs_strs))+']'
00062
00063 def get_parent_path(path):
00064 path_tokens = path.split('/')
00065 if len(path_tokens) > 2:
00066 parent_path = '/'.join(path_tokens[0:-1])
00067 else:
00068 parent_path = '/'.join(path_tokens[0:1])
00069 return parent_path
00070
00071 def get_label(path):
00072 path_tokens = path.split('/')
00073 return path_tokens[-1]
00074
00075 def hex2t(color_str):
00076 color_tuple = [int(color_str[i:i+2],16)/255.0 for i in range(1,len(color_str),2)]
00077 return color_tuple
00078
00079
00080
00081
00082 class ContainerNode():
00083 def __init__(self, server_name, msg):
00084
00085 self._server_name = server_name
00086 self._path = msg.path
00087 splitpath = msg.path.split('/')
00088 self._label = splitpath[-1]
00089 self._dir = '/'.join(splitpath[0:-1])
00090
00091 self._children = msg.children
00092 self._internal_outcomes = msg.internal_outcomes
00093 self._outcomes_from = msg.outcomes_from
00094 self._outcomes_to = msg.outcomes_to
00095
00096 self._container_outcomes = msg.container_outcomes
00097
00098
00099 self._initial_states = []
00100 self._active_states = []
00101 self._last_active_states = []
00102 self._local_data = smach.UserData()
00103 self._info = ''
00104
00105 def update_structure(self, msg):
00106 needs_update = False
00107
00108 if self._children != msg.children\
00109 or self._internal_outcomes != msg.internal_outcomes\
00110 or self._outcomes_from != msg.outcomes_from\
00111 or self._outcomes_to != msg.outcomes_to\
00112 or self._container_outcomes != msg.container_outcomes:
00113 needs_update = True
00114
00115 if needs_update:
00116 self._children = msg.children
00117 self._internal_outcomes = msg.internal_outcomes
00118 self._outcomes_from = msg.outcomes_from
00119 self._outcomes_to = msg.outcomes_to
00120
00121 self._container_outcomes = msg.container_outcomes
00122
00123 return needs_update
00124
00125
00126 def update_status(self, msg):
00127 needs_update = False
00128 if set(msg.initial_states) != set(self._initial_states):
00129 self._structure_changed = True
00130 needs_update = True
00131 if set(msg.active_states) != set(self._active_states):
00132 needs_update = True
00133
00134 self._initial_states = msg.initial_states
00135 self._last_active_states = self._active_states
00136 self._active_states = msg.active_states
00137 while True:
00138 try:
00139 self._local_data._data = pickle.loads(msg.local_data)
00140 break
00141 except ImportError as ie:
00142
00143 modulename = ie.args[0][16:]
00144 packagename = modulename[0:modulename.find('.')]
00145 roslib.load_manifest(packagename)
00146 self._local_data._data = pickle.loads(msg.local_data)
00147
00148 self._info = msg.info
00149
00150 return needs_update
00151
00152 def get_dotcode(self, selected_paths, closed_paths, depth, max_depth, containers, show_all, attrs={}):
00153 dotstr = 'subgraph "cluster_%s" {\n' % (self._path)
00154 if depth == 0:
00155
00156 attrs['color'] = '#00000000'
00157 attrs['fillcolor'] = '#0000000F'
00158
00159
00160
00161 dotstr += graph_attr_string(attrs)
00162
00163
00164 proxy_attrs = {
00165 'URL':self._path,
00166 'shape':'plaintext',
00167 'color':'gray',
00168 'fontsize':'18',
00169 'fontweight':'18',
00170 'rank':'min',
00171 'height':'0.01'}
00172 proxy_attrs['label'] = self._label
00173 dotstr += '"%s" %s;\n' % (
00174 '/'.join([self._path,'__proxy__']),
00175 attr_string(proxy_attrs))
00176
00177
00178 if max_depth == -1 or depth <= max_depth:
00179
00180 dotstr += 'subgraph "cluster_%s" {\n' % '/'.join([self._path,'__outcomes__'])
00181 outcomes_attrs = {
00182 'style':'rounded,filled',
00183 'rank':'sink',
00184 'color':'#FFFFFFFF',
00185 'fillcolor':'#FFFFFF00'
00186 }
00187 dotstr += graph_attr_string(outcomes_attrs)
00188
00189 for outcome_label in self._container_outcomes:
00190 outcome_path = ':'.join([self._path,outcome_label])
00191 outcome_attrs = {
00192 'shape':'box',
00193 'height':'0.3',
00194 'style':'filled,rounded',
00195 'fontsize':'12',
00196 'fillcolor':'#FE464f',
00197 'color':'#780006',
00198 'fontcolor':'#780006',
00199 'label':outcome_label,
00200 'URL':':'.join([self._path,outcome_label])
00201 }
00202 dotstr += '"%s" %s;\n' % (outcome_path,attr_string(outcome_attrs))
00203 dotstr += "}\n"
00204
00205
00206 for child_label in self._children:
00207 child_attrs = {
00208 'style':'filled,setlinewidth(2)',
00209 'color':'#000000FF',
00210 'fillcolor':'#FFFFFF00'
00211 }
00212
00213 child_path = '/'.join([self._path,child_label])
00214
00215 if child_path in containers:
00216 child_attrs['style'] += ',rounded'
00217
00218 dotstr += containers[child_path].get_dotcode(
00219 selected_paths,
00220 closed_paths,
00221 depth+1, max_depth,
00222 containers,
00223 show_all,
00224 child_attrs)
00225 else:
00226 child_attrs['label'] = child_label
00227 child_attrs['URL'] = child_path
00228 dotstr += '"%s" %s;\n' % (child_path, attr_string(child_attrs))
00229
00230
00231 internal_edges = zip(
00232 self._internal_outcomes,
00233 self._outcomes_from,
00234 self._outcomes_to)
00235
00236
00237 internal_edges += [('','__proxy__',initial_child) for initial_child in self._initial_states]
00238
00239 has_explicit_transitions = []
00240 for (outcome_label,from_label,to_label) in internal_edges:
00241 if to_label != 'None' or outcome_label == to_label:
00242 has_explicit_transitions.append(from_label)
00243
00244
00245 for (outcome_label,from_label,to_label) in internal_edges:
00246
00247 from_path = '/'.join([self._path, from_label])
00248
00249 if show_all \
00250 or to_label != 'None'\
00251 or from_label not in has_explicit_transitions \
00252 or (outcome_label == from_label) \
00253 or from_path in containers:
00254
00255 if to_label == 'None':
00256 to_label = outcome_label
00257
00258 to_path = '/'.join([self._path, to_label])
00259
00260 edge_attrs = {
00261 'URL':':'.join([from_path,outcome_label,to_path]),
00262 'fontsize':'12',
00263 'label':outcome_label}
00264 edge_attrs['style'] = 'setlinewidth(2)'
00265
00266
00267
00268
00269
00270 from_key = '"%s"' % from_path
00271 if from_path in containers:
00272 if max_depth == -1 or depth+1 <= max_depth:
00273 from_key = '"%s:%s"' % ( from_path, outcome_label)
00274 else:
00275 edge_attrs['ltail'] = 'cluster_'+from_path
00276 from_path = '/'.join([from_path,'__proxy__'])
00277 from_key = '"%s"' % ( from_path )
00278
00279 to_key = ''
00280 if to_label in self._container_outcomes:
00281 to_key = '"%s:%s"' % (self._path,to_label)
00282 edge_attrs['color'] = '#00000055'
00283 else:
00284 if to_path in containers:
00285 edge_attrs['lhead'] = 'cluster_'+to_path
00286 to_path = '/'.join([to_path,'__proxy__'])
00287 to_key = '"%s"' % to_path
00288
00289 dotstr += '%s -> %s %s;\n' % (
00290 from_key, to_key, attr_string(edge_attrs))
00291
00292 dotstr += '}\n'
00293 return dotstr
00294
00295 def set_styles(self, selected_paths, depth, max_depth, items, subgraph_shapes, containers):
00296
00297
00298 """
00299 if depth == 0:
00300 container_shapes = subgraph_shapes['cluster_'+self._path]
00301 container_color = (0,0,0,0)
00302 container_fillcolor = (0,0,0,0)
00303
00304 for shape in container_shapes:
00305 shape.pen.color = container_color
00306 shape.pen.fillcolor = container_fillcolor
00307 """
00308
00309
00310
00311
00312 if max_depth == -1 or depth <= max_depth:
00313
00314 for child_label in self._children:
00315 child_path = '/'.join([self._path,child_label])
00316
00317 child_color = [0.5,0.5,0.5,1]
00318 child_fillcolor = [1,1,1,1]
00319 child_linewidth = 2
00320
00321 active_color = hex2t('#5C7600FF')
00322 active_fillcolor = hex2t('#C0F700FF')
00323
00324 initial_color = hex2t('#000000FF')
00325 initial_fillcolor = hex2t('#FFFFFFFF')
00326
00327 if child_label in self._active_states:
00328
00329 child_color = active_color
00330 child_fillcolor = active_fillcolor
00331 child_linewidth = 5
00332 elif child_label in self._initial_states:
00333
00334
00335 child_color = initial_color
00336 child_linewidth = 2
00337
00338
00339 if child_path in selected_paths:
00340 child_color = hex2t('#FB000DFF')
00341
00342
00343 if child_path in containers:
00344 subgraph_id = 'cluster_'+child_path
00345 if subgraph_id in subgraph_shapes:
00346 if child_label in self._active_states:
00347 child_fillcolor[3] = 0.25
00348 elif 0 and child_label in self._initial_states:
00349 child_fillcolor[3] = 0.25
00350 else:
00351 if max_depth > 0:
00352 v = 1.0-0.25*((depth+1)/float(max_depth))
00353 else:
00354 v = 0.85
00355 child_fillcolor = [v,v,v,1.0]
00356
00357
00358 for shape in subgraph_shapes['cluster_'+child_path]:
00359 pen = shape.pen
00360 if len(pen.color) > 3:
00361 pen_color_opacity = pen.color[3]
00362 if pen_color_opacity < 0.01:
00363 pen_color_opacity = 0
00364 else:
00365 pen_color_opacity = 0.5
00366 shape.pen.color = child_color[0:3]+[pen_color_opacity]
00367 shape.pen.fillcolor = [child_fillcolor[i] for i in range(min(3,len(pen.fillcolor)))]
00368 shape.pen.linewidth = child_linewidth
00369
00370 containers[child_path].set_styles(
00371 selected_paths,
00372 depth+1, max_depth,
00373 items,
00374 subgraph_shapes,
00375 containers)
00376 else:
00377 if child_path in items:
00378 for shape in items[child_path].shapes:
00379 if not isinstance(shape,xdot.xdot.TextShape):
00380 shape.pen.color = child_color
00381 shape.pen.fillcolor = child_fillcolor
00382 shape.pen.linewidth = child_linewidth
00383 else:
00384
00385 pass
00386
00387 class SmachViewerFrame(wx.Frame):
00388 def __init__(self):
00389 wx.Frame.__init__(self, None, -1, "Smach Viewer", size=(720,480))
00390
00391
00392 self._containers = {}
00393 self._top_containers = {}
00394 self._update_cond = threading.Condition()
00395 self._needs_refresh = True
00396
00397 vbox = wx.BoxSizer(wx.VERTICAL)
00398
00399
00400
00401 self.content_splitter = wx.SplitterWindow(self, -1,style = wx.SP_LIVE_UPDATE)
00402 self.content_splitter.SetMinimumPaneSize(24)
00403 self.content_splitter.SetSashGravity(0.85)
00404
00405
00406
00407 viewer = wx.Panel(self.content_splitter,-1)
00408
00409
00410 nb = wx.Notebook(viewer,-1,style=wx.NB_TOP | wx.WANTS_CHARS)
00411 viewer_box = wx.BoxSizer()
00412 viewer_box.Add(nb,1,wx.EXPAND | wx.ALL, 4)
00413 viewer.SetSizer(viewer_box)
00414
00415
00416 graph_view = wx.Panel(nb,-1)
00417 gv_vbox = wx.BoxSizer(wx.VERTICAL)
00418 graph_view.SetSizer(gv_vbox)
00419
00420
00421 toolbar = wx.ToolBar(graph_view, -1)
00422
00423 toolbar.AddControl(wx.StaticText(toolbar,-1,"Path: "))
00424
00425 self.path_combo = wx.ComboBox(toolbar, -1, style=wx.CB_DROPDOWN)
00426 self.path_combo .Bind(wx.EVT_COMBOBOX, self.set_path)
00427 self.path_combo.Append('/')
00428 self.path_combo.SetValue('/')
00429 toolbar.AddControl(self.path_combo)
00430
00431 self.depth_spinner = wx.SpinCtrl(toolbar, -1,
00432 size=wx.Size(50,-1),
00433 min=-1,
00434 max=1337,
00435 initial=-1)
00436 self.depth_spinner.Bind(wx.EVT_SPINCTRL,self.set_depth)
00437 self._max_depth = -1
00438 toolbar.AddControl(wx.StaticText(toolbar,-1," Depth: "))
00439 toolbar.AddControl(self.depth_spinner)
00440
00441 toggle_all = wx.ToggleButton(toolbar,-1,'Show Implicit')
00442 toggle_all.Bind(wx.EVT_TOGGLEBUTTON, self.toggle_all_transitions)
00443 self._show_all_transitions = False
00444
00445 toolbar.AddControl(wx.StaticText(toolbar,-1," "))
00446 toolbar.AddControl(toggle_all)
00447
00448 toolbar.AddControl(wx.StaticText(toolbar,-1," "))
00449 toolbar.AddLabelTool(wx.ID_HELP, 'Help',
00450 wx.ArtProvider.GetBitmap(wx.ART_HELP,wx.ART_OTHER,(16,16)) )
00451 toolbar.Realize()
00452
00453
00454 self.Bind(wx.EVT_TOOL, self.ShowControlsDialog, id=wx.ID_HELP)
00455
00456
00457 self.widget = xdot.wxxdot.WxDotWindow(graph_view, -1)
00458
00459 gv_vbox.Add(toolbar, 0, wx.EXPAND)
00460 gv_vbox.Add(self.widget, 1, wx.EXPAND)
00461
00462
00463 self.tree = wx.TreeCtrl(nb,-1,style=wx.TR_HAS_BUTTONS)
00464 nb.AddPage(graph_view,"Graph View")
00465 nb.AddPage(self.tree,"Tree View")
00466
00467
00468
00469 borders = wx.LEFT | wx.RIGHT | wx.TOP
00470 border = 4
00471 self.ud_win = wx.ScrolledWindow(self.content_splitter, -1)
00472 self.ud_gs = wx.BoxSizer(wx.VERTICAL)
00473
00474 self.ud_gs.Add(wx.StaticText(self.ud_win,-1,"Path:"),0, borders, border)
00475
00476 self.path_input = wx.ComboBox(self.ud_win,-1,style=wx.CB_DROPDOWN)
00477 self.path_input.Bind(wx.EVT_COMBOBOX,self.selection_changed)
00478 self.ud_gs.Add(self.path_input,0,wx.EXPAND | borders, border)
00479
00480
00481 self.ud_gs.Add(wx.StaticText(self.ud_win,-1,"Userdata:"),0, borders, border)
00482
00483 self.ud_txt = wx.TextCtrl(self.ud_win,-1,style=wx.TE_MULTILINE | wx.TE_READONLY)
00484 self.ud_gs.Add(self.ud_txt,1,wx.EXPAND | borders, border)
00485
00486
00487 self.is_button = wx.Button(self.ud_win,-1,"Set as Initial State")
00488 self.is_button.Bind(wx.EVT_BUTTON, self.on_set_initial_state)
00489 self.is_button.Disable()
00490 self.ud_gs.Add(self.is_button,0,wx.EXPAND | wx.BOTTOM | borders, border)
00491
00492 self.ud_win.SetSizer(self.ud_gs)
00493
00494
00495
00496 self.content_splitter.SplitVertically(viewer, self.ud_win, 512)
00497
00498
00499 self.statusbar = wx.StatusBar(self,-1)
00500
00501
00502 vbox.Add(self.content_splitter, 1, wx.EXPAND | wx.ALL)
00503 vbox.Add(self.statusbar, 0, wx.EXPAND)
00504
00505 self.SetSizer(vbox)
00506 self.Center()
00507
00508
00509 self._client = smach_ros.IntrospectionClient()
00510 self._containers= {}
00511 self._selected_paths = []
00512
00513
00514 self._structure_subs = {}
00515 self._status_subs = {}
00516
00517 self.Bind(wx.EVT_IDLE,self.OnIdle)
00518 self.Bind(wx.EVT_CLOSE,self.OnQuit)
00519
00520
00521 self.widget.register_select_callback(self.select_cb)
00522 self._path = '/'
00523 self._needs_zoom = True
00524 self._structure_changed = True
00525
00526
00527 self._keep_running = True
00528 self._server_list_thread = threading.Thread(target=self._update_server_list)
00529 self._server_list_thread.start()
00530
00531 self._update_graph_thread = threading.Thread(target=self._update_graph)
00532 self._update_graph_thread.start()
00533 self._update_tree_thread = threading.Thread(target=self._update_tree)
00534 self._update_tree_thread.start()
00535
00536
00537 def OnQuit(self,event):
00538 self._update_cond.acquire()
00539 self._keep_running = False
00540 self._update_cond.notify_all()
00541 self._update_cond.release()
00542
00543 self._server_list_thread.join()
00544 self._update_graph_thread.join()
00545 self._update_tree_thread.join()
00546
00547 event.Skip()
00548
00549 def update_graph(self):
00550 self._update_cond.acquire()
00551 self._update_cond.notify_all()
00552 self._update_cond.release()
00553
00554 def on_set_initial_state(self, event):
00555 state_path = self._selected_paths[0]
00556 parent_path = get_parent_path(state_path)
00557 state = get_label(state_path)
00558
00559 server_name = self._containers[parent_path]._server_name
00560 self._client.set_initial_state(server_name,parent_path,[state],timeout = rospy.Duration(60.0))
00561
00562 def set_path(self, event):
00563 self._path = self.path_combo.GetValue()
00564 self._needs_zoom = True
00565 self.update_graph()
00566
00567 def set_depth(self, event):
00568 self._max_depth = self.depth_spinner.GetValue()
00569 self._needs_zoom = True
00570 self.update_graph()
00571
00572 def toggle_all_transitions(self, event):
00573 self._show_all_transitions = not self._show_all_transitions
00574 self._structure_changed = True
00575 self.update_graph()
00576
00577 def select_cb(self, item, event):
00578 self.statusbar.SetStatusText(item.url)
00579 if event.ButtonUp(wx.MOUSE_BTN_LEFT):
00580 self._selected_paths = [item.url]
00581 self.path_input.SetValue(item.url)
00582 wx.PostEvent(
00583 self.path_input.GetEventHandler(),
00584 wx.CommandEvent(wx.wxEVT_COMMAND_COMBOBOX_SELECTED,self.path_input.GetId()))
00585 self.update_graph()
00586
00587 def selection_changed(self, event):
00588 path_input_str = self.path_input.GetValue()
00589 if len(path_input_str) > 0:
00590 path = path_input_str.split(':')[0]
00591 if path not in self._containers:
00592 parent_path = get_parent_path(path)
00593 else:
00594 parent_path = path
00595 if parent_path in self._containers:
00596 self.is_button.Enable()
00597 container = self._containers[parent_path]
00598
00599 pos = self.ud_txt.HitTestPos(wx.Point(0,0))
00600 sel = self.ud_txt.GetSelection()
00601 ud_str = ''
00602 for (k,v) in container._local_data._data.iteritems():
00603 ud_str += str(k)+": "
00604 vstr = str(v)
00605
00606 if vstr.find('\n') != -1:
00607 ud_str += '\n'
00608 ud_str+=vstr+'\n\n'
00609
00610 self.ud_txt.SetValue(ud_str)
00611 self.ud_txt.ShowPosition(pos[1])
00612 if sel != (0,0):
00613 self.ud_txt.SetSelection(sel[0],sel[1])
00614 else:
00615 self.is_button.Disable()
00616
00617 def _structure_msg_update(self, msg, server_name):
00618 if not self._keep_running:
00619 return
00620
00621 path = msg.path
00622 pathsplit = path.split('/')
00623 dir = '/'.join(pathsplit[0:-1])
00624
00625
00626
00627
00628 needs_redraw = False
00629 if path in self._containers:
00630 needs_redraw = self._containers[path].update_structure(msg)
00631 else:
00632
00633 needs_redraw= True
00634 self._needs_zoom = True
00635 container = ContainerNode(server_name, msg)
00636 self._containers[path] = container
00637
00638 if dir=='':
00639 self._top_containers[path] = container
00640
00641 self.path_combo.Append(path)
00642 self.path_input.Append(path)
00643
00644 self._update_cond.acquire()
00645 if needs_redraw:
00646 self._structure_changed = True
00647 self._needs_zoom = True
00648 self._update_cond.notify_all()
00649 self._update_cond.release()
00650
00651 def _status_msg_update(self, msg):
00652 if not self._keep_running:
00653 return
00654 path = msg.path
00655
00656 needs_redraw = False
00657 if path in self._containers:
00658 container = self._containers[path]
00659 if container.update_status(msg):
00660
00661 """
00662 for child_label in container._children:
00663 child_path = '/'.join([path,child_label])
00664 if child_path in self.widget.items:
00665 if child_label in container._active_states:
00666 #print 'SET "'+child_path+'" ACTIVE'
00667 pass
00668 for shape in self.widget.items[child_path].shapes:
00669 if child_label in container._active_states:
00670 shape.pen.fillcolor = (0,1,0,1)
00671 elif child_label in container._last_active_states:
00672 shape.pen.fillcolor = (1,0.85,0.85,1)
00673 else:
00674 shape.pen.fillcolor = (1,1,1,1)
00675 """
00676 self._update_cond.acquire()
00677 self._update_cond.notify_all()
00678 self._update_cond.release()
00679
00680 path_input_str = self.path_input.GetValue()
00681 if path_input_str == path or get_parent_path(path_input_str) == path:
00682 wx.PostEvent(
00683 self.path_input.GetEventHandler(),
00684 wx.CommandEvent(wx.wxEVT_COMMAND_COMBOBOX_SELECTED,self.path_input.GetId()))
00685
00686 def _update_graph(self,zoom=False):
00687 while self._keep_running and not rospy.is_shutdown():
00688 self._update_cond.acquire()
00689 self._update_cond.wait()
00690
00691 if self._structure_changed or self._needs_zoom:
00692 dotstr = ""
00693 dotstr = "digraph {\n\t"
00694 dotstr += "compound=true;"
00695 dotstr += "outputmode=nodesfirst;"
00696 dotstr += "labeljust=l;"
00697 dotstr += "nodesep=0.5;"
00698
00699 dotstr += "mclimit=5;"
00700 dotstr += "clusterrank=local;"
00701 dotstr += "ranksep=0.75;"
00702
00703
00704 dotstr += "ordering=\"\";"
00705 dotstr += "\n"
00706
00707 if self._path in self._containers:
00708 dotstr += self._containers[self._path].get_dotcode(
00709 self._selected_paths,[],
00710 0,self._max_depth,
00711 self._containers,
00712 self._show_all_transitions)
00713 elif self._path == '/':
00714 for path,tc in self._top_containers.iteritems():
00715 dotstr += tc.get_dotcode(
00716 self._selected_paths,[],
00717 0,self._max_depth,
00718 self._containers,
00719 self._show_all_transitions)
00720 dotstr += '\n'
00721 else:
00722 dotstr += '"__empty__" [label="Path not available.", shape="plaintext"]\n'
00723
00724 dotstr+='}\n'
00725 self.set_dotcode(dotstr,zoom)
00726 self._structure_changed = False
00727
00728 if self._path in self._containers:
00729 self._containers[self._path].set_styles(
00730 self._selected_paths,
00731 0,self._max_depth,
00732 self.widget.items_by_url,
00733 self.widget.subgraph_shapes,
00734 self._containers)
00735 elif self._path == '/':
00736 for path,tc in self._top_containers.iteritems():
00737 tc.set_styles(
00738 self._selected_paths,
00739 0,self._max_depth,
00740 self.widget.items_by_url,
00741 self.widget.subgraph_shapes,
00742 self._containers)
00743 self.widget.Refresh()
00744 self._update_cond.release()
00745
00746 def set_dotcode(self, dotcode, zoom=True):
00747 if self.widget.set_dotcode(dotcode, None):
00748 self.SetTitle('Smach Viewer')
00749 if zoom or self._needs_zoom:
00750 self.widget.zoom_to_fit()
00751 self._needs_zoom = False
00752 self._needs_refresh = True
00753 wx.PostEvent(self.GetEventHandler(), wx.IdleEvent())
00754
00755 def _update_tree(self):
00756 while self._keep_running and not rospy.is_shutdown():
00757 self._update_cond.acquire()
00758 self._update_cond.wait()
00759 self.tree.DeleteAllItems()
00760 self._tree_nodes = {}
00761 for path,tc in self._top_containers.iteritems():
00762 self.add_to_tree(path, None)
00763 self._update_cond.release()
00764
00765 def add_to_tree(self, path, parent):
00766 if parent is None:
00767 container = self.tree.AddRoot(get_label(path))
00768 else:
00769 container = self.tree.AppendItem(parent,get_label(path))
00770
00771
00772 for label in self._containers[path]._children:
00773 child_path = '/'.join([path,label])
00774 if child_path in self._containers.keys():
00775 self.add_to_tree(child_path, container)
00776 else:
00777 self.tree.AppendItem(container,label)
00778
00779
00780
00781 def append_tree(self, container, parent = None):
00782 if not parent:
00783 node = self.tree.AddRoot(container._label)
00784 for child_label in container._children:
00785 self.tree.AppendItem(node,child_label)
00786
00787 def OnIdle(self, event):
00788 if self._needs_refresh:
00789 self.Refresh()
00790
00791 self._needs_refresh = False
00792
00793 def _update_server_list(self):
00794 while self._keep_running:
00795
00796 server_names = self._client.get_servers()
00797 new_server_names = [sn for sn in server_names if sn not in self._status_subs]
00798
00799
00800 for server_name in new_server_names:
00801 self._structure_subs[server_name] = rospy.Subscriber(
00802 server_name+smach_ros.introspection.STRUCTURE_TOPIC,
00803 SmachContainerStructure,
00804 callback = self._structure_msg_update,
00805 callback_args = server_name,
00806 queue_size=50)
00807
00808 self._status_subs[server_name] = rospy.Subscriber(
00809 server_name+smach_ros.introspection.STATUS_TOPIC,
00810 SmachContainerStatus,
00811 callback = self._status_msg_update,
00812 queue_size=50)
00813
00814
00815 rospy.sleep(1.0)
00816
00817
00818
00819
00820
00821
00822
00823
00824
00825
00826 def ShowControlsDialog(self,event):
00827 dial = wx.MessageDialog(None,
00828 "Pan: Arrow Keys\nZoom: PageUp / PageDown\nZoom To Fit: F\nRefresh: R",
00829 'Keyboard Controls', wx.OK)
00830 dial.ShowModal()
00831
00832 def OnExit(self, event):
00833 pass
00834
00835 def set_filter(self, filter):
00836 self.widget.set_filter(filter)
00837
00838 def main():
00839 app = wx.App()
00840
00841 frame = SmachViewerFrame()
00842 frame.set_filter('dot')
00843
00844 frame.Show()
00845
00846 dotstr="""
00847 digraph {
00848 compound=true;
00849 labeljust=l
00850 esep=10
00851 subgraph "cluster_/intro_test" {
00852 label = "intro_test"
00853 "/intro_test:user_data" [label=user_data, shape=note]
00854
00855 "/intro_test/GETTER1" [label=GETTER1, shape=ellipse]
00856
00857 subgraph "cluster_/intro_test/S2" {
00858 label = "S2"
00859 "/intro_test/S2:user_data" [label=user_data, shape=note]
00860
00861
00862 "/intro_test/S2/SETTER" [label=SETTER, shape=ellipse]
00863 }
00864
00865 subgraph "cluster_/intro_test/S3" {
00866 label = "S3"
00867 "/intro_test/S3:user_data" [label=user_data, shape=note]
00868
00869 "/intro_test/S3/SETTER" [label=SETTER, shape=ellipse]
00870 }
00871
00872 "/intro_test/GETTER2" [label=GETTER2, shape=ellipse]
00873
00874 "/intro_test/GETTER1" -> "/intro_test/S2/SETTER" [label=done, lhead="cluster_/intro_test/S2"]
00875 "/intro_test/S2/SETTER" -> "/intro_test/S3/SETTER" [label=done, ltail="cluster_/intro_test/S2", lhead="cluster_/intro_test/S3"]
00876 "/intro_test/S3/SETTER" -> "/intro_test/GETTER2" [label=done, ltail="cluster_/intro_test/S3"]
00877 }
00878 }
00879 """
00880
00881
00882 app.MainLoop()
00883
00884 if __name__ == '__main__':
00885 rospy.init_node('smach_viewer',anonymous=False, disable_signals=True,log_level=rospy.INFO)
00886
00887
00888 main()