caddy_plug.py
Go to the documentation of this file.
00001 '''
00002 Created on Sep 10, 2013
00003  \todo Add license information here
00004 @author: dnad
00005 '''
00006 import os
00007 import rospy
00008 
00009 from qt_gui.plugin import Plugin
00010 from python_qt_binding import loadUi, QtCore
00011 from caddy_gui import CaddyGui
00012 from std_msgs.msg import Float32MultiArray
00013 from std_msgs.msg import String, Int32
00014 from geometry_msgs.msg import Point
00015 
00016 class CaddyGuiROS(QtCore.QObject):
00017     
00018     def __init__(self, gui):
00019         QtCore.QObject.__init__(self)
00020         self._gui = gui;
00021         self._gui.bindHook(self)
00022         
00023     def setup(self):
00024         #Define event
00025         QtCore.QObject.connect(self, QtCore.SIGNAL("onDiverText"), self._gui.newChatMessage)
00026         QtCore.QObject.connect(self, QtCore.SIGNAL("onDiverDefaults"), self._gui.newDefaultMessage)
00027         QtCore.QObject.connect(self, QtCore.SIGNAL("onDiverOrigin"), self._gui.newOriginPosition)
00028         QtCore.QObject.connect(self, QtCore.SIGNAL("onManagerState"), self._gui.newManagerState)
00029         QtCore.QObject.connect(self, QtCore.SIGNAL("onPladyposInfo"), self._gui.newPladyposInfo)
00030         
00031         self.diverText = rospy.Subscriber("diver_text",String,
00032                             lambda data:
00033                                 self.emit(QtCore.SIGNAL("onDiverText"),data.data, "Diver"));
00034         self.defaultMsgs = rospy.Subscriber("diver_defaults",Int32,
00035                             lambda data:
00036                                 self.emit(QtCore.SIGNAL("onDiverDefaults"),data.data));
00037         self.diverOrigin = rospy.Subscriber("diver_origin",Point,
00038                             lambda data: 
00039                                 self.emit(QtCore.SIGNAL("onDiverOrigin"),data));
00040         self.managerState = rospy.Subscriber("usbl_current_state",Int32,
00041                             lambda data:
00042                                 self.emit(QtCore.SIGNAL("onManagerState"),data.data));
00043         self.pladyposInfo = rospy.Subscriber("pladypos_info",Float32MultiArray,
00044                             lambda data:
00045                                 self.emit(QtCore.SIGNAL("onPladyposInfo"),data.data));
00046             
00047         self.outText = rospy.Publisher("usbl_text", String);
00048         self.outDefaults = rospy.Publisher("usbl_defaults",Int32);
00049         self.outKml = rospy.Publisher("kml_file",String);
00050         self.outMode = rospy.Publisher("usbl_force_state",Int32);
00051         
00052     def sendText(self, text):
00053         data = String();
00054         data.data = text;
00055         self.outText.publish(data);
00056     
00057     def sendDefault(self, idx):
00058         data = Int32();
00059         data.data = idx;
00060         self.outDefaults.publish(data);
00061         
00062     def sendKml(self, path):
00063         data = String();
00064         data.data = path;
00065         self.outKml.publish(data);
00066         
00067     def setManagerState(self, state):
00068         data = Int32();
00069         data.data = state;
00070         self.outMode.publish(data);
00071               
00072     def unload(self):
00073         self.diverText.unregister();
00074         self.defaultMsgs.unregister();
00075         self.managerState.unregister();
00076         self.diverOrigin.unregister();       
00077         self.outText.unregister();
00078         self.outDefaults.unregister();
00079         self.outKml.unregister();
00080         self.outMode.unregister();
00081         self.pladyposInfo.unregister();
00082 
00083 class CaddyGuiPlug(Plugin):
00084 
00085     def __init__(self, context):
00086         super(CaddyGuiPlug, self).__init__(context)
00087         # Give QObjects reasonable names
00088         self.setObjectName('CaddyGuiPlug')
00089 
00090         # Process standalone plugin command-line arguments
00091         from argparse import ArgumentParser
00092         parser = ArgumentParser()
00093         # Add argument(s) to the parser.
00094         parser.add_argument("-q", "--quiet", action="store_true",
00095                       dest="quiet",
00096                       help="Put plugin in silent mode")
00097         args, unknowns = parser.parse_known_args(context.argv())
00098         if not args.quiet:
00099             print 'arguments: ', args
00100             print 'unknowns: ', unknowns
00101 
00102         # Create QWidget
00103         self._gui = CaddyGui()
00104         self._ros = CaddyGuiROS(self._gui)
00105         # Get path to UI file which is a sibling of this file
00106         # in this example the .ui and .py file are in the same folder
00107         ui_file = os.path.join(os.path.dirname(os.path.realpath(__file__)), 'resource/CaddyGui.ui')
00108         # Extend the widget with all attributes and children from UI file
00109         loadUi(ui_file, self._gui._widget)
00110         # Give QObjects reasonable names
00111         self._gui._widget.setObjectName('CaddyGui')
00112         self._gui.setup()
00113         self._ros.setup()
00114         
00115         # Show _widget.windowTitle on left-top of each plugin (when 
00116         # it's set in _widget). This is useful when you open multiple 
00117         # plugins at once. Also if you open multiple instances of your 
00118         # plugin at once, these lines add number to make it easy to 
00119         # tell from pane to pane.
00120         if context.serial_number() > 1:
00121             self._widget.setWindowTitle(self._widget.windowTitle() + (' (%d)' % context.serial_number()))
00122         # Add widget to the user interface
00123         context.add_widget(self._gui._widget)      
00124 
00125     def shutdown_plugin(self):
00126         # TODO unregister all publishers here
00127         self._gui.unload();
00128         self._ros.unload()
00129         pass
00130 
00131     def save_settings(self, plugin_settings, instance_settings):
00132         # TODO save intrinsic configuration, usually using:
00133         # instance_settings.set_value(k, v)
00134         pass
00135 
00136     def restore_settings(self, plugin_settings, instance_settings):
00137         # TODO restore intrinsic configuration, usually using:
00138         # v = instance_settings.value(k)
00139         pass
00140 
00141     #def trigger_configuration(self):
00142         # Comment in to signal that the plugin has a way to configure
00143         # This will enable a setting button (gear icon) in each dock widget title bar
00144         # Usually used to open a modal configuration dialog


caddy_ui
Author(s): Gyula NagyJane Doe
autogenerated on Fri Feb 7 2014 11:36:10