00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011 #include <vector>
00012 #include <string>
00013 #include <fstream>
00014
00015 #include <QPushButton>
00016 #include <QHBoxLayout>
00017 #include <QString>
00018 #include <QFileDialog>
00019 #include <QSlider>
00020 #include <QLabel>
00021 #include <QGroupBox>
00022 #include <QComboBox>
00023 #include <QCheckBox>
00024
00025 #include <or_msgs/OrLearnCommand.h>
00026 #include "Modules/ORLearningModule.h"
00027
00028 #include "../ImageMessagesDisplay/ImageSourceSelector.h"
00029
00030 #include "ObjectLearningControl.h"
00031
00032 #define THIS ObjectLearningControl
00033
00034 using namespace puma2;
00035
00036 THIS::THIS ( ros::NodeHandle *nh, QWidget *parent ) : QWidget ( parent )
00037 {
00038 m_Ready = false;
00039
00040
00041 QGridLayout* mainLayout = new QGridLayout();
00042
00043
00044 QSlider* thresholdSlider = new QSlider ( Qt::Horizontal );
00045 thresholdSlider->setRange ( 0, 100 );
00046 thresholdSlider->setTickPosition ( QSlider::TicksBothSides );
00047 QLabel* thresholdLabel = new QLabel();
00048 QHBoxLayout* thresholdSliderLayout = new QHBoxLayout();
00049 thresholdSliderLayout->addWidget ( thresholdSlider );
00050 thresholdSliderLayout->addWidget ( thresholdLabel );
00051 QGroupBox* thresholdSliderGroupBox = new QGroupBox ( "Background deletion threshold" );
00052 thresholdSliderGroupBox->setLayout ( thresholdSliderLayout );
00053 mainLayout->addWidget ( thresholdSliderGroupBox, 0, 0, 2, 1 );
00054
00055
00056 QSlider* openSlider = new QSlider ( Qt::Horizontal );
00057 openSlider->setRange ( 0, 50 );
00058 openSlider->setTickPosition ( QSlider::TicksBothSides );
00059 QLabel* openLabel = new QLabel();
00060 QHBoxLayout* openSliderLayout = new QHBoxLayout();
00061 openSliderLayout->addWidget ( openSlider );
00062 openSliderLayout->addWidget ( openLabel );
00063 QGroupBox* openSliderGroupBox = new QGroupBox ( "Mask open radius" );
00064 openSliderGroupBox->setLayout ( openSliderLayout );
00065 mainLayout->addWidget ( openSliderGroupBox, 0, 1, 2, 1 );
00066
00067
00068 QSlider* borderSlider = new QSlider ( Qt::Horizontal );
00069 borderSlider->setRange ( 0, 50 );
00070 borderSlider->setTickPosition ( QSlider::TicksBothSides );
00071 QLabel* borderLabel = new QLabel();
00072 QHBoxLayout* borderSliderLayout = new QHBoxLayout();
00073 borderSliderLayout->addWidget ( borderSlider );
00074 borderSliderLayout->addWidget ( borderLabel );
00075 QGroupBox* borderSliderGroupBox = new QGroupBox ( "Additional border" );
00076 borderSliderGroupBox->setLayout ( borderSliderLayout );
00077 mainLayout->addWidget ( borderSliderGroupBox, 0, 2, 2, 1 );
00078
00079
00080 QCheckBox* isolateCheckbox = new QCheckBox ( "Single segment" );
00081 mainLayout->addWidget ( isolateCheckbox, 1, 3 );
00082
00083
00084 ImageSourceSelector* sourceSelector = new ImageSourceSelector ( ImageSources::TopCamera, this, ImageSources::TopCamera, ImageSources::SourceId ( 99 ) );
00085 setCameraId ( ImageSources::TopCamera );
00086 connect ( sourceSelector, SIGNAL ( sourceSelected ( ImageSources::SourceId ) ), this, SLOT ( setCameraId ( ImageSources::SourceId ) ) );
00087 mainLayout->addWidget ( sourceSelector, 0, 3 );
00088
00089
00090 grabBackgroundButton = new QPushButton ( "Grab background" );
00091 grabForegroundButton = new QPushButton ( "Grab foreground" );
00092
00093 mainLayout->addWidget ( grabBackgroundButton, 0, 4 );
00094 mainLayout->addWidget ( grabForegroundButton, 1, 4 );
00095
00096 loadBackgroundButton = new QPushButton ( "Load background" );
00097 loadForegroundButton = new QPushButton ( "Load foreground" );
00098
00099 mainLayout->addWidget ( loadBackgroundButton, 0, 5 );
00100 mainLayout->addWidget ( loadForegroundButton, 1, 5 );
00101
00102 mainLayout->setColumnStretch ( 0, 2 );
00103 mainLayout->setColumnStretch ( 1, 2 );
00104 mainLayout->setColumnStretch ( 2, 1 );
00105 mainLayout->setColumnStretch ( 3, 1 );
00106
00107 setLayout ( mainLayout );
00108
00109 connect ( grabBackgroundButton , SIGNAL ( clicked() ), this, SLOT ( grabBackgroundImage() ) );
00110 connect ( grabForegroundButton , SIGNAL ( clicked() ), this, SLOT ( grabForegroundImage() ) );
00111
00112 connect ( loadBackgroundButton , SIGNAL ( clicked() ), this, SLOT ( loadBackgroundImage() ) );
00113 connect ( loadForegroundButton , SIGNAL ( clicked() ), this, SLOT ( loadForegroundImage() ) );
00114
00115 connect ( thresholdSlider, SIGNAL ( valueChanged ( int ) ), thresholdLabel, SLOT ( setNum ( int ) ) );
00116 connect ( thresholdSlider, SIGNAL ( valueChanged ( int ) ), this, SLOT ( setThreshold ( int ) ) );
00117
00118 connect ( openSlider, SIGNAL ( valueChanged ( int ) ), openLabel, SLOT ( setNum ( int ) ) );
00119 connect ( openSlider, SIGNAL ( valueChanged ( int ) ), this, SLOT ( setOpenRadius ( int ) ) );
00120
00121 connect ( borderSlider, SIGNAL ( valueChanged ( int ) ), borderLabel, SLOT ( setNum ( int ) ) );
00122 connect ( borderSlider, SIGNAL ( valueChanged ( int ) ), this, SLOT ( setBorderSize ( int ) ) );
00123
00124 connect ( isolateCheckbox, SIGNAL ( stateChanged ( int ) ), this, SLOT ( setIsolateLargestSegment ( int ) ) );
00125
00126 thresholdSlider->setValue ( 25 );
00127 thresholdSlider->setTracking ( false );
00128
00129 openSlider->setValue ( 15 );
00130 openSlider->setTracking ( false );
00131
00132 borderSlider->setValue ( 5 );
00133 borderSlider->setTracking ( false );
00134
00135 isolateCheckbox->setCheckState ( Qt::Checked );
00136
00137 m_LastImageFolder = "/images/ObjectRecognition";
00138
00139
00140 m_ORLearnCommandPublisher = nh->advertise<or_msgs::OrLearnCommand>("/or/learn_commands", 10);
00141 m_Ready = true;
00142 }
00143
00144
00145 THIS::~THIS() {}
00146
00147 void THIS::setCameraId ( ImageSources::SourceId cameraId )
00148 {
00149
00150 m_CameraId = cameraId;
00151 }
00152
00153 void THIS::setIsolateLargestSegment ( int state )
00154 {
00155 or_msgs::OrLearnCommand learnCommandMsg;
00156 learnCommandMsg.command = ORLearningModule::SetIsolateLargestSegment;
00157
00158 if ( state == Qt::Checked ) {
00159 learnCommandMsg.string_value = "true";
00160 } else if ( state == Qt::Unchecked ) {
00161 learnCommandMsg.string_value = "false";
00162 }
00163
00164 if(m_Ready)
00165 {
00166 m_ORLearnCommandPublisher.publish(learnCommandMsg);
00167 }
00168 }
00169
00170
00171 void THIS::setThreshold ( int value )
00172 {
00173 if(m_Ready)
00174 {
00175 or_msgs::OrLearnCommand learnCommandMsg;
00176 learnCommandMsg.command = ORLearningModule::SetDifferenceThreshold;
00177 learnCommandMsg.int_value = value;
00178 m_ORLearnCommandPublisher.publish(learnCommandMsg);
00179 }
00180 }
00181
00182 void THIS::setOpenRadius ( int value )
00183 {
00184 if(m_Ready)
00185 {
00186 or_msgs::OrLearnCommand learnCommandMsg;
00187 learnCommandMsg.command = ORLearningModule::SetOpenRadius;
00188 learnCommandMsg.int_value = value;
00189 m_ORLearnCommandPublisher.publish(learnCommandMsg);
00190 }
00191 }
00192
00193 void THIS::setBorderSize ( int value )
00194 {
00195 if(m_Ready)
00196 {
00197 or_msgs::OrLearnCommand learnCommandMsg;
00198 learnCommandMsg.command = ORLearningModule::SetBorderSize;
00199 learnCommandMsg.int_value = value;
00200 m_ORLearnCommandPublisher.publish(learnCommandMsg);
00201 }
00202 }
00203
00204 void THIS::grabBackgroundImage()
00205 {
00206 if(m_Ready)
00207 {
00208 or_msgs::OrLearnCommand learnCommandMsg;
00209 learnCommandMsg.command = ORLearningModule::GrabBackgroundImage;
00210
00211 m_ORLearnCommandPublisher.publish(learnCommandMsg);
00212 }
00213 }
00214
00215 void THIS::grabForegroundImage()
00216 {
00217 if(m_Ready)
00218 {
00219 or_msgs::OrLearnCommand learnCommandMsg;
00220 learnCommandMsg.command = ORLearningModule::GrabForegroundImage;
00221
00222 m_ORLearnCommandPublisher.publish(learnCommandMsg);
00223 }
00224 }
00225
00226 void THIS::loadBackgroundImage()
00227 {
00228 QStringList files = QFileDialog::getOpenFileNames ( this, tr ( "Load Image" ), m_LastOpenPath );
00229
00230 for ( int i = 0; i < files.size(); i++ )
00231 {
00232 QString file=files.at ( i );
00233 QDir fileDir ( file );
00234 fileDir.cdUp();
00235 m_LastOpenPath = fileDir.absolutePath();
00236
00237 if(m_Ready)
00238 {
00239 or_msgs::OrLearnCommand learnCommandMsg;
00240 learnCommandMsg.command = ORLearningModule::LoadBackgroundImage;
00241 learnCommandMsg.string_value = file.toStdString();
00242 m_ORLearnCommandPublisher.publish(learnCommandMsg);
00243 }
00244 }
00245 }
00246
00247 void THIS::loadForegroundImage()
00248 {
00249 QStringList files = QFileDialog::getOpenFileNames ( this, tr ( "Load Image" ), m_LastOpenPath );
00250
00251 for ( int i = 0; i < files.size(); i++ )
00252 {
00253 QString file=files.at ( i );
00254 QDir fileDir ( file );
00255 fileDir.cdUp();
00256 m_LastOpenPath = fileDir.absolutePath();
00257
00258 if(m_Ready)
00259 {
00260 or_msgs::OrLearnCommand learnCommandMsg;
00261 learnCommandMsg.command = ORLearningModule::LoadForegroundImage;
00262 learnCommandMsg.string_value = file.toStdString();
00263 m_ORLearnCommandPublisher.publish(learnCommandMsg);
00264 }
00265 }
00266 }
00267
00268
00269 #undef THIS