dotcode.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2008, Willow Garage, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of Willow Garage, Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 
33 # this is a modified version of rx/rxgraph/src/rxgraph/dotcode.py
34 
35 import re
36 import copy
37 
38 import rosgraph.impl.graph
39 import roslib
40 import math
41 
42 import rospy
43 import pydot
44 
45 try:
46  unicode
47  # we're on python2, or the "unicode" function has already been defined elsewhere
48 except NameError:
49  unicode = str
50  # we're on python3
51 
52 # node/node connectivity
53 NODE_NODE_GRAPH = 'node_node'
54 # node/topic connections where an actual network connection exists
55 NODE_TOPIC_GRAPH = 'node_topic'
56 # all node/topic connections, even if no actual network connection
57 NODE_TOPIC_ALL_GRAPH = 'node_topic_all'
58 
59 QUIET_NAMES = ['/diag_agg', '/runtime_logger', '/pr2_dashboard', '/rviz',
60  '/rosout', '/cpu_monitor', '/monitor', '/hd_monitor',
61  '/rxloggerlevel', '/clock', '/rqt', '/statistics']
62 
63 
64 def _conv(n):
65  """Convert a node name to a valid dot name, which can't contain the leading space"""
66  if n.startswith(' '):
67  return 't_' + n[1:]
68  else:
69  return 'n_' + n
70 
71 
72 def matches_any(name, patternlist):
73  if patternlist is None or len(patternlist) == 0:
74  return False
75  for pattern in patternlist:
76  if unicode(name).strip() == pattern:
77  return True
78  if re.match("^[a-zA-Z0-9_/]+$", pattern) is None:
79  if re.match(unicode(pattern), name.strip()) is not None:
80  return True
81  return False
82 
83 
85 
86  def __init__(self, incoming=None, outgoing=None):
87  self.incoming = incoming or []
88  self.outgoing = outgoing or []
89 
90 
92 
93  # topic/topic -> graph.edge object
94  edges = dict([])
95 
96  # ROS node name -> graph.node object
97  nodes = dict([])
98 
99  def __init__(self):
100  try:
101  from rosgraph_msgs.msg import TopicStatistics
102  self.stats_sub = rospy.Subscriber(
103  '/statistics', TopicStatistics, self.statistics_callback)
104  except ImportError:
105  # not supported before Indigo
106  pass
107 
108  def statistics_callback(self, msg):
109 
110  # add connections (if new)
111  if msg.node_sub not in self.edges:
112  self.edges[msg.node_sub] = dict([])
113 
114  if msg.topic not in self.edges[msg.node_sub]:
115  self.edges[msg.node_sub][msg.topic] = dict([])
116 
117  self.edges[msg.node_sub][msg.topic][msg.node_pub] = msg
118 
119  def _get_max_traffic(self):
120  traffic = 10000 # start at 10kb
121  for sub in self.edges:
122  for topic in self.edges[sub]:
123  for pub in self.edges[sub][topic]:
124  traffic = max(traffic, self.edges[sub][topic][pub].traffic)
125  return traffic
126 
127  def _get_max_age(self):
128  age = 0.1 # start at 100ms
129  for sub in self.edges:
130  for topic in self.edges[sub]:
131  for pub in self.edges[sub][topic]:
132  age = max(age, self.edges[sub][topic][pub].stamp_age_mean.to_sec())
133  return age
134 
135  def _get_max_age_on_topic(self, sub, topic):
136  age = 0.0
137  for pub in self.edges[sub][topic]:
138  age = max(age, self.edges[sub][topic][pub].stamp_age_mean.to_sec())
139  return age
140 
141  def _calc_edge_color(self, sub, topic, pub=None):
142 
143  age = 0.0
144 
145  if pub is None:
146  age = self._get_max_age_on_topic(sub, topic)
147  elif sub in self.edges and topic in self.edges[sub] and pub in self.edges[sub][topic]:
148  age = self.edges[sub][topic][pub].stamp_age_mean.to_sec()
149 
150  if age == 0.0:
151  return [0, 0, 0]
152 
153  # calc coloring using the age
154  heat = max(age, 0) / self._get_max_age()
155 
156  # we assume that heat is normalized between 0.0 (green) and 1.0 (red)
157  # 0.0->green(0,255,0) to 0.5->yellow (255,255,0) to red 1.0(255,0,0)
158  if heat < 0:
159  red = 0
160  green = 0
161  elif heat <= 0.5:
162  red = int(heat * 255 * 2)
163  green = 255
164  elif heat > 0.5:
165  red = 255
166  green = 255 - int((heat - 0.5) * 255 * 2)
167  else:
168  red = 0
169  green = 0
170  return [red, green, 0]
171 
172  def _calc_edge_penwidth(self, sub, topic, pub=None):
173  if pub is None and sub in self.edges and topic in self.edges[sub]:
174  traffic = 0
175  for p in self.edges[sub][topic]:
176  if pub is None or p == pub:
177  traffic += self.edges[sub][topic][p].traffic
178 
179  # calc penwidth using the traffic in kb/s
180  return int(traffic / self._get_max_traffic() * 5)
181  else:
182  return 1
183 
184  def _calc_statistic_info(self, sub, topic, pub=None):
185  if pub is None and sub in self.edges and topic in self.edges[sub]:
186  conns = len(self.edges[sub][topic])
187  if conns == 1:
188  pub = next(iter(self.edges[sub][topic].keys()))
189  else:
190  penwidth = self._calc_edge_penwidth(sub, topic)
191  color = self._calc_edge_color(sub, topic)
192  label = "(" + unicode(conns) + " connections)"
193  return [label, penwidth, color]
194 
195  if sub in self.edges and topic in self.edges[sub] and pub in self.edges[sub][topic]:
196  penwidth = self._calc_edge_penwidth(sub, topic, pub)
197  color = self._calc_edge_color(sub, topic, pub)
198  period = self.edges[sub][topic][pub].period_mean.to_sec()
199  if period > 0.0:
200  freq = unicode(round(1.0 / period, 1))
201  else:
202  freq = "?"
203  age = self.edges[sub][topic][pub].stamp_age_mean.to_sec()
204  age_string = ""
205  if age > 0.0:
206  age_string = " // " + unicode(round(age, 2) * 1000) + " ms"
207  label = freq + " Hz" + age_string
208  return [label, penwidth, color]
209  else:
210  return [None, None, None]
211 
212  def _add_edge(self, edge, dotcode_factory, dotgraph, is_topic=False):
213  if is_topic:
214  sub = edge.end
215  topic = edge.label
216  pub = edge.start
217  [stat_label, penwidth, color] = self._calc_statistic_info(sub, topic, pub)
218  if stat_label is not None:
219  temp_label = edge.label + "\\n" + stat_label
220  dotcode_factory.add_edge_to_graph(
221  dotgraph,
222  _conv(edge.start),
223  _conv(edge.end),
224  label=temp_label,
225  url='topic:%s' % edge.label,
226  penwidth=penwidth,
227  color=color)
228  else:
229  dotcode_factory.add_edge_to_graph(
230  dotgraph,
231  _conv(edge.start),
232  _conv(edge.end),
233  label=edge.label,
234  url='topic:%s' % edge.label)
235  else:
236  sub = edge.end.strip()
237  topic = edge.start.strip()
238  [stat_label, penwidth, color] = self._calc_statistic_info(sub, topic)
239  if stat_label is not None:
240  temp_label = edge.label + "\\n" + stat_label
241  dotcode_factory.add_edge_to_graph(
242  dotgraph,
243  _conv(edge.start),
244  _conv(edge.end),
245  label=temp_label,
246  penwidth=penwidth,
247  color=color)
248  else:
249  dotcode_factory.add_edge_to_graph(
250  dotgraph, _conv(edge.start), _conv(edge.end), label=edge.label)
251 
252  def _add_node(self, node, rosgraphinst, dotcode_factory, dotgraph, unreachable):
253  if node in rosgraphinst.bad_nodes:
254  if unreachable:
255  return ''
256  bn = rosgraphinst.bad_nodes[node]
257  if bn.type == rosgraph.impl.graph.BadNode.DEAD:
258  dotcode_factory.add_node_to_graph(
259  dotgraph,
260  nodename=_conv(node),
261  nodelabel=node,
262  shape="ellipse",
263  url=node + " (DEAD)",
264  color="red")
265  elif bn.type == rosgraph.impl.graph.BadNode.WONKY:
266  dotcode_factory.add_node_to_graph(
267  dotgraph,
268  nodename=_conv(node),
269  nodelabel=node,
270  shape="ellipse",
271  url=node + " (WONKY)",
272  color="orange")
273  else:
274  dotcode_factory.add_node_to_graph(
275  dotgraph,
276  nodename=_conv(node),
277  nodelabel=node,
278  shape="ellipse",
279  url=node + " (UNKNOWN)",
280  color="red")
281  else:
282  dotcode_factory.add_node_to_graph(
283  dotgraph,
284  nodename=_conv(node),
285  nodelabel=node,
286  shape='ellipse',
287  url=node)
288 
289  def _add_topic_node(self, node, dotcode_factory, dotgraph, quiet):
290  label = rosgraph.impl.graph.node_topic(node)
291  dotcode_factory.add_node_to_graph(
292  dotgraph,
293  nodename=_conv(node),
294  nodelabel=label,
295  shape='box',
296  url="topic:%s" % label)
297 
298  def _add_topic_node_group(self, node, dotcode_factory, dotgraph, quiet):
299  label = rosgraph.impl.graph.node_topic(node)
300  dotcode_factory.add_node_to_graph(
301  dotgraph,
302  nodename=_conv(node),
303  nodelabel=label,
304  shape='box3d',
305  url='topic:%s' % label)
306 
307  def _quiet_filter(self, name):
308  # ignore viewers
309  for n in QUIET_NAMES:
310  if n in name:
311  return False
312  return True
313 
314  def quiet_filter_topic_edge(self, edge):
315  for quiet_label in ['/time', '/clock', '/rosout', '/statistics']:
316  if quiet_label == edge.label:
317  return False
318  return self._quiet_filter(edge.start) and self._quiet_filter(edge.end)
319 
320  def generate_namespaces(self, graph, graph_mode, quiet=False):
321  """
322  Determine the namespaces of the nodes being displayed
323  """
324  namespaces = []
325  if graph_mode == NODE_NODE_GRAPH:
326  nodes = graph.nn_nodes
327  if quiet:
328  nodes = [n for n in nodes if n not in QUIET_NAMES]
329  namespaces = list(set([roslib.names.namespace(n) for n in nodes]))
330 
331  elif graph_mode == NODE_TOPIC_GRAPH or \
332  graph_mode == NODE_TOPIC_ALL_GRAPH:
333  nn_nodes = graph.nn_nodes
334  nt_nodes = graph.nt_nodes
335  if quiet:
336  nn_nodes = [n for n in nn_nodes if n not in QUIET_NAMES]
337  nt_nodes = [n for n in nt_nodes if n not in QUIET_NAMES]
338  if nn_nodes or nt_nodes:
339  namespaces = [roslib.names.namespace(n) for n in nn_nodes]
340  # an annoyance with the rosgraph library is that it
341  # prepends a space to topic names as they have to have
342  # different graph node namees from nodes. we have to strip here
343  namespaces.extend([roslib.names.namespace(n[1:]) for n in nt_nodes])
344 
345  return list(set(namespaces))
346 
347  def _filter_orphaned_edges(self, edges, nodes):
348  nodenames = [unicode(n).strip() for n in nodes]
349  # currently using and rule as the or rule generates orphan nodes with the current logic
350  return [e for e in edges if e.start.strip() in nodenames and e.end.strip() in nodenames]
351 
352  def _filter_orphaned_topics(self, nt_nodes, edges):
353  '''remove topic graphnodes without connected ROS nodes'''
354  removal_nodes = []
355  for n in nt_nodes:
356  keep = False
357  for e in edges:
358  if e.start.strip() == unicode(n).strip() or e.end.strip() == unicode(n).strip():
359  keep = True
360  break
361  if not keep:
362  removal_nodes.append(n)
363  for n in removal_nodes:
364  nt_nodes.remove(n)
365  return nt_nodes
366 
367  def _split_filter_string(self, ns_filter):
368  '''splits a string after each comma, and treats tokens with leading dash as exclusions.
369  Adds .* as inclusion if no other inclusion option was given'''
370  includes = []
371  excludes = []
372  for name in ns_filter.split(','):
373  if name.strip().startswith('-'):
374  excludes.append(name.strip()[1:])
375  else:
376  includes.append(name.strip())
377  if includes == [] or includes == ['/'] or includes == ['']:
378  includes = ['.*']
379  return includes, excludes
380 
381  def _get_node_edge_map(self, edges):
382  '''
383  returns a dict mapping node name to edge objects partitioned in incoming and outgoing edges
384  '''
385  node_connections = {}
386  for edge in edges:
387  if edge.start not in node_connections:
388  node_connections[edge.start] = NodeConnections()
389  if edge.end not in node_connections:
390  node_connections[edge.end] = NodeConnections()
391  node_connections[edge.start].outgoing.append(edge)
392  node_connections[edge.end].incoming.append(edge)
393  return node_connections
394 
396  self,
397  nodes_in,
398  edges_in,
399  node_connections,
400  hide_single_connection_topics,
401  hide_dead_end_topics):
402  '''
403  removes certain ending topic nodes and their edges from list of nodes and edges
404 
405  @param hide_single_connection_topics:
406  if true removes topics that are only published/subscribed by one node
407  @param hide_dead_end_topics: if true removes topics having only publishers
408  '''
409  if not hide_dead_end_topics and not hide_single_connection_topics:
410  return nodes_in, edges_in
411  # do not manipulate incoming structures
412  nodes = copy.copy(nodes_in)
413  edges = copy.copy(edges_in)
414  removal_nodes = []
415  for n in nodes:
416  if n in node_connections:
417  node_edges = []
418  has_out_edges = False
419  node_edges.extend(node_connections[n].outgoing)
420  if len(node_connections[n].outgoing) > 0:
421  has_out_edges = True
422  node_edges.extend(node_connections[n].incoming)
423  if (hide_single_connection_topics and len(node_edges) < 2) or \
424  (hide_dead_end_topics and not has_out_edges):
425  removal_nodes.append(n)
426  for e in node_edges:
427  if e in edges:
428  edges.remove(e)
429  for n in removal_nodes:
430  nodes.remove(n)
431  return nodes, edges
432 
433  def _accumulate_action_topics(self, nodes_in, edges_in, node_connections):
434  '''takes topic nodes, edges and node connections.
435  Returns topic nodes where action topics have been removed,
436  edges where the edges to action topics have been removed, and
437  a map with the connection to each virtual action topic node'''
438  removal_nodes = []
439  action_nodes = {}
440  # do not manipulate incoming structures
441  nodes = copy.copy(nodes_in)
442  edges = copy.copy(edges_in)
443  for n in nodes:
444  if unicode(n).endswith('/feedback'):
445  prefix = unicode(n)[:-len('/feedback')].strip()
446  action_topic_nodes = []
447  action_topic_edges_out = list()
448  action_topic_edges_in = list()
449  for suffix in ['/status', '/result', '/goal', '/cancel', '/feedback']:
450  for n2 in nodes:
451  if unicode(n2).strip() == prefix + suffix:
452  action_topic_nodes.append(n2)
453  if n2 in node_connections:
454  action_topic_edges_out.extend(node_connections[n2].outgoing)
455  action_topic_edges_in.extend(node_connections[n2].incoming)
456  if len(action_topic_nodes) == 5:
457  # found action
458  removal_nodes.extend(action_topic_nodes)
459  for e in action_topic_edges_out:
460  if e in edges:
461  edges.remove(e)
462  for e in action_topic_edges_in:
463  if e in edges:
464  edges.remove(e)
465  action_nodes[prefix] = {'topics': action_topic_nodes,
466  'outgoing': action_topic_edges_out,
467  'incoming': action_topic_edges_in}
468  for n in removal_nodes:
469  nodes.remove(n)
470  return nodes, edges, action_nodes
471 
473  self,
474  cluster_namespaces_level,
475  node_list,
476  dotcode_factory,
477  dotgraph,
478  rank,
479  orientation,
480  simplify):
481  namespace_clusters = {}
482  if cluster_namespaces_level > 0:
483  for node in node_list:
484  if unicode(node.strip()).count('/') > 2:
485  for i in range(
486  2, min(2 + cluster_namespaces_level, len(node.strip().split('/')))):
487  namespace = '/'.join(node.strip().split('/')[:i])
488  parent_namespace = '/'.join(node.strip().split('/')[:i - 1])
489  if namespace not in namespace_clusters:
490  if parent_namespace == '':
491  namespace_clusters[namespace] = \
492  dotcode_factory.add_subgraph_to_graph(
493  dotgraph,
494  namespace,
495  rank=rank,
496  rankdir=orientation,
497  simplify=simplify)
498  elif parent_namespace in namespace_clusters:
499  namespace_clusters[namespace] = \
500  dotcode_factory.add_subgraph_to_graph(
501  namespace_clusters[parent_namespace],
502  namespace,
503  rank=rank,
504  rankdir=orientation,
505  simplify=simplify)
506  elif unicode(node.strip()).count('/') == 2:
507  namespace = '/'.join(node.strip().split('/')[0:2])
508  if namespace not in namespace_clusters:
509  namespace_clusters[namespace] = dotcode_factory.add_subgraph_to_graph(
510  dotgraph,
511  namespace,
512  rank=rank,
513  rankdir=orientation,
514  simplify=simplify)
515  return namespace_clusters
516 
517  def _group_tf_nodes(self, nodes_in, edges_in, node_connections):
518  '''takes topic nodes, edges and node connections.
519  Returns topic nodes where tf topics have been removed,
520  edges where the edges to tf topics have been removed, and
521  a map with all the connections to the resulting tf group node'''
522  removal_nodes = []
523  tf_topic_edges_in = []
524  tf_topic_edges_out = []
525  # do not manipulate incoming structures
526  nodes = copy.copy(nodes_in)
527  edges = copy.copy(edges_in)
528  for n in nodes:
529  if unicode(n).strip() in ['/tf', '/tf_static']:
530  tf_topic_edges_in.extend(
531  [x for x in node_connections[n].incoming if x in edges and x.end in nodes])
532  tf_topic_edges_out.extend(
533  [x for x in node_connections[n].outgoing if x in edges and x.start in nodes])
534  removal_nodes.append(n)
535 
536  for e in tf_topic_edges_out:
537  if e in edges:
538  edges.remove(e)
539  for e in tf_topic_edges_in:
540  if e in edges:
541  edges.remove(e)
542  for n in removal_nodes:
543  if n in nodes:
544  nodes.remove(n)
545  if not tf_topic_edges_in and not tf_topic_edges_out:
546  return nodes, edges, None
547 
548  return nodes, edges, {'outgoing': tf_topic_edges_out, 'incoming': tf_topic_edges_in}
549 
550  def _accumulate_image_topics(self, nodes_in, edges_in, node_connections):
551  '''takes topic nodes, edges and node connections.
552  Returns topic nodes where image topics have been removed,
553  edges where the edges to image topics have been removed, and
554  a map with the connection to each virtual image topic node'''
555  removal_nodes = []
556  image_nodes = {}
557  # do not manipulate incoming structures
558  nodes = copy.copy(nodes_in)
559  edges = copy.copy(edges_in)
560  for n in nodes:
561  if unicode(n).endswith('/compressed'):
562  prefix = unicode(n)[:-len('/compressed')].strip()
563  image_topic_nodes = []
564  image_topic_edges_out = list()
565  image_topic_edges_in = list()
566  for suffix in ['/compressed', '/compressedDepth', '/theora', '']:
567  for n2 in nodes:
568  if unicode(n2).strip() == prefix + suffix:
569  image_topic_nodes.append(n2)
570  if n2 in node_connections:
571  image_topic_edges_out.extend(node_connections[n2].outgoing)
572  image_topic_edges_in.extend(node_connections[n2].incoming)
573  if len(image_topic_nodes) >= 3:
574  # found action
575  removal_nodes.extend(image_topic_nodes)
576  for e in image_topic_edges_out:
577  if e in edges:
578  edges.remove(e)
579  for e in image_topic_edges_in:
580  if e in edges:
581  edges.remove(e)
582  image_nodes[prefix] = {'topics': image_topic_nodes,
583  'outgoing': image_topic_edges_out,
584  'incoming': image_topic_edges_in}
585  for n in removal_nodes:
586  nodes.remove(n)
587  return nodes, edges, image_nodes
588 
590  self,
591  nodes_in,
592  edges_in,
593  node_connections,
594  hide_tf_nodes,
595  hide_dynamic_reconfigure):
596  if not hide_tf_nodes and not hide_dynamic_reconfigure:
597  return nodes_in, edges_in
598  # do not manipulate incoming structures
599  nodes = copy.copy(nodes_in)
600  edges = copy.copy(edges_in)
601  removal_nodes = []
602  for n in nodes:
603  if hide_dynamic_reconfigure and unicode(n).endswith('/parameter_updates'):
604  prefix = unicode(n)[:-len('/parameter_updates')].strip()
605  dynamic_reconfigure_topic_nodes = []
606  for suffix in ['/parameter_updates', '/parameter_descriptions']:
607  for n2 in nodes:
608  if unicode(n2).strip() == prefix + suffix:
609  dynamic_reconfigure_topic_nodes.append(n2)
610  if len(dynamic_reconfigure_topic_nodes) == 2:
611  for n1 in dynamic_reconfigure_topic_nodes:
612  if n1 in node_connections:
613  for e in node_connections[n1].outgoing + node_connections[n1].incoming:
614  if e in edges:
615  edges.remove(e)
616  removal_nodes.append(n1)
617  continue
618  if hide_tf_nodes and unicode(n).strip() in ['/tf', '/tf_static']:
619  if n in node_connections:
620  for e in node_connections[n].outgoing + node_connections[n].incoming:
621  if e in edges:
622  edges.remove(e)
623  removal_nodes.append(n)
624  continue
625  for n in removal_nodes:
626  if n in nodes:
627  nodes.remove(n)
628  return nodes, edges
629 
630  def generate_dotgraph(
631  self,
632  rosgraphinst,
633  ns_filter,
634  topic_filter,
635  graph_mode,
636  dotcode_factory,
637  hide_single_connection_topics=False,
638  hide_dead_end_topics=False,
639  cluster_namespaces_level=0,
640  accumulate_actions=True,
641  orientation='LR',
642  rank='same', # None, same, min, max, source, sink
643  ranksep=0.2, # vertical distance between layers
644  rankdir='TB', # direction of layout (TB top > bottom, LR left > right)
645  simplify=True, # remove double edges
646  quiet=False,
647  unreachable=False,
648  group_tf_nodes=False,
649  hide_tf_nodes=False,
650  group_image_nodes=False,
651  hide_dynamic_reconfigure=False):
652  """
653  See generate_dotcode
654  """
655  includes, excludes = self._split_filter_string(ns_filter)
656  topic_includes, topic_excludes = self._split_filter_string(topic_filter)
657 
658  nn_nodes = []
659  nt_nodes = []
660  # create the node definitions
661  if graph_mode == NODE_NODE_GRAPH:
662  nn_nodes = rosgraphinst.nn_nodes
663  nn_nodes = \
664  [n for n in nn_nodes if matches_any(n, includes) and not matches_any(n, excludes)]
665  edges = rosgraphinst.nn_edges
666  edges = \
667  [e for e in edges if matches_any(
668  e.label, topic_includes) and not matches_any(e.label, topic_excludes)]
669 
670  elif graph_mode == NODE_TOPIC_GRAPH or \
671  graph_mode == NODE_TOPIC_ALL_GRAPH:
672  nn_nodes = rosgraphinst.nn_nodes
673  nt_nodes = rosgraphinst.nt_nodes
674  nn_nodes = \
675  [n for n in nn_nodes if matches_any(n, includes) and not matches_any(n, excludes)]
676  nt_nodes = \
677  [n for n in nt_nodes if matches_any(n, topic_includes) and
678  not matches_any(n, topic_excludes)]
679 
680  # create the edge definitions, unwrap EdgeList objects into python lists
681  if graph_mode == NODE_TOPIC_GRAPH:
682  edges = [e for e in rosgraphinst.nt_edges]
683  else:
684  edges = [e for e in rosgraphinst.nt_all_edges]
685 
686  if quiet:
687  nn_nodes = list(filter(self._quiet_filter, nn_nodes))
688  nt_nodes = list(filter(self._quiet_filter, nt_nodes))
689  if graph_mode == NODE_NODE_GRAPH:
690  edges = list(filter(self.quiet_filter_topic_edge, edges))
691 
692  # for accumulating actions topics
693  action_nodes = {}
694  # for accumulating image topics
695  image_nodes = {}
696  # for accumulating tf node connections
697  tf_connections = None
698 
699  if graph_mode != NODE_NODE_GRAPH and (hide_single_connection_topics or
700  hide_dead_end_topics or accumulate_actions or
701  group_tf_nodes or hide_tf_nodes or
702  group_image_nodes or hide_dynamic_reconfigure):
703  # maps outgoing and incoming edges to nodes
704  node_connections = self._get_node_edge_map(edges)
705 
706  nt_nodes, edges = self._filter_leaf_topics(
707  nt_nodes,
708  edges,
709  node_connections,
710  hide_single_connection_topics,
711  hide_dead_end_topics)
712 
713  nt_nodes, edges = self._filter_hidden_topics(
714  nt_nodes,
715  edges,
716  node_connections,
717  hide_tf_nodes,
718  hide_dynamic_reconfigure)
719 
720  if accumulate_actions:
721  nt_nodes, edges, action_nodes = self._accumulate_action_topics(
722  nt_nodes, edges, node_connections)
723  if group_image_nodes:
724  nt_nodes, edges, image_nodes = self._accumulate_image_topics(
725  nt_nodes, edges, node_connections)
726  if group_tf_nodes and not hide_tf_nodes:
727  nt_nodes, edges, tf_connections = self._group_tf_nodes(
728  nt_nodes, edges, node_connections)
729 
730  edges = self._filter_orphaned_edges(edges, nn_nodes + nt_nodes)
731  nt_nodes = self._filter_orphaned_topics(nt_nodes, edges)
732 
733  # create the graph
734  # result = "digraph G {\n
735  # rankdir=%(orientation)s;\n%(nodes_str)s\n%(edges_str)s}\n" % vars()
736  dotgraph = dotcode_factory.get_graph(
737  rank=rank,
738  ranksep=ranksep,
739  simplify=simplify,
740  rankdir=orientation)
741 
742  ACTION_TOPICS_SUFFIX = '/action_topics'
743  IMAGE_TOPICS_SUFFIX = '/image_topics'
744 
745  node_list = (nt_nodes or []) + \
746  [action_prefix + ACTION_TOPICS_SUFFIX for (action_prefix, _) in action_nodes.items()] + \
747  [image_prefix + IMAGE_TOPICS_SUFFIX for (image_prefix, _) in image_nodes.items()] + \
748  nn_nodes if nn_nodes is not None else []
749 
750  namespace_clusters = self._populate_node_graph(
751  cluster_namespaces_level,
752  node_list,
753  dotcode_factory,
754  dotgraph,
755  rank,
756  orientation,
757  simplify)
758 
759  for n in nt_nodes or []:
760  # cluster topics with same namespace
761  if cluster_namespaces_level > 0 and \
762  unicode(n).strip().count('/') > 1 and \
763  len(n.strip().split('/')[1]) > 0:
764  if n.count('/') <= cluster_namespaces_level:
765  namespace = unicode('/'.join(n.strip().split('/')[:-1]))
766  else:
767  namespace = '/'.join(n.strip().split('/')[:cluster_namespaces_level + 1])
768  self._add_topic_node(
769  n, dotcode_factory=dotcode_factory, dotgraph=namespace_clusters[namespace], quiet=quiet)
770  else:
771  self._add_topic_node(
772  n, dotcode_factory=dotcode_factory, dotgraph=dotgraph, quiet=quiet)
773 
774  for n in [action_prefix + ACTION_TOPICS_SUFFIX for (action_prefix, _) in action_nodes.items()] + \
775  [image_prefix + IMAGE_TOPICS_SUFFIX for (image_prefix, _) in image_nodes.items()]:
776  # cluster topics with same namespace
777  if cluster_namespaces_level > 0 and \
778  unicode(n).strip().count('/') > 1 and \
779  len(unicode(n).strip().split('/')[1]) > 0:
780  if n.strip().count('/') <= cluster_namespaces_level:
781  namespace = unicode('/'.join(n.strip().split('/')[:-1]))
782  else:
783  namespace = '/'.join(n.strip().split('/')[:cluster_namespaces_level + 1])
785  'n' + n, dotcode_factory=dotcode_factory, dotgraph=namespace_clusters[namespace], quiet=quiet)
786  else:
788  'n' + n, dotcode_factory=dotcode_factory, dotgraph=dotgraph, quiet=quiet)
789 
790  if tf_connections != None:
791  # render tf nodes as a single node
793  'n/tf', dotcode_factory=dotcode_factory, dotgraph=dotgraph, quiet=quiet)
794  for out_edge in tf_connections.get('outgoing', []):
795  dotcode_factory.add_edge_to_graph(dotgraph, _conv('n/tf'), _conv(out_edge.end))
796  for in_edge in tf_connections.get('incoming', []):
797  dotcode_factory.add_edge_to_graph(dotgraph, _conv(in_edge.start), _conv('n/tf'))
798 
799  # for ROS node, if we have created a namespace clusters for
800  # one of its peer topics, drop it into that cluster
801  for n in nn_nodes or []:
802  if cluster_namespaces_level > 0 and \
803  n.strip().count('/') > 1 and \
804  len(n.strip().split('/')[1]) > 0:
805  if n.count('/') <= cluster_namespaces_level:
806  namespace = unicode('/'.join(n.strip().split('/')[:-1]))
807  else:
808  namespace = '/'.join(n.strip().split('/')[:cluster_namespaces_level + 1])
809  self._add_node(
810  n,
811  rosgraphinst=rosgraphinst,
812  dotcode_factory=dotcode_factory,
813  dotgraph=namespace_clusters[namespace],
814  unreachable=unreachable)
815  else:
816  self._add_node(
817  n,
818  rosgraphinst=rosgraphinst,
819  dotcode_factory=dotcode_factory,
820  dotgraph=dotgraph,
821  unreachable=unreachable)
822 
823  for e in edges:
824  self._add_edge(
825  e, dotcode_factory, dotgraph=dotgraph, is_topic=(graph_mode == NODE_NODE_GRAPH))
826 
827  for (action_prefix, node_connections) in action_nodes.items():
828  for out_edge in node_connections.get('outgoing', []):
829  dotcode_factory.add_edge_to_graph(
830  dotgraph,
831  _conv('n' + action_prefix + ACTION_TOPICS_SUFFIX),
832  _conv(out_edge.end))
833  for in_edge in node_connections.get('incoming', []):
834  dotcode_factory.add_edge_to_graph(
835  dotgraph,
836  _conv(in_edge.start),
837  _conv('n' + action_prefix + ACTION_TOPICS_SUFFIX))
838  for (image_prefix, node_connections) in image_nodes.items():
839  for out_edge in node_connections.get('outgoing', []):
840  dotcode_factory.add_edge_to_graph(
841  dotgraph,
842  _conv('n' + image_prefix + IMAGE_TOPICS_SUFFIX),
843  _conv(out_edge.end))
844  for in_edge in node_connections.get('incoming', []):
845  dotcode_factory.add_edge_to_graph(
846  dotgraph,
847  _conv(in_edge.start),
848  _conv('n' + image_prefix + IMAGE_TOPICS_SUFFIX))
849 
850  return dotgraph
851 
852  def generate_dotcode(
853  self,
854  rosgraphinst,
855  ns_filter,
856  topic_filter,
857  graph_mode,
858  dotcode_factory,
859  hide_single_connection_topics=False,
860  hide_dead_end_topics=False,
861  cluster_namespaces_level=0,
862  accumulate_actions=True,
863  orientation='LR',
864  rank='same', # None, same, min, max, source, sink
865  ranksep=0.2, # vertical distance between layers
866  rankdir='TB', # direction of layout (TB top > bottom, LR left > right)
867  simplify=True, # remove double edges
868  quiet=False,
869  unreachable=False,
870  hide_tf_nodes=False,
871  group_tf_nodes=False,
872  group_image_nodes=False,
873  hide_dynamic_reconfigure=False):
874  """
875  @param rosgraphinst: RosGraph instance
876  @param ns_filter: nodename filter
877  @type ns_filter: string
878  @param topic_filter: topicname filter
879  @type ns_filter: string
880  @param graph_mode str: NODE_NODE_GRAPH | NODE_TOPIC_GRAPH | NODE_TOPIC_ALL_GRAPH
881  @type graph_mode: str
882  @param orientation: rankdir value (see ORIENTATIONS dict)
883  @type dotcode_factory: object
884  @param dotcode_factory: abstract factory manipulating dot language objects
885  @param hide_single_connection_topics: if true remove topics with just one connection
886  @param hide_dead_end_topics: if true remove topics with publishers only
887  @param cluster_namespaces_level: if > 0 places box around members of same namespace
888  (TODO: multiple namespace layers)
889  @param accumulate_actions: if true each 5 action topic graph nodes are shown as single graph node
890  @return: dotcode generated from graph singleton
891  @rtype: str
892  """
893  dotgraph = self.generate_dotgraph(
894  rosgraphinst=rosgraphinst,
895  ns_filter=ns_filter,
896  topic_filter=topic_filter,
897  graph_mode=graph_mode,
898  dotcode_factory=dotcode_factory,
899  hide_single_connection_topics=hide_single_connection_topics,
900  hide_dead_end_topics=hide_dead_end_topics,
901  cluster_namespaces_level=cluster_namespaces_level,
902  accumulate_actions=accumulate_actions,
903  orientation=orientation,
904  rank=rank,
905  ranksep=ranksep,
906  rankdir=rankdir,
907  simplify=simplify,
908  quiet=quiet,
909  unreachable=unreachable,
910  hide_tf_nodes=hide_tf_nodes,
911  group_tf_nodes=group_tf_nodes,
912  group_image_nodes=group_image_nodes,
913  hide_dynamic_reconfigure=hide_dynamic_reconfigure)
914  dotcode = dotcode_factory.create_dot(dotgraph)
915  return dotcode
def _filter_hidden_topics(self, nodes_in, edges_in, node_connections, hide_tf_nodes, hide_dynamic_reconfigure)
Definition: dotcode.py:595
def _accumulate_action_topics(self, nodes_in, edges_in, node_connections)
Definition: dotcode.py:433
def _group_tf_nodes(self, nodes_in, edges_in, node_connections)
Definition: dotcode.py:517
def _filter_leaf_topics(self, nodes_in, edges_in, node_connections, hide_single_connection_topics, hide_dead_end_topics)
Definition: dotcode.py:401
def generate_dotgraph(self, rosgraphinst, ns_filter, topic_filter, graph_mode, dotcode_factory, hide_single_connection_topics=False, hide_dead_end_topics=False, cluster_namespaces_level=0, accumulate_actions=True, orientation='LR', rank='same', ranksep=0.2, rankdir='TB', simplify=True, quiet=False, unreachable=False, group_tf_nodes=False, hide_tf_nodes=False, group_image_nodes=False, hide_dynamic_reconfigure=False)
Definition: dotcode.py:651
def _calc_edge_penwidth(self, sub, topic, pub=None)
Definition: dotcode.py:172
def generate_dotcode(self, rosgraphinst, ns_filter, topic_filter, graph_mode, dotcode_factory, hide_single_connection_topics=False, hide_dead_end_topics=False, cluster_namespaces_level=0, accumulate_actions=True, orientation='LR', rank='same', ranksep=0.2, rankdir='TB', simplify=True, quiet=False, unreachable=False, hide_tf_nodes=False, group_tf_nodes=False, group_image_nodes=False, hide_dynamic_reconfigure=False)
Definition: dotcode.py:873
def _get_max_age_on_topic(self, sub, topic)
Definition: dotcode.py:135
def _filter_orphaned_edges(self, edges, nodes)
Definition: dotcode.py:347
def _split_filter_string(self, ns_filter)
Definition: dotcode.py:367
def matches_any(name, patternlist)
Definition: dotcode.py:72
def _add_node(self, node, rosgraphinst, dotcode_factory, dotgraph, unreachable)
Definition: dotcode.py:252
def _add_topic_node_group(self, node, dotcode_factory, dotgraph, quiet)
Definition: dotcode.py:298
def __init__(self, incoming=None, outgoing=None)
Definition: dotcode.py:86
def _filter_orphaned_topics(self, nt_nodes, edges)
Definition: dotcode.py:352
def _add_edge(self, edge, dotcode_factory, dotgraph, is_topic=False)
Definition: dotcode.py:212
def _calc_statistic_info(self, sub, topic, pub=None)
Definition: dotcode.py:184
def _accumulate_image_topics(self, nodes_in, edges_in, node_connections)
Definition: dotcode.py:550
def generate_namespaces(self, graph, graph_mode, quiet=False)
Definition: dotcode.py:320
def _conv(n)
Definition: dotcode.py:64
def _add_topic_node(self, node, dotcode_factory, dotgraph, quiet)
Definition: dotcode.py:289
def _populate_node_graph(self, cluster_namespaces_level, node_list, dotcode_factory, dotgraph, rank, orientation, simplify)
Definition: dotcode.py:480
def _calc_edge_color(self, sub, topic, pub=None)
Definition: dotcode.py:141


rqt_graph
Author(s): Dirk Thomas
autogenerated on Thu Jun 6 2019 19:16:52