$search
00001 #!/usr/bin/env python 00002 # Software License Agreement (BSD License) 00003 # 00004 # Copyright (c) 2008, 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 Willow Garage, Inc. 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 # Revision $Id$ 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 # have to import wx last due to xdot playing with the wx version 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 # #2839 by default, changes zoom, but we can cancel this for certain events 00116 zoom = True 00117 00118 # throttle calls to g.update(). we want fast refresh 00119 # on changes to the viewer's ns_filter, less so on the 00120 # graph polling. 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 # only alter the zoom flag if this is the sole change reason 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 #compute path-combo box 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 # store dotcode if requested 00158 if output_file: 00159 with file(output_file, 'w') as f: 00160 f.write(dotcode) 00161 00162 #information still changing, shorter yield 00163 time.sleep(0.1) 00164 else: 00165 # no new information, let bad nodes update 00166 g.bad_update() 00167 time.sleep(0.1) 00168 00169 changed = False 00170 00171 except wx.PyDeadObjectError: 00172 # shutdown 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