controller_manager.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Copyright (C) 2013, Georgia Tech
00003 # Copyright (C) 2015, PAL Robotics S.L.
00004 #
00005 # Redistribution and use in source and binary forms, with or without
00006 # modification, are permitted provided that the following conditions are met:
00007 # * Redistributions of source code must retain the above copyright notice,
00008 # this list of conditions and the following disclaimer.
00009 # * Redistributions in binary form must reproduce the above copyright
00010 # notice, this list of conditions and the following disclaimer in the
00011 # documentation and/or other materials provided with the distribution.
00012 # * Neither the name of PAL Robotics S.L. nor the names of its
00013 # contributors may be used to endorse or promote products derived from
00014 # this software without specific prior written permission.
00015 #
00016 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00017 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00018 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00019 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00020 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00021 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00022 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00023 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00024 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00025 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00026 # POSSIBILITY OF SUCH DAMAGE.
00027 
00028 import os
00029 import rospkg
00030 import rospy
00031 
00032 from python_qt_binding import loadUi
00033 from python_qt_binding.QtCore import QAbstractTableModel, QModelIndex, Qt,\
00034                                      QTimer, QVariant, Signal
00035 from python_qt_binding.QtGui import QCursor, QFont, QFormLayout, QHeaderView,\
00036                                     QIcon, QMenu, QStandardItem,\
00037                                     QStandardItemModel, QStyledItemDelegate,\
00038                                     QWidget
00039 from qt_gui.plugin import Plugin
00040 
00041 from controller_manager_msgs.msg import ControllerState
00042 from controller_manager_msgs.srv import *
00043 from controller_manager_msgs.utils\
00044     import ControllerLister, ControllerManagerLister,\
00045     get_rosparam_controller_names
00046 
00047 from update_combo import update_combo
00048 
00049 
00050 class ControllerManager(Plugin):
00051     """
00052     Graphical frontend for managing ros_control controllers.
00053     """
00054     _cm_update_freq = 1  # Hz
00055 
00056     def __init__(self, context):
00057         super(ControllerManager, self).__init__(context)
00058         self.setObjectName('ControllerManager')
00059 
00060         # Create QWidget and extend it with all the attributes and children
00061         # from the UI file
00062         self._widget = QWidget()
00063         rp = rospkg.RosPack()
00064         ui_file = os.path.join(rp.get_path('rqt_controller_manager'),
00065                                'resource',
00066                                'controller_manager.ui')
00067         loadUi(ui_file, self._widget)
00068         self._widget.setObjectName('ControllerManagerUi')
00069 
00070         # Pop-up that displays controller information
00071         self._popup_widget = QWidget()
00072         ui_file = os.path.join(rp.get_path('rqt_controller_manager'),
00073                                'resource',
00074                                'controller_info.ui')
00075         loadUi(ui_file, self._popup_widget)
00076         self._popup_widget.setObjectName('ControllerInfoUi')
00077 
00078         # Show _widget.windowTitle on left-top of each plugin (when
00079         # it's set in _widget). This is useful when you open multiple
00080         # plugins at once. Also if you open multiple instances of your
00081         # plugin at once, these lines add number to make it easy to
00082         # tell from pane to pane.
00083         if context.serial_number() > 1:
00084             self._widget.setWindowTitle(self._widget.windowTitle() +
00085                                         (' (%d)' % context.serial_number()))
00086         # Add widget to the user interface
00087         context.add_widget(self._widget)
00088 
00089         # Initialize members
00090         self._cm_ns = []  # Namespace of the selected controller manager
00091         self._controllers = []  # State of each controller
00092         self._table_model = None
00093         self._controller_lister = None
00094 
00095         # Controller manager service proxies
00096         self._load_srv = None
00097         self._unload_srv = None
00098         self._switch_srv = None
00099 
00100         # Controller state icons
00101         rospack = rospkg.RosPack()
00102         path = rospack.get_path('rqt_controller_manager')
00103         self._icons = {'running': QIcon(path + '/resource/led_green.png'),
00104                        'stopped': QIcon(path + '/resource/led_red.png'),
00105                        'uninitialized': QIcon(path + '/resource/led_off.png')}
00106 
00107         # Controllers display
00108         table_view = self._widget.table_view
00109         table_view.setContextMenuPolicy(Qt.CustomContextMenu)
00110         table_view.customContextMenuRequested.connect(self._on_ctrl_menu)
00111 
00112         table_view.doubleClicked.connect(self._on_ctrl_info)
00113 
00114         header = table_view.horizontalHeader()
00115         header.setResizeMode(QHeaderView.ResizeToContents)
00116         header.setContextMenuPolicy(Qt.CustomContextMenu)
00117         header.customContextMenuRequested.connect(self._on_header_menu)
00118 
00119         # Timer for controller manager updates
00120         self._list_cm = ControllerManagerLister()
00121         self._update_cm_list_timer = QTimer(self)
00122         self._update_cm_list_timer.setInterval(1000.0 /
00123                                                self._cm_update_freq)
00124         self._update_cm_list_timer.timeout.connect(self._update_cm_list)
00125         self._update_cm_list_timer.start()
00126 
00127         # Timer for running controller updates
00128         self._update_ctrl_list_timer = QTimer(self)
00129         self._update_ctrl_list_timer.setInterval(1000.0 /
00130                                                  self._cm_update_freq)
00131         self._update_ctrl_list_timer.timeout.connect(self._update_controllers)
00132         self._update_ctrl_list_timer.start()
00133 
00134         # Signal connections
00135         w = self._widget
00136         w.cm_combo.currentIndexChanged[str].connect(self._on_cm_change)
00137 
00138     def shutdown_plugin(self):
00139         self._update_cm_list_timer.stop()
00140         self._update_ctrl_list_timer.stop()
00141         self._popup_widget.hide()
00142 
00143     def save_settings(self, plugin_settings, instance_settings):
00144         instance_settings.set_value('cm_ns', self._cm_ns)
00145 
00146     def restore_settings(self, plugin_settings, instance_settings):
00147         # Restore last session's controller_manager, if present
00148         self._update_cm_list()
00149         cm_ns = instance_settings.value('cm_ns')
00150         cm_combo = self._widget.cm_combo
00151         cm_list = [cm_combo.itemText(i) for i in range(cm_combo.count())]
00152         try:
00153             idx = cm_list.index(cm_ns)
00154             cm_combo.setCurrentIndex(idx)
00155         except (ValueError):
00156             pass
00157 
00158     # def trigger_configuration(self):
00159         # Comment in to signal that the plugin has a way to configure
00160         # This will enable a setting button (gear icon) in each dock widget
00161         # title bar
00162         # Usually used to open a modal configuration dialog
00163 
00164     def _update_cm_list(self):
00165         update_combo(self._widget.cm_combo, self._list_cm())
00166 
00167     def _on_cm_change(self, cm_ns):
00168         self._cm_ns = cm_ns
00169 
00170         # Setup services for communicating with the selected controller manager
00171         self._set_cm_services(cm_ns)
00172 
00173         # Controller lister for the selected controller manager
00174         if cm_ns:
00175             self._controller_lister = ControllerLister(cm_ns)
00176             self._update_controllers()
00177         else:
00178             self._controller_lister = None
00179 
00180     def _set_cm_services(self, cm_ns):
00181         if cm_ns:
00182             # NOTE: Persistent services are used for performance reasons.
00183             # If the controller manager dies, we detect it and disconnect from
00184             # it anyway
00185             load_srv_name = _append_ns(cm_ns, 'load_controller')
00186             self._load_srv = rospy.ServiceProxy(load_srv_name,
00187                                                 LoadController,
00188                                                 persistent=True)
00189             unload_srv_name = _append_ns(cm_ns, 'unload_controller')
00190             self._unload_srv = rospy.ServiceProxy(unload_srv_name,
00191                                                   UnloadController,
00192                                                   persistent=True)
00193             switch_srv_name = _append_ns(cm_ns, 'switch_controller')
00194             self._switch_srv = rospy.ServiceProxy(switch_srv_name,
00195                                                   SwitchController,
00196                                                   persistent=True)
00197         else:
00198             self._load_srv = None
00199             self._unload_srv = None
00200             self._switch_srv = None
00201 
00202     def _update_controllers(self):
00203         # Find controllers associated to the selected controller manager
00204         controllers = self._list_controllers()
00205 
00206         # Update controller display, if necessary
00207         if self._controllers != controllers:
00208             self._controllers = controllers
00209             self._show_controllers()  # NOTE: Model is recomputed from scratch
00210 
00211     def _list_controllers(self):
00212         """
00213         @return List of controllers associated to a controller manager
00214         namespace. Contains both stopped/running controllers, as returned by
00215         the C{list_controllers} service, plus uninitialized controllers with
00216         configurations loaded in the parameter server.
00217         @rtype [str]
00218         """
00219         if not self._cm_ns:
00220             return []
00221 
00222         # Add loaded controllers first
00223         controllers = self._controller_lister()
00224 
00225         # Append potential controller configs found in the parameter server
00226         all_ctrls_ns = _resolve_controllers_ns(self._cm_ns)
00227         for name in get_rosparam_controller_names(all_ctrls_ns):
00228             add_ctrl = not any(name == ctrl.name for ctrl in controllers)
00229             if add_ctrl:
00230                 type_str = _rosparam_controller_type(all_ctrls_ns, name)
00231                 uninit_ctrl = ControllerState(name=name,
00232                                               type=type_str,
00233                                               state='uninitialized')
00234                 controllers.append(uninit_ctrl)
00235         return controllers
00236 
00237     def _show_controllers(self):
00238         table_view = self._widget.table_view
00239         self._table_model = ControllerTable(self._controllers, self._icons)
00240         table_view.setModel(self._table_model)
00241 
00242     def _on_ctrl_menu(self, pos):
00243         # Get data of selected controller
00244         row = self._widget.table_view.rowAt(pos.y())
00245         if row < 0:
00246             return  # Cursor is not under a valid item
00247 
00248         ctrl = self._controllers[row]
00249 
00250         # Show context menu
00251         menu = QMenu(self._widget.table_view)
00252         if ctrl.state == 'running':
00253             action_stop = menu.addAction(self._icons['stopped'], 'Stop')
00254             action_kill = menu.addAction(self._icons['uninitialized'],
00255                                          'Stop and Unload')
00256         elif ctrl.state == 'stopped':
00257             action_start = menu.addAction(self._icons['running'], 'Start')
00258             action_unload = menu.addAction(self._icons['uninitialized'],
00259                                            'Unload')
00260         elif ctrl.state == 'uninitialized':
00261             action_load = menu.addAction(self._icons['stopped'], 'Load')
00262             action_spawn = menu.addAction(self._icons['running'],
00263                                           'Load and Start')
00264 
00265         action = menu.exec_(self._widget.table_view.mapToGlobal(pos))
00266 
00267         # Evaluate user action
00268         if ctrl.state == 'running':
00269             if action is action_stop:
00270                 self._stop_controller(ctrl.name)
00271             elif action is action_kill:
00272                 self._stop_controller(ctrl.name)
00273                 self._unload_controller(ctrl.name)
00274         elif ctrl.state == 'stopped':
00275             if action is action_start:
00276                 self._start_controller(ctrl.name)
00277             elif action is action_unload:
00278                 self._unload_controller(ctrl.name)
00279         elif ctrl.state == 'uninitialized':
00280             if action is action_load:
00281                 self._load_controller(ctrl.name)
00282             if action is action_spawn:
00283                 self._load_controller(ctrl.name)
00284                 self._start_controller(ctrl.name)
00285 
00286     def _on_ctrl_info(self, index):
00287         popup = self._popup_widget
00288 
00289         ctrl = self._controllers[index.row()]
00290         popup.ctrl_name.setText(ctrl.name)
00291         popup.ctrl_type.setText(ctrl.type)
00292 
00293         res_model = QStandardItemModel()
00294         model_root = QStandardItem('Claimed Resources')
00295         res_model.appendRow(model_root)
00296         for hw_res in ctrl.claimed_resources:
00297             hw_iface_item = QStandardItem(hw_res.hardware_interface)
00298             model_root.appendRow(hw_iface_item)
00299             for res in hw_res.resources:
00300                 res_item = QStandardItem(res)
00301                 hw_iface_item.appendRow(res_item)
00302 
00303         popup.resource_tree.setModel(res_model)
00304         popup.resource_tree.setItemDelegate(FontDelegate(popup.resource_tree))
00305         popup.resource_tree.expandAll()
00306         popup.move(QCursor.pos())
00307         popup.show()
00308 
00309     def _on_header_menu(self, pos):
00310         header = self._widget.table_view.horizontalHeader()
00311 
00312         # Show context menu
00313         menu = QMenu(self._widget.table_view)
00314         action_toggle_auto_resize = menu.addAction('Toggle Auto-Resize')
00315         action = menu.exec_(header.mapToGlobal(pos))
00316 
00317         # Evaluate user action
00318         if action is action_toggle_auto_resize:
00319             if header.resizeMode(0) == QHeaderView.ResizeToContents:
00320                 header.setResizeMode(QHeaderView.Interactive)
00321             else:
00322                 header.setResizeMode(QHeaderView.ResizeToContents)
00323 
00324     def _load_controller(self, name):
00325         self._load_srv.call(LoadControllerRequest(name=name))
00326 
00327     def _unload_controller(self, name):
00328         self._unload_srv.call(UnloadControllerRequest(name=name))
00329 
00330     def _start_controller(self, name):
00331         strict = SwitchControllerRequest.STRICT
00332         req = SwitchControllerRequest(start_controllers=[name],
00333                                       stop_controllers=[],
00334                                       strictness=strict)
00335         self._switch_srv.call(req)
00336 
00337     def _stop_controller(self, name):
00338         strict = SwitchControllerRequest.STRICT
00339         req = SwitchControllerRequest(start_controllers=[],
00340                                       stop_controllers=[name],
00341                                       strictness=strict)
00342         self._switch_srv.call(req)
00343 
00344 
00345 class ControllerTable(QAbstractTableModel):
00346     """
00347     Model containing controller information for tabular display.
00348 
00349     The model allows display of basic read-only information like controller
00350     name and state.
00351     """
00352     def __init__(self, controller_info,  icons, parent=None):
00353         QAbstractTableModel.__init__(self, parent)
00354         self._data = controller_info
00355         self._icons = icons
00356 
00357     def rowCount(self, parent):
00358         return len(self._data)
00359 
00360     def columnCount(self, parent):
00361         return 2
00362 
00363     def headerData(self, col, orientation, role):
00364         if orientation == Qt.Horizontal and role == Qt.DisplayRole:
00365             if col == 0:
00366                 return 'controller'
00367             elif col == 1:
00368                 return 'state'
00369         else:
00370             return None
00371 
00372     def data(self, index, role):
00373         if not index.isValid():
00374             return None
00375 
00376         ctrl = self._data[index.row()]
00377 
00378         if role == Qt.DisplayRole:
00379             if index.column() == 0:
00380                 return ctrl.name
00381             elif index.column() == 1:
00382                 return ctrl.state
00383 
00384         if role == Qt.DecorationRole:
00385             if index.column() == 0:
00386                 return self._icons[ctrl.state]
00387 
00388         if role == Qt.FontRole:
00389             if index.column() == 0:
00390                 bf = QFont()
00391                 bf.setBold(True)
00392                 return bf
00393 
00394         if role == Qt.TextAlignmentRole:
00395             if index.column() == 1:
00396                 return Qt.AlignCenter
00397 
00398 
00399 class FontDelegate(QStyledItemDelegate):
00400     """
00401     Simple delegate for customizing font weight and italization when
00402     displaying resources claimed by a controller
00403     """
00404     def paint(self, painter, option, index):
00405         if not index.parent().isValid():
00406             # Root level
00407             option.font.setWeight(QFont.Bold)
00408         if index.parent().isValid() and not index.parent().parent().isValid():
00409             # Hardware interface level
00410             option.font.setItalic(True)
00411             option.font.setWeight(QFont.Bold)
00412         QStyledItemDelegate.paint(self, painter, option, index)
00413 
00414 
00415 def _resolve_controllers_ns(cm_ns):
00416     """
00417     Resolve the namespace containing controller configurations from that of
00418     the controller manager.
00419     Controllers are assumed to live one level above the controller
00420     manager, e.g.
00421 
00422         >>> _resolve_controller_ns('/path/to/controller_manager')
00423         '/path/to'
00424 
00425     In the particular case in which the controller manager is not
00426     namespaced, the controller is assumed to live in the root namespace
00427 
00428         >>> _resolve_controller_ns('/')
00429         '/'
00430         >>> _resolve_controller_ns('')
00431         '/'
00432     @param cm_ns Controller manager namespace (can be an empty string)
00433     @type cm_ns str
00434     @return Controllers namespace
00435     @rtype str
00436     """
00437     ns = cm_ns.rsplit('/', 1)[0]
00438     if not ns:
00439         ns += '/'
00440     return ns
00441 
00442 
00443 def _append_ns(in_ns, suffix):
00444     """
00445     Append a sub-namespace (suffix) to the input namespace
00446     @param in_ns Input namespace
00447     @type in_ns str
00448     @return Suffix namespace
00449     @rtype str
00450     """
00451     ns = in_ns
00452     if ns[-1] != '/':
00453         ns += '/'
00454     ns += suffix
00455     return ns
00456 
00457 
00458 def _rosparam_controller_type(ctrls_ns, ctrl_name):
00459     """
00460     Get a controller's type from its ROS parameter server configuration
00461     @param ctrls_ns Namespace where controllers should be located
00462     @type ctrls_ns str
00463     @param ctrl_name Controller name
00464     @type ctrl_name str
00465     @return Controller type
00466     @rtype str
00467     """
00468     type_param = _append_ns(ctrls_ns, ctrl_name) + '/type'
00469     return rospy.get_param(type_param)


rqt_controller_manager
Author(s): Kelsey Hawkins , Adolfo Rodríguez Tsouroukdissian
autogenerated on Thu Dec 1 2016 03:46:09