image_snapshot.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 import os
00004 
00005 import rospy
00006 import roslib
00007 
00008 roslib.load_manifest("jsk_pr2_startup")
00009 
00010 ##
00011 import std_srvs
00012 import std_msgs
00013 
00014 ##
00015 from qt_gui.plugin import Plugin
00016 from python_qt_binding import loadUi
00017 from python_qt_binding.QtGui import QWidget
00018 
00019 from python_qt_binding.QtGui import QLabel, QTreeWidget, QTreeWidgetItem, QVBoxLayout, QCheckBox, QWidget, QToolBar, QLineEdit, QPushButton
00020 from python_qt_binding.QtCore import Qt, QTimer
00021 
00022 class ImageSnapShotGUI(Plugin):
00023     def __init__(self, context):
00024         super(ImageSnapShotGUI, self).__init__(context)
00025         # Give QObjects reasonable names
00026         self.setObjectName('ImageSnapShotGUI')
00027 
00028         # Process standalone plugin command-line arguments
00029         from argparse import ArgumentParser
00030         parser = ArgumentParser()
00031         # Add argument(s) to the parser.
00032         parser.add_argument("-q", "--quiet", action="store_true",
00033                             dest="quiet",
00034                             help="Put plugin in silent mode")
00035         args, unknowns = parser.parse_known_args(context.argv())
00036         self._toolbar = QToolBar()
00037         self._toolbar.addWidget(QLabel('ImageSnapShot'))
00038 
00039         # Create a container widget and give it a layout
00040         self._container = QWidget()
00041         self._layout    = QVBoxLayout()
00042         self._container.setLayout(self._layout)
00043         self._layout.addWidget(self._toolbar)
00044 
00045         # Add a button for ....
00046         self._go_button = QPushButton('Head')
00047         self._go_button.clicked.connect(self._head)
00048         self._layout.addWidget(self._go_button)
00049 
00050         self._clear_button = QPushButton('L arm')
00051         self._clear_button.clicked.connect(self._larm)
00052         self._layout.addWidget(self._clear_button)
00053 
00054         self._clear_button = QPushButton('R arm')
00055         self._clear_button.clicked.connect(self._rarm)
00056         self._layout.addWidget(self._clear_button)
00057 
00058         # self._step_run_button.setStyleSheet('QPushButton {color: black}')
00059         context.add_widget(self._container)
00060 
00061         self._head_pub = rospy.Publisher('/head_snap/snapshot', std_msgs.msg.Empty)
00062         self._lhand_pub = rospy.Publisher('/lhand_snap/snapshot', std_msgs.msg.Empty)
00063         self._rhand_pub = rospy.Publisher('/rhand_snap/snapshot', std_msgs.msg.Empty)
00064 
00065     def _head(self):
00066         #go = rospy.ServiceProxy('/head_snap/snapshot', std_srvs.srv.Empty)
00067         #go()
00068         self._head_pub.publish(std_msgs.msg.Empty())
00069     def _larm(self):
00070         #go = rospy.ServiceProxy('/lhand_snap/snapshot', std_srvs.srv.Empty)
00071         #go()
00072         self._lhand_pub.publish(std_msgs.msg.Empty())
00073     def _rarm(self):
00074         #go = rospy.ServiceProxy('/rhand_snap/snapshot', std_srvs.srv.Empty)
00075         #go()
00076         self._rhand_pub.publish(std_msgs.msg.Empty())
00077 
00078     def shutdown_plugin(self):
00079         pass
00080     def save_settings(self, plugin_settings, instance_settings):
00081         pass
00082     def restore_settings(self, plugin_settings, instance_settings):
00083         pass


jsk_pr2_startup
Author(s):
autogenerated on Wed Sep 16 2015 10:32:17