behaviour_tree.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2011, 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 from __future__ import division
34 
35 import argparse
36 import fnmatch
37 import functools
38 import py_trees
39 import py_trees_msgs.msg as py_trees_msgs
40 import os
41 import re
42 import rosbag
43 import rospkg
44 import rospy
45 import sys
46 import termcolor
47 import uuid_msgs.msg as uuid_msgs
48 
49 from . import visibility
50 
51 from .dotcode_behaviour import RosBehaviourTreeDotcodeGenerator
52 from .dynamic_timeline import DynamicTimeline
53 from .dynamic_timeline_listener import DynamicTimelineListener
54 from .timeline_listener import TimelineListener
55 from qt_dotgraph.dot_to_qt import DotToQtGenerator
56 from qt_dotgraph.pydotfactory import PydotFactory
57 from qt_dotgraph.pygraphvizfactory import PygraphvizFactory
58 from rqt_bag.bag_timeline import BagTimeline
59 # from rqt_bag.bag_widget import BagGraphicsView
60 from rqt_graph.interactive_graphics_view import InteractiveGraphicsView
61 
62 from python_qt_binding import loadUi
63 from python_qt_binding.QtCore import QFile, QIODevice, QObject, Qt, Signal, QEvent, Slot
64 from python_qt_binding.QtGui import QIcon, QImage, QPainter, QKeySequence
65 from python_qt_binding.QtSvg import QSvgGenerator
66 try: # indigo
67  from python_qt_binding.QtGui import QFileDialog, QGraphicsView, QGraphicsScene, QWidget, QShortcut
68 except ImportError: # kinetic+ (pyqt5)
69  from python_qt_binding.QtWidgets import QFileDialog, QGraphicsView, QGraphicsScene, QWidget, QShortcut
70 
71 from . import qt_dotgraph
72 
73 
74 class RosBehaviourTree(QObject):
75 
76  _deferred_fit_in_view = Signal()
77  _refresh_view = Signal()
78  _refresh_combo = Signal()
79  _message_changed = Signal()
80  _message_cleared = Signal()
81  _expected_type = py_trees_msgs.BehaviourTree()._type
82  _empty_topic = "No valid topics available"
83  _unselected_topic = "Not subscribing"
84  no_roscore_switch = "--no-roscore"
85 
86  class ComboBoxEventFilter(QObject):
87  """Event filter for the combo box. Will filter left mouse button presses,
88  calling a signal when they happen
89 
90  """
91  def __init__(self, signal):
92  """
93 
94  :param Signal signal: signal that is emitted when a left mouse button press happens
95  """
97  self.signal = signal
98 
99  def eventFilter(self, obj, event):
100  if event.type() == QEvent.MouseButtonPress and event.button() == Qt.LeftButton:
101  self.signal.emit()
102  return False
103 
104  def __init__(self, context):
105  super(RosBehaviourTree, self).__init__(context)
106  self.setObjectName('RosBehaviourTree')
107 
108  parser = argparse.ArgumentParser()
109  RosBehaviourTree.add_arguments(parser, False)
110  # if the context doesn't have an argv attribute then assume we're running with --no-roscore
111  if not hasattr(context, 'argv'):
112  args = sys.argv[1:]
113  # Can run the viewer with or without live updating. Running without is
114  # intended for viewing of bags only
115  self.live_update = False
116  else:
117  args = context.argv()
118  self.live_update = True
119 
120  parsed_args = parser.parse_args(args)
121 
122  self.context = context
123  self.initialized = False
124  self._current_dotcode = None # dotcode for the tree that is currently displayed
125  self._viewing_bag = False # true if a bag file is loaded
126  # True if next or previous buttons are pressed. Reset if the tree being
127  # viewed is the last one in the list.
128  self._browsing_timeline = False
129 
130  self._widget = QWidget()
131 
132  # factory builds generic dotcode items
133  self.dotcode_factory = PygraphvizFactory() # PydotFactory()
134  # self.dotcode_factory = PygraphvizFactory()
135  # generator builds rosgraph
136  self.dotcode_generator = RosBehaviourTreeDotcodeGenerator()
137  self.current_topic = None
138  self.behaviour_sub = None
139  self._tip_message = None # message of the tip of the tree
140  self._saved_settings_topic = None # topic subscribed to by previous instance
141  self.visibility_level = py_trees.common.VisibilityLevel.DETAIL
142 
143  # dot_to_qt transforms into Qt elements using dot layout
145 
146  rp = rospkg.RosPack()
147  ui_file = os.path.join(rp.get_path('rqt_py_trees'), 'resource', 'RosBehaviourTree.ui')
148  loadUi(ui_file, self._widget, {'InteractiveGraphicsView': InteractiveGraphicsView})
149  self._widget.setObjectName('RosBehaviourTreeUi')
150  if hasattr(context, 'serial_number') and context.serial_number() > 1:
151  self._widget.setWindowTitle(self._widget.windowTitle() + (' (%d)' % context.serial_number()))
152 
153  self._scene = QGraphicsScene()
154  self._scene.setBackgroundBrush(Qt.white)
155  self._widget.graphics_view.setScene(self._scene)
156 
157  self._widget.highlight_connections_check_box.toggled.connect(self._redraw_graph_view)
158  self._widget.auto_fit_graph_check_box.toggled.connect(self._redraw_graph_view)
159  self._widget.fit_in_view_push_button.setIcon(QIcon.fromTheme('zoom-original'))
160  self._widget.fit_in_view_push_button.pressed.connect(self._fit_in_view)
161 
162  self._widget.load_bag_push_button.setIcon(QIcon.fromTheme('document-open'))
163  self._widget.load_bag_push_button.pressed.connect(self._load_bag)
164  self._widget.load_dot_push_button.setIcon(QIcon.fromTheme('document-open'))
165  self._widget.load_dot_push_button.pressed.connect(self._load_dot)
166  self._widget.save_dot_push_button.setIcon(QIcon.fromTheme('document-save-as'))
167  self._widget.save_dot_push_button.pressed.connect(self._save_dot)
168  self._widget.save_as_svg_push_button.setIcon(QIcon.fromTheme('document-save-as'))
169  self._widget.save_as_svg_push_button.pressed.connect(self._save_svg)
170  self._widget.save_as_image_push_button.setIcon(QIcon.fromTheme('image'))
171  self._widget.save_as_image_push_button.pressed.connect(self._save_image)
172 
173  for text in visibility.combo_to_py_trees:
174  self._widget.visibility_level_combo_box.addItem(text)
175  self._widget.visibility_level_combo_box.setCurrentIndex(self.visibility_level)
176  self._widget.visibility_level_combo_box.currentIndexChanged['QString'].connect(self._update_visibility_level)
177 
178  # set up the function that is called whenever the box is resized -
179  # ensures that the timeline is correctly drawn.
180  self._widget.resizeEvent = self._resize_event
181 
182  self._timeline = None
183  self._timeline_listener = None
184 
185  # Connect the message changed function of this object to a corresponding
186  # signal. This signal will be activated whenever the message being
187  # viewed changes.
188  self._message_changed.connect(self.message_changed)
189  self._message_cleared.connect(self.message_cleared)
190 
191  # Set up combo box for topic selection
192  # when the refresh_combo signal happens, update the combo topics available
193  self._refresh_combo.connect(self._update_combo_topics)
194  # filter events to catch the event which opens the combo box
196  self._widget.topic_combo_box.installEventFilter(self._combo_event_filter)
197  self._widget.topic_combo_box.activated.connect(self._choose_topic)
198  self._update_combo_topics()
199 
200  # Set up navigation buttons
201  self._widget.previous_tool_button.pressed.connect(self._previous)
202  self._widget.previous_tool_button.setIcon(QIcon.fromTheme('go-previous'))
203  self._widget.next_tool_button.pressed.connect(self._next)
204  self._widget.next_tool_button.setIcon(QIcon.fromTheme('go-next'))
205  self._widget.first_tool_button.pressed.connect(self._first)
206  self._widget.first_tool_button.setIcon(QIcon.fromTheme('go-first'))
207  self._widget.last_tool_button.pressed.connect(self._last)
208  self._widget.last_tool_button.setIcon(QIcon.fromTheme('go-last'))
209 
210  # play, pause and stop buttons
211  self._widget.play_tool_button.pressed.connect(self._play)
212  self._widget.play_tool_button.setIcon(QIcon.fromTheme('media-playback-start'))
213  self._widget.stop_tool_button.pressed.connect(self._stop)
214  self._widget.stop_tool_button.setIcon(QIcon.fromTheme('media-playback-stop'))
215  # also connect the navigation buttons so that they stop the timer when
216  # pressed while the tree is playing.
217  self._widget.first_tool_button.pressed.connect(self._stop)
218  self._widget.previous_tool_button.pressed.connect(self._stop)
219  self._widget.last_tool_button.pressed.connect(self._stop)
220  self._widget.next_tool_button.pressed.connect(self._stop)
221 
222  # set up shortcuts for navigation (vim)
223  next_shortcut_vi = QShortcut(QKeySequence("l"), self._widget)
224  next_shortcut_vi.activated.connect(self._widget.next_tool_button.pressed)
225  previous_shortcut_vi = QShortcut(QKeySequence("h"), self._widget)
226  previous_shortcut_vi.activated.connect(self._widget.previous_tool_button.pressed)
227  first_shortcut_vi = QShortcut(QKeySequence("^"), self._widget)
228  first_shortcut_vi.activated.connect(self._widget.first_tool_button.pressed)
229  last_shortcut_vi = QShortcut(QKeySequence("$"), self._widget)
230  last_shortcut_vi.activated.connect(self._widget.last_tool_button.pressed)
231 
232  # shortcuts for emacs
233  next_shortcut_emacs = QShortcut(QKeySequence("Ctrl+f"), self._widget)
234  next_shortcut_emacs.activated.connect(self._widget.next_tool_button.pressed)
235  previous_shortcut_emacs = QShortcut(QKeySequence("Ctrl+b"), self._widget)
236  previous_shortcut_emacs.activated.connect(self._widget.previous_tool_button.pressed)
237  first_shortcut_emacs = QShortcut(QKeySequence("Ctrl+a"), self._widget)
238  first_shortcut_emacs.activated.connect(self._widget.first_tool_button.pressed)
239  last_shortcut_emacs = QShortcut(QKeySequence("Ctrl+e"), self._widget)
240  last_shortcut_emacs.activated.connect(self._widget.last_tool_button.pressed)
241 
242  # set up stuff for dotcode cache
244  self._dotcode_cache = {}
245  # cache is ordered on timestamps from messages, but earliest timestamp
246  # isn't necessarily the message that was viewed the longest time ago, so
247  # need to store keys
249 
250  # set up stuff for scene cache (dotcode cache doesn't seem to make much difference)
252  self._scene_cache = {}
254 
255  # Update the timeline buttons to correspond with a completely
256  # uninitialised state.
257  self._set_timeline_buttons(first_snapshot=False, previous_snapshot=False, next_snapshot=False, last_snapshot=False)
258 
259  self._deferred_fit_in_view.connect(self._fit_in_view,
260  Qt.QueuedConnection)
261  self._deferred_fit_in_view.emit()
262 
263  # This is used to store a timer which controls how fast updates happen when the play button is pressed.
264  self._play_timer = None
265 
266  # updates the view
267  self._refresh_view.connect(self._refresh_tree_graph)
268 
269  self._force_refresh = False
270 
271  if self.live_update:
272  context.add_widget(self._widget)
273  else:
274  self.initialized = True # this needs to be set for trees to be displayed
275  context.setCentralWidget(self._widget)
276 
277  if parsed_args.bag:
278  self._load_bag(parsed_args.bag)
279  elif parsed_args.latest_bag:
280  # if the latest bag is requested, load it from the default directory, or
281  # the one specified in the args
282  bag_dir = parsed_args.bag_dir or os.getenv('ROS_HOME', os.path.expanduser('~/.ros')) + '/behaviour_trees'
283  self.open_latest_bag(bag_dir, parsed_args.by_time)
284 
285  @Slot(str)
286  def _update_visibility_level(self, visibility_level):
287  """
288  We match the combobox index to the visibility levels defined in py_trees.common.VisibilityLevel.
289  """
290  self.visibility_level = visibility.combo_to_py_trees[visibility_level]
291  self._refresh_tree_graph()
292 
293  @staticmethod
294  def add_arguments(parser, group=True):
295  """Allows for the addition of arguments to the rqt_gui loading method
296 
297  :param bool group: If set to false, this indicates that the function is
298  being called from the rqt_py_trees script as opposed to the inside
299  of rqt_gui.main. We use this to ensure that the same arguments can
300  be passed with and without the --no-roscore argument set. If it is
301  set, the rqt_gui code is bypassed. We need to make sure that all the
302  arguments are displayed with -h.
303 
304  """
305  operate_object = parser
306  if group:
307  operate_object = parser.add_argument_group('Options for the rqt_py_trees viewer')
308 
309  operate_object.add_argument('bag', action='store', nargs='?', help='Load this bag when the viewer starts')
310  operate_object.add_argument('-l', '--latest-bag', action='store_true', help='Load the latest bag available in the bag directory. Bag files are expected to be under the bag directory in the following structure: year-month-day/behaviour_tree_hour-minute-second.bag. If this structure is not followed, the bag file which was most recently modified is used.')
311  operate_object.add_argument('--bag-dir', action='store', help='Specify the directory in which to look for bag files. The default is $ROS_HOME/behaviour_trees, if $ROS_HOME is set, or ~/.ros/behaviour_trees otherwise.')
312  operate_object.add_argument('-m', '--by-time', action='store_true', help='The latest bag is defined by the time at which the file was last modified, rather than the date and time specified in the filename.')
313  operate_object.add_argument(RosBehaviourTree.no_roscore_switch, action='store_true', help='Run the viewer without roscore. It is only possible to view bag files if this is set.')
314 
315  def open_latest_bag(self, bag_dir, by_time=False):
316  """Open the latest bag in the given directory
317 
318  :param str bag_dir: the directory in which to look for bags
319  :param bool by_time: if true, the latest bag is the one with the latest
320  modification time, not the latest date-time specified by its filename
321 
322  """
323  if not os.path.isdir(bag_dir):
324  rospy.logwarn("Requested bag directory {0} is invalid. Latest bag will not be loaded.".format(bag_dir))
325  return
326 
327  files = []
328  for root, unused_dirnames, filenames in os.walk(bag_dir, topdown=True):
329  files.extend(fnmatch.filter(map(lambda p: os.path.join(root, p), filenames), '*.bag'))
330 
331  if not files:
332  rospy.logwarn("No files with extension .bag found in directory {0}".format(bag_dir))
333  return
334 
335  if not by_time:
336  # parse the file list with a regex to get only those which have the
337  # format year-month-day/behaviour_tree_hour-minute-second.bag
338  re_str = '.*\/\d{4}-\d{2}-\d{2}\/behaviour_tree_\d{2}-\d{2}-\d{2}.bag'
339  expr = re.compile(re_str)
340  valid = filter(lambda f: expr.match(f), files)
341 
342  # if no files match the regex, use modification time instead
343  if not valid:
344  by_time = True
345  else:
346  # dates are monotonically increasing, so the last one is the latest
347  latest_bag = sorted(valid)[-1]
348 
349  if by_time:
350  latest_bag = sorted(files, cmp=lambda x, y: cmp(os.path.getctime(x), os.path.getctime(y)))[-1]
351 
352  self._load_bag(latest_bag)
353 
355  """
356  Get the message in the list or bag that is being viewed that should be
357  displayed.
358  """
359  msg = None
360  if self._timeline_listener:
361  try:
362  msg = self._timeline_listener.msg
363  except KeyError:
364  pass
365 
366  return py_trees_msgs.BehaviourTree() if msg is None else msg
367 
368  def _choose_topic(self, index):
369  """Updates the topic that is subscribed to based on changes to the combo box
370  text. If the topic is unchanged, nothing will happnen. Otherwise, the
371  old subscriber will be unregistered, and a new one initialised for the
372  updated topic. If the selected topic corresponds to the unselected
373  topic, the subscriber will be unregistered and a new one will not be
374  created.
375 
376  """
377  selected_topic = self._widget.topic_combo_box.currentText()
378  if selected_topic != self._empty_topic and self.current_topic != selected_topic:
379  self.current_topic = selected_topic
380  # destroy the old timeline and clear the scene
381  if self._timeline:
382  self._timeline.handle_close()
383  self._widget.timeline_graphics_view.setScene(None)
384 
385  if selected_topic != self._unselected_topic:
386  # set up a timeline to track the messages coming from the subscriber
387  self._set_dynamic_timeline()
388 
390  """
391  Update the topics displayed in the combo box that the user can use to select
392  which topic they want to listen on for trees, filtered so that only
393  topics with the correct message type are shown.
394  """
395  # Only update topics if we're running with live updating
396  if not self.live_update:
397  self._widget.topic_combo_box.setEnabled(False)
398  return
399 
400  self._widget.topic_combo_box.clear()
401  topic_list = rospy.get_published_topics()
402 
403  valid_topics = []
404  for topic_path, topic_type in topic_list:
405  if topic_type == RosBehaviourTree._expected_type:
406  valid_topics.append(topic_path)
407 
408  if not valid_topics:
409  self._widget.topic_combo_box.addItem(RosBehaviourTree._empty_topic)
410  return
411 
412  # always add an item which does nothing so that it is possible to listen to nothing.
413  self._widget.topic_combo_box.addItem(RosBehaviourTree._unselected_topic)
414  for topic in valid_topics:
415  self._widget.topic_combo_box.addItem(topic)
416  # if the topic corresponds to the one that was active the last time
417  # the viewer was run, automatically set that one as the one we look
418  # at
419  if topic == self._saved_settings_topic:
420  self._widget.topic_combo_box.setCurrentIndex(self._widget.topic_combo_box.count() - 1)
421  self._choose_topic(self._widget.topic_combo_box.currentIndex())
422 
423  def _set_timeline_buttons(self, first_snapshot=None, previous_snapshot=None, next_snapshot=None, last_snapshot=None):
424  """
425  Allows timeline buttons to be enabled and disabled.
426  """
427  if first_snapshot is not None:
428  self._widget.first_tool_button.setEnabled(first_snapshot)
429  if previous_snapshot is not None:
430  self._widget.previous_tool_button.setEnabled(previous_snapshot)
431  if next_snapshot is not None:
432  self._widget.next_tool_button.setEnabled(next_snapshot)
433  if last_snapshot is not None:
434  self._widget.last_tool_button.setEnabled(last_snapshot)
435 
436  def _play(self):
437  """
438  Start a timer which will automatically call the next function every time its
439  duration is up. Only works if the current message is not the final one.
440  """
441  if not self._play_timer:
442  self._play_timer = rospy.Timer(rospy.Duration(1), self._timer_next)
443 
444  def _timer_next(self, timer):
445  """
446  Helper function for the timer so that it can call the next function without
447  breaking.
448  """
449  self._next()
450 
451  def _stop(self):
452  """Stop the play timer, if it exists.
453  """
454  if self._play_timer:
455  self._play_timer.shutdown()
456  self._play_timer = None
457 
458  def _first(self):
459  """Navigate to the first message. Activates the next and last buttons, disables
460  first and previous, and refreshes the view. Also changes the state to be
461  browsing the timeline.
462 
463  """
464  self._timeline.navigate_start()
465 
466  self._set_timeline_buttons(first_snapshot=False, previous_snapshot=False, next_snapshot=True, last_snapshot=True)
467  self._refresh_view.emit()
468  self._browsing_timeline = True
469 
470  def _previous(self):
471  """Navigate to the previous message. Activates the next and last buttons, and
472  refreshes the view. If the current message is the second message, then
473  the first and previous buttons are disabled. Changes the state to be
474  browsing the timeline.
475  """
476  # if already at the beginning, do nothing
477  if self._timeline._timeline_frame.playhead == self._timeline._get_start_stamp():
478  return
479 
480  # otherwise, go to the previous message
481  self._timeline.navigate_previous()
482  # now browsing the timeline
483  self._browsing_timeline = True
484  self._set_timeline_buttons(last_snapshot=True, next_snapshot=True)
485  # if now at the beginning, disable timeline buttons.
486  if self._timeline._timeline_frame.playhead == self._timeline._get_end_stamp():
487  self._set_timeline_buttons(next_snapshot=False, last_snapshot=False)
488 
489  self._refresh_view.emit()
490 
491  def _last(self):
492  """Navigate to the last message. Activates the first and previous buttons,
493  disables next and last, and refreshes the view. The user is no longer
494  browsing the timeline after this is called.
495 
496  """
497  self._timeline.navigate_end()
498 
499  self._set_timeline_buttons(first_snapshot=True, previous_snapshot=True, next_snapshot=False, last_snapshot=False)
500  self._refresh_view.emit()
501  self._browsing_timeline = False
502  self._new_messages = 0
503 
504  def _next(self):
505  """Navigate to the next message. Activates the first and previous buttons. If
506  the current message is the second from last, disables the next and last
507  buttons, and stops browsing the timeline.
508 
509  """
510  # if already at the end, do nothing
511  if self._timeline._timeline_frame.playhead == self._timeline._get_end_stamp():
512  return
513 
514  # otherwise, go to the next message
515  self._timeline.navigate_next()
516  self._set_timeline_buttons(first_snapshot=True, previous_snapshot=True)
517  # if now at the end, disable timeline buttons and shutdown the play timer if active
518  if self._timeline._timeline_frame.playhead == self._timeline._get_end_stamp():
519  self._set_timeline_buttons(next_snapshot=False, last_snapshot=False)
520  self._browsing_timeline = False
521  if self._play_timer:
522  self._play_timer.shutdown()
523 
524  self._refresh_view.emit()
525 
526  def save_settings(self, plugin_settings, instance_settings):
527  instance_settings.set_value('visibility_level', self.visibility_level)
528  instance_settings.set_value('auto_fit_graph_check_box_state',
529  self._widget.auto_fit_graph_check_box.isChecked())
530  instance_settings.set_value('highlight_connections_check_box_state',
531  self._widget.highlight_connections_check_box.isChecked())
532  combo_text = self._widget.topic_combo_box.currentText()
533  if combo_text not in [self._empty_topic, self._unselected_topic]:
534  instance_settings.set_value('combo_box_subscribed_topic', combo_text)
535 
536  def restore_settings(self, plugin_settings, instance_settings):
537  try:
538  self._widget.auto_fit_graph_check_box.setChecked(
539  instance_settings.value('auto_fit_graph_check_box_state', True) in [True, 'true'])
540  self._widget.highlight_connections_check_box.setChecked(
541  instance_settings.value('highlight_connections_check_box_state', True) in [True, 'true'])
542  self._saved_settings_topic = instance_settings.value('combo_box_subscribed_topic', None)
543  saved_visibility_level = instance_settings.value('visibility_level', 1)
544  except TypeError as e:
545  self._widget.auto_fit_graph_check_box.setChecked(True)
546  self._widget.highlight_connections_check_box.setChecked(True)
547  self._saved_settings_topic = None
548  saved_visibility_level = 1
549  rospy.logerr("Rqt PyTrees: incompatible qt app configuration found, try removing ~/.config/ros.org/rqt_gui.ini")
550  rospy.logerr("Rqt PyTrees: %s" % e)
551  self._widget.visibility_level_combo_box.setCurrentIndex(visibility.saved_setting_to_combo_index[saved_visibility_level])
552  self.initialized = True
553  self._update_combo_topics()
554  self._refresh_tree_graph()
555 
557  """Refresh the graph view by regenerating the dotcode from the current message.
558 
559  """
560  if not self.initialized:
561  return
563 
564  def _generate_dotcode(self, message):
565  """
566  Get the dotcode for the given message, checking the cache for dotcode that
567  was previously generated, and adding to the cache if it wasn't there.
568  Cache replaces LRU.
569 
570  Mostly stolen from rqt_bag.MessageLoaderThread
571 
572  :param py_trees_msgs.BehavoiurTree message
573  """
574  if message is None:
575  return ""
576 
577  #######################################################
578  # Get the tip, from the perspective of the root
579  #######################################################
580  # this is pretty inefficient, and ignores caching
581  tip_id = None
582  self._tip_message = None
583  # reverse behaviour list - construction puts the root at the end (with
584  # visitor, at least)
585  for behaviour in reversed(message.behaviours):
586  # root has empty parent ID
587  if str(behaviour.parent_id) == str(uuid_msgs.UniqueID()):
588  # parent is the root behaviour, so
589  tip_id = behaviour.tip_id
590 
591  # Run through the behaviours and do a couple of things:
592  # - get the tip
593  # - protect against feedback messages with quotes (https://bitbucket.org/yujinrobot/gopher_crazy_hospital/issues/72/rqt_py_trees-fails-to-display-tree)
594  if self._tip_message is None:
595  for behaviour in message.behaviours:
596  if str(behaviour.own_id) == str(tip_id):
597  self._tip_message = behaviour.message
598  if '"' in behaviour.message:
599  print("%s" % termcolor.colored('[ERROR] found double quotes in the feedback message [%s]' % behaviour.message, 'red'))
600  behaviour.message = behaviour.message.replace('"', '')
601  print("%s" % termcolor.colored('[ERROR] stripped to stop from crashing, but do catch the culprit! [%s]' % behaviour.message, 'red'))
602 
603  key = str(message.header.stamp) # stamps are unique
604  if key in self._dotcode_cache:
605  return self._dotcode_cache[key]
606 
607  force_refresh = self._force_refresh
608  self._force_refresh = False
609 
610  visible_behaviours = visibility.filter_behaviours_by_visibility_level(message.behaviours, self.visibility_level)
611 
612  # cache miss
613  dotcode = self.dotcode_generator.generate_dotcode(dotcode_factory=self.dotcode_factory,
614  behaviours=visible_behaviours,
615  timestamp=message.header.stamp,
616  force_refresh=force_refresh
617  )
618  self._dotcode_cache[key] = dotcode
619  self._dotcode_cache_keys.append(key)
620 
621  if len(self._dotcode_cache) > self._dotcode_cache_capacity:
622  oldest = self._dotcode_cache_keys[0]
623  del self._dotcode_cache[oldest]
624  self._dotcode_cache_keys.remove(oldest)
625 
626  return dotcode
627 
628  def _update_graph_view(self, dotcode):
629  if dotcode == self._current_dotcode:
630  return
631  self._current_dotcode = dotcode
632  self._redraw_graph_view()
633 
635  key = str(self.get_current_message().header.stamp)
636  if key in self._scene_cache:
637  new_scene = self._scene_cache[key]
638  else: # cache miss
639  new_scene = QGraphicsScene()
640  new_scene.setBackgroundBrush(Qt.white)
641 
642  if self._widget.highlight_connections_check_box.isChecked():
643  highlight_level = 3
644  else:
645  highlight_level = 1
646 
647  # (nodes, edges) = self.dot_to_qt.graph_to_qt_items(self.dotcode_generator.graph,
648  # highlight_level)
649  # this function is very expensive
650  (nodes, edges) = self.dot_to_qt.dotcode_to_qt_items(self._current_dotcode,
651  highlight_level)
652 
653  for node_item in nodes.itervalues():
654  new_scene.addItem(node_item)
655  for edge_items in edges.itervalues():
656  for edge_item in edge_items:
657  edge_item.add_to_scene(new_scene)
658 
659  new_scene.setSceneRect(new_scene.itemsBoundingRect())
660 
661  # put the scene in the cache
662  self._scene_cache[key] = new_scene
663  self._scene_cache_keys.append(key)
664 
665  if len(self._scene_cache) > self._scene_cache_capacity:
666  oldest = self._scene_cache_keys[0]
667  del self._scene_cache[oldest]
668  self._scene_cache_keys.remove(oldest)
669 
670  # after construction, set the scene and fit to the view
671  self._scene = new_scene
672 
673  self._widget.graphics_view.setScene(self._scene)
674  self._widget.message_label.setText(self._tip_message)
675 
676  if self._widget.auto_fit_graph_check_box.isChecked():
677  self._fit_in_view()
678 
679  def _resize_event(self, event):
680  """Activated when the window is resized. Will re-fit the behaviour tree in the
681  window, and update the size of the timeline scene rectangle so that it
682  is correctly drawn.
683 
684  """
685  self._fit_in_view()
686  if self._timeline:
687  self._timeline.setSceneRect(0, 0, self._widget.timeline_graphics_view.width() - 2, max(self._widget.timeline_graphics_view.height() - 2, self._timeline._timeline_frame._history_bottom))
688 
689  def timeline_changed(self):
690  """Should be called whenever the timeline changes. At the moment this is only
691  used to ensure that the first and previous buttons are correctly
692  disabled when a new message coming in on the timeline pushes the
693  playhead to be at the first message
694 
695  """
696  if self._timeline._timeline_frame.playhead == self._timeline._get_start_stamp():
697  self._set_timeline_buttons(first_snapshot=False, previous_snapshot=False)
698  else:
699  self._set_timeline_buttons(first_snapshot=True, previous_snapshot=True)
700 
701  def message_changed(self):
702  """
703  This function should be called when the message being viewed changes. Will
704  change the current message and update the view. Also ensures that the
705  timeline buttons are correctly set for the current position of the
706  playhead on the timeline.
707  """
708  if self._timeline._timeline_frame.playhead == self._timeline._get_end_stamp():
709  self._set_timeline_buttons(last_snapshot=False, next_snapshot=False)
710  else:
711  self._set_timeline_buttons(last_snapshot=True, next_snapshot=True)
712 
713  if self._timeline._timeline_frame.playhead == self._timeline._get_start_stamp():
714  self._set_timeline_buttons(first_snapshot=False, previous_snapshot=False)
715  else:
716  self._set_timeline_buttons(first_snapshot=True, previous_snapshot=True)
717 
718  self._refresh_view.emit()
719 
720  def message_cleared(self):
721  """
722  This function should be called when the message being viewed was cleared.
723  Currently no situation where this happens?
724  """
725  pass
726 
727  def no_right_click_press_event(self, func):
728  """Decorator for ignoring right click events on mouse press
729  """
730  @functools.wraps(func)
731  def wrapper(event):
732  if event.type() == QEvent.MouseButtonPress and event.button() == Qt.RightButton:
733  event.ignore()
734  else:
735  func(event)
736  return wrapper
737 
739  """
740  Set the timeline to a dynamic timeline, listening to messages on the topic
741  selected in the combo box.
742  """
743  self._timeline = DynamicTimeline(self, publish_clock=False)
744  # connect timeline events so that the timeline will update when events happen
745  self._widget.timeline_graphics_view.mousePressEvent = self.no_right_click_press_event(self._timeline.on_mouse_down)
746  self._widget.timeline_graphics_view.mouseReleaseEvent = self._timeline.on_mouse_up
747  self._widget.timeline_graphics_view.mouseMoveEvent = self._timeline.on_mouse_move
748  self._widget.timeline_graphics_view.wheelEvent = self._timeline.on_mousewheel
749  self._widget.timeline_graphics_view.setScene(self._timeline)
750 
751  # Don't show scrollbars - the timeline adjusts to the size of the view
752  self._widget.timeline_graphics_view.setHorizontalScrollBarPolicy(Qt.ScrollBarAlwaysOff)
753  self._widget.timeline_graphics_view.setVerticalScrollBarPolicy(Qt.ScrollBarAlwaysOff)
754  # Send a resize event so that the timeline knows the size of the view it's in
755  self._resize_event(None)
756 
757  self._timeline.add_topic(self.current_topic, py_trees_msgs.BehaviourTree)
758 
759  # Create a listener for the timeline which will call the emit function
760  # on the given signals when the message being viewed changes or is
761  # cleared. The message being viewed changing generally happens when the
762  # user moves the slider around.
763  self._timeline_listener = DynamicTimelineListener(self._timeline, self.current_topic, self._message_changed, self._message_cleared)
764  # Need to add a listener to make sure that we can get information about
765  # messages that are on the topic that we're interested in.
766  self._timeline.add_listener(self.current_topic, self._timeline_listener)
767 
768  self._timeline.navigate_end()
769  self._timeline._redraw_timeline(None)
770  self._timeline.timeline_updated.connect(self.timeline_changed)
771 
772  def _set_bag_timeline(self, bag):
773  """Set the timeline of this object to a bag timeline, hooking the graphics view
774  into mouse and wheel functions of the timeline.
775 
776  """
777  self._timeline = BagTimeline(self, publish_clock=False)
778  # connect timeline events so that the timeline will update when events happen
779  self._widget.timeline_graphics_view.mousePressEvent = self.no_right_click_press_event(self._timeline.on_mouse_down)
780  self._widget.timeline_graphics_view.mouseReleaseEvent = self._timeline.on_mouse_up
781  self._widget.timeline_graphics_view.mouseMoveEvent = self._timeline.on_mouse_move
782  self._widget.timeline_graphics_view.wheelEvent = self._timeline.on_mousewheel
783  self._widget.timeline_graphics_view.setScene(self._timeline)
784 
785  # Don't show scrollbars - the timeline adjusts to the size of the view
786  self._widget.timeline_graphics_view.setHorizontalScrollBarPolicy(Qt.ScrollBarAlwaysOff)
787  self._widget.timeline_graphics_view.setVerticalScrollBarPolicy(Qt.ScrollBarAlwaysOff)
788  # Send a resize event so that the timeline knows the size of the view it's in
789  self._resize_event(None)
790 
791  self._timeline.add_bag(bag)
792  # Create a listener for the timeline which will call the emit function
793  # on the given signals when the message being viewed changes or is
794  # cleared. The message being viewed changing generally happens when the
795  # user moves the slider around.
796  self._timeline_listener = TimelineListener(self._timeline, self.current_topic, self._message_changed, self._message_cleared)
797  # Need to add a listener to make sure that we can get information about
798  # messages that are on the topic that we're interested in.
799  self._timeline.add_listener(self.current_topic, self._timeline_listener)
800  # Go to the first message in the timeline of the bag.
801  self._timeline.navigate_start()
802 
803  def _load_bag(self, file_name=None):
804  """Load a bag from file. If no file name is given, a dialogue will pop up and
805  the user will be asked to select a file. If the bag file selected
806  doesn't have any valid topic, nothing will happen. If there are valid
807  topics, we load the bag and add a timeline for managing it.
808 
809  """
810  if file_name is None:
811  file_name, _ = QFileDialog.getOpenFileName(
812  self._widget,
813  self.tr('Open trees from bag file'),
814  None,
815  self.tr('ROS bag (*.bag)'))
816  if file_name is None or file_name == "":
817  return
818 
819  rospy.loginfo("Reading bag from {0}".format(file_name))
820  bag = rosbag.Bag(file_name, 'r')
821  # ugh...
822  topics = bag.get_type_and_topic_info()[1].keys()
823  types = []
824  for i in range(0, len(bag.get_type_and_topic_info()[1].values())):
825  types.append(bag.get_type_and_topic_info()[1].values()[i][0])
826 
827  tree_topics = [] # only look at the first matching topic
828  for ind, tp in enumerate(types):
829  if tp == 'py_trees_msgs/BehaviourTree':
830  tree_topics.append(topics[ind])
831 
832  if len(tree_topics) == 0:
833  rospy.logerr('Requested bag did not contain any valid topics.')
834  return
835 
836  self.message_list = []
837  self._viewing_bag = True
838  rospy.loginfo('Reading behaviour trees from topic {0}'.format(tree_topics[0]))
839  for unused_topic, msg, unused_t in bag.read_messages(topics=[tree_topics[0]]):
840  self.message_list.append(msg)
841 
842  self.current_topic = tree_topics[0]
843  self._set_timeline_buttons(first_snapshot=True, previous_snapshot=True, next_snapshot=False, last_snapshot=False)
844  self._set_bag_timeline(bag)
845  self._refresh_view.emit()
846 
847  def _load_dot(self, file_name=None):
848  if file_name is None:
849  file_name, _ = QFileDialog.getOpenFileName(
850  self._widget,
851  self.tr('Open tree from DOT file'),
852  None,
853  self.tr('DOT graph (*.dot)'))
854  if file_name is None or file_name == '':
855  return
856 
857  try:
858  fhandle = open(file_name, 'rb')
859  dotcode = fhandle.read()
860  fhandle.close()
861  except IOError:
862  return
863  self._update_graph_view(dotcode)
864 
865  def _fit_in_view(self):
866  self._widget.graphics_view.fitInView(self._scene.itemsBoundingRect(),
867  Qt.KeepAspectRatio)
868 
869  def _save_dot(self):
870  file_name, _ = QFileDialog.getSaveFileName(self._widget,
871  self.tr('Save as DOT'),
872  'frames.dot',
873  self.tr('DOT graph (*.dot)'))
874  if file_name is None or file_name == '':
875  return
876 
877  dot_file = QFile(file_name)
878  if not dot_file.open(QIODevice.WriteOnly | QIODevice.Text):
879  return
880 
881  dot_file.write(self._current_dotcode)
882  dot_file.close()
883 
884  def _save_svg(self):
885  file_name, _ = QFileDialog.getSaveFileName(
886  self._widget,
887  self.tr('Save as SVG'),
888  'frames.svg',
889  self.tr('Scalable Vector Graphic (*.svg)'))
890  if file_name is None or file_name == '':
891  return
892 
893  generator = QSvgGenerator()
894  generator.setFileName(file_name)
895  generator.setSize((self._scene.sceneRect().size() * 2.0).toSize())
896 
897  painter = QPainter(generator)
898  painter.setRenderHint(QPainter.Antialiasing)
899  self._scene.render(painter)
900  painter.end()
901 
902  def _save_image(self):
903  file_name, _ = QFileDialog.getSaveFileName(
904  self._widget,
905  self.tr('Save as image'),
906  'frames.png',
907  self.tr('Image (*.bmp *.jpg *.png *.tiff)'))
908  if file_name is None or file_name == '':
909  return
910 
911  img = QImage((self._scene.sceneRect().size() * 2.0).toSize(),
912  QImage.Format_ARGB32_Premultiplied)
913  painter = QPainter(img)
914  painter.setRenderHint(QPainter.Antialiasing)
915  self._scene.render(painter)
916  painter.end()
917  img.save(file_name)
def restore_settings(self, plugin_settings, instance_settings)
def _update_visibility_level(self, visibility_level)
_tip_message
Get the tip, from the perspective of the root.
def save_settings(self, plugin_settings, instance_settings)
def open_latest_bag(self, bag_dir, by_time=False)
def _set_timeline_buttons(self, first_snapshot=None, previous_snapshot=None, next_snapshot=None, last_snapshot=None)


rqt_py_trees
Author(s): Thibault Kruse, Michal Staniaszek, Daniel Stonier, Naveed Usmani
autogenerated on Mon Jun 10 2019 14:55:56