ObjectRecognitionDisplay.cpp
Go to the documentation of this file.
00001 /*******************************************************************************
00002  *  ObjectRecognitionDisplay.cpp
00003  *
00004  *  (C) 2006 AG Aktives Sehen <agas@uni-koblenz.de>
00005  *           Universitaet Koblenz-Landau
00006  *
00007  *  Additional information:
00008  *  $Id: ObjectRecognitionDisplay.cpp 23656 2008-03-30 18:21:56Z dgossow $
00009  *******************************************************************************/
00010 
00011 #include <QGridLayout>
00012 #include <QLabel>
00013 #include <QMatrix>
00014 #include <QPixmap>
00015 #include <QSize>
00016 #include <QComboBox>
00017 #include <QCheckBox>
00018 #include <QPushButton>
00019 #include <QHBoxLayout>
00020 #include <QVBoxLayout>
00021 #include <QDockWidget>
00022 #include <QGroupBox>
00023 #include <QWidget>
00024 #include <QPushButton>
00025 #include <QVBoxLayout>
00026 #include <QString>
00027 #include <QTableWidget>
00028 #include <QHeaderView>
00029 #include <QFileDialog>
00030 #include <QGroupBox>
00031 #include <QLabel>
00032 #include <QMessageBox>
00033 #include <QComboBox>
00034 
00035 #include <or_msgs/OrCommand.h>
00036 
00037 #include "ObjectRecognitionDisplay.h"
00038 #include "Modules/ORControlModule.h"
00039 
00040 #include "Widgets/ImageMessagesDisplay/ImageSourceSelector.h"
00041 #include "Widgets/GLImageWidget/GLImageWidget.h"
00042 
00043 // TODO
00044 //#include "Architecture/Serializer/BinaryInStream.h"
00045 //#include "Architecture/Serializer/ExtendedInStream.h"
00046 
00047 // TODO
00048 //#include "Messages/ORObjectNamesM.h"
00049 //#include "Messages/GetImageM.h"
00050 //#include "Messages/ORObjectPropertiesM.h"
00051 //#include "Messages/ORCommandM.h"
00052 //#include "Messages/ORMatchResultM.h"
00053 //#include "Messages/ImageM.h"
00054 
00055 #include "Workers/Puma2/ThermalToColorOperator.h"
00056 #include "Workers/ImageSources/ImageSources.h"
00057 #include "Workers/ObjectRecognition/ObjectProperties.h"
00058 
00059 //included for debug Purposes
00060 #include <iostream>
00061 #include <fstream>
00062 
00063 #define THIS ObjectRecognitionDisplay
00064 
00065 using namespace std;
00066 using namespace puma2;
00067 
00068 
00069 THIS::THIS ( ros::NodeHandle *nh, QBoxLayout* checkboxLayout, QWidget* parent ) : QGLWidget ( parent )
00070 {
00071     m_Ready = false;
00072     m_LastOpenPath = "./objectProperties";
00073 
00074     QVBoxLayout* mainLayout = new QVBoxLayout();
00075 
00076     m_GlImageWidget = new GLImageWidget ( this );
00077     //mainLayout->addWidget ( m_GlImageWidget, 1 );
00078 
00079     //Add 'Grab Image' Widget
00080     QHBoxLayout* grabImageLayout = new QHBoxLayout();
00081     QWidget* grabImageContainer = new QWidget();
00082     grabImageContainer->setMaximumWidth ( 600 );
00083     grabImageContainer->setLayout ( grabImageLayout );
00084 
00085     //Image source selector
00086     ImageSourceSelector* sourceSelector = new ImageSourceSelector( ImageSources::TopCamera, this, ImageSources::TopCamera, ImageSources::SourceId(99) );
00087     setCameraId( ImageSources::TopCamera );
00088     connect( sourceSelector, SIGNAL( sourceSelected( ImageSources::SourceId ) ), this, SLOT( setCameraId( ImageSources::SourceId ) ) );
00089     //grabImageLayout->addWidget(sourceSelector);
00090 
00091     //'Grab Image' Button
00092     QPushButton* grabButton=new QPushButton ( "Grab Image" );
00093     grabImageLayout->addWidget ( grabButton );
00094     connect ( grabButton, SIGNAL ( clicked() ), this, SLOT ( grabImage() ) );
00095 
00096     QPushButton* loadButton=new QPushButton ( "Load Image" );
00097     grabImageLayout->addWidget ( loadButton );
00098     connect ( loadButton, SIGNAL ( clicked() ), this, SLOT ( loadImage() ) );
00099 
00100     QPushButton* startLoopButton=new QPushButton ( "Start Recognition Loop" );
00101     grabImageLayout->addWidget ( startLoopButton );
00102     connect ( startLoopButton, SIGNAL ( clicked() ), this, SLOT ( startLoop() ) );
00103 
00104     QPushButton* stopLoopButton=new QPushButton ( "Stop Recognition Loop" );
00105     grabImageLayout->addWidget ( stopLoopButton );
00106     connect ( stopLoopButton, SIGNAL ( clicked() ), this, SLOT ( stopLoop() ) );
00107 
00108     mainLayout->addWidget ( grabImageContainer );
00109 
00110 
00111     QGroupBox* groupBox1=new QGroupBox ( tr ( "Scene Image Features" ) );
00112 
00113     QVBoxLayout* checkboxLayout1=new QVBoxLayout();
00114     addCheckBox ( checkboxLayout1, m_OptionCheckBoxes, "boundingBoxes", "Bounding Boxes", true );
00115     addCheckBox ( checkboxLayout1, m_OptionCheckBoxes, "sceneAreas", "KeyPoint Area", false );
00116     addCheckBox ( checkboxLayout1, m_OptionCheckBoxes, "sceneArrows", "KeyPoint Orientation", false );
00117     addCheckBox ( checkboxLayout1, m_OptionCheckBoxes, "sceneCircles", "KeyPoint Circles", false );
00118     addCheckBox ( checkboxLayout1, m_OptionCheckBoxes, "sceneArrowsWithinOutline", "KeyPoints within projected outline", false );
00119     checkboxLayout1->setSpacing ( 0 );
00120     checkboxLayout1->setMargin ( 0 );
00121     checkboxLayout1->setContentsMargins ( 10,0,0,0 );
00122     groupBox1->setLayout ( checkboxLayout1 );
00123     checkboxLayout->addWidget ( groupBox1 );
00124 
00125 
00126     QGroupBox* groupBox2=new QGroupBox ( tr ( "Object matching" ) );
00127 
00128     QVBoxLayout* checkboxLayout2=new QVBoxLayout();
00129     addCheckBox ( checkboxLayout2, m_OptionCheckBoxes, "outline", "Object Outline", true );
00130     addCheckBox ( checkboxLayout2, m_OptionCheckBoxes, "stage1", "Stage 1 matches", false );
00131 
00132 
00133     addCheckBox ( checkboxLayout2, m_OptionCheckBoxes, "stage2", "Stage 2 matches", false );
00134 
00135     binChooserComboBox = new QComboBox();
00136     binChooserComboBox->setEnabled(false);
00137     checkboxLayout2->addWidget ( binChooserComboBox );
00138     connect ( binChooserComboBox,SIGNAL ( currentIndexChanged(int) ),this,SLOT ( optionsChanged() ) );
00139 
00140     addCheckBox ( checkboxLayout2, m_OptionCheckBoxes, "stage3", "Stage 3 matches", true );
00141     addCheckBox ( checkboxLayout2, m_OptionCheckBoxes, "scene", "Scene Matches", true );
00142     addCheckBox ( checkboxLayout2, m_OptionCheckBoxes, "object", "Object Matches", true );
00143     addCheckBox ( checkboxLayout2, m_OptionCheckBoxes, "areas", "KeyPoint Area", false );
00144     addCheckBox ( checkboxLayout2, m_OptionCheckBoxes, "arrows", "KeyPoint Orientation", true );
00145     addCheckBox ( checkboxLayout2, m_OptionCheckBoxes, "lines", "KeyPoint correspondences", true );
00146     checkboxLayout2->setSpacing ( 0 );
00147     groupBox2->setLayout ( checkboxLayout2 );
00148     checkboxLayout->addWidget ( groupBox2 );
00149     checkboxLayout->addStretch();
00150 
00151     //Add 'Objects' header
00152     m_ObjCheckboxLayout=new QVBoxLayout();
00153     m_ObjectsGroupBox=new QGroupBox ( "Objects (0)" );
00154     m_ObjCheckboxLayout->setSpacing ( 0 );
00155 
00156     //Add Objects List
00157     m_ObjectsList = new QTableWidget();
00158     m_ObjectsList->setColumnCount ( 3 );
00159     m_ObjectsList->setRowCount ( 0 );
00160     QStringList headerList;
00161     headerList << "" << "Name" << "Type";
00162     m_ObjectsList->setHorizontalHeaderLabels ( headerList );
00163 
00164     QTableWidgetItem *checkHeaderItem = new QTableWidgetItem();
00165     checkHeaderItem->setFlags ( Qt::ItemIsUserCheckable | Qt::ItemIsEnabled );
00166     checkHeaderItem->setCheckState ( Qt::Checked );
00167 
00168     m_ObjectsList->horizontalHeader()->setResizeMode ( 0, QHeaderView::Interactive );
00169     m_ObjectsList->horizontalHeader()->setResizeMode ( 1, QHeaderView::Interactive );
00170     m_ObjectsList->horizontalHeader()->setResizeMode ( 2, QHeaderView::Stretch );
00171     m_ObjectsList->verticalHeader()->hide();
00172     m_ObjectsList->setSelectionMode ( QAbstractItemView::NoSelection );
00173     m_ObjectsList->setSortingEnabled ( true );
00174     m_ObjCheckboxLayout->addWidget ( m_ObjectsList );
00175 
00176     connect ( m_ObjectsList, SIGNAL ( cellClicked ( int,int ) ), this ,SLOT ( cellClicked ( int,int ) ) );
00177 
00178     //Add load and delete Buttons
00179     QHBoxLayout* loadDeleteLayout = new QHBoxLayout();
00180     QPushButton* loadObjectButton = new QPushButton ( "Load" );
00181     loadDeleteLayout->addWidget ( loadObjectButton );
00182     m_DeleteObjectButton = new QPushButton ( "Delete" );;
00183     loadDeleteLayout->addWidget ( m_DeleteObjectButton );
00184     m_DeleteObjectButton->setEnabled ( false );
00185     QWidget* loadDeleteContainer = new QWidget();
00186     loadDeleteContainer->setLayout ( loadDeleteLayout );
00187     m_ObjCheckboxLayout->addWidget ( loadDeleteContainer );
00188     m_ObjectsGroupBox->setLayout ( m_ObjCheckboxLayout );
00189     checkboxLayout->addWidget ( m_ObjectsGroupBox );
00190     checkboxLayout->addStretch();
00191 
00192     //signal slot connections of load and delete Buttons
00193     connect ( loadObjectButton,SIGNAL ( clicked() ),this,SLOT ( loadObjectDialog() ) );
00194     connect ( m_DeleteObjectButton,SIGNAL ( clicked() ),this,SLOT ( deleteObject() ) );
00195 
00196     mainLayout->setSpacing ( 0 );
00197     setLayout ( mainLayout );
00198 
00199     //m_Timer=Timer ( ProfilerEntry::CODE_SEGMENT,"GUI Thread","OR Display" ); // TODO
00200 
00201     //m_GlImageWidget->addVectorObject ( VectorObject2D ( Circle2D ( 320,240,100 ).vertices(),1,0,0,1.0 ) );
00202     //m_GlImageWidget->addVectorObject ( VectorObject2D ( Line2D ( Point2D ( 220,140 ), Point2D ( 420,340 ) ).vertices(),0,1,0,1.0 ) );
00203     //m_GlImageWidget->addVectorObject ( VectorObject2D ( Box2D<> ( 220,140,420,340 ).vertices(),0,0,1,1.0 ) );
00204     //m_GlImageWidget->setColorImage ( new ColorImageRGB8 ( 640,480 ) );
00205 
00206     m_SelectedRow = 0;
00207 
00208     m_ORCommandPublisher = nh->advertise<or_msgs::OrCommand>("/or/commands", 10);
00209     m_Ready = true;
00210 }
00211 
00212 THIS::~THIS()
00213 {
00214 }
00215 
00216 void THIS::grabImage()
00217 {
00218     if(m_Ready)
00219     {
00220         or_msgs::OrCommand commandMsg;
00221         commandMsg.command = ORControlModule::GrabSingleImage;
00222         commandMsg.int_value = m_CameraId; // TODO handle camera id in receiving node - use ros topics for cameraid
00223         m_ORCommandPublisher.publish(commandMsg);
00224     }
00225 }
00226 
00227 void THIS::loadImage()
00228 {
00229     if(m_Ready)
00230     {
00231         QStringList files = QFileDialog::getOpenFileNames ( this, tr ( "Load Image" ), m_LastOpenPath );
00232 
00233         for ( int i = 0; i < files.size(); i++ )
00234         {
00235             QString file=files.at ( i );
00236             QDir fileDir ( file );
00237             fileDir.cdUp();
00238             m_LastOpenPath = fileDir.absolutePath();
00239 
00240             or_msgs::OrCommand commandMsg;
00241             commandMsg.command = ORControlModule::LoadSingleImage;
00242             commandMsg.string_value = file.toStdString();
00243             m_ORCommandPublisher.publish(commandMsg);
00244         }
00245     }
00246 }
00247 
00248 void THIS::startLoop()
00249 {
00250     if(m_Ready)
00251     {
00252         or_msgs::OrCommand commandMsg;
00253         commandMsg.command = ORControlModule::StartRecognitionLoop;
00254         commandMsg.int_value = m_CameraId;
00255         m_ORCommandPublisher.publish(commandMsg);
00256     }
00257 }
00258 
00259 void THIS::stopLoop()
00260 {
00261     if(m_Ready)
00262     {
00263         or_msgs::OrCommand commandMsg;
00264         commandMsg.command = ORControlModule::StopRecognitionLoop;
00265         m_ORCommandPublisher.publish(commandMsg);
00266     }
00267 }
00268 
00269 void THIS::addCheckBox ( QBoxLayout* checkboxLayout, std::map<std::string,QCheckBox*>& CBMap, std::string id, std::string label, bool checked )
00270 {
00271     CBMap[id] = new QCheckBox();
00272     CBMap[id]->setText ( label.c_str() );
00273     checkboxLayout -> addWidget ( CBMap[id] );
00274     CBMap[id]->setChecked ( checked );
00275     connect ( CBMap[id], SIGNAL ( stateChanged ( int ) ), this ,SLOT ( optionsChanged() ) );
00276 }
00277 
00278 // TODO
00279 //void THIS::processMessage ( Message* message )
00280 //{
00281 //  m_Timer.startMeasure();
00282 //  switch ( message->getType() )
00283 //  {
00284 
00285 //    case MessageTypes::IMAGE_M:
00286 //    {
00287 //      ImageM* castMessage = Message::castTo<ImageM> ( message );
00288 //      if ( castMessage->getSourceId() == ImageSources::ORPrimary )
00289 //      {
00290 //        m_GlImageWidget->clearForms();
00291 //        std::list< VectorObject2D >::iterator vectorObjectIt;
00292 //        std::list< VectorObject2D > vectorObjects = castMessage->getVectorObjects();
00293 //        for ( vectorObjectIt = vectorObjects.begin(); vectorObjectIt != vectorObjects.end(); vectorObjectIt++ )
00294 //        {
00295 //          m_GlImageWidget->addVectorObject ( *vectorObjectIt );
00296 //        }
00297 //        switch ( castMessage->getColorFormat() )
00298 //        {
00299 //          case ImageGrabber::RGB8:
00300 //            TRACE_SYSTEMINFO( "Received image" )
00301 //                m_GlImageWidget->setColorImage ( castMessage->getRgbImage() );
00302 //            break;
00303 //          case ImageGrabber::Y8UV8:
00304 //            m_GlImageWidget->setColorImage ( castMessage->getGrayLevelImage(), castMessage->getUvImage() );
00305 //            break;
00306 //          default:
00307 //            break;
00308 //        }
00309 //      }
00310 //    }
00311 //    break;
00312 
00313 //    case MessageTypes::OR_MATCH_RESULT_M:
00314 //    {
00315 //      ORMatchResultM* castMessage = Message::castTo<ORMatchResultM> ( message );
00316 //      m_SceneKeyPoints = *( castMessage->getSceneKeyPoints() );
00317 //                      m_BoundingBoxes = castMessage->getBoundingBoxes();
00318 //      std::vector<MatchResult*> matchResultsPtr =  castMessage->getMatchResults();
00319 //      m_MatchResults.clear();
00320 //      m_MatchResults.reserve( matchResultsPtr.size() );
00321 //      for ( unsigned i=0; i<matchResultsPtr.size(); i++ )
00322 //      {
00323 //        m_MatchResults.push_back( *(matchResultsPtr[i]) );
00324 //      }
00325 //      updateDisplay();
00326 //      m_GlImageWidget->setColorImage( castMessage->getSceneImage() );
00327 
00328 //      initBinChooser();
00329 //    }
00330 //    break;
00331 
00332 //    default:
00333 //      break;
00334 //  }
00335 //  m_Timer.submit();
00336 //}
00337 
00338 void THIS::setCameraId( ImageSources::SourceId cameraId )
00339 {
00340     //   TRACE_INFO( Tracer::toString(cameraId) );
00341     m_CameraId=cameraId;
00342 }
00343 
00344 void THIS::initBinChooser()
00345 {
00346     //update bin chooser box for stage2
00347     for(unsigned int i=0;i<m_MatchResults.size();++i)
00348     {
00349         //Update available bins for stage2
00350         binChooserComboBox->clear();
00351 
00352         int maxBinValue = 0;
00353         int maxBinIndex = 0;
00354         for(unsigned int j=0;j<m_MatchResults[i].stage2Matches.size();++j)
00355         {
00356             std::string sIndex;
00357             std::stringstream outIndex;
00358             outIndex << j;
00359             sIndex = outIndex.str();
00360 
00361             int binValue = m_MatchResults[i].stage2Matches[j].size();
00362             std::string sValue;
00363             std::stringstream outValue;
00364             outValue << binValue;
00365             sValue = outValue.str();
00366 
00367             if(maxBinValue<binValue)
00368             {
00369                 maxBinValue=binValue;
00370                 maxBinIndex=j;
00371             }
00372 
00373             binChooserComboBox->addItem(QString(sIndex.c_str()).append(" (").append(sValue.c_str()).append(")"));
00374             binChooserComboBox->setEnabled(binValue>0);
00375         }
00376         binChooserComboBox->setCurrentIndex(maxBinIndex);
00377         binChooserComboBox->setItemText(maxBinIndex,(binChooserComboBox->currentText()).append(QString("*")));
00378     }
00379 }
00380 
00381 void THIS::cellClicked ( int row, int column )
00382 {
00383     m_DeleteObjectButton->setEnabled ( true );
00384 
00385     //Highlight clicked Cell
00386     m_ObjectsList->setSortingEnabled ( false );
00387     QColor rowColor ( 235,235,235 );
00388     for ( int i=0;i<m_ObjectsList->rowCount();++i )
00389     {
00390         if ( m_ObjectsList->item ( i,0 )->backgroundColor() !=QColor ( 0,0,0 ) )
00391         {
00392             m_ObjectsList->item ( i,0 )->setBackgroundColor ( rowColor );
00393         }
00394         m_ObjectsList->item ( i,1 )->setBackgroundColor ( rowColor );
00395         m_ObjectsList->item ( i,2 )->setBackgroundColor ( rowColor );
00396     }
00397 
00398     QColor selColor ( 119,136,153 );
00399     if ( m_ObjectsList->item ( row,0 )->backgroundColor() !=QColor ( 0,0,0 ) )
00400     {
00401         m_ObjectsList->item ( row,0 )->setBackgroundColor ( selColor );
00402     }
00403     m_ObjectsList->item ( row,1 )->setBackgroundColor ( selColor );
00404     m_ObjectsList->item ( row,2 )->setBackgroundColor ( selColor );
00405 
00406     m_SelectedRow = row;
00407 
00408     m_ObjectsList->setSortingEnabled ( true );
00409 
00410     //Draw updated matches
00411     updateDisplay();
00412 }
00413 
00414 void THIS::optionsChanged()
00415 {
00416     updateDisplay();
00417 }
00418 
00419 void THIS::deleteObject()
00420 {
00421     if ( ( m_SelectedRow >= 0 ) && ( m_SelectedRow < m_ObjectsList->rowCount() ) )
00422     {
00423         string name = m_ObjectsList->item ( m_SelectedRow, 1 )->text().toStdString();
00424 
00425         if(m_Ready)
00426         {
00427             or_msgs::OrCommand commandMsg;
00428             commandMsg.command = ORControlModule::UnloadObject;
00429             commandMsg.string_value = name;
00430             m_ORCommandPublisher.publish(commandMsg);
00431         }
00432     }
00433 }
00434 
00435 void THIS::updateDisplay()
00436 {
00437     m_GlImageWidget->clearForms();
00438 
00439     if ( m_OptionCheckBoxes["sceneAreas"]->isChecked() )
00440     {
00441         for ( unsigned i=0; i < m_SceneKeyPoints.size(); i++ )
00442         {
00443             std::vector<Point2D> bBox1 = m_SceneKeyPoints[ i ].getBoundingBox();
00444             m_GlImageWidget->addVectorObject( VectorObject2D( bBox1, 0, 0, 0, 5.0, VectorObject2D::Lines ) );
00445             m_GlImageWidget->addVectorObject( VectorObject2D( bBox1, 1, 1, 0.5, 3.0, VectorObject2D::Lines ) );
00446         }
00447     }
00448 
00449     if ( m_OptionCheckBoxes["sceneCircles"]->isChecked() )
00450     {
00451         for ( unsigned i=0; i < m_SceneKeyPoints.size(); i++ )
00452         {
00453             std::vector<Point2D> circle = m_SceneKeyPoints[ i ].getCircle();
00454             m_GlImageWidget->addVectorObject( VectorObject2D( circle, 0, 0, 0, 5.0, VectorObject2D::Lines ) );
00455             m_GlImageWidget->addVectorObject( VectorObject2D( circle, 1, 1, 1, 3.0, VectorObject2D::Lines ) );
00456         }
00457     }
00458 
00459     if ( m_OptionCheckBoxes["sceneArrows"]->isChecked() )
00460     {
00461         for ( unsigned i=0; i < m_SceneKeyPoints.size(); i++ )
00462         {
00463             std::vector<Point2D> arrow1 = m_SceneKeyPoints[ i ].getCenterArrow();
00464             m_GlImageWidget->addVectorObject( VectorObject2D( arrow1, 0, 0, 0, 3.0, VectorObject2D::Lines ) );
00465             m_GlImageWidget->addVectorObject( VectorObject2D( arrow1, 0.5, 1, 1, 1.0, VectorObject2D::Lines ) );
00466         }
00467     }
00468 
00469     if ( m_OptionCheckBoxes["boundingBoxes"]->isChecked() )
00470     {
00471         for(unsigned i=0;i<m_BoundingBoxes.size();++i)
00472         {
00473             m_GlImageWidget->addVectorObject( VectorObject2D( m_BoundingBoxes[i].vertices(), 1, 1, 0, 1.0, VectorObject2D::Lines ) );
00474         }
00475     }
00476 
00477     for ( unsigned int i=0; i<m_MatchResults.size(); i++ )
00478     {
00479         MatchResult& matchResult = m_MatchResults[i];
00480 
00481         int objectRow = m_ObjectRows[ matchResult.objectName ];
00482         if ( m_ObjectsList->item ( objectRow, 0 )->checkState() ==Qt::Unchecked )
00483         {
00484             continue;
00485         }
00486 
00487         //FIXME: abhngig von objekt -> muss upgedatet werden
00488         if ( m_OptionCheckBoxes["sceneArrowsWithinOutline"]->isChecked() )
00489         {
00490             for ( unsigned i=0; i < matchResult.sceneKeyPointsWithinOutline.size(); i++ )
00491             {
00492                 std::vector<Point2D> arrow1 = matchResult.sceneKeyPointsWithinOutline.at(i).getCenterArrow();
00493                 m_GlImageWidget->addVectorObject( VectorObject2D( arrow1, 1, 1, 0, 1.0, VectorObject2D::Lines ) );
00494             }
00495         }
00496 
00497         if ( m_OptionCheckBoxes["outline"]->isChecked())
00498         {
00499             std::vector<Point2D> objectOutlineScene;
00500             matchResult.homography.transform( matchResult.outline, objectOutlineScene );
00501             m_GlImageWidget->addVectorObject( VectorObject2D( objectOutlineScene, 1, 0, 0, 3.0, VectorObject2D::Lines ) );
00502             m_GlImageWidget->addVectorObject( VectorObject2D( objectOutlineScene, 0, 0, 0, 1.0, VectorObject2D::Lines ) );
00503 
00504             std::vector<Point2D> objectbBoxScene;
00505             matchResult.homography.transform( matchResult.bBox, objectbBoxScene );
00506             m_GlImageWidget->addVectorObject( VectorObject2D( objectbBoxScene, 0, 0, 0, 3.0, VectorObject2D::Lines ) );
00507             m_GlImageWidget->addVectorObject( VectorObject2D( objectbBoxScene, 1, 1, 1, 1.0, VectorObject2D::Lines ) );
00508 
00509             std::vector<Point2D> centerCircleObjPoints;
00510             std::vector<Point2D> centerCircleScenePoints;
00511             Circle2D centerCircle( matchResult.center, 10 );
00512             centerCircleObjPoints = centerCircle.vertices();
00513             matchResult.homography.transform( centerCircleObjPoints, centerCircleScenePoints );
00514             m_GlImageWidget->addVectorObject( VectorObject2D( centerCircleScenePoints, 1, 0, 0, 3.0, VectorObject2D::Lines ) );
00515         }
00516 
00517         if ( m_OptionCheckBoxes["stage1"]->isChecked() )
00518         {
00519             updateMatches( matchResult, matchResult.stage1Matches );
00520         }
00521         else if ( m_OptionCheckBoxes["stage2"]->isChecked() )
00522         {
00523             //Update matches for chosen bin
00524             int index = binChooserComboBox->currentIndex();
00525 
00526             if(index>=0)
00527             {
00528                 updateMatches( matchResult, matchResult.stage2Matches[binChooserComboBox->currentIndex()] );
00529             }
00530         }
00531         else if ( m_OptionCheckBoxes["stage3"]->isChecked() )
00532         {
00533             updateMatches( matchResult, matchResult.stage3Matches );
00534         }
00535     }
00536 
00537     m_GlImageWidget->updateGL();
00538 }
00539 
00540 void THIS::updateMatches( MatchResult& matchResult, std::list<KeyPointMatch> &matches )
00541 {
00542     if ( m_OptionCheckBoxes["areas"]->isChecked() )
00543     {
00544         // draw scene keyPoint areas
00545         if ( m_OptionCheckBoxes["scene"]->isChecked() )
00546         {
00547             for ( std::list<KeyPointMatch>::iterator match = matches.begin(); match != matches.end(); match++ )
00548             {
00549                 std::vector<Point2D> bBox1 = m_SceneKeyPoints[ matchResult.keyPointIndexMap.at( match->index1 ) ].getBoundingBox();
00550                 m_GlImageWidget->addVectorObject( VectorObject2D( bBox1, 1, 1, 0, 1.0, VectorObject2D::Lines ) );
00551             }
00552         }
00553 
00554         if ( m_OptionCheckBoxes["object"]->isChecked())
00555         {
00556             for ( std::list<KeyPointMatch>::iterator match = matches.begin(); match != matches.end(); match++ )
00557             {
00558                 std::vector<Point2D> bBox2 = matchResult.objectKeyPoints[ match->index2 ].getBoundingBox();
00559                 std::vector<Point2D> bBox2Trans;
00560                 matchResult.homography.transform( bBox2, bBox2Trans );
00561                 m_GlImageWidget->addVectorObject( VectorObject2D( bBox2Trans, 0, 1, 1, 1.0, VectorObject2D::Lines ) );
00562             }
00563         }
00564 
00565     }
00566 
00567     if ( m_OptionCheckBoxes["arrows"]->isChecked() )
00568     {
00569         if ( m_OptionCheckBoxes["scene"]->isChecked() )
00570         {
00571             for ( std::list<KeyPointMatch>::iterator match = matches.begin(); match != matches.end(); match++ )
00572             {
00573                 std::vector<Point2D> arrow1 = m_SceneKeyPoints[ matchResult.keyPointIndexMap.at( match->index1 ) ].getCenterArrow();
00574                 m_GlImageWidget->addVectorObject( VectorObject2D( arrow1, 1, 1, 0, 1.0, VectorObject2D::Lines ) );
00575             }
00576         }
00577         if ( m_OptionCheckBoxes["object"]->isChecked())
00578         {
00579             for ( std::list<KeyPointMatch>::iterator match = matches.begin(); match != matches.end(); match++ )
00580             {
00581                 std::vector<Point2D> arrow2 = matchResult.objectKeyPoints[ match->index2 ].getCenterArrow();
00582                 std::vector<Point2D> arrow2Trans;
00583                 matchResult.homography.transform( arrow2, arrow2Trans );
00584                 m_GlImageWidget->addVectorObject( VectorObject2D( arrow2Trans, 0, 1, 1, 1.0, VectorObject2D::Lines ) );
00585             }
00586         }
00587     }
00588 
00589     if ( m_OptionCheckBoxes["lines"]->isChecked())
00590     {
00591         for ( std::list<KeyPointMatch>::iterator match = matches.begin(); match != matches.end(); match++ )
00592         {
00593             std::vector<Point2D> line;
00594             line.push_back( m_SceneKeyPoints[ matchResult.keyPointIndexMap.at( match->index1 ) ].position() );
00595             line.push_back( matchResult.homography.transform( matchResult.objectKeyPoints[ match->index2 ].position() ) );
00596             m_GlImageWidget->addVectorObject( VectorObject2D( line, 1, 1, 1, 1.0, VectorObject2D::Lines ) );
00597         }
00598     }
00599 }
00600 
00601 
00602 void THIS::loadObjectDialog()
00603 {
00604     QStringList files = QFileDialog::getOpenFileNames ( this, tr ( "Load Object" ), m_LastOpenPath,"Objectproperties (*.objprop)" );
00605 
00606     for ( int i = 0; i < files.size(); i++ )
00607     {
00608         //        QString file=files.at ( i );
00609         //        QDir fileDir ( file );
00610         //        fileDir.cdUp();
00611         //        m_LastOpenPath = fileDir.absolutePath();
00612 
00613         QFileInfo fileInfo( files.at ( i ) );
00614         QString absolutePath = fileInfo.absoluteFilePath();
00615 
00616         std::cerr << "m_LastOpenPath: " << absolutePath.toStdString() << std::endl;
00617 
00618         loadObject( absolutePath.toStdString() );
00619     }
00620 }
00621 
00622 void THIS::loadObject ( string file )
00623 {
00624     // file contains absolut path, here the directory is removed to retain only <objname>.objprops
00625     int slashPos = file.find_last_of( '/' );
00626     // here the file extension .objprops is removed
00627     file = file.substr( slashPos, file.length() - slashPos - 8 );
00628 
00629     std::cerr << "Loading object file: " << file << std::endl;
00630 
00631     if(m_Ready)
00632     {
00633         or_msgs::OrCommand commandMsg;
00634         commandMsg.command = ORControlModule::LoadObject;
00635         commandMsg.string_value = file;
00636         m_ORCommandPublisher.publish(commandMsg);
00637     }
00638 }
00639 
00640 void THIS::updateObjectTable(std::vector<std::string> names, std::vector<std::string> types)
00641 {
00642     ROS_INFO_STREAM("Updating Object Table, new size: " << names.size());
00643 
00644     m_ObjectsList->setSortingEnabled ( false );
00645 
00646     //save old state of checkboxes and recognition
00647     QVector< std::string > m_UncheckedObjects;
00648     QVector< std::string > m_RecognizedObjects;
00649     for ( int i=0;i<m_ObjectsList->rowCount();++i )
00650     {
00651         if ( m_ObjectsList->item ( i,0 )->checkState() ==Qt::Unchecked )
00652         {
00653             m_UncheckedObjects.push_back ( m_ObjectsList->item ( i,1 )->text().toStdString() );
00654         }
00655         if ( m_ObjectsList->item ( i,0 )->backgroundColor() == ( QColor ( 0,0,0 ) ) )
00656         {
00657             m_RecognizedObjects.push_back ( m_ObjectsList->item ( i,1 )->text().toStdString() );
00658         }
00659     }
00660 
00661     m_ObjectsList->setRowCount ( 0 );
00662     m_ObjectRows.clear();
00663 
00664     QColor rowColor ( 235,235,235 );
00665 
00666     for(unsigned pos = 0; pos < names.size(); pos++)
00667     {
00668         std::string name = names.at(pos);
00669         int indexRow = m_ObjectsList->rowCount();
00670         m_ObjectRows[name] = indexRow;
00671         m_ObjectsList->insertRow ( indexRow );
00672 
00673         //create item with checkbox
00674         QTableWidgetItem* item = new QTableWidgetItem();
00675         item->setBackground ( rowColor );
00676         m_ObjectsList->setItem ( indexRow,0,item );
00677 
00678         //keep state of checkboxes
00679         if ( m_UncheckedObjects.contains ( names.at(pos).c_str() ) )
00680         {
00681             m_ObjectsList->item ( indexRow,0 )->setCheckState ( Qt::Unchecked );
00682         }
00683         else
00684         {
00685             m_ObjectsList->item ( indexRow,0 )->setCheckState ( Qt::Checked );
00686         }
00687         //highlight recognized table entries
00688         if ( m_RecognizedObjects.contains ( names.at(pos).c_str() ) )
00689         {
00690             m_ObjectsList->item ( indexRow,0 )->setBackgroundColor ( QColor ( 0,0,0 ) );
00691         }
00692 
00693         //create item with object name
00694         QString objectName = QString::fromStdString ( name );
00695         item = new QTableWidgetItem ( objectName );
00696         item->setBackground ( rowColor );
00697         m_ObjectsList->setItem ( indexRow,1,item );
00698 
00699         //create item with object type
00700         item = new QTableWidgetItem ( QString ( types.at(pos).c_str() ) );
00701         item->setBackground ( rowColor );
00702         item->setTextAlignment ( Qt::AlignCenter );
00703         m_ObjectsList->setItem ( indexRow,2,item );
00704 
00705         //select row in table that was just added
00706         m_ObjectsList->selectRow ( indexRow );
00707         m_ObjectsList->scrollToItem ( m_ObjectsList->item ( indexRow,1 ), QAbstractItemView::EnsureVisible );
00708     }
00709     m_ObjectsList->setSortingEnabled ( true );
00710     m_ObjectsList->sortItems ( 1, Qt::AscendingOrder );
00711     m_ObjectsList->resizeColumnToContents ( 0 );
00712     m_DeleteObjectButton->setEnabled ( false );
00713     m_ObjectsGroupBox->setTitle ( "Objects ("+QString::number ( m_ObjectsList->rowCount() ) +")" );
00714 
00715 }
00716 
00717 #undef THIS


obj_rec_gui
Author(s): AGAS/agas@uni-koblenz.de
autogenerated on Mon Oct 6 2014 02:53:43