arm_cart_control_interface.py
Go to the documentation of this file.
00001 #! /usr/bin/python
00002 
00003 import sys
00004 from PyQt4 import QtCore, QtGui, uic
00005 import functools
00006 
00007 import roslib
00008 roslib.load_manifest("rospy")
00009 roslib.load_manifest("std_msgs")
00010 roslib.load_manifest("std_srvs")
00011 import rospy
00012 from std_msgs.msg import String
00013 from std_srvs.srv import Empty, EmptyResponse
00014 
00015 from arm_cart_control_gui import Ui_Frame as QTArmControlGUIFrame
00016 
00017 MOVE_BUTTONS = ['translate_up', 
00018                 'translate_down',
00019                 'translate_left', 
00020                 'translate_right', 
00021                 'translate_in', 
00022                 'translate_out',
00023                 'rotate_x_pos', 
00024                 'rotate_x_neg', 
00025                 'rotate_y_pos', 
00026                 'rotate_y_neg', 
00027                 'rotate_z_pos', 
00028                 'rotate_z_neg'] 
00029 
00030 TEXT_BUTTONS = ['reset_rotation']
00031 
00032 BUTTON_STYLESHEET = """image: url(:/resources/%s_%s.png);
00033                        background-image: url(:/resources/empty.png);"""
00034 MONITOR_RATE = 20.
00035 
00036 class ArmCartControlGUIFrame(QtGui.QFrame):
00037     def __init__(self):
00038         super(ArmCartControlGUIFrame, self).__init__()
00039         self.enable_buttons = False
00040         self.disable_buttons = False
00041         self.set_ctrl_name = None
00042         self.set_status = None
00043         self.hide_button = None
00044         self.show_button = None
00045 
00046         self.button_clk_pub = rospy.Publisher("/arm_ctrl_gui/button_clk", String)
00047         self.buttons_enable_srv = rospy.Service("/arm_ctrl_gui/buttons_enable", Empty, 
00048                                                 self._buttons_enable_cb)
00049         self.buttons_disable_srv = rospy.Service("/arm_ctrl_gui/buttons_disable", Empty,
00050                                                  self._buttons_disable_cb)
00051         self.set_ctrl_name_sub = rospy.Subscriber("/arm_ctrl_gui/set_controller_name", String,
00052                                                   self._set_ctrl_name_cb)
00053         self.set_status_sub = rospy.Subscriber("/arm_ctrl_gui/set_status", String,
00054                                                self._set_status_cb)
00055         self.hide_button_sub = rospy.Subscriber("/arm_ctrl_gui/hide_button", String,
00056                                                 self._hide_button_cb)
00057         self.show_button_sub = rospy.Subscriber("/arm_ctrl_gui/show_button", String,
00058                                                 self._show_button_cb)
00059 
00060         self.init_ui()
00061 
00062     def init_ui(self):
00063         self.ui = QTArmControlGUIFrame()
00064         self.ui.setupUi(self)
00065         self.buttons_enabled()
00066         for button in MOVE_BUTTONS + TEXT_BUTTONS:
00067             _publish_button_clk = functools.partial(self._publish_button_clk, button)
00068             exec("self.ui.%s.clicked.connect(_publish_button_clk)" % button)
00069 
00070         self.monitor_timer = QtCore.QTimer(self)
00071         QtCore.QObject.connect(self.monitor_timer, QtCore.SIGNAL("timeout()"), self.monitor_cb)
00072         self.monitor_timer.start(MONITOR_RATE)
00073 
00074     def _buttons_enable_cb(self, req):
00075         self.enable_buttons = True
00076         return EmptyResponse()
00077 
00078     def _buttons_disable_cb(self, req):
00079         self.disable_buttons = True
00080         return EmptyResponse()
00081 
00082     def _publish_button_clk(self, button):
00083         self.button_clk_pub.publish(button)
00084 
00085     def _set_ctrl_name_cb(self, msg):
00086         self.set_ctrl_name = msg.data
00087 
00088     def _set_status_cb(self, msg):
00089         self.set_status = msg.data
00090 
00091     def _hide_button_cb(self, msg):
00092         self.hide_button = msg.data
00093 
00094     def _show_button_cb(self, msg):
00095         self.show_button = msg.data
00096 
00097     def monitor_cb(self):
00098         if self.enable_buttons:
00099             self.buttons_enabled(True)
00100             self.enable_buttons = False
00101         if self.disable_buttons:
00102             self.buttons_enabled(False)
00103             self.disable_buttons = False
00104         if self.set_ctrl_name is not None:
00105             self.ui.controller_name.setText(self.set_ctrl_name)
00106             self.set_ctrl_name = None
00107         if self.set_status is not None:
00108             self.ui.status_text.setText(self.set_status)
00109             self.set_status = None
00110         if self.hide_button is not None:
00111             exec("self.ui.%s.hide()" % self.hide_button)
00112             self.hide_button = None
00113         if self.show_button is not None:
00114             exec("self.ui.%s.show()" % self.show_button)
00115             self.show_button = None
00116 
00117     def buttons_enabled(self, enabled=True):
00118         for button in MOVE_BUTTONS:
00119             exec("cur_button = self.ui.%s" % button)
00120             if enabled:
00121                 cur_button.setEnabled(True)
00122                 cur_button.setStyleSheet(BUTTON_STYLESHEET % (button, 'on'))
00123             else:
00124                 cur_button.setDisabled(True)
00125                 cur_button.setStyleSheet(BUTTON_STYLESHEET % (button, 'off'))
00126         for button in TEXT_BUTTONS:
00127             exec("cur_button = self.ui.%s" % button)
00128             if enabled:
00129                 cur_button.setEnabled(True)
00130             else:
00131                 cur_button.setDisabled(True)
00132 
00133 def main():
00134     rospy.init_node("arm_cart_control_interface")
00135     app = QtGui.QApplication(sys.argv)
00136     frame = ArmCartControlGUIFrame()
00137     frame.show()
00138     sys.exit(app.exec_())
00139 
00140 if __name__ == "__main__":
00141     main()


hrl_ellipsoidal_control
Author(s): Kelsey Hawkins
autogenerated on Wed Nov 27 2013 11:41:49