rqt_ros_graph.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2012, Willow Garage, Inc.
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions
00008 # are met:
00009 #
00010 #  * Redistributions of source code must retain the above copyright
00011 #    notice, this list of conditions and the following disclaimer.
00012 #  * Redistributions in binary form must reproduce the above
00013 #    copyright notice, this list of conditions and the following
00014 #    disclaimer in the documentation and/or other materials provided
00015 #    with the distribution.
00016 #  * Neither the name of Willow Garage, Inc. nor the names of its
00017 #    contributors may be used to endorse or promote products derived
00018 #    from this software without specific prior written permission.
00019 #
00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 # POSSIBILITY OF SUCH DAMAGE.
00032 #
00033 # Author: Isaac Saito
00034 
00035 from __future__ import division
00036 
00037 from python_qt_binding.QtCore import Qt
00038 import rospy
00039 
00040 
00041 class RqtRosGraph(object):
00042 
00043     DELIM_GRN = '/'
00044 
00045     @staticmethod
00046     def get_full_grn(model_index):
00047         """
00048         @deprecated: Not completed.
00049 
00050         Create full path format of GRN (Graph Resource Names, see
00051         http://www.ros.org/wiki/Names). Build GRN by recursively transcending
00052         parents & children of a given QModelIndex instance.
00053 
00054         A complete example of GRN: /wide_stereo/left/image_color/compressed
00055 
00056         Upon its very 1st call, the argument is the index where user clicks on
00057         on the view object (here QTreeView is used but should work with other
00058         View too. Not tested yet though). str_grn can be 0-length string.
00059 
00060         :type model_index: QModelIndex
00061         :type str_grn: str
00062         :param str_grn: This could be an incomplete or a complete GRN format.
00063         :rtype: str
00064         """
00065 
00066         children_grn_list = RqtRosGraph.get_lower_grn_dfs(model_index)
00067         parent_data = model_index.data()
00068         rospy.logdebug('parent_data={}'.format(parent_data))
00069         if parent_data == None:  # model_index is 1st-order node of a tree.
00070             upper_grn = RqtRosGraph.get_upper_grn(model_index, '')
00071             grn_list = []
00072             for child_grn in children_grn_list:
00073                 grn_full = upper_grn + child_grn
00074                 rospy.logdebug('grn_full={} upper_grn={} child_grn={}'.format(
00075                                                grn_full, upper_grn, child_grn))
00076                 grn_list.append(grn_full)
00077         else:
00078             grn_list = children_grn_list
00079 
00080         #Create a string where namespace is delimited by slash.
00081         grn = ''
00082         for s in grn_list:
00083             grn += RqtRosGraph.DELIM_GRN + s
00084 
00085         return grn
00086 
00087     @staticmethod
00088     def get_lower_grn_dfs(model_index, grn_prev=''):
00089         """
00090         Traverse all children treenodes and returns a list of "partial"
00091         GRNs. Partial means that this method returns names under current level.
00092 
00093         Ex. Consider a tree like this:
00094 
00095         Root
00096          |--TopitemA
00097          |    |--1
00098          |      |--2
00099          |        |--3
00100          |          |--4
00101          |          |--5
00102          |            |--6
00103          |            |--7
00104          |--TopitemB
00105 
00106         Re-formatted in GRN (omitting root):
00107 
00108           TopitemA/1/2/3/4
00109           TopitemA/1/2/3/5/6
00110           TopitemA/1/2/3/5/7
00111           TopitemB
00112 
00113          Might not be obvious from tree representation but there are 4 nodes as
00114          GRN form suggests.
00115 
00116          (doc from here TBD)
00117 
00118         :type model_index: QModelIndex
00119         :type grn_prev: str
00120         :rtype: str[]
00121         """
00122         i_child = 0
00123         list_grn_children_all = []
00124         while True:  # Loop per child.
00125             grn_curr = grn_prev + RqtRosGraph.DELIM_GRN + str(
00126                                                             model_index.data())
00127             child_qmindex = model_index.child(i_child, 0)
00128 
00129             if (not child_qmindex.isValid()):
00130                 rospy.logdebug('!! DEADEND i_child=#{} grn_curr={}'.format(
00131                                                            i_child, grn_curr))
00132                 if i_child == 0:
00133                     # Only when the current node has no children, add current
00134                     # GRN to the returning list.
00135                     list_grn_children_all.append(grn_curr)
00136                 return list_grn_children_all
00137 
00138             rospy.logdebug('Child#{} grn_curr={}'.format(i_child, grn_curr))
00139 
00140             list_grn_children = RqtRosGraph.get_lower_grn_dfs(child_qmindex,
00141                                                               grn_curr)
00142             for child_grn in list_grn_children:
00143                 child_grn = (grn_prev +
00144                              (RqtRosGraph.DELIM_GRN + grn_curr) +
00145                              (RqtRosGraph.DELIM_GRN + child_grn))
00146 
00147             list_grn_children_all = list_grn_children_all + list_grn_children
00148             rospy.logdebug('111 lennodes={} list_grn_children={}'.format(
00149                                 len(list_grn_children_all), list_grn_children))
00150             rospy.logdebug('122 list_grn_children_all={}'.format(
00151                                                         list_grn_children_all))
00152             i_child += 1
00153         return list_grn_children_all
00154 
00155     @staticmethod
00156     def get_upper_grn(model_index, str_grn):
00157         if model_index.data(Qt.DisplayRole) == None:
00158             return str_grn
00159         str_grn = (RqtRosGraph.DELIM_GRN +
00160                    str(model_index.data(Qt.DisplayRole)) +
00161                    str_grn)
00162         rospy.logdebug('get_full_grn_recur out str=%s', str_grn)
00163         return RqtRosGraph.get_upper_grn(model_index.parent(), str_grn)


rqt_py_common
Author(s): Dorian Scholz, Isaac Saito
autogenerated on Mon Oct 6 2014 07:15:13