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


rxgraph
Author(s): Ken Conley
autogenerated on Mon Oct 6 2014 07:26:06