change_controllers.py
Go to the documentation of this file.
00001 # Copyright (c) 2011, Dirk Thomas, TU Darmstadt
00002 # All rights reserved.
00003 #
00004 # Redistribution and use in source and binary forms, with or without
00005 # modification, are permitted provided that the following conditions
00006 # are met:
00007 #
00008 #   * Redistributions of source code must retain the above copyright
00009 #     notice, this list of conditions and the following disclaimer.
00010 #   * Redistributions in binary form must reproduce the above
00011 #     copyright notice, this list of conditions and the following
00012 #     disclaimer in the documentation and/or other materials provided
00013 #     with the distribution.
00014 #   * Neither the name of the TU Darmstadt nor the names of its
00015 #     contributors may be used to endorse or promote products derived
00016 #     from this software without specific prior written permission.
00017 #
00018 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00019 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00020 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00021 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00022 # COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00023 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00024 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00025 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00026 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00027 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00028 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029 # POSSIBILITY OF SUCH DAMAGE.
00030 
00031 
00032 import os
00033 import rospy
00034 import rospkg
00035 
00036 from qt_gui.plugin import Plugin
00037 from python_qt_binding import loadUi
00038 
00039 from QtCore import QEvent, QObject, Qt, QTimer, Slot
00040 from QtGui import QShortcut, QMessageBox, QWidget, QIcon
00041 from controller_manager_msgs.srv import ListControllers, SwitchController, LoadController
00042 from sr_robot_msgs.srv import ChangeControlType
00043 from sr_robot_msgs.msg import ControlType
00044 
00045 
00046 class SrGuiChangeControllers(Plugin):
00047 
00048     """
00049     A rosgui plugin for loading the different controllers
00050     """
00051     ICON_DIR = os.path.join(
00052         rospkg.RosPack().get_path('sr_visualization_icons'), 'icons')
00053     CONTROLLER_ON_ICON = QIcon(os.path.join(ICON_DIR, 'green.png'))
00054     CONTROLLER_OFF_ICON = QIcon(os.path.join(ICON_DIR, 'red.png'))
00055 
00056     controllers = {
00057         "valve": ["sh_ffj0_muscle_valve_controller",
00058                   "sh_ffj3_muscle_valve_controller",
00059                   "sh_ffj4_muscle_valve_controller",
00060                   "sh_mfj0_muscle_valve_controller",
00061                   "sh_mfj3_muscle_valve_controller",
00062                   "sh_mfj4_muscle_valve_controller",
00063                   "sh_rfj0_muscle_valve_controller",
00064                   "sh_rfj3_muscle_valve_controller",
00065                   "sh_rfj4_muscle_valve_controller",
00066                   "sh_lfj0_muscle_valve_controller",
00067                   "sh_lfj3_muscle_valve_controller",
00068                   "sh_lfj4_muscle_valve_controller",
00069                   "sh_lfj5_muscle_valve_controller",
00070                   "sh_thj1_muscle_valve_controller",
00071                   "sh_thj2_muscle_valve_controller",
00072                   "sh_thj3_muscle_valve_controller",
00073                   "sh_thj4_muscle_valve_controller",
00074                   "sh_thj5_muscle_valve_controller",
00075                   "sh_wrj1_muscle_valve_controller",
00076                   "sh_wrj2_muscle_valve_controller"],
00077         "position": ["sh_ffj0_muscle_position_controller",
00078                      "sh_ffj3_muscle_position_controller",
00079                      "sh_ffj4_muscle_position_controller",
00080                      "sh_mfj0_muscle_position_controller",
00081                      "sh_mfj3_muscle_position_controller",
00082                      "sh_mfj4_muscle_position_controller",
00083                      "sh_rfj0_muscle_position_controller",
00084                      "sh_rfj3_muscle_position_controller",
00085                      "sh_rfj4_muscle_position_controller",
00086                      "sh_lfj0_muscle_position_controller",
00087                      "sh_lfj3_muscle_position_controller",
00088                      "sh_lfj4_muscle_position_controller",
00089                      "sh_lfj5_muscle_position_controller",
00090                      "sh_thj1_muscle_position_controller",
00091                      "sh_thj2_muscle_position_controller",
00092                      "sh_thj3_muscle_position_controller",
00093                      "sh_thj4_muscle_position_controller",
00094                      "sh_thj5_muscle_position_controller",
00095                      "sh_wrj1_muscle_position_controller",
00096                      "sh_wrj2_muscle_position_controller"],
00097         "stop": []}
00098 
00099     def __init__(self, context):
00100         super(SrGuiChangeControllers, self).__init__(context)
00101         self.setObjectName('SrGuiChangeControllers')
00102 
00103         self._publisher = None
00104         self._widget = QWidget()
00105 
00106         ui_file = os.path.join(rospkg.RosPack().get_path(
00107             'sr_gui_change_muscle_controllers'), 'uis', 'SrChangeControllers.ui')
00108         loadUi(ui_file, self._widget)
00109         self._widget.setObjectName('SrChangeControllersUi')
00110         context.add_widget(self._widget)
00111 
00112         # Setting the initial state of the controller buttons
00113         self._widget.btn_valve.setIcon(self.CONTROLLER_OFF_ICON)
00114         self._widget.btn_valve.setChecked(False)
00115         self._widget.btn_position.setIcon(self.CONTROLLER_OFF_ICON)
00116         self._widget.btn_position.setChecked(False)
00117 
00118         # attaching the button press event to their actions
00119         self._widget.btn_stop.pressed.connect(self.on_stop_ctrl_clicked_)
00120         self._widget.btn_valve.pressed.connect(self.on_valve_ctrl_clicked_)
00121         self._widget.btn_position.pressed.connect(
00122             self.on_position_ctrl_clicked_)
00123 
00124     def on_stop_ctrl_clicked_(self):
00125         """
00126         Stop the controller
00127         """
00128         self._widget.btn_stop.setEnabled(False)
00129         self._widget.btn_valve.setIcon(self.CONTROLLER_OFF_ICON)
00130         self._widget.btn_valve.setChecked(False)
00131         self._widget.btn_position.setIcon(self.CONTROLLER_OFF_ICON)
00132         self._widget.btn_position.setChecked(False)
00133         self.change_ctrl("stop")
00134         self._widget.btn_stop.setEnabled(True)
00135 
00136     def on_valve_ctrl_clicked_(self):
00137         """
00138         Switch to valve control
00139         """
00140         self._widget.btn_valve.setEnabled(False)
00141         if not self._widget.btn_valve.isChecked():
00142             self._widget.btn_valve.setIcon(self.CONTROLLER_ON_ICON)
00143             self._widget.btn_valve.setChecked(True)
00144             self._widget.btn_position.setIcon(self.CONTROLLER_OFF_ICON)
00145             self._widget.btn_position.setChecked(False)
00146             rospy.loginfo("Valve checked: " + str(
00147                 self._widget.btn_valve.isChecked()))
00148             self.change_ctrl("valve")
00149         else:
00150             self._widget.btn_valve.setIcon(self.CONTROLLER_OFF_ICON)
00151             self._widget.btn_valve.setChecked(False)
00152             rospy.loginfo("Valve checked: " + str(
00153                 self._widget.btn_valve.isChecked()))
00154             self.change_ctrl("stop")
00155         self._widget.btn_valve.setEnabled(True)
00156 
00157     def on_position_ctrl_clicked_(self):
00158         """
00159         Switch to position control
00160         """
00161         self._widget.btn_position.setEnabled(False)
00162         if not self._widget.btn_position.isChecked():
00163             self._widget.btn_position.setIcon(self.CONTROLLER_ON_ICON)
00164             self._widget.btn_position.setChecked(True)
00165             self._widget.btn_valve.setIcon(self.CONTROLLER_OFF_ICON)
00166             self._widget.btn_valve.setChecked(False)
00167             rospy.loginfo("Position checked: " + str(
00168                 self._widget.btn_position.isChecked()))
00169             self.change_ctrl("position")
00170         else:
00171             self._widget.btn_position.setIcon(self.CONTROLLER_OFF_ICON)
00172             self._widget.btn_position.setChecked(False)
00173             rospy.loginfo("Position checked: " + str(
00174                 self._widget.btn_position.isChecked()))
00175             self.change_ctrl("stop")
00176         self._widget.btn_position.setEnabled(True)
00177 
00178     def change_ctrl(self, controller):
00179         """
00180         Switch controller type
00181         """
00182         success = True
00183         list_controllers = rospy.ServiceProxy(
00184             'controller_manager/list_controllers', ListControllers)
00185         try:
00186             resp1 = list_controllers()
00187         except rospy.ServiceException:
00188             success = False
00189 
00190         if success:
00191             current_controllers = [
00192                 c.name for c in resp1.controller if c.state == "running"]
00193             all_loaded_controllers = [c.name for c in resp1.controller]
00194 
00195             controllers_to_start = self.controllers[controller]
00196             controllers_to_start.append('joint_state_controller')
00197 
00198             load_controllers = rospy.ServiceProxy(
00199                 'controller_manager/load_controller', LoadController)
00200             for load_control in controllers_to_start:
00201                 if load_control not in all_loaded_controllers:
00202                     try:
00203                         resp1 = load_controllers(load_control)
00204                     except rospy.ServiceException:
00205                         success = False
00206                     if not resp1.ok:
00207                         success = False
00208 
00209             switch_controllers = rospy.ServiceProxy(
00210                 'controller_manager/switch_controller', SwitchController)
00211             try:
00212                 resp1 = switch_controllers(
00213                     controllers_to_start, current_controllers, SwitchController._request_class.BEST_EFFORT)
00214             except rospy.ServiceException:
00215                 success = False
00216 
00217             if not resp1.ok:
00218                 success = False
00219 
00220         if not success:
00221             rospy.logwarn(
00222                 "Failed to change some of the controllers. This is normal if this is not a 5 finger hand.")
00223 
00224     def _unregisterPublisher(self):
00225         if self._publisher is not None:
00226             self._publisher.unregister()
00227             self._publisher = None
00228 
00229     def shutdown_plugin(self):
00230         self._unregisterPublisher()
00231 
00232     def save_settings(self, global_settings, perspective_settings):
00233         pass
00234 
00235     def restore_settings(self, global_settings, perspective_settings):
00236         pass


sr_gui_change_muscle_controllers
Author(s): Ugo Cupcic
autogenerated on Thu Jun 6 2019 21:13:51