Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022 import sys
00023 import signal
00024
00025
00026 import rospy
00027 import rospkg
00028
00029
00030 from PyQt4 import QtGui, uic
00031
00032
00033 from opencv_tut.msg import valueMatrix
00034 pub = rospy.Publisher('opencv_tut/find_keypoints_gui', valueMatrix)
00035 class MyWindow(QtGui.QMainWindow):
00036 def __init__(self):
00037 super(MyWindow, self).__init__()
00038 self.rospack = rospkg.RosPack()
00039 path = self.rospack.get_path('opencv_tut')
00040 uic.loadUi(path + '/resources/gui_keypoints.ui', self)
00041 self.setMinMax()
00042 self.setLabels()
00043 self.setTick()
00044
00045 self.zero_zero_slider.valueChanged.connect(self.zero_zero_cb)
00046 self.zero_one_slider.valueChanged.connect(self.zero_one_cb)
00047 self.zero_two_slider.valueChanged.connect(self.zero_two_cb)
00048 self.one_zero_slider.valueChanged.connect(self.one_zero_cb)
00049 self.one_one_slider.valueChanged.connect(self.one_one_cb)
00050 self.one_two_slider.valueChanged.connect(self.one_two_cb)
00051 self.two_zero_slider.valueChanged.connect(self.two_zero_cb)
00052 self.two_one_slider.valueChanged.connect(self.two_one_cb)
00053 self.two_two_slider.valueChanged.connect(self.two_two_cb)
00054 self.alpha_slider.valueChanged.connect(self.alpha_cb)
00055 self.beta_slider.valueChanged.connect(self.beta_cb)
00056 self.Detector_choice.currentIndexChanged.connect(self.Detector_choice_cb)
00057
00058 self.Contrast_tick.stateChanged.connect(self.Contrast_cb)
00059 self.Keypoints_tick.stateChanged.connect(self.Keypoints_cb)
00060 self.Original_tick.stateChanged.connect(self.Original_cb)
00061 self.Sharpen_tick.stateChanged.connect(self.Sharpen_cb)
00062 self.Combined_tick.stateChanged.connect(self.Combined_cb)
00063
00064 self.show()
00065
00066 def setLabels(self):
00067 self.zero_zero_label.setText(str(0))
00068 self.zero_one_label.setText(str(-1))
00069 self.zero_two_label.setText(str(0))
00070 self.one_zero_label.setText(str(-1))
00071 self.one_one_label.setText(str(5))
00072 self.one_two_label.setText(str(-1))
00073 self.two_zero_label.setText(str(0))
00074 self.two_one_label.setText(str(-1))
00075 self.two_two_label.setText(str(0))
00076 self.alpha_value_label.setText(str(2.2))
00077 self.beta_value_label.setText(str(50))
00078
00079
00080 def setMinMax(self):
00081 self.zero_zero_slider.setMinimum(-100)
00082 self.zero_one_slider.setMinimum(-100)
00083 self.zero_two_slider.setMinimum(-100)
00084 self.one_zero_slider.setMinimum(-100)
00085 self.one_one_slider.setMinimum(-100)
00086 self.one_two_slider.setMinimum(-100)
00087 self.two_zero_slider.setMinimum(-100)
00088 self.two_one_slider.setMinimum(-100)
00089 self.two_two_slider.setMinimum(-100)
00090 self.alpha_slider.setMinimum(0)
00091 self.beta_slider.setMinimum(-200)
00092
00093 self.zero_zero_slider.setMaximum(100)
00094 self.zero_one_slider.setMaximum(100)
00095 self.zero_two_slider.setMaximum(100)
00096 self.one_zero_slider.setMaximum(100)
00097 self.one_one_slider.setMaximum(100)
00098 self.one_two_slider.setMaximum(100)
00099 self.two_zero_slider.setMaximum(100)
00100 self.two_one_slider.setMaximum(100)
00101 self.two_two_slider.setMaximum(100)
00102 self.alpha_slider.setMaximum(30)
00103 self.beta_slider.setMaximum(200)
00104
00105 self.zero_zero_slider.setValue(00)
00106 self.zero_one_slider.setValue(-10)
00107 self.zero_two_slider.setValue(0)
00108 self.one_zero_slider.setValue(-10)
00109 self.one_one_slider.setValue(50)
00110 self.one_two_slider.setValue(-10)
00111 self.two_zero_slider.setValue(0)
00112 self.two_one_slider.setValue(-10)
00113 self.two_two_slider.setValue(0)
00114 self.alpha_slider.setValue(22)
00115 self.beta_slider.setValue(50)
00116
00117 def setTick(self):
00118 self.Contrast_tick.setChecked(False)
00119 self.Keypoints_tick.setChecked(True)
00120 self.Original_tick.setChecked(False)
00121 self.Sharpen_tick.setChecked(False)
00122 self.Combined_tick.setChecked(False)
00123
00124 def Detector_choice_cb(self):
00125 value = self.Detector_choice.currentText()
00126 rospy.loginfo("Called: %s", value)
00127 msg = valueMatrix()
00128 msg.header.frame_id = str(value)
00129 pub.publish(msg)
00130
00131 def Contrast_cb(self):
00132 tick = self.Contrast_tick.checkState()
00133 self.pubTickMsg("Contrast", tick)
00134 rospy.loginfo("contrast: %s", tick)
00135
00136 def Keypoints_cb(self):
00137 tick = self.Keypoints_tick.checkState()
00138 self.pubTickMsg("Keypoints", tick)
00139 rospy.loginfo("keypoints: %s", tick)
00140
00141 def Original_cb(self):
00142 tick = self.Original_tick.checkState()
00143 self.pubTickMsg("Original", tick)
00144 rospy.loginfo("original: %s", tick)
00145
00146 def Combined_cb(self):
00147 tick = self.Combined_tick.checkState()
00148 self.pubTickMsg("Combined", tick)
00149 rospy.loginfo("Combined: %s", tick)
00150
00151 def Sharpen_cb(self):
00152 tick = self.Sharpen_tick.checkState()
00153 self.pubTickMsg("Sharpen", tick)
00154 rospy.loginfo("sharpen: %s", tick)
00155
00156 def zero_zero_cb(self):
00157 value_f = float(self.zero_zero_slider.value())
00158 value = float(value_f/10)
00159 self.zero_zero_label.setText(str(value))
00160 self.pubValMsg("zero_zero", value)
00161 rospy.loginfo("zero_zero %s", value)
00162
00163 def zero_one_cb(self):
00164 value_f = float(self.zero_one_slider.value())
00165 value = float(value_f/10)
00166 self.zero_one_label.setText(str(value))
00167 self.pubValMsg("zero_one", value)
00168 rospy.loginfo("zero_one%s", value)
00169
00170 def zero_two_cb(self):
00171 value_f = float(self.zero_two_slider.value())
00172 value = float(value_f/10)
00173 self.zero_two_label.setText(str(value))
00174 self.pubValMsg("zero_two", value)
00175 rospy.loginfo("zero_two%s", value)
00176
00177 def one_zero_cb(self):
00178 value_f = float(self.one_zero_slider.value())
00179 value = float(value_f/10)
00180 rospy.loginfo("value: %s" , value)
00181 self.one_zero_label.setText(str(value))
00182 self.pubValMsg("one_zero", value)
00183
00184 def one_one_cb(self):
00185 value_f = float(self.one_one_slider.value())
00186 value = float(value_f/10)
00187 self.one_one_label.setText(str(value))
00188 self.pubValMsg("one_one", value)
00189 rospy.loginfo("one_one%s", value)
00190
00191 def one_two_cb(self):
00192 value_f = float(self.one_two_slider.value())
00193 value = float(value_f/10)
00194 self.one_two_label.setText(str(value))
00195 self.pubValMsg("one_two", value)
00196 rospy.loginfo("one_two%s", value)
00197
00198 def two_zero_cb(self):
00199 value_f = float(self.two_zero_slider.value())
00200 value = float(value_f/10)
00201 self.two_zero_label.setText(str(value))
00202 self.pubValMsg("two_zero", value)
00203 rospy.loginfo("two_zero%s", value)
00204
00205 def two_one_cb(self):
00206 value_f = float(self.two_one_slider.value())
00207 value = float(value_f/10)
00208 self.two_one_label.setText(str(value))
00209 self.pubValMsg("two_one", value)
00210 rospy.loginfo("two_one%s", value)
00211
00212 def two_two_cb(self):
00213 value_f = float(self.two_two_slider.value())
00214 value = float(value_f/10)
00215 self.two_two_label.setText(str(value))
00216 self.pubValMsg("two_two", value)
00217 rospy.loginfo("two_two%s", value)
00218
00219 def alpha_cb(self):
00220 value = float(self.alpha_slider.value())
00221 value_dec = float(value/10)
00222 self.alpha_value_label.setText(str(value_dec))
00223 self.pubValMsg("alpha", value_dec)
00224
00225 def beta_cb(self):
00226 value = self.beta_slider.value()
00227 self.beta_value_label.setText(str(value))
00228 self.pubValMsg("beta", value)
00229
00230 def pubValMsg(self, name, value):
00231 msg = valueMatrix()
00232 msg.header.frame_id = name
00233 msg.value = value
00234 pub.publish(msg)
00235
00236 def pubTickMsg(self, name, tick):
00237 msg = valueMatrix()
00238 msg.header.frame_id = name
00239 msg.tick = tick
00240 pub.publish(msg)
00241
00242 if __name__ == '__main__':
00243 rospy.init_node('find_keypoints_gui')
00244 app = QtGui.QApplication(sys.argv)
00245 signal.signal(signal.SIGINT, signal.SIG_DFL)
00246 myWindow = MyWindow()
00247 sys.exit(app.exec_())