joint_slider.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright 2012 Shadow Robot Company Ltd.
00004 #
00005 # This program is free software: you can redistribute it and/or modify it
00006 # under the terms of the GNU General Public License as published by the Free
00007 # Software Foundation, either version 2 of the License, or (at your option)
00008 # any later version.
00009 #
00010 # This program is distributed in the hope that it will be useful, but WITHOUT
00011 # ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
00012 # FITNESS FOR A PARTICULAR PURPOSE.  See the GNU General Public License for
00013 # more details.
00014 #
00015 # You should have received a copy of the GNU General Public License along
00016 # with this program.  If not, see <http://www.gnu.org/licenses/>.
00017 #
00018 
00019 import os
00020 import sys
00021 
00022 import roslib
00023 roslib.load_manifest('sr_gui_joint_slider')
00024 import rospy
00025 
00026 from xml.etree import ElementTree as ET
00027 
00028 from qt_gui.plugin import Plugin
00029 from python_qt_binding import loadUi
00030 
00031 from QtCore import QEvent, QObject, Qt, QTimer, Slot
00032 from QtGui import QWidget, QShortcut, QMessageBox, QFrame
00033 from pr2_mechanism_msgs.srv import ListControllers, SwitchController, LoadController
00034 
00035 from sr_gui_joint_slider.jointSlider import JointController, Joint, CANHandSlider, EtherCATHandSlider, ArmSlider, CANHandSelectionSlider, EtherCATSelectionSlider, ArmSelectionSlider
00036 from etherCAT_hand_lib import EtherCAT_Hand_Lib
00037 from shadowhand_ros import ShadowHand_ROS
00038 
00039 class SrGuiJointSlider(Plugin):
00040 
00041     def __init__(self, context):
00042         super(SrGuiJointSlider, self).__init__(context)
00043         self.setObjectName('SrGuiJointSlider')
00044 
00045         self._widget = QWidget()
00046 
00047         ui_file = os.path.join(os.path.dirname(os.path.realpath(__file__)), '../../uis/SrJointSlider.ui')
00048         loadUi(ui_file, self._widget)
00049 
00050         self._widget.setObjectName('SrJointSliderUi')
00051         context.add_widget(self._widget)
00052 
00053         #read the xml configuration file
00054         config_file = os.path.join(os.path.dirname(os.path.realpath(__file__)), '../../model/slide_joints.xml')
00055         self.tree = ET.ElementTree()
00056         self.tree.parse(config_file)
00057         self.robots = None
00058 
00059         self.sliders = list()
00060         self.selection_slider = None
00061 
00062         robot_types = self.get_robot_types(self.tree)
00063         self._widget.comboBox.addItems(robot_types)
00064         self._widget.comboBox.setCurrentIndex(-1)
00065 
00066         self.is_active = True
00067         self.robot_lib_CAN = None
00068         self.robot_lib_eth = None
00069 
00070         self._widget.comboBox.activated.connect(self.on_robot_type_changed_)
00071         self._widget.reloadButton.pressed.connect(self.on_reload_button_cicked_)
00072         self._widget.refreshButton.pressed.connect(self.on_refresh_button_cicked_)
00073         self._widget.sliderReleaseCheckBox.stateChanged.connect(self.on_slider_release_checkbox_clicked_)
00074 
00075     def _unregister(self):
00076         if self.robot_lib_eth is not None:
00077             self.robot_lib_eth.on_close()
00078 
00079     def shutdown_plugin(self):
00080         self._unregister()
00081 
00082     def save_settings(self, global_settings, perspective_settings):
00083         pass
00084 
00085     def restore_settings(self, global_settings, perspective_settings):
00086         pass
00087 
00088     def get_robot_types(self, config):
00089         if sys.version_info < (2, 7):
00090             self.robots = list(config.getiterator("robot"))
00091         else:
00092             self.robots = list(config.iter("robot"))
00093         robot_types = list()
00094         for element in self.robots:
00095             robot_types.append(element.attrib["name"])
00096         return robot_types
00097 
00098     def on_robot_type_changed_(self):
00099         #We first read the config from the file into a joints list
00100         j = self.robots[self._widget.comboBox.currentIndex()].find("joints")
00101         if sys.version_info < (2, 7):
00102             config_joints = list(j.getiterator("joint"))
00103         else:
00104             #For Python version 2.7 and later
00105             config_joints = list(j.iter("joint"))
00106 
00107         #Read the joints configuration
00108         self.joints = list()
00109         for config_joint in config_joints:
00110             if sys.version_info < (2, 7):
00111                 config_joint_controllers = list(config_joint.getiterator("controller"))
00112             else:
00113                 config_joint_controllers = list(config_joint.iter("controller"))
00114             joint_controllers = list()
00115             for config_controller in config_joint_controllers:
00116                 name = config_controller.attrib["name"]
00117                 command_topic = config_controller.findtext("command_topic")
00118                 msg_type = config_controller.findtext("msg_type")
00119                 min = int(config_controller.findtext("min"))
00120                 max = int(config_controller.findtext("max"))
00121                 controller = JointController(name, command_topic, msg_type, min, max)
00122                 joint_controllers.append(controller)
00123             name = config_joint.attrib["name"]
00124             joint = Joint(name, joint_controllers)
00125             self.joints.append(joint)
00126 
00127         #Clear existing slider widgets from layout
00128         self.delete_old_sliders_()
00129 
00130         #Load the correct robot library
00131         self.load_robot_library_()
00132         
00133         self._widget.sliderReleaseCheckBox.setCheckState(Qt.Unchecked)
00134 
00135         if self.is_active:
00136             #Create and load the new slider widgets
00137             self.load_new_sliders_()
00138             
00139         self._widget.reloadButton.setEnabled(True)
00140 
00141     def on_reload_button_cicked_(self):
00142         #Clear existing slider widgets from layout
00143         self.delete_old_sliders_()
00144 
00145         #Load the correct robot library
00146         self.load_robot_library_()
00147         
00148         self._widget.sliderReleaseCheckBox.setCheckState(Qt.Unchecked)
00149 
00150         if self.is_active:
00151             #Create and load the new slider widgets
00152             self.load_new_sliders_()
00153     
00154     def on_refresh_button_cicked_(self):
00155         #Call refresh for every slider
00156         for slider in self.sliders:
00157             slider.refresh()
00158     
00159     def on_slider_release_checkbox_clicked_(self, state):
00160         if state == Qt.Checked:
00161             #Call set_new_slider_behaviour for every slider
00162             # the tracking behaviour will be set to false
00163             for slider in self.sliders:
00164                 slider.set_new_slider_behaviour(False)
00165         else:
00166             #Call set_new_slider_behaviour for every slider
00167             for slider in self.sliders:
00168                 slider.set_new_slider_behaviour(True)
00169             
00170         
00171 
00172     def delete_old_sliders_(self):
00173         #Clear existing slider widgets from layout
00174         for old_slider in self.sliders:
00175             self._widget.horizontalLayout.removeWidget(old_slider)
00176             old_slider.close()
00177             old_slider.deleteLater()
00178 
00179         #Empty the slider list
00180         self.sliders = list()
00181 
00182         if(self.selection_slider is not None):
00183             self._widget.horizontalLayout.removeWidget(self.selection_slider)
00184             self.selection_slider.close()
00185             self.selection_slider.deleteLater()
00186             self.selection_slider = None
00187 
00188     def load_robot_library_(self):
00189         #Load the correct robot library
00190         if self._widget.comboBox.currentText() in ["CAN Hand", "Arm"]:
00191             self.is_active = True
00192             if self.robot_lib_CAN is None:
00193                 self.robot_lib_CAN = ShadowHand_ROS()
00194         elif self._widget.comboBox.currentText() == "EtherCAT Hand":
00195             self.is_active = True
00196             if self.robot_lib_eth is not None:
00197                 self.robot_lib_eth.on_close()
00198                 self.robot_lib_eth = None
00199             if self.robot_lib_eth is None:
00200                 self.robot_lib_eth = EtherCAT_Hand_Lib()
00201                 if not self.robot_lib_eth.activate_joint_states():
00202                     btn_pressed = QMessageBox.warning(self._widget, "Warning", "The EtherCAT Hand node doesn't seem to be running. Try to reload the sliders when it is.")
00203                     self.is_active = False
00204                     if self.robot_lib_eth is not None:
00205                         self.robot_lib_eth.on_close()
00206                         self.robot_lib_eth = None
00207         else:
00208             rospy.logwarn("Unknown robot name: " + self._widget.comboBox.currentText())
00209 
00210     def load_new_sliders_(self):
00211         #Create the new slider widgets
00212         self.sliders = list()
00213         for joint in self.joints:
00214             slider = None
00215             if self._widget.comboBox.currentText() == "CAN Hand":
00216                 slider = CANHandSlider(joint, '../../uis/Slider.ui', self.robot_lib_CAN, self, self._widget.scrollAreaWidgetContents)
00217             elif self._widget.comboBox.currentText() == "EtherCAT Hand":
00218                 try:
00219                     slider = EtherCATHandSlider(joint, '../../uis/Slider.ui', self.robot_lib_eth, self, self._widget.scrollAreaWidgetContents)
00220                 except Exception, e:
00221                     rospy.loginfo(e)
00222             elif self._widget.comboBox.currentText() == "Arm":
00223                 slider = ArmSlider(joint, '../../uis/Slider.ui', self.robot_lib_CAN, self, self._widget.scrollAreaWidgetContents)
00224             else:
00225                 rospy.logwarn("Unknown robot name: " + self._widget.comboBox.currentText())
00226 
00227             if slider != None:
00228                 slider.setMaximumWidth(100)
00229                 #Load the new slider
00230                 self._widget.horizontalLayout.addWidget(slider)
00231                 #Put the slider in the list
00232                 self.sliders.append(slider)
00233 
00234         #Create the slider to move all the selected joint sliders
00235         if self._widget.comboBox.currentText() == "CAN Hand":
00236             self.selection_slider = CANHandSelectionSlider("Change sel.", 0, 100, '../../uis/SelectionSlider.ui', self.robot_lib_CAN, self, self._widget.scrollAreaWidgetContents)
00237         elif self._widget.comboBox.currentText() == "EtherCAT Hand":
00238             self.selection_slider = EtherCATSelectionSlider("Change sel.", 0, 100, '../../uis/SelectionSlider.ui', self, self._widget.scrollAreaWidgetContents)
00239         elif self._widget.comboBox.currentText() == "Arm":
00240             self.selection_slider = ArmSelectionSlider("Change sel.", 0, 100, '../../uis/SelectionSlider.ui', self.robot_lib_CAN, self, self._widget.scrollAreaWidgetContents)
00241         else:
00242             rospy.logwarn("Unknown robot name: " + self._widget.comboBox.currentText())
00243 
00244         self.selection_slider.setMaximumWidth(100)
00245         self._widget.horizontalLayout.addWidget(self.selection_slider)


sr_gui_joint_slider
Author(s): Toni Oliver
autogenerated on Fri Jan 3 2014 12:07:23