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, rospy, rospkg
00033 
00034 from qt_gui.plugin import Plugin
00035 from python_qt_binding import loadUi
00036 
00037 from QtCore import QEvent, QObject, Qt, QTimer, Slot
00038 from QtGui import QShortcut, QMessageBox, QWidget, QIcon
00039 from pr2_mechanism_msgs.srv import ListControllers, SwitchController, LoadController
00040 from sr_robot_msgs.srv import ChangeControlType
00041 from sr_robot_msgs.msg import ControlType
00042 
00043 class SrGuiChangeControllers(Plugin):
00044     """
00045     A rosgui plugin for loading the different controllers
00046     """
00047     ICON_DIR = os.path.join(rospkg.RosPack().get_path('sr_visualization_icons'), 'icons')
00048     CONTROLLER_ON_ICON = QIcon(os.path.join(ICON_DIR, 'green.png'))
00049     CONTROLLER_OFF_ICON = QIcon(os.path.join(ICON_DIR, 'red.png'))
00050 
00051     controllers = {"valve": ["sh_ffj0_muscle_valve_controller", "sh_ffj3_muscle_valve_controller", "sh_ffj4_muscle_valve_controller", "sh_mfj0_muscle_valve_controller", "sh_mfj3_muscle_valve_controller", "sh_mfj4_muscle_valve_controller", "sh_rfj0_muscle_valve_controller", "sh_rfj3_muscle_valve_controller", "sh_rfj4_muscle_valve_controller", "sh_lfj0_muscle_valve_controller", "sh_lfj3_muscle_valve_controller", "sh_lfj4_muscle_valve_controller", "sh_lfj5_muscle_valve_controller", "sh_thj1_muscle_valve_controller", "sh_thj2_muscle_valve_controller", "sh_thj3_muscle_valve_controller", "sh_thj4_muscle_valve_controller", "sh_thj5_muscle_valve_controller", "sh_wrj1_muscle_valve_controller", "sh_wrj2_muscle_valve_controller"],
00052                    "position": ["sh_ffj0_muscle_position_controller", "sh_ffj3_muscle_position_controller", "sh_ffj4_muscle_position_controller", "sh_mfj0_muscle_position_controller", "sh_mfj3_muscle_position_controller", "sh_mfj4_muscle_position_controller", "sh_rfj0_muscle_position_controller", "sh_rfj3_muscle_position_controller", "sh_rfj4_muscle_position_controller", "sh_lfj0_muscle_position_controller", "sh_lfj3_muscle_position_controller", "sh_lfj4_muscle_position_controller", "sh_lfj5_muscle_position_controller", "sh_thj1_muscle_position_controller", "sh_thj2_muscle_position_controller", "sh_thj3_muscle_position_controller", "sh_thj4_muscle_position_controller", "sh_thj5_muscle_position_controller", "sh_wrj1_muscle_position_controller", "sh_wrj2_muscle_position_controller"],
00053                    "stop": []}
00054 
00055     def __init__(self, context):
00056         super(SrGuiChangeControllers, self).__init__(context)
00057         self.setObjectName('SrGuiChangeControllers')
00058 
00059         self._publisher = None
00060         self._widget = QWidget()
00061 
00062         ui_file = os.path.join(rospkg.RosPack().get_path('sr_gui_change_muscle_controllers'), 'uis', 'SrChangeControllers.ui')
00063         loadUi(ui_file, self._widget)
00064         self._widget.setObjectName('SrChangeControllersUi')
00065         context.add_widget(self._widget)
00066         
00067         #Setting the initial state of the controller buttons
00068         self._widget.btn_valve.setIcon(self.CONTROLLER_OFF_ICON)
00069         self._widget.btn_valve.setChecked(False)
00070         self._widget.btn_position.setIcon(self.CONTROLLER_OFF_ICON)
00071         self._widget.btn_position.setChecked(False)
00072 
00073         #attaching the button press event to their actions
00074         self._widget.btn_stop.pressed.connect(self.on_stop_ctrl_clicked_)
00075         self._widget.btn_valve.pressed.connect(self.on_valve_ctrl_clicked_)
00076         self._widget.btn_position.pressed.connect(self.on_position_ctrl_clicked_)
00077         
00078     def on_stop_ctrl_clicked_(self):
00079         """
00080         Stop the controller
00081         """
00082         self._widget.btn_stop.setEnabled(False)
00083         self._widget.btn_valve.setIcon(self.CONTROLLER_OFF_ICON)
00084         self._widget.btn_valve.setChecked(False)
00085         self._widget.btn_position.setIcon(self.CONTROLLER_OFF_ICON)
00086         self._widget.btn_position.setChecked(False)
00087         self.change_ctrl( "stop" )
00088         self._widget.btn_stop.setEnabled(True)
00089 
00090     def on_valve_ctrl_clicked_(self):
00091         """
00092         Switch to valve control
00093         """
00094         self._widget.btn_valve.setEnabled(False)
00095         if not self._widget.btn_valve.isChecked():
00096             self._widget.btn_valve.setIcon(self.CONTROLLER_ON_ICON)
00097             self._widget.btn_valve.setChecked(True)
00098             self._widget.btn_position.setIcon(self.CONTROLLER_OFF_ICON)
00099             self._widget.btn_position.setChecked(False)
00100             rospy.loginfo("Valve checked: " + str(self._widget.btn_valve.isChecked()))
00101             self.change_ctrl( "valve" )
00102         else:
00103             self._widget.btn_valve.setIcon(self.CONTROLLER_OFF_ICON)
00104             self._widget.btn_valve.setChecked(False)
00105             rospy.loginfo("Valve checked: " + str(self._widget.btn_valve.isChecked()))
00106             self.change_ctrl( "stop" )
00107         self._widget.btn_valve.setEnabled(True)
00108 
00109     def on_position_ctrl_clicked_(self):
00110         """
00111         Switch to position control
00112         """
00113         self._widget.btn_position.setEnabled(False)
00114         if not self._widget.btn_position.isChecked():
00115             self._widget.btn_position.setIcon(self.CONTROLLER_ON_ICON)
00116             self._widget.btn_position.setChecked(True)
00117             self._widget.btn_valve.setIcon(self.CONTROLLER_OFF_ICON)
00118             self._widget.btn_valve.setChecked(False)
00119             rospy.loginfo("Position checked: " + str(self._widget.btn_position.isChecked()))
00120             self.change_ctrl( "position" )
00121         else:
00122             self._widget.btn_position.setIcon(self.CONTROLLER_OFF_ICON)
00123             self._widget.btn_position.setChecked(False)
00124             rospy.loginfo("Position checked: " + str(self._widget.btn_position.isChecked()))
00125             self.change_ctrl( "stop" )
00126         self._widget.btn_position.setEnabled(True)
00127 
00128     def change_ctrl(self, controller):
00129         """
00130         Switch controller type
00131         """
00132         success = True
00133         list_controllers = rospy.ServiceProxy('pr2_controller_manager/list_controllers', ListControllers)
00134         try:
00135             resp1 = list_controllers()
00136         except rospy.ServiceException:
00137             success = False
00138 
00139         if success:
00140             current_controllers = []
00141             all_loaded_controllers = resp1.controllers
00142             for state,tmp_contrl in zip(resp1.state,resp1.controllers):
00143                 if state == "running":
00144                     current_controllers.append(tmp_contrl)
00145 
00146             controllers_to_start = self.controllers[controller]
00147 
00148             load_controllers = rospy.ServiceProxy('pr2_controller_manager/load_controller', LoadController)
00149             for load_control in controllers_to_start:
00150                 if load_control not in all_loaded_controllers:
00151                     try:
00152                         resp1 = load_controllers(load_control)
00153                     except rospy.ServiceException:
00154                         success = False
00155                     if not resp1.ok:
00156                         success = False
00157 
00158             switch_controllers = rospy.ServiceProxy('pr2_controller_manager/switch_controller', SwitchController)
00159             try:
00160                 resp1 = switch_controllers(controllers_to_start, current_controllers, SwitchController._request_class.BEST_EFFORT)
00161             except rospy.ServiceException:
00162                 success = False
00163 
00164             if not resp1.ok:
00165                 success = False
00166 
00167         if not success:
00168             rospy.logwarn("Failed to change some of the controllers. This is normal if this is not a 5 finger hand.")
00169 
00170     def _unregisterPublisher(self):
00171         if self._publisher is not None:
00172             self._publisher.unregister()
00173             self._publisher = None
00174 
00175     def shutdown_plugin(self):
00176         self._unregisterPublisher()
00177 
00178     def save_settings(self, global_settings, perspective_settings):
00179         pass
00180 
00181     def restore_settings(self, global_settings, perspective_settings):
00182         pass
00183 


sr_gui_change_muscle_controllers
Author(s): Ugo Cupcic
autogenerated on Fri Aug 28 2015 13:17:10