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 from __future__ import with_statement
00037
00038 import sys
00039 import time
00040 import threading
00041 import traceback
00042
00043 import rosgraph.impl.graph
00044 import rxgraph.dotcode
00045 from rxgraph.dotcode import generate_dotcode, generate_namespaces, NODE_NODE_GRAPH, NODE_TOPIC_GRAPH, NODE_TOPIC_ALL_GRAPH
00046 from rxgraph.viewer import RxGraphViewerFrame
00047
00048 import roslib.scriptutil
00049 import rostopic
00050 import rosnode
00051
00052
00053 import wx
00054
00055 def get_info_text(selection_url):
00056 if selection_url is None:
00057 return ''
00058 if selection_url.startswith('node:'):
00059 try:
00060 node_name = selection_url[5:]
00061 master = roslib.scriptutil.get_master()
00062 node_api = rosnode.get_api_uri(master, node_name)
00063 return rosnode.get_node_info_description(node_name) + rosnode.get_node_connection_info_description(node_api)
00064 except rosnode.ROSNodeException, e:
00065 return "ERROR: %s"%str(e)
00066
00067 elif selection_url.startswith('topic:'):
00068 try:
00069 return rostopic.get_info_text(selection_url[6:])
00070 except rostopic.ROSTopicException, e:
00071 return "ERROR: %s"%str(e)
00072
00073 class DotUpdate(threading.Thread):
00074 """Thread to control update of dot file"""
00075
00076 def __init__(self, graph, viewer, output_file=None):
00077 threading.Thread.__init__(self, name="DotUpdate")
00078 self.viewer = viewer
00079 self.graph = graph
00080 self.output_file = output_file
00081 self.selection_url = None
00082 self.selection_update = False
00083
00084 def select_callback(self, target, event):
00085 try:
00086 url = target.url
00087 if url:
00088 self.selection_url = url
00089 self.selection_update = True
00090 except:
00091 pass
00092
00093 def run(self):
00094 viewer = self.viewer
00095 current_ns_filter = viewer.ns_filter
00096 g = self.graph
00097 output_file = self.output_file
00098 last_graph_mode = NODE_NODE_GRAPH
00099 quiet = False
00100
00101 orientation = rxgraph.dotcode.ORIENTATIONS[0]
00102 info_text = ''
00103
00104 g.set_master_stale(5.0)
00105 g.set_node_stale(5.0)
00106
00107 GUPDATE_INTERVAL = 0.5
00108 INFO_UPDATE_INTERVAL = 10.
00109
00110 last_gupdate = time.time() - GUPDATE_INTERVAL
00111 last_info_update = time.time() - GUPDATE_INTERVAL
00112 try:
00113 while not is_shutdown():
00114
00115
00116 zoom = True
00117
00118
00119
00120
00121 now = time.time()
00122 if now - last_gupdate >= GUPDATE_INTERVAL:
00123 changed = g.update()
00124 last_gupdate = now
00125
00126 if now - last_info_update >= INFO_UPDATE_INTERVAL or self.selection_update:
00127 last_info_update = now
00128 if self.selection_url is not None:
00129 info_text = get_info_text(self.selection_url)
00130
00131 graph_mode = NODE_TOPIC_ALL_GRAPH if viewer.topic_boxes else NODE_NODE_GRAPH
00132
00133 changed |= viewer.ns_filter != current_ns_filter
00134 changed |= quiet != viewer.quiet
00135 changed |= graph_mode != last_graph_mode
00136 if self.selection_update:
00137 self.selection_update = False
00138
00139 if not changed:
00140 changed = True
00141 zoom = False
00142
00143 quiet = viewer.quiet
00144 last_graph_mode = graph_mode
00145
00146 if changed:
00147 current_ns_filter = viewer.ns_filter
00148 dotcode = generate_dotcode(g, current_ns_filter, graph_mode, orientation, quiet)
00149
00150
00151 namespaces = generate_namespaces(g, graph_mode, quiet)
00152 viewer.update_namespaces(namespaces)
00153
00154 viewer.set_dotcode(dotcode, zoom=zoom)
00155 viewer.set_info_text(info_text)
00156
00157
00158 if output_file:
00159 with file(output_file, 'w') as f:
00160 f.write(dotcode)
00161
00162
00163 time.sleep(0.1)
00164 else:
00165
00166 g.bad_update()
00167 time.sleep(0.1)
00168
00169 changed = False
00170
00171 except wx.PyDeadObjectError:
00172
00173 pass
00174 except:
00175 traceback.print_exc()
00176
00177 _is_shutdown = False
00178 def is_shutdown():
00179 return _is_shutdown
00180
00181 def set_shutdown(is_shutdown):
00182 global _is_shutdown
00183 _is_shutdown = is_shutdown
00184
00185 def init_frame():
00186 frame = RxGraphViewerFrame()
00187 frame.set_dotcode(rxgraph.dotcode.INIT_DOTCODE)
00188 return frame
00189
00190 def init_updater(frame, node_ns=None, topic_ns=None, output_file=None):
00191 graph = rosgraph.impl.graph.Graph(node_ns, topic_ns)
00192 updater = DotUpdate(graph, frame, output_file=output_file)
00193 frame.register_select_cb(updater.select_callback)
00194 return updater