reverted eclipse project name to find_object
git-svn-id: http://find-object.googlecode.com/svn/trunk/find_object@11 620bd6b2-0a58-f614-fd9a-1bd335dccda9
This commit is contained in:
commit
e78b7ca029
94
.cproject
Normal file
94
.cproject
Normal file
@ -0,0 +1,94 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<?fileVersion 4.0.0?>
|
||||||
|
|
||||||
|
<cproject storage_type_id="org.eclipse.cdt.core.XmlProjectDescriptionStorage">
|
||||||
|
<storageModule moduleId="org.eclipse.cdt.core.settings">
|
||||||
|
<cconfiguration id="cdt.managedbuild.toolchain.gnu.base.1122816744">
|
||||||
|
<storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="cdt.managedbuild.toolchain.gnu.base.1122816744" moduleId="org.eclipse.cdt.core.settings" name="Default">
|
||||||
|
<externalSettings/>
|
||||||
|
<extensions>
|
||||||
|
<extension id="org.eclipse.cdt.core.ELF" point="org.eclipse.cdt.core.BinaryParser"/>
|
||||||
|
<extension id="org.eclipse.cdt.core.GmakeErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
|
||||||
|
<extension id="org.eclipse.cdt.core.CWDLocator" point="org.eclipse.cdt.core.ErrorParser"/>
|
||||||
|
<extension id="org.eclipse.cdt.core.GCCErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
|
||||||
|
<extension id="org.eclipse.cdt.core.GASErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
|
||||||
|
<extension id="org.eclipse.cdt.core.GLDErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
|
||||||
|
</extensions>
|
||||||
|
</storageModule>
|
||||||
|
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
|
||||||
|
<configuration artifactName="${ProjName}" buildProperties="" description="" id="cdt.managedbuild.toolchain.gnu.base.1122816744" name="Default" parent="org.eclipse.cdt.build.core.emptycfg">
|
||||||
|
<folderInfo id="cdt.managedbuild.toolchain.gnu.base.1122816744.306079558" name="/" resourcePath="">
|
||||||
|
<toolChain id="cdt.managedbuild.toolchain.gnu.base.1536867206" name="cdt.managedbuild.toolchain.gnu.base" superClass="cdt.managedbuild.toolchain.gnu.base">
|
||||||
|
<targetPlatform archList="all" binaryParser="org.eclipse.cdt.core.ELF" id="cdt.managedbuild.target.gnu.platform.base.1135530120" name="Debug Platform" osList="linux,hpux,aix,qnx" superClass="cdt.managedbuild.target.gnu.platform.base"/>
|
||||||
|
<builder arguments="-C ${ProjDirPath}/build VERBOSE=true" command="make" id="cdt.managedbuild.target.gnu.builder.base.673178816" keepEnvironmentInBuildfile="false" managedBuildOn="false" name="Gnu Make Builder" superClass="cdt.managedbuild.target.gnu.builder.base"/>
|
||||||
|
<tool id="cdt.managedbuild.tool.gnu.archiver.base.881773237" name="GCC Archiver" superClass="cdt.managedbuild.tool.gnu.archiver.base"/>
|
||||||
|
<tool id="cdt.managedbuild.tool.gnu.cpp.compiler.base.2094327183" name="GCC C++ Compiler" superClass="cdt.managedbuild.tool.gnu.cpp.compiler.base">
|
||||||
|
<inputType id="cdt.managedbuild.tool.gnu.cpp.compiler.input.424205109" superClass="cdt.managedbuild.tool.gnu.cpp.compiler.input"/>
|
||||||
|
</tool>
|
||||||
|
<tool id="cdt.managedbuild.tool.gnu.c.compiler.base.86959710" name="GCC C Compiler" superClass="cdt.managedbuild.tool.gnu.c.compiler.base">
|
||||||
|
<inputType id="cdt.managedbuild.tool.gnu.c.compiler.input.1730465962" superClass="cdt.managedbuild.tool.gnu.c.compiler.input"/>
|
||||||
|
</tool>
|
||||||
|
<tool id="cdt.managedbuild.tool.gnu.c.linker.base.467751471" name="GCC C Linker" superClass="cdt.managedbuild.tool.gnu.c.linker.base"/>
|
||||||
|
<tool id="cdt.managedbuild.tool.gnu.cpp.linker.base.921357809" name="GCC C++ Linker" superClass="cdt.managedbuild.tool.gnu.cpp.linker.base">
|
||||||
|
<inputType id="cdt.managedbuild.tool.gnu.cpp.linker.input.2123576755" superClass="cdt.managedbuild.tool.gnu.cpp.linker.input">
|
||||||
|
<additionalInput kind="additionalinputdependency" paths="$(USER_OBJS)"/>
|
||||||
|
<additionalInput kind="additionalinput" paths="$(LIBS)"/>
|
||||||
|
</inputType>
|
||||||
|
</tool>
|
||||||
|
<tool id="cdt.managedbuild.tool.gnu.assembler.base.961100725" name="GCC Assembler" superClass="cdt.managedbuild.tool.gnu.assembler.base">
|
||||||
|
<inputType id="cdt.managedbuild.tool.gnu.assembler.input.652879249" superClass="cdt.managedbuild.tool.gnu.assembler.input"/>
|
||||||
|
</tool>
|
||||||
|
</toolChain>
|
||||||
|
</folderInfo>
|
||||||
|
</configuration>
|
||||||
|
</storageModule>
|
||||||
|
<storageModule moduleId="org.eclipse.cdt.core.externalSettings"/>
|
||||||
|
<storageModule moduleId="org.eclipse.cdt.core.language.mapping"/>
|
||||||
|
</cconfiguration>
|
||||||
|
</storageModule>
|
||||||
|
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
|
||||||
|
<project id="find_object.null.1999159200" name="find_object"/>
|
||||||
|
</storageModule>
|
||||||
|
<storageModule moduleId="scannerConfiguration">
|
||||||
|
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
|
||||||
|
</storageModule>
|
||||||
|
<storageModule moduleId="org.eclipse.cdt.make.core.buildtargets">
|
||||||
|
<buildTargets>
|
||||||
|
<target name="CMake-MinGW-Debug" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
|
<buildCommand>cmake</buildCommand>
|
||||||
|
<buildArguments>-E chdir build/ cmake -G "MinGW Makefiles" -D CMAKE_BUILD_TYPE=Debug ../</buildArguments>
|
||||||
|
<buildTarget/>
|
||||||
|
<stopOnError>true</stopOnError>
|
||||||
|
<useDefaultCommand>false</useDefaultCommand>
|
||||||
|
<runAllBuilders>true</runAllBuilders>
|
||||||
|
</target>
|
||||||
|
<target name="CMake-MinGW-Release" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
|
<buildCommand>cmake</buildCommand>
|
||||||
|
<buildArguments>-E chdir build/ cmake -G "MinGW Makefiles" -D CMAKE_BUILD_TYPE=Release ../</buildArguments>
|
||||||
|
<buildTarget/>
|
||||||
|
<stopOnError>true</stopOnError>
|
||||||
|
<useDefaultCommand>false</useDefaultCommand>
|
||||||
|
<runAllBuilders>true</runAllBuilders>
|
||||||
|
</target>
|
||||||
|
<target name="CMake-Unix-Debug" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
|
<buildCommand>cmake</buildCommand>
|
||||||
|
<buildArguments>-E chdir build/ cmake -G "Unix Makefiles" -D CMAKE_BUILD_TYPE=Debug ../</buildArguments>
|
||||||
|
<buildTarget/>
|
||||||
|
<stopOnError>true</stopOnError>
|
||||||
|
<useDefaultCommand>false</useDefaultCommand>
|
||||||
|
<runAllBuilders>true</runAllBuilders>
|
||||||
|
</target>
|
||||||
|
<target name="CMake-Unix-Release" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
|
<buildCommand>cmake</buildCommand>
|
||||||
|
<buildArguments>-E chdir build/ cmake -G "Unix Makefiles" -D CMAKE_BUILD_TYPE=Release ../</buildArguments>
|
||||||
|
<buildTarget/>
|
||||||
|
<stopOnError>true</stopOnError>
|
||||||
|
<useDefaultCommand>false</useDefaultCommand>
|
||||||
|
<runAllBuilders>true</runAllBuilders>
|
||||||
|
</target>
|
||||||
|
</buildTargets>
|
||||||
|
</storageModule>
|
||||||
|
<storageModule moduleId="refreshScope" versionNumber="1">
|
||||||
|
<resource resourceType="PROJECT" workspacePath="/find_object"/>
|
||||||
|
</storageModule>
|
||||||
|
</cproject>
|
||||||
79
.project
Normal file
79
.project
Normal file
@ -0,0 +1,79 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<projectDescription>
|
||||||
|
<name>find_object</name>
|
||||||
|
<comment></comment>
|
||||||
|
<projects>
|
||||||
|
</projects>
|
||||||
|
<buildSpec>
|
||||||
|
<buildCommand>
|
||||||
|
<name>org.eclipse.cdt.managedbuilder.core.genmakebuilder</name>
|
||||||
|
<triggers>clean,full,incremental,</triggers>
|
||||||
|
<arguments>
|
||||||
|
<dictionary>
|
||||||
|
<key>?name?</key>
|
||||||
|
<value></value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.append_environment</key>
|
||||||
|
<value>true</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.autoBuildTarget</key>
|
||||||
|
<value>all</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.buildArguments</key>
|
||||||
|
<value>-C ${ProjDirPath}/build VERBOSE=true</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.buildCommand</key>
|
||||||
|
<value>make</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.cleanBuildTarget</key>
|
||||||
|
<value>clean</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.contents</key>
|
||||||
|
<value>org.eclipse.cdt.make.core.activeConfigSettings</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.enableAutoBuild</key>
|
||||||
|
<value>false</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.enableCleanBuild</key>
|
||||||
|
<value>true</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.enableFullBuild</key>
|
||||||
|
<value>true</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.fullBuildTarget</key>
|
||||||
|
<value>all</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.stopOnError</key>
|
||||||
|
<value>true</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.useDefaultBuildCmd</key>
|
||||||
|
<value>false</value>
|
||||||
|
</dictionary>
|
||||||
|
</arguments>
|
||||||
|
</buildCommand>
|
||||||
|
<buildCommand>
|
||||||
|
<name>org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder</name>
|
||||||
|
<triggers>full,incremental,</triggers>
|
||||||
|
<arguments>
|
||||||
|
</arguments>
|
||||||
|
</buildCommand>
|
||||||
|
</buildSpec>
|
||||||
|
<natures>
|
||||||
|
<nature>org.eclipse.cdt.core.cnature</nature>
|
||||||
|
<nature>org.eclipse.cdt.core.ccnature</nature>
|
||||||
|
<nature>org.eclipse.cdt.managedbuilder.core.managedBuildNature</nature>
|
||||||
|
<nature>org.eclipse.cdt.managedbuilder.core.ScannerConfigNature</nature>
|
||||||
|
</natures>
|
||||||
|
</projectDescription>
|
||||||
17
CMakeLists.txt
Normal file
17
CMakeLists.txt
Normal file
@ -0,0 +1,17 @@
|
|||||||
|
# Top-Level CmakeLists.txt
|
||||||
|
cmake_minimum_required(VERSION 2.8.2)
|
||||||
|
PROJECT( FindObject )
|
||||||
|
|
||||||
|
ADD_DEFINITIONS(-DPROJECT_NAME="${PROJECT_NAME}")
|
||||||
|
|
||||||
|
####### OUTPUT DIR #######
|
||||||
|
SET(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/bin)
|
||||||
|
SET(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/bin)
|
||||||
|
SET(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/lib)
|
||||||
|
|
||||||
|
####### DEPENDENCIES #######
|
||||||
|
FIND_PACKAGE(OpenCV REQUIRED) # tested on 2.3.1
|
||||||
|
FIND_PACKAGE(Qt4 COMPONENTS QtCore QtGui) # tested on Qt4.7
|
||||||
|
|
||||||
|
####### SOURCES (Projects) #######
|
||||||
|
ADD_SUBDIRECTORY( src )
|
||||||
13
README
Normal file
13
README
Normal file
@ -0,0 +1,13 @@
|
|||||||
|
|
||||||
|
Requirements :
|
||||||
|
-Cmake (tested on 2.8.2)
|
||||||
|
-Qt4 (tested on 4.7)
|
||||||
|
-OpenCV (tested on 2.3.1)
|
||||||
|
|
||||||
|
Build from source:
|
||||||
|
$ cd find_object/build
|
||||||
|
$ cmake ..
|
||||||
|
$ make
|
||||||
|
$ cd ../bin
|
||||||
|
$ ./find_object
|
||||||
|
(enjoy!)
|
||||||
BIN
doc/Add_object.png
Normal file
BIN
doc/Add_object.png
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 651 KiB |
BIN
doc/Find_object.png
Normal file
BIN
doc/Find_object.png
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 886 KiB |
BIN
doc/Parameters.png
Normal file
BIN
doc/Parameters.png
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 670 KiB |
276
src/AddObjectDialog.cpp
Normal file
276
src/AddObjectDialog.cpp
Normal file
@ -0,0 +1,276 @@
|
|||||||
|
|
||||||
|
#include "AddObjectDialog.h"
|
||||||
|
#include "ui_addObjectDialog.h"
|
||||||
|
#include "Object.h"
|
||||||
|
#include "KeypointItem.h"
|
||||||
|
#include "Camera.h"
|
||||||
|
#include "qtipl.h"
|
||||||
|
|
||||||
|
#include <stdio.h>
|
||||||
|
|
||||||
|
#include <QtGui/QGraphicsScene>
|
||||||
|
#include <QtGui/QGraphicsPixmapItem>
|
||||||
|
#include <QtGui/QMessageBox>
|
||||||
|
|
||||||
|
#include <opencv2/imgproc/imgproc_c.h>
|
||||||
|
#include <opencv2/highgui/highgui_c.h>
|
||||||
|
|
||||||
|
AddObjectDialog::AddObjectDialog(QList<Object*> * objects, QWidget * parent, Qt::WindowFlags f) :
|
||||||
|
QDialog(parent, f),
|
||||||
|
camera_(0),
|
||||||
|
objects_(objects),
|
||||||
|
cvImage_(0)
|
||||||
|
{
|
||||||
|
ui_ = new Ui_addObjectDialog();
|
||||||
|
ui_->setupUi(this);
|
||||||
|
|
||||||
|
camera_ = Settings::createCamera();
|
||||||
|
|
||||||
|
connect(&cameraTimer_, SIGNAL(timeout()), this, SLOT(update()));
|
||||||
|
|
||||||
|
connect(ui_->pushButton_cancel, SIGNAL(clicked()), this, SLOT(cancel()));
|
||||||
|
connect(ui_->pushButton_back, SIGNAL(clicked()), this, SLOT(back()));
|
||||||
|
connect(ui_->pushButton_next, SIGNAL(clicked()), this, SLOT(next()));
|
||||||
|
connect(ui_->pushButton_takePicture, SIGNAL(clicked()), this, SLOT(takePicture()));
|
||||||
|
|
||||||
|
connect(ui_->cameraView->scene(), SIGNAL(selectionChanged()), this, SLOT(updateNextButton()));
|
||||||
|
|
||||||
|
this->setState(kTakePicture);
|
||||||
|
}
|
||||||
|
|
||||||
|
AddObjectDialog::~AddObjectDialog()
|
||||||
|
{
|
||||||
|
if(cvImage_)
|
||||||
|
{
|
||||||
|
cvReleaseImage(&cvImage_);
|
||||||
|
}
|
||||||
|
if(camera_)
|
||||||
|
{
|
||||||
|
delete camera_;
|
||||||
|
}
|
||||||
|
delete ui_;
|
||||||
|
}
|
||||||
|
|
||||||
|
void AddObjectDialog::closeEvent(QCloseEvent* event)
|
||||||
|
{
|
||||||
|
QDialog::closeEvent(event);
|
||||||
|
}
|
||||||
|
|
||||||
|
void AddObjectDialog::next()
|
||||||
|
{
|
||||||
|
setState(state_+1);
|
||||||
|
}
|
||||||
|
void AddObjectDialog::back()
|
||||||
|
{
|
||||||
|
setState(state_-1);
|
||||||
|
}
|
||||||
|
void AddObjectDialog::cancel()
|
||||||
|
{
|
||||||
|
this->reject();
|
||||||
|
}
|
||||||
|
void AddObjectDialog::takePicture()
|
||||||
|
{
|
||||||
|
next();
|
||||||
|
}
|
||||||
|
|
||||||
|
void AddObjectDialog::updateNextButton()
|
||||||
|
{
|
||||||
|
if(state_ == kSelectFeatures)
|
||||||
|
{
|
||||||
|
if(ui_->cameraView->scene()->selectedItems().size() > 0)
|
||||||
|
{
|
||||||
|
ui_->pushButton_next->setEnabled(true);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
ui_->pushButton_next->setEnabled(false);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void AddObjectDialog::setState(int state)
|
||||||
|
{
|
||||||
|
state_ = state;
|
||||||
|
if(state == kTakePicture)
|
||||||
|
{
|
||||||
|
ui_->pushButton_cancel->setEnabled(true);
|
||||||
|
ui_->pushButton_back->setEnabled(false);
|
||||||
|
ui_->pushButton_next->setEnabled(false);
|
||||||
|
ui_->pushButton_takePicture->setEnabled(true);
|
||||||
|
ui_->label_instruction->setText(tr("Place the object in front of the camera and click \"Take picture\"."));
|
||||||
|
ui_->pushButton_next->setText(tr("Next"));
|
||||||
|
ui_->cameraView->setVisible(true);
|
||||||
|
ui_->objectView->setVisible(false);
|
||||||
|
ui_->cameraView->setGraphicsViewMode(false);
|
||||||
|
if(!camera_->init())
|
||||||
|
{
|
||||||
|
QMessageBox::critical(this, tr("Camera error"), tr("Camera initialization failed! (with device %1)").arg(Settings::getCamera_deviceId().toInt()));
|
||||||
|
ui_->pushButton_takePicture->setEnabled(false);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
cameraTimer_.start(1000/Settings::getCamera_imageRate().toInt());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if(state == kSelectFeatures)
|
||||||
|
{
|
||||||
|
cameraTimer_.stop();
|
||||||
|
camera_->close();
|
||||||
|
|
||||||
|
ui_->pushButton_cancel->setEnabled(true);
|
||||||
|
ui_->pushButton_back->setEnabled(true);
|
||||||
|
ui_->pushButton_next->setEnabled(false);
|
||||||
|
ui_->pushButton_takePicture->setEnabled(false);
|
||||||
|
ui_->label_instruction->setText(tr("Select features representing the object."));
|
||||||
|
ui_->pushButton_next->setText(tr("Next"));
|
||||||
|
ui_->cameraView->setVisible(true);
|
||||||
|
ui_->objectView->setVisible(false);
|
||||||
|
ui_->cameraView->setGraphicsViewMode(true);
|
||||||
|
}
|
||||||
|
else if(state == kVerifySelection)
|
||||||
|
{
|
||||||
|
cameraTimer_.stop();
|
||||||
|
camera_->close();
|
||||||
|
|
||||||
|
ui_->pushButton_cancel->setEnabled(true);
|
||||||
|
ui_->pushButton_back->setEnabled(true);
|
||||||
|
ui_->pushButton_takePicture->setEnabled(false);
|
||||||
|
ui_->pushButton_next->setText(tr("End"));
|
||||||
|
ui_->cameraView->setVisible(true);
|
||||||
|
ui_->objectView->setVisible(true);
|
||||||
|
ui_->cameraView->setGraphicsViewMode(true);
|
||||||
|
|
||||||
|
std::vector<cv::KeyPoint> selectedKeypoints = ui_->cameraView->selectedKeypoints();
|
||||||
|
|
||||||
|
// Select keypoints
|
||||||
|
if(selectedKeypoints.size() && cvImage_)
|
||||||
|
{
|
||||||
|
CvRect roi = computeROI(selectedKeypoints);
|
||||||
|
cvSetImageROI(cvImage_, roi);
|
||||||
|
if(roi.x != 0 || roi.y != 0)
|
||||||
|
{
|
||||||
|
for(unsigned int i=0; i<selectedKeypoints.size(); ++i)
|
||||||
|
{
|
||||||
|
selectedKeypoints.at(i).pt.x -= roi.x;
|
||||||
|
selectedKeypoints.at(i).pt.y -= roi.y;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
ui_->objectView->setData(selectedKeypoints, cv::Mat(), cvImage_);
|
||||||
|
cvResetImageROI(cvImage_);
|
||||||
|
ui_->pushButton_next->setEnabled(true);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
printf("Please select items\n");
|
||||||
|
ui_->pushButton_next->setEnabled(false);
|
||||||
|
}
|
||||||
|
ui_->label_instruction->setText(tr("Selection : %1 features").arg(selectedKeypoints.size()));
|
||||||
|
}
|
||||||
|
else if(state == kClosing)
|
||||||
|
{
|
||||||
|
std::vector<cv::KeyPoint> selectedKeypoints = ui_->cameraView->selectedKeypoints();
|
||||||
|
if(selectedKeypoints.size())
|
||||||
|
{
|
||||||
|
// Extract descriptors
|
||||||
|
cv::Mat descriptors;
|
||||||
|
cv::DescriptorExtractor * extractor = Settings::createDescriptorsExtractor();
|
||||||
|
extractor->compute(cvImage_, selectedKeypoints, descriptors);
|
||||||
|
delete extractor;
|
||||||
|
if(selectedKeypoints.size() != descriptors.rows)
|
||||||
|
{
|
||||||
|
printf("ERROR : keypoints=%lu != descriptors=%d\n", selectedKeypoints.size(), descriptors.rows);
|
||||||
|
}
|
||||||
|
|
||||||
|
CvRect roi = computeROI(selectedKeypoints);
|
||||||
|
cvSetImageROI(cvImage_, roi);
|
||||||
|
if(roi.x != 0 || roi.y != 0)
|
||||||
|
{
|
||||||
|
for(unsigned int i=0; i<selectedKeypoints.size(); ++i)
|
||||||
|
{
|
||||||
|
selectedKeypoints.at(i).pt.x -= roi.x;
|
||||||
|
selectedKeypoints.at(i).pt.y -= roi.y;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
objects_->append(new Object(0, selectedKeypoints, descriptors, cvImage_, Settings::currentDetectorType(), Settings::currentDescriptorType()));
|
||||||
|
cvResetImageROI(cvImage_);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
this->accept();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void AddObjectDialog::update()
|
||||||
|
{
|
||||||
|
if(cvImage_)
|
||||||
|
{
|
||||||
|
cvReleaseImage(&cvImage_);
|
||||||
|
cvImage_ = 0;
|
||||||
|
}
|
||||||
|
cvImage_ = camera_->takeImage();
|
||||||
|
if(cvImage_)
|
||||||
|
{
|
||||||
|
// convert to grayscale
|
||||||
|
if(cvImage_->nChannels != 1 || cvImage_->depth != IPL_DEPTH_8U)
|
||||||
|
{
|
||||||
|
IplImage * imageGrayScale = cvCreateImage(cvSize(cvImage_->width, cvImage_->height), IPL_DEPTH_8U, 1);
|
||||||
|
cvCvtColor(cvImage_, imageGrayScale, CV_BGR2GRAY);
|
||||||
|
cvReleaseImage(&cvImage_);
|
||||||
|
cvImage_ = imageGrayScale;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Extract keypoints
|
||||||
|
cv::FeatureDetector * detector = Settings::createFeaturesDetector();
|
||||||
|
cv::vector<cv::KeyPoint> keypoints;
|
||||||
|
detector->detect(cvImage_, keypoints);
|
||||||
|
delete detector;
|
||||||
|
|
||||||
|
ui_->cameraView->setData(keypoints, cv::Mat(), cvImage_);
|
||||||
|
ui_->cameraView->update();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
CvRect AddObjectDialog::computeROI(const std::vector<cv::KeyPoint> & kpts)
|
||||||
|
{
|
||||||
|
CvRect roi;
|
||||||
|
int x1,x2,h1,h2;
|
||||||
|
for(unsigned int i=0; i<kpts.size(); ++i)
|
||||||
|
{
|
||||||
|
float radius = kpts.at(i).size / 2;
|
||||||
|
if(i==0)
|
||||||
|
{
|
||||||
|
x1 = int(kpts.at(i).pt.x - radius);
|
||||||
|
x2 = int(kpts.at(i).pt.x + radius);
|
||||||
|
h1 = int(kpts.at(i).pt.y - radius);
|
||||||
|
h2 = int(kpts.at(i).pt.y + radius);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
if(x1 > int(kpts.at(i).pt.x - radius))
|
||||||
|
{
|
||||||
|
x1 = int(kpts.at(i).pt.x - radius);
|
||||||
|
}
|
||||||
|
else if(x2 < int(kpts.at(i).pt.x + radius))
|
||||||
|
{
|
||||||
|
x2 = int(kpts.at(i).pt.x + radius);
|
||||||
|
}
|
||||||
|
if(h1 > int(kpts.at(i).pt.y - radius))
|
||||||
|
{
|
||||||
|
h1 = int(kpts.at(i).pt.y - radius);
|
||||||
|
}
|
||||||
|
else if(h2 < int(kpts.at(i).pt.y + radius))
|
||||||
|
{
|
||||||
|
h2 = int(kpts.at(i).pt.y + radius);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
roi.x = x1;
|
||||||
|
roi.y = h1;
|
||||||
|
roi.width = x2-x1;
|
||||||
|
roi.height = h2-h1;
|
||||||
|
printf("ptx=%d, pty=%d\n", (int)kpts.at(i).pt.x, (int)kpts.at(i).pt.y);
|
||||||
|
printf("x=%d, y=%d, w=%d, h=%d\n", roi.x, roi.y, roi.width, roi.height);
|
||||||
|
}
|
||||||
|
|
||||||
|
return roi;
|
||||||
|
}
|
||||||
47
src/AddObjectDialog.h
Normal file
47
src/AddObjectDialog.h
Normal file
@ -0,0 +1,47 @@
|
|||||||
|
#ifndef ADDOBJECTDIALOG_H_
|
||||||
|
#define ADDOBJECTDIALOG_H_
|
||||||
|
|
||||||
|
#include <QtGui/QDialog>
|
||||||
|
#include <QtCore/QTimer>
|
||||||
|
#include <opencv2/features2d/features2d.hpp>
|
||||||
|
#include <opencv2/core/core_c.h>
|
||||||
|
|
||||||
|
class Ui_addObjectDialog;
|
||||||
|
class Object;
|
||||||
|
class Camera;
|
||||||
|
class KeypointItem;
|
||||||
|
|
||||||
|
class AddObjectDialog : public QDialog {
|
||||||
|
|
||||||
|
Q_OBJECT
|
||||||
|
|
||||||
|
public:
|
||||||
|
AddObjectDialog(QList<Object*> * objects, QWidget * parent = 0, Qt::WindowFlags f = 0);
|
||||||
|
virtual ~AddObjectDialog();
|
||||||
|
|
||||||
|
private slots:
|
||||||
|
void update();
|
||||||
|
void next();
|
||||||
|
void back();
|
||||||
|
void cancel();
|
||||||
|
void takePicture();
|
||||||
|
void updateNextButton();
|
||||||
|
|
||||||
|
protected:
|
||||||
|
virtual void closeEvent(QCloseEvent* event);
|
||||||
|
|
||||||
|
private:
|
||||||
|
void setState(int state);
|
||||||
|
CvRect computeROI(const std::vector<cv::KeyPoint> & kpts);
|
||||||
|
private:
|
||||||
|
Ui_addObjectDialog * ui_;
|
||||||
|
Camera * camera_;
|
||||||
|
QTimer cameraTimer_;
|
||||||
|
QList<Object*> * objects_;
|
||||||
|
IplImage * cvImage_;
|
||||||
|
|
||||||
|
enum State{kTakePicture, kSelectFeatures, kVerifySelection, kClosing};
|
||||||
|
int state_;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* ADDOBJECTDIALOG_H_ */
|
||||||
69
src/CMakeLists.txt
Normal file
69
src/CMakeLists.txt
Normal file
@ -0,0 +1,69 @@
|
|||||||
|
|
||||||
|
|
||||||
|
### Qt Gui stuff ###
|
||||||
|
SET(headers_ui
|
||||||
|
./MainWindow.h
|
||||||
|
./AddObjectDialog.h
|
||||||
|
./Object.h
|
||||||
|
./Camera.h
|
||||||
|
./ParametersToolBox.h
|
||||||
|
)
|
||||||
|
|
||||||
|
SET(uis
|
||||||
|
./ui/mainWindow.ui
|
||||||
|
./ui/addObjectDialog.ui
|
||||||
|
)
|
||||||
|
|
||||||
|
#SET(qrc
|
||||||
|
# ./GuiLib.qrc
|
||||||
|
#)
|
||||||
|
|
||||||
|
# generate rules for building source files from the resources
|
||||||
|
#QT4_ADD_RESOURCES(srcs_qrc ${qrc})
|
||||||
|
|
||||||
|
#Generate .h files from the .ui files
|
||||||
|
QT4_WRAP_UI(moc_uis ${uis})
|
||||||
|
|
||||||
|
#This will generate moc_* for Qt
|
||||||
|
QT4_WRAP_CPP(moc_srcs ${headers_ui})
|
||||||
|
### Qt Gui stuff end###
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
SET(SRC_FILES
|
||||||
|
./MainWindow.cpp
|
||||||
|
./AddObjectDialog.cpp
|
||||||
|
./KeypointItem.cpp
|
||||||
|
./qtipl.cpp
|
||||||
|
./main.cpp
|
||||||
|
./Camera.cpp
|
||||||
|
./ParametersToolBox.cpp
|
||||||
|
./Settings.cpp
|
||||||
|
./Object.cpp
|
||||||
|
${moc_srcs}
|
||||||
|
${moc_uis}
|
||||||
|
#${srcs_qrc}
|
||||||
|
)
|
||||||
|
|
||||||
|
SET(INCLUDE_DIRS
|
||||||
|
${CMAKE_CURRENT_SOURCE_DIR}
|
||||||
|
${OpenCV_INCLUDE_DIRS}
|
||||||
|
${CMAKE_CURRENT_BINARY_DIR} # for qt ui generated in binary dir
|
||||||
|
)
|
||||||
|
|
||||||
|
INCLUDE(${QT_USE_FILE})
|
||||||
|
|
||||||
|
SET(LIBRARIES
|
||||||
|
${QT_LIBRARIES}
|
||||||
|
${OpenCV_LIBS}
|
||||||
|
)
|
||||||
|
|
||||||
|
#include files
|
||||||
|
INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
|
||||||
|
|
||||||
|
# create an executable file
|
||||||
|
ADD_EXECUTABLE(find_object ${SRC_FILES})
|
||||||
|
# Linking with Qt libraries
|
||||||
|
TARGET_LINK_LIBRARIES(find_object ${LIBRARIES})
|
||||||
|
|
||||||
95
src/Camera.cpp
Normal file
95
src/Camera.cpp
Normal file
@ -0,0 +1,95 @@
|
|||||||
|
/*
|
||||||
|
* Camera.cpp
|
||||||
|
*
|
||||||
|
* Created on: 2011-10-21
|
||||||
|
* Author: matlab
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "Camera.h"
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <opencv2/imgproc/imgproc_c.h>
|
||||||
|
|
||||||
|
Camera::Camera(int deviceId,
|
||||||
|
int imageWidth,
|
||||||
|
int imageHeight,
|
||||||
|
QObject * parent) :
|
||||||
|
QObject(parent),
|
||||||
|
capture_(0),
|
||||||
|
deviceId_(deviceId),
|
||||||
|
imageWidth_(imageWidth),
|
||||||
|
imageHeight_(imageHeight)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
Camera::~Camera()
|
||||||
|
{
|
||||||
|
this->close();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Camera::init()
|
||||||
|
{
|
||||||
|
if(!capture_)
|
||||||
|
{
|
||||||
|
capture_ = cvCaptureFromCAM(deviceId_);
|
||||||
|
if(capture_)
|
||||||
|
{
|
||||||
|
cvSetCaptureProperty(capture_, CV_CAP_PROP_FRAME_WIDTH, double(imageWidth_));
|
||||||
|
cvSetCaptureProperty(capture_, CV_CAP_PROP_FRAME_HEIGHT, double(imageHeight_));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if(!capture_)
|
||||||
|
{
|
||||||
|
printf("Failed to create a capture object!\n");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void Camera::close()
|
||||||
|
{
|
||||||
|
if(capture_)
|
||||||
|
{
|
||||||
|
cvReleaseCapture(&capture_);
|
||||||
|
capture_ = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
IplImage * Camera::takeImage()
|
||||||
|
{
|
||||||
|
IplImage * img = 0;
|
||||||
|
if(capture_)
|
||||||
|
{
|
||||||
|
if(cvGrabFrame(capture_)) // capture a frame
|
||||||
|
{
|
||||||
|
img = cvRetrieveFrame(capture_); // retrieve the captured frame
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
printf("CameraVideo: Could not grab a frame, the end of the feed may be reached...\n");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
//resize
|
||||||
|
if(img &&
|
||||||
|
imageWidth_ &&
|
||||||
|
imageHeight_ &&
|
||||||
|
imageWidth_ != (unsigned int)img->width &&
|
||||||
|
imageHeight_ != (unsigned int)img->height)
|
||||||
|
{
|
||||||
|
// declare a destination IplImage object with correct size, depth and channels
|
||||||
|
IplImage * resampledImg = cvCreateImage( cvSize(imageWidth_, imageHeight_),
|
||||||
|
img->depth,
|
||||||
|
img->nChannels );
|
||||||
|
|
||||||
|
//use cvResize to resize source to a destination image (linear interpolation)
|
||||||
|
cvResize(img, resampledImg);
|
||||||
|
img = resampledImg;
|
||||||
|
}
|
||||||
|
else if(img)
|
||||||
|
{
|
||||||
|
img = cvCloneImage(img);
|
||||||
|
}
|
||||||
|
|
||||||
|
return img;
|
||||||
|
}
|
||||||
|
|
||||||
47
src/Camera.h
Normal file
47
src/Camera.h
Normal file
@ -0,0 +1,47 @@
|
|||||||
|
/*
|
||||||
|
* Camera.h
|
||||||
|
*
|
||||||
|
* Created on: 2011-10-21
|
||||||
|
* Author: matlab
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef CAMERA_H_
|
||||||
|
#define CAMERA_H_
|
||||||
|
|
||||||
|
#include <opencv2/highgui/highgui.hpp>
|
||||||
|
#include <QtCore/QObject>
|
||||||
|
#include "Settings.h"
|
||||||
|
|
||||||
|
class Camera : public QObject {
|
||||||
|
Q_OBJECT
|
||||||
|
public:
|
||||||
|
Camera(int deviceId = Settings::defaultCamera_deviceId(),
|
||||||
|
int width = Settings::defaultCamera_imageWidth(),
|
||||||
|
int height = Settings::defaultCamera_imageHeight(),
|
||||||
|
QObject * parent = 0);
|
||||||
|
virtual ~Camera();
|
||||||
|
|
||||||
|
void setDeviceId(int deviceId) {deviceId_=deviceId;}
|
||||||
|
void setImageWidth(int imageWidth) {imageWidth_=imageWidth;}
|
||||||
|
void setImageHeight(int imageHeight) {imageHeight_=imageHeight;}
|
||||||
|
|
||||||
|
int getDeviceId() const {return deviceId_;}
|
||||||
|
int getImageWidth() const {return imageWidth_;}
|
||||||
|
int getImageHeight() const {return imageHeight_;}
|
||||||
|
|
||||||
|
signals:
|
||||||
|
void ready();
|
||||||
|
|
||||||
|
public:
|
||||||
|
bool init();
|
||||||
|
void close();
|
||||||
|
IplImage * takeImage();
|
||||||
|
|
||||||
|
private:
|
||||||
|
CvCapture * capture_;
|
||||||
|
int deviceId_;
|
||||||
|
int imageWidth_;
|
||||||
|
int imageHeight_;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* CAMERA_H_ */
|
||||||
109
src/KeypointItem.cpp
Normal file
109
src/KeypointItem.cpp
Normal file
@ -0,0 +1,109 @@
|
|||||||
|
|
||||||
|
|
||||||
|
#include "KeypointItem.h"
|
||||||
|
|
||||||
|
#include <QtGui/QPen>
|
||||||
|
#include <QtGui/QBrush>
|
||||||
|
#include <QtGui/QGraphicsScene>
|
||||||
|
|
||||||
|
KeypointItem::KeypointItem(int id, qreal x, qreal y, int r, const QString & info, const QColor & color, QGraphicsItem * parent) :
|
||||||
|
QGraphicsEllipseItem(x, y, r, r, parent),
|
||||||
|
_info(info),
|
||||||
|
_placeHolder(0),
|
||||||
|
_id(id)
|
||||||
|
{
|
||||||
|
this->setPen(QPen(color));
|
||||||
|
this->setBrush(QBrush(color));
|
||||||
|
this->setAcceptsHoverEvents(true);
|
||||||
|
this->setFlag(QGraphicsItem::ItemIsFocusable, true);
|
||||||
|
this->setFlag(QGraphicsItem::ItemIsSelectable, true);
|
||||||
|
_width = pen().width();
|
||||||
|
}
|
||||||
|
|
||||||
|
KeypointItem::~KeypointItem()
|
||||||
|
{
|
||||||
|
/*if(_placeHolder)
|
||||||
|
{
|
||||||
|
delete _placeHolder;
|
||||||
|
}*/
|
||||||
|
}
|
||||||
|
|
||||||
|
void KeypointItem::setColor(const QColor & color)
|
||||||
|
{
|
||||||
|
this->setPen(QPen(color));
|
||||||
|
this->setBrush(QBrush(color));
|
||||||
|
if(_placeHolder)
|
||||||
|
{
|
||||||
|
QList<QGraphicsItem *> items = _placeHolder->children();
|
||||||
|
if(items.size())
|
||||||
|
{
|
||||||
|
((QGraphicsTextItem *)items.front())->setDefaultTextColor(this->pen().color().rgb());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void KeypointItem::showDescription()
|
||||||
|
{
|
||||||
|
if(!_placeHolder)
|
||||||
|
{
|
||||||
|
_placeHolder = new QGraphicsRectItem();
|
||||||
|
_placeHolder->setVisible(false);
|
||||||
|
this->scene()->addItem(_placeHolder);
|
||||||
|
_placeHolder->setBrush(QBrush(QColor ( 0, 0, 0, 170 ))); // Black transparent background
|
||||||
|
QGraphicsTextItem * text = new QGraphicsTextItem(_placeHolder);
|
||||||
|
text->setDefaultTextColor(this->pen().color().rgb());
|
||||||
|
text->setPlainText(_info);
|
||||||
|
_placeHolder->setRect(text->boundingRect());
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
QPen pen = this->pen();
|
||||||
|
this->setPen(QPen(pen.color(), _width+2));
|
||||||
|
_placeHolder->setZValue(this->zValue()+1);
|
||||||
|
_placeHolder->setPos(this->mapToScene(0,0));
|
||||||
|
_placeHolder->setVisible(true);
|
||||||
|
}
|
||||||
|
|
||||||
|
void KeypointItem::hideDescription()
|
||||||
|
{
|
||||||
|
if(_placeHolder)
|
||||||
|
{
|
||||||
|
_placeHolder->setVisible(false);
|
||||||
|
}
|
||||||
|
this->setPen(QPen(pen().color(), _width));
|
||||||
|
}
|
||||||
|
|
||||||
|
void KeypointItem::hoverEnterEvent ( QGraphicsSceneHoverEvent * event )
|
||||||
|
{
|
||||||
|
QGraphicsScene * scene = this->scene();
|
||||||
|
if(scene && scene->focusItem() == 0)
|
||||||
|
{
|
||||||
|
this->showDescription();
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
this->setPen(QPen(pen().color(), _width+2));
|
||||||
|
}
|
||||||
|
QGraphicsEllipseItem::hoverEnterEvent(event);
|
||||||
|
}
|
||||||
|
|
||||||
|
void KeypointItem::hoverLeaveEvent ( QGraphicsSceneHoverEvent * event )
|
||||||
|
{
|
||||||
|
if(!this->hasFocus())
|
||||||
|
{
|
||||||
|
this->hideDescription();
|
||||||
|
}
|
||||||
|
QGraphicsEllipseItem::hoverEnterEvent(event);
|
||||||
|
}
|
||||||
|
|
||||||
|
void KeypointItem::focusInEvent ( QFocusEvent * event )
|
||||||
|
{
|
||||||
|
this->showDescription();
|
||||||
|
QGraphicsEllipseItem::focusInEvent(event);
|
||||||
|
}
|
||||||
|
|
||||||
|
void KeypointItem::focusOutEvent ( QFocusEvent * event )
|
||||||
|
{
|
||||||
|
this->hideDescription();
|
||||||
|
QGraphicsEllipseItem::focusOutEvent(event);
|
||||||
|
}
|
||||||
37
src/KeypointItem.h
Normal file
37
src/KeypointItem.h
Normal file
@ -0,0 +1,37 @@
|
|||||||
|
|
||||||
|
#ifndef KEYPOINTITEM_H_
|
||||||
|
#define KEYPOINTITEM_H_
|
||||||
|
|
||||||
|
#include <QtGui/QGraphicsEllipseItem>
|
||||||
|
#include <QtGui/QGraphicsTextItem>
|
||||||
|
#include <QtGui/QPen>
|
||||||
|
#include <QtGui/QBrush>
|
||||||
|
|
||||||
|
class KeypointItem : public QGraphicsEllipseItem
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
KeypointItem(int id, qreal x, qreal y, int r, const QString & info, const QColor & color = Qt::green, QGraphicsItem * parent = 0);
|
||||||
|
virtual ~KeypointItem();
|
||||||
|
|
||||||
|
void setColor(const QColor & color);
|
||||||
|
int id() const {return _id;}
|
||||||
|
|
||||||
|
protected:
|
||||||
|
virtual void hoverEnterEvent ( QGraphicsSceneHoverEvent * event );
|
||||||
|
virtual void hoverLeaveEvent ( QGraphicsSceneHoverEvent * event );
|
||||||
|
virtual void focusInEvent ( QFocusEvent * event );
|
||||||
|
virtual void focusOutEvent ( QFocusEvent * event );
|
||||||
|
|
||||||
|
private:
|
||||||
|
void showDescription();
|
||||||
|
void hideDescription();
|
||||||
|
|
||||||
|
private:
|
||||||
|
QString _info;
|
||||||
|
QGraphicsRectItem * _placeHolder;
|
||||||
|
int _width;
|
||||||
|
int _id;
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
#endif /* KEYPOINTITEM_H_ */
|
||||||
476
src/MainWindow.cpp
Normal file
476
src/MainWindow.cpp
Normal file
@ -0,0 +1,476 @@
|
|||||||
|
|
||||||
|
#include "MainWindow.h"
|
||||||
|
#include "AddObjectDialog.h"
|
||||||
|
#include "ui_mainWindow.h"
|
||||||
|
#include "qtipl.h"
|
||||||
|
#include "KeypointItem.h"
|
||||||
|
#include "Object.h"
|
||||||
|
#include "Camera.h"
|
||||||
|
#include "Settings.h"
|
||||||
|
#include "ParametersToolBox.h"
|
||||||
|
|
||||||
|
#include <iostream>
|
||||||
|
#include <stdio.h>
|
||||||
|
|
||||||
|
#include "opencv2/calib3d/calib3d.hpp"
|
||||||
|
|
||||||
|
#include <QtCore/QTextStream>
|
||||||
|
#include <QtCore/QFile>
|
||||||
|
|
||||||
|
#include <QtGui/QFileDialog>
|
||||||
|
#include <QtGui/QMessageBox>
|
||||||
|
#include <QtGui/QGraphicsScene>
|
||||||
|
|
||||||
|
MainWindow::MainWindow(QWidget * parent) :
|
||||||
|
QMainWindow(parent),
|
||||||
|
camera_(0)
|
||||||
|
{
|
||||||
|
ui_ = new Ui_mainWindow();
|
||||||
|
ui_->setupUi(this);
|
||||||
|
|
||||||
|
connect(&cameraTimer_, SIGNAL(timeout()), this, SLOT(update()));
|
||||||
|
|
||||||
|
QByteArray geometry;
|
||||||
|
Settings::loadSettings(Settings::iniDefaultFileName, &geometry);
|
||||||
|
this->restoreGeometry(geometry);
|
||||||
|
|
||||||
|
ui_->toolBox->setupUi();
|
||||||
|
ui_->dockWidget_parameters->hide();
|
||||||
|
ui_->menuView->addAction(ui_->dockWidget_parameters->toggleViewAction());
|
||||||
|
ui_->menuView->addAction(ui_->dockWidget_objects->toggleViewAction());
|
||||||
|
|
||||||
|
ui_->imageView_source->setGraphicsViewMode(false);
|
||||||
|
|
||||||
|
//reset button
|
||||||
|
connect(ui_->pushButton_restoreDefaults, SIGNAL(clicked()), ui_->toolBox, SLOT(resetCurrentPage()));
|
||||||
|
|
||||||
|
ui_->actionStop_camera->setEnabled(false);
|
||||||
|
ui_->actionSave_objects->setEnabled(false);
|
||||||
|
|
||||||
|
// Actions
|
||||||
|
connect(ui_->actionAdd_object, SIGNAL(triggered()), this, SLOT(addObject()));
|
||||||
|
connect(ui_->actionStart_camera, SIGNAL(triggered()), this, SLOT(startCamera()));
|
||||||
|
connect(ui_->actionStop_camera, SIGNAL(triggered()), this, SLOT(stopCamera()));
|
||||||
|
connect(ui_->actionExit, SIGNAL(triggered()), this, SLOT(close()));
|
||||||
|
connect(ui_->actionSave_objects, SIGNAL(triggered()), this, SLOT(saveObjects()));
|
||||||
|
connect(ui_->actionLoad_objects, SIGNAL(triggered()), this, SLOT(loadObjects()));
|
||||||
|
}
|
||||||
|
|
||||||
|
MainWindow::~MainWindow()
|
||||||
|
{
|
||||||
|
this->stopCamera();
|
||||||
|
if(camera_)
|
||||||
|
{
|
||||||
|
delete camera_;
|
||||||
|
camera_ = 0;
|
||||||
|
}
|
||||||
|
dataTree_ = cv::Mat();
|
||||||
|
qDeleteAll(objects_.begin(), objects_.end());
|
||||||
|
objects_.clear();
|
||||||
|
delete ui_;
|
||||||
|
}
|
||||||
|
|
||||||
|
void MainWindow::closeEvent(QCloseEvent * event)
|
||||||
|
{
|
||||||
|
Settings::saveSettings(Settings::iniDefaultFileName, this->saveGeometry());
|
||||||
|
QMainWindow::closeEvent(event);
|
||||||
|
}
|
||||||
|
|
||||||
|
void MainWindow::loadObjects()
|
||||||
|
{
|
||||||
|
QString fileName = QFileDialog::getOpenFileName(this, tr("Load objects..."), "", "*.obj");
|
||||||
|
if(!fileName.isEmpty())
|
||||||
|
{
|
||||||
|
QFile file(fileName);
|
||||||
|
file.open(QIODevice::ReadOnly);
|
||||||
|
QDataStream in(&file);
|
||||||
|
while(!in.atEnd())
|
||||||
|
{
|
||||||
|
Object * obj = new Object();
|
||||||
|
obj->load(in);
|
||||||
|
bool alreadyLoaded = false;
|
||||||
|
for(int i=0; i<objects_.size(); ++i)
|
||||||
|
{
|
||||||
|
if(objects_.at(i)->id() == obj->id())
|
||||||
|
{
|
||||||
|
alreadyLoaded = true;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if(!alreadyLoaded)
|
||||||
|
{
|
||||||
|
objects_.append(obj);
|
||||||
|
showObject(obj);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
delete obj;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
file.close();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
void MainWindow::saveObjects()
|
||||||
|
{
|
||||||
|
QString fileName = QFileDialog::getSaveFileName(this, tr("Save objects..."), Settings::currentDetectorType()+Settings::currentDescriptorType()+QString("%1.obj").arg(objects_.size()), "*.obj");
|
||||||
|
if(!fileName.isEmpty())
|
||||||
|
{
|
||||||
|
if(!fileName.endsWith(".obj"))
|
||||||
|
{
|
||||||
|
fileName.append(".obj");//default
|
||||||
|
}
|
||||||
|
|
||||||
|
QFile file(fileName);
|
||||||
|
file.open(QIODevice::WriteOnly);
|
||||||
|
QDataStream out(&file);
|
||||||
|
for(int i=0; i<objects_.size(); ++i)
|
||||||
|
{
|
||||||
|
objects_.at(i)->save(out);
|
||||||
|
}
|
||||||
|
file.close();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void MainWindow::removeObject(Object * object)
|
||||||
|
{
|
||||||
|
if(object)
|
||||||
|
{
|
||||||
|
objects_.removeOne(object);
|
||||||
|
object->deleteLater();
|
||||||
|
this->updateData();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void MainWindow::addObject()
|
||||||
|
{
|
||||||
|
this->stopCamera();
|
||||||
|
AddObjectDialog dialog(&objects_, this);
|
||||||
|
if(dialog.exec() == QDialog::Accepted)
|
||||||
|
{
|
||||||
|
showObject(objects_.last());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void MainWindow::showObject(Object * obj)
|
||||||
|
{
|
||||||
|
if(obj)
|
||||||
|
{
|
||||||
|
obj->setGraphicsViewMode(false);
|
||||||
|
QList<Object*> objs = ui_->objects_area->findChildren<Object*>();
|
||||||
|
QVBoxLayout * vLayout = new QVBoxLayout();
|
||||||
|
int id = Settings::getGeneral_nextObjID().toInt();
|
||||||
|
if(obj->id() == 0)
|
||||||
|
{
|
||||||
|
obj->setId(id++);
|
||||||
|
Settings::setGeneral_nextObjID(id);
|
||||||
|
}
|
||||||
|
else if(obj->id() > id)
|
||||||
|
{
|
||||||
|
id = obj->id()+1;
|
||||||
|
Settings::setGeneral_nextObjID(id);
|
||||||
|
}
|
||||||
|
|
||||||
|
QLabel * title = new QLabel(QString("%1 (%2)").arg(obj->id()).arg(QString::number(obj->keypoints().size())), this);
|
||||||
|
QLabel * detectedLabel = new QLabel(this);
|
||||||
|
QLabel * detectorDescriptorType = new QLabel(QString("%1/%2").arg(obj->detectorType()).arg(obj->descriptorType()), this);
|
||||||
|
detectedLabel->setObjectName(QString("%1detection").arg(obj->id()));
|
||||||
|
QHBoxLayout * hLayout = new QHBoxLayout();
|
||||||
|
hLayout->addWidget(title);
|
||||||
|
hLayout->addWidget(detectorDescriptorType);
|
||||||
|
hLayout->addWidget(detectedLabel);
|
||||||
|
hLayout->addStretch(1);
|
||||||
|
vLayout->addLayout(hLayout);
|
||||||
|
vLayout->addWidget(obj);
|
||||||
|
objects_.last()->setDeletable(true);
|
||||||
|
connect(obj, SIGNAL(removalTriggered(Object*)), this, SLOT(removeObject(Object*)));
|
||||||
|
connect(obj, SIGNAL(destroyed(QObject *)), title, SLOT(deleteLater()));
|
||||||
|
connect(obj, SIGNAL(destroyed(QObject *)), detectedLabel, SLOT(deleteLater()));
|
||||||
|
connect(obj, SIGNAL(destroyed(QObject *)), detectorDescriptorType, SLOT(deleteLater()));
|
||||||
|
connect(obj, SIGNAL(destroyed(QObject *)), vLayout, SLOT(deleteLater()));
|
||||||
|
ui_->verticalLayout_objects->insertLayout(ui_->verticalLayout_objects->count()-1, vLayout);
|
||||||
|
|
||||||
|
this->updateData();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void MainWindow::updateData()
|
||||||
|
{
|
||||||
|
if(objects_.size())
|
||||||
|
{
|
||||||
|
ui_->actionSave_objects->setEnabled(true);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
ui_->actionSave_objects->setEnabled(false);
|
||||||
|
}
|
||||||
|
|
||||||
|
dataTree_ = cv::Mat();
|
||||||
|
dataRange_.clear();
|
||||||
|
int count = 0;
|
||||||
|
int dim = -1;
|
||||||
|
int type = -1;
|
||||||
|
// Get the total size and verify descriptors
|
||||||
|
for(int i=0; i<objects_.size(); ++i)
|
||||||
|
{
|
||||||
|
if(dim >= 0 && objects_.at(i)->descriptors().cols != dim)
|
||||||
|
{
|
||||||
|
QMessageBox::critical(this, tr("Error"), tr("Descriptors of the objects are not all the same size!\nObjects opened must have all the same size (and from the same descriptor extractor)."));
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
dim = objects_.at(i)->descriptors().cols;
|
||||||
|
if(type >= 0 && objects_.at(i)->descriptors().type() != type)
|
||||||
|
{
|
||||||
|
QMessageBox::critical(this, tr("Error"), tr("Descriptors of the objects are not all the same type!\nObjects opened must have been processed by the same descriptor extractor."));
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
type = objects_.at(i)->descriptors().type();
|
||||||
|
count += objects_.at(i)->descriptors().rows;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Copy data
|
||||||
|
if(count)
|
||||||
|
{
|
||||||
|
cv::Mat data(count, dim, type);
|
||||||
|
printf("Total descriptors=%d, dim=%d, type=%d\n",count, dim, type);
|
||||||
|
int row = 0;
|
||||||
|
for(int i=0; i<objects_.size(); ++i)
|
||||||
|
{
|
||||||
|
cv::Mat dest(data, cv::Range(row, row+objects_.at(i)->descriptors().rows));
|
||||||
|
objects_.at(i)->descriptors().copyTo(dest);
|
||||||
|
row += objects_.at(i)->descriptors().rows;
|
||||||
|
dataRange_.append(row);
|
||||||
|
}
|
||||||
|
data.convertTo(dataTree_, CV_32F);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void MainWindow::startCamera()
|
||||||
|
{
|
||||||
|
if(camera_)
|
||||||
|
{
|
||||||
|
camera_->close();
|
||||||
|
delete camera_;
|
||||||
|
}
|
||||||
|
camera_ = Settings::createCamera();
|
||||||
|
connect(camera_, SIGNAL(ready()), this, SLOT(update()));
|
||||||
|
if(camera_->init())
|
||||||
|
{
|
||||||
|
cameraTimer_.start(1000/Settings::getCamera_imageRate().toInt());
|
||||||
|
ui_->actionStop_camera->setEnabled(true);
|
||||||
|
ui_->actionStart_camera->setEnabled(false);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
QMessageBox::critical(this, tr("Camera error"), tr("Camera initialization failed! (with device %1)").arg(Settings::getCamera_deviceId().toInt()));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void MainWindow::stopCamera()
|
||||||
|
{
|
||||||
|
if(camera_)
|
||||||
|
{
|
||||||
|
cameraTimer_.stop();
|
||||||
|
camera_->close();
|
||||||
|
delete camera_;
|
||||||
|
camera_ = 0;
|
||||||
|
}
|
||||||
|
ui_->actionStop_camera->setEnabled(false);
|
||||||
|
ui_->actionStart_camera->setEnabled(true);
|
||||||
|
}
|
||||||
|
|
||||||
|
void MainWindow::update()
|
||||||
|
{
|
||||||
|
// reset objects color
|
||||||
|
for(int i=0; i<objects_.size(); ++i)
|
||||||
|
{
|
||||||
|
objects_[i]->resetKptsColor();
|
||||||
|
}
|
||||||
|
|
||||||
|
if(camera_)
|
||||||
|
{
|
||||||
|
IplImage * cvImage = camera_->takeImage();
|
||||||
|
if(cvImage)
|
||||||
|
{
|
||||||
|
QTime time;
|
||||||
|
|
||||||
|
//Convert to grayscale
|
||||||
|
IplImage * imageGrayScale = 0;
|
||||||
|
if(cvImage->nChannels != 1 || cvImage->depth != IPL_DEPTH_8U)
|
||||||
|
{
|
||||||
|
imageGrayScale = cvCreateImage(cvSize(cvImage->width,cvImage->height), IPL_DEPTH_8U, 1);
|
||||||
|
cvCvtColor(cvImage, imageGrayScale, CV_BGR2GRAY);
|
||||||
|
}
|
||||||
|
cv::Mat img;
|
||||||
|
if(imageGrayScale)
|
||||||
|
{
|
||||||
|
img = cv::Mat(imageGrayScale);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
img = cv::Mat(cvImage);
|
||||||
|
}
|
||||||
|
|
||||||
|
// EXTRACT KEYPOINTS
|
||||||
|
time.start();
|
||||||
|
cv::FeatureDetector * detector = Settings::createFeaturesDetector();
|
||||||
|
std::vector<cv::KeyPoint> keypoints;
|
||||||
|
detector->detect(img, keypoints);
|
||||||
|
delete detector;
|
||||||
|
ui_->label_timeDetection->setText(QString::number(time.elapsed()));
|
||||||
|
|
||||||
|
// EXTRACT DESCRIPTORS
|
||||||
|
time.start();
|
||||||
|
cv::Mat descriptors;
|
||||||
|
cv::DescriptorExtractor * extractor = Settings::createDescriptorsExtractor();
|
||||||
|
extractor->compute(img, keypoints, descriptors);
|
||||||
|
delete extractor;
|
||||||
|
if(keypoints.size() != descriptors.rows)
|
||||||
|
{
|
||||||
|
printf("ERROR : kpt=%lu != descriptors=%d\n", keypoints.size(), descriptors.rows);
|
||||||
|
}
|
||||||
|
if(imageGrayScale)
|
||||||
|
{
|
||||||
|
cvReleaseImage(&imageGrayScale);
|
||||||
|
}
|
||||||
|
ui_->label_timeExtraction->setText(QString::number(time.elapsed()));
|
||||||
|
|
||||||
|
// COMPARE
|
||||||
|
int alpha = 20*255/100;
|
||||||
|
if(!dataTree_.empty())
|
||||||
|
{
|
||||||
|
// CREATE INDEX
|
||||||
|
time.start();
|
||||||
|
cv::Mat environment(descriptors.rows, descriptors.cols, CV_32F);
|
||||||
|
descriptors.convertTo(environment, CV_32F);
|
||||||
|
cv::flann::Index treeFlannIndex(environment, cv::flann::KDTreeIndexParams());
|
||||||
|
ui_->label_timeIndexing->setText(QString::number(time.elapsed()));
|
||||||
|
|
||||||
|
// DO NEAREST NEIGHBOR
|
||||||
|
time.start();
|
||||||
|
int k = 2;
|
||||||
|
int emax = 64;
|
||||||
|
cv::Mat results(dataTree_.rows, k, CV_32SC1); // results index
|
||||||
|
cv::Mat dists(dataTree_.rows, k, CV_32FC1); // Distance results are CV_32FC1
|
||||||
|
treeFlannIndex.knnSearch(dataTree_, results, dists, k, cv::flann::SearchParams(emax) ); // maximum number of leafs checked
|
||||||
|
ui_->label_timeMatching->setText(QString::number(time.elapsed()));
|
||||||
|
|
||||||
|
|
||||||
|
// PROCESS RESULTS
|
||||||
|
time.start();
|
||||||
|
ui_->imageView_source->setData(keypoints, cv::Mat(), cvImage);
|
||||||
|
int j=0;
|
||||||
|
std::vector<cv::Point2f> mpts_1, mpts_2;
|
||||||
|
std::vector<int> indexes_1, indexes_2;
|
||||||
|
std::vector<uchar> outlier_mask;
|
||||||
|
for(unsigned int i=0; i<dataTree_.rows; ++i)
|
||||||
|
{
|
||||||
|
// Check if this descriptor matches with those of the objects
|
||||||
|
// Apply NNDR
|
||||||
|
if(dists.at<float>(i,0) <= Settings::getNN_nndrRatio().toFloat() * dists.at<float>(i,1))
|
||||||
|
{
|
||||||
|
if(j>0)
|
||||||
|
{
|
||||||
|
mpts_1.push_back(objects_.at(j)->keypoints().at(i-dataRange_.at(j-1)).pt);
|
||||||
|
indexes_1.push_back(i-dataRange_.at(j-1));
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
mpts_1.push_back(objects_.at(j)->keypoints().at(i).pt);
|
||||||
|
indexes_1.push_back(i);
|
||||||
|
}
|
||||||
|
mpts_2.push_back(ui_->imageView_source->keypoints().at(results.at<int>(i,0)).pt);
|
||||||
|
indexes_2.push_back(results.at<int>(i,0));
|
||||||
|
}
|
||||||
|
|
||||||
|
if(i+1 >= dataRange_.at(j))
|
||||||
|
{
|
||||||
|
QLabel * label = ui_->dockWidget_objects->findChild<QLabel*>(QString("%1detection").arg(objects_.at(j)->id()));
|
||||||
|
if(mpts_1.size() >= Settings::getHomography_minimumInliers().toInt())
|
||||||
|
{
|
||||||
|
cv::Mat H = findHomography(mpts_1,
|
||||||
|
mpts_2,
|
||||||
|
cv::RANSAC,
|
||||||
|
Settings::getHomography_ransacReprojThr().toDouble(),
|
||||||
|
outlier_mask);
|
||||||
|
int inliers=0, outliers=0;
|
||||||
|
QColor color((Qt::GlobalColor)(j % 12 + 7 ));
|
||||||
|
color.setAlpha(alpha);
|
||||||
|
for(int k=0; k<mpts_1.size();++k)
|
||||||
|
{
|
||||||
|
if(outlier_mask.at(k))
|
||||||
|
{
|
||||||
|
++inliers;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
++outliers;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// COLORIZE
|
||||||
|
if(inliers >= Settings::getHomography_minimumInliers().toInt())
|
||||||
|
{
|
||||||
|
for(int k=0; k<mpts_1.size();++k)
|
||||||
|
{
|
||||||
|
if(outlier_mask.at(k))
|
||||||
|
{
|
||||||
|
objects_.at(j)->setKptColor(indexes_1.at(k), color);
|
||||||
|
ui_->imageView_source->setKptColor(indexes_2.at(k), color);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
objects_.at(j)->setKptColor(indexes_1.at(k), QColor(0,0,0,alpha));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
label->setText(QString("%1 in %2 out").arg(inliers).arg(outliers));
|
||||||
|
QTransform hTransform(
|
||||||
|
H.at<double>(0,0), H.at<double>(1,0), H.at<double>(2,0),
|
||||||
|
H.at<double>(0,1), H.at<double>(1,1), H.at<double>(2,1),
|
||||||
|
H.at<double>(0,2), H.at<double>(1,2), H.at<double>(2,2));
|
||||||
|
QPen rectPen(color);
|
||||||
|
rectPen.setWidth(4);
|
||||||
|
QGraphicsRectItem * rectItem = ui_->imageView_source->scene()->addRect(objects_.at(j)->image().rect(), rectPen);
|
||||||
|
rectItem->setTransform(hTransform);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
label->setText(QString("Too low inliers (%1)").arg(inliers));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
label->setText(QString("Too low matches (%1)").arg(mpts_1.size()));
|
||||||
|
}
|
||||||
|
mpts_1.clear();
|
||||||
|
mpts_2.clear();
|
||||||
|
indexes_1.clear();
|
||||||
|
indexes_2.clear();
|
||||||
|
outlier_mask.clear();
|
||||||
|
++j;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
ui_->imageView_source->setData(keypoints, cv::Mat(), cvImage);
|
||||||
|
}
|
||||||
|
|
||||||
|
//Update object pictures
|
||||||
|
for(int i=0; i<objects_.size(); ++i)
|
||||||
|
{
|
||||||
|
objects_[i]->update();
|
||||||
|
}
|
||||||
|
|
||||||
|
ui_->label_nfeatures->setText(QString::number(keypoints.size()));
|
||||||
|
ui_->imageView_source->update();
|
||||||
|
ui_->label_timeGui->setText(QString::number(time.elapsed()));
|
||||||
|
|
||||||
|
cvReleaseImage(&cvImage);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
ui_->label_detectorDescriptorType->setText(QString("%1/%2").arg(Settings::currentDetectorType()).arg(Settings::currentDescriptorType()));
|
||||||
|
ui_->label_timeRefreshRate->setText(QString("(%1 Hz - %2 Hz)").arg(QString::number(1000/cameraTimer_.interval())).arg(QString::number(int(1000.0f/(float)(updateRate_.elapsed())))));
|
||||||
|
//printf("GUI refresh rate %f Hz\n", 1000.0f/(float)(updateRate_.elapsed()));
|
||||||
|
updateRate_.start();
|
||||||
|
}
|
||||||
56
src/MainWindow.h
Normal file
56
src/MainWindow.h
Normal file
@ -0,0 +1,56 @@
|
|||||||
|
|
||||||
|
|
||||||
|
#ifndef MAINWINDOW_H_
|
||||||
|
#define MAINWINDOW_H_
|
||||||
|
|
||||||
|
#include <QtGui/QMainWindow>
|
||||||
|
#include <QtCore/QSet>
|
||||||
|
#include <QtCore/QTimer>
|
||||||
|
#include <QtCore/QTime>
|
||||||
|
|
||||||
|
#include <opencv2/core/core.hpp>
|
||||||
|
#include <opencv2/features2d/features2d.hpp>
|
||||||
|
#include <opencv2/imgproc/imgproc_c.h>
|
||||||
|
|
||||||
|
class Ui_mainWindow;
|
||||||
|
class Object;
|
||||||
|
class Camera;
|
||||||
|
class ParametersToolBox;
|
||||||
|
class QLabel;
|
||||||
|
|
||||||
|
class MainWindow : public QMainWindow
|
||||||
|
{
|
||||||
|
Q_OBJECT
|
||||||
|
|
||||||
|
public:
|
||||||
|
MainWindow(QWidget * parent = 0);
|
||||||
|
virtual ~MainWindow();
|
||||||
|
|
||||||
|
protected:
|
||||||
|
virtual void closeEvent(QCloseEvent * event);
|
||||||
|
|
||||||
|
private slots:
|
||||||
|
void addObject();
|
||||||
|
void startCamera();
|
||||||
|
void stopCamera();
|
||||||
|
void loadObjects();
|
||||||
|
void saveObjects();
|
||||||
|
void update();
|
||||||
|
void updateData();
|
||||||
|
void removeObject(Object * object);
|
||||||
|
|
||||||
|
private:
|
||||||
|
void showObject(Object * obj);
|
||||||
|
|
||||||
|
private:
|
||||||
|
Ui_mainWindow * ui_;
|
||||||
|
Camera * camera_;
|
||||||
|
QList<Object*> objects_;
|
||||||
|
QTimer cameraTimer_;
|
||||||
|
cv::Mat dataTree_;
|
||||||
|
QList<int> dataRange_;
|
||||||
|
QTime updateRate_;
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* MainWindow_H_ */
|
||||||
517
src/Object.cpp
Normal file
517
src/Object.cpp
Normal file
@ -0,0 +1,517 @@
|
|||||||
|
/*
|
||||||
|
* Object.cpp
|
||||||
|
*
|
||||||
|
* Created on: 2011-10-23
|
||||||
|
* Author: matlab
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
/*
|
||||||
|
* VisualObject.h
|
||||||
|
*
|
||||||
|
* Created on: 2011-10-21
|
||||||
|
* Author: matlab
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "Object.h"
|
||||||
|
#include "KeypointItem.h"
|
||||||
|
#include "qtipl.h"
|
||||||
|
|
||||||
|
#include <opencv2/highgui/highgui.hpp>
|
||||||
|
|
||||||
|
#include <QtGui/QWidget>
|
||||||
|
#include <QtGui/QContextMenuEvent>
|
||||||
|
#include <QtGui/QMenu>
|
||||||
|
#include <QtGui/QMenu>
|
||||||
|
#include <QtGui/QFileDialog>
|
||||||
|
#include <QtGui/QAction>
|
||||||
|
#include <QtGui/QGraphicsView>
|
||||||
|
#include <QtGui/QGraphicsScene>
|
||||||
|
#include <QtGui/QVBoxLayout>
|
||||||
|
|
||||||
|
#include <QtCore/QDir>
|
||||||
|
|
||||||
|
#include <stdio.h>
|
||||||
|
|
||||||
|
Object::Object(QWidget * parent) :
|
||||||
|
QWidget(parent),
|
||||||
|
iplImage_(0),
|
||||||
|
graphicsView_(0),
|
||||||
|
id_(0),
|
||||||
|
graphicsViewMode_(true),
|
||||||
|
detectorType_("NA"),
|
||||||
|
descriptorType_("NA")
|
||||||
|
{
|
||||||
|
setupUi();
|
||||||
|
}
|
||||||
|
Object::Object(int id,
|
||||||
|
const std::vector<cv::KeyPoint> & keypoints,
|
||||||
|
const cv::Mat & descriptors,
|
||||||
|
const IplImage * iplImage,
|
||||||
|
const QString & detectorType,
|
||||||
|
const QString & descriptorType,
|
||||||
|
QWidget * parent) :
|
||||||
|
QWidget(parent),
|
||||||
|
iplImage_(0),
|
||||||
|
graphicsView_(0),
|
||||||
|
id_(id),
|
||||||
|
graphicsViewMode_(true),
|
||||||
|
detectorType_(detectorType),
|
||||||
|
descriptorType_(descriptorType)
|
||||||
|
{
|
||||||
|
setupUi();
|
||||||
|
this->setData(keypoints, descriptors, iplImage);
|
||||||
|
}
|
||||||
|
Object::~Object()
|
||||||
|
{
|
||||||
|
if(iplImage_)
|
||||||
|
{
|
||||||
|
cvReleaseImage(&iplImage_);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void Object::setupUi()
|
||||||
|
{
|
||||||
|
graphicsView_ = new QGraphicsView(this);
|
||||||
|
graphicsView_->setVisible(true);
|
||||||
|
graphicsView_->setTransformationAnchor(QGraphicsView::AnchorUnderMouse);
|
||||||
|
graphicsView_->setScene(new QGraphicsScene(graphicsView_));
|
||||||
|
|
||||||
|
this->setLayout(new QVBoxLayout(graphicsView_));
|
||||||
|
this->layout()->addWidget(graphicsView_);
|
||||||
|
this->layout()->setContentsMargins(0,0,0,0);
|
||||||
|
|
||||||
|
_menu = new QMenu(tr(""), this);
|
||||||
|
_showImage = _menu->addAction(tr("Show image"));
|
||||||
|
_showImage->setCheckable(true);
|
||||||
|
_showImage->setChecked(true);
|
||||||
|
_showFeatures = _menu->addAction(tr("Show features"));
|
||||||
|
_showFeatures->setCheckable(true);
|
||||||
|
_showFeatures->setChecked(true);
|
||||||
|
_mirrorView = _menu->addAction(tr("Mirror view"));
|
||||||
|
_mirrorView->setCheckable(true);
|
||||||
|
_mirrorView->setChecked(false);
|
||||||
|
_plainView = _menu->addAction(tr("Plain view"));
|
||||||
|
_plainView->setCheckable(true);
|
||||||
|
_plainView->setChecked(!graphicsViewMode_);
|
||||||
|
_menu->addSeparator();
|
||||||
|
_saveImage = _menu->addAction(tr("Save picture..."));
|
||||||
|
_menu->addSeparator();
|
||||||
|
_delete = _menu->addAction(tr("Delete"));
|
||||||
|
_delete->setEnabled(false);
|
||||||
|
|
||||||
|
this->setId(id_);
|
||||||
|
|
||||||
|
graphicsView_->setRubberBandSelectionMode(Qt::ContainsItemShape);
|
||||||
|
graphicsView_->setDragMode(QGraphicsView::RubberBandDrag);
|
||||||
|
}
|
||||||
|
|
||||||
|
void Object::setId(int id)
|
||||||
|
{
|
||||||
|
id_=id;
|
||||||
|
if(id_)
|
||||||
|
{
|
||||||
|
_savedFileName = QString("object_%1.png").arg(id_);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void Object::setGraphicsViewMode(bool on)
|
||||||
|
{
|
||||||
|
graphicsViewMode_ = on;
|
||||||
|
graphicsView_->setVisible(on);
|
||||||
|
//update items' color
|
||||||
|
if(on)
|
||||||
|
{
|
||||||
|
if(keypointItems_.size() == 0)
|
||||||
|
{
|
||||||
|
this->setupGraphicsView();
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
for(int i=0; i<keypointItems_.size(); ++i)
|
||||||
|
{
|
||||||
|
keypointItems_[i]->setColor(kptColors_.at(i));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
graphicsView_->fitInView(graphicsView_->sceneRect(), Qt::KeepAspectRatio);
|
||||||
|
_plainView->setChecked(!on);
|
||||||
|
this->update();
|
||||||
|
}
|
||||||
|
|
||||||
|
// ownership transferred
|
||||||
|
void Object::setData(const std::vector<cv::KeyPoint> & keypoints, const cv::Mat & descriptors, const IplImage * image)
|
||||||
|
{
|
||||||
|
keypoints_ = keypoints;
|
||||||
|
descriptors_ = descriptors;
|
||||||
|
kptColors_ = QVector<QColor>(keypoints.size(), defaultColor());
|
||||||
|
keypointItems_.clear();
|
||||||
|
if(iplImage_)
|
||||||
|
{
|
||||||
|
cvReleaseImage(&iplImage_);
|
||||||
|
iplImage_ = 0;
|
||||||
|
}
|
||||||
|
if(image)
|
||||||
|
{
|
||||||
|
/* create destination image
|
||||||
|
Note that cvGetSize will return the width and the height of ROI */
|
||||||
|
iplImage_ = cvCreateImage(cvGetSize(image),
|
||||||
|
image->depth,
|
||||||
|
image->nChannels);
|
||||||
|
|
||||||
|
/* copy subimage */
|
||||||
|
cvCopy(image, iplImage_, NULL);
|
||||||
|
|
||||||
|
image_ = QPixmap::fromImage(Ipl2QImage(iplImage_));
|
||||||
|
this->setMinimumSize(image_.size());
|
||||||
|
}
|
||||||
|
if(graphicsViewMode_)
|
||||||
|
{
|
||||||
|
this->setupGraphicsView();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void Object::resetKptsColor()
|
||||||
|
{
|
||||||
|
for(int i=0; i<kptColors_.size(); ++i)
|
||||||
|
{
|
||||||
|
kptColors_[i] = defaultColor();
|
||||||
|
if(graphicsViewMode_)
|
||||||
|
{
|
||||||
|
keypointItems_[i]->setColor(this->defaultColor());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void Object::setKptColor(unsigned int index, const QColor & color)
|
||||||
|
{
|
||||||
|
if(index < kptColors_.size())
|
||||||
|
{
|
||||||
|
kptColors_[index] = color;
|
||||||
|
}
|
||||||
|
|
||||||
|
if(graphicsViewMode_)
|
||||||
|
{
|
||||||
|
if(index < keypointItems_.size())
|
||||||
|
{
|
||||||
|
keypointItems_.at(index)->setColor(color);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Object::isImageShown() const
|
||||||
|
{
|
||||||
|
return _showImage->isChecked();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Object::isFeaturesShown() const
|
||||||
|
{
|
||||||
|
return _showFeatures->isChecked();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Object::isMirrorView() const
|
||||||
|
{
|
||||||
|
return _mirrorView->isChecked();
|
||||||
|
}
|
||||||
|
|
||||||
|
QGraphicsScene * Object::scene() const
|
||||||
|
{
|
||||||
|
return graphicsView_->scene();
|
||||||
|
}
|
||||||
|
|
||||||
|
void Object::setDeletable(bool deletable)
|
||||||
|
{
|
||||||
|
_delete->setEnabled(deletable);
|
||||||
|
}
|
||||||
|
|
||||||
|
void Object::save(QDataStream & streamPtr) const
|
||||||
|
{
|
||||||
|
streamPtr << id_ << detectorType_ << descriptorType_;
|
||||||
|
streamPtr << (int)keypoints_.size();
|
||||||
|
for(int j=0; j<keypoints_.size(); ++j)
|
||||||
|
{
|
||||||
|
streamPtr << keypoints_.at(j).angle <<
|
||||||
|
keypoints_.at(j).class_id <<
|
||||||
|
keypoints_.at(j).octave <<
|
||||||
|
keypoints_.at(j).pt.x <<
|
||||||
|
keypoints_.at(j).pt.y <<
|
||||||
|
keypoints_.at(j).response <<
|
||||||
|
keypoints_.at(j).size;
|
||||||
|
}
|
||||||
|
|
||||||
|
qint64 dataSize = descriptors_.elemSize()*descriptors_.cols*descriptors_.rows;
|
||||||
|
streamPtr << descriptors_.rows <<
|
||||||
|
descriptors_.cols <<
|
||||||
|
descriptors_.type() <<
|
||||||
|
dataSize;
|
||||||
|
streamPtr << QByteArray((char*)descriptors_.data, dataSize);
|
||||||
|
streamPtr << image_;
|
||||||
|
}
|
||||||
|
|
||||||
|
void Object::load(QDataStream & streamPtr)
|
||||||
|
{
|
||||||
|
std::vector<cv::KeyPoint> kpts;
|
||||||
|
cv::Mat descriptors;
|
||||||
|
|
||||||
|
int nKpts;
|
||||||
|
streamPtr >> id_ >> detectorType_ >> descriptorType_ >> nKpts;
|
||||||
|
for(int i=0;i<nKpts;++i)
|
||||||
|
{
|
||||||
|
cv::KeyPoint kpt;
|
||||||
|
streamPtr >>
|
||||||
|
kpt.angle >>
|
||||||
|
kpt.class_id >>
|
||||||
|
kpt.octave >>
|
||||||
|
kpt.pt.x >>
|
||||||
|
kpt.pt.y >>
|
||||||
|
kpt.response >>
|
||||||
|
kpt.size;
|
||||||
|
kpts.push_back(kpt);
|
||||||
|
}
|
||||||
|
|
||||||
|
int rows,cols,type;
|
||||||
|
qint64 dataSize;
|
||||||
|
streamPtr >> rows >> cols >> type >> dataSize;
|
||||||
|
QByteArray data;
|
||||||
|
streamPtr >> data;
|
||||||
|
descriptors = cv::Mat(rows, cols, type, data.data()).clone();
|
||||||
|
streamPtr >> image_;
|
||||||
|
this->setData(kpts, descriptors, 0);
|
||||||
|
this->setMinimumSize(image_.size());
|
||||||
|
}
|
||||||
|
|
||||||
|
void Object::paintEvent(QPaintEvent *event)
|
||||||
|
{
|
||||||
|
if(graphicsViewMode_)
|
||||||
|
{
|
||||||
|
QWidget::paintEvent(event);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
if(!image_.isNull())
|
||||||
|
{
|
||||||
|
//Scale
|
||||||
|
float w = image_.width();
|
||||||
|
float h = image_.height();
|
||||||
|
float widthRatio = this->rect().width() / w;
|
||||||
|
float heightRatio = this->rect().height() / h;
|
||||||
|
float ratio = 1.0f;
|
||||||
|
//printf("w=%f, h=%f, wR=%f, hR=%f, sW=%f, sH=%f\n", w, h, widthRatio, heightRatio, sceneRect.width(), sceneRect.height());
|
||||||
|
if(widthRatio < heightRatio)
|
||||||
|
{
|
||||||
|
ratio = widthRatio;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
ratio = heightRatio;
|
||||||
|
}
|
||||||
|
|
||||||
|
//printf("ratio=%f\n",ratio);
|
||||||
|
|
||||||
|
w *= ratio;
|
||||||
|
h *= ratio;
|
||||||
|
|
||||||
|
float offsetX = 0.0f;
|
||||||
|
float offsetY = 0.0f;
|
||||||
|
if(w < this->rect().width())
|
||||||
|
{
|
||||||
|
offsetX = (this->rect().width() - w)/2.0f;
|
||||||
|
}
|
||||||
|
if(h < this->rect().height())
|
||||||
|
{
|
||||||
|
offsetY = (this->rect().height() - h)/2.0f;
|
||||||
|
}
|
||||||
|
QPainter painter(this);
|
||||||
|
|
||||||
|
|
||||||
|
if(_mirrorView->isChecked())
|
||||||
|
{
|
||||||
|
painter.translate(offsetX+w, offsetY);
|
||||||
|
painter.scale(-ratio, ratio);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
painter.translate(offsetX, offsetY);
|
||||||
|
painter.scale(ratio, ratio);
|
||||||
|
}
|
||||||
|
|
||||||
|
if(_showImage->isChecked())
|
||||||
|
{
|
||||||
|
painter.drawPixmap(QPoint(0,0), image_);
|
||||||
|
}
|
||||||
|
if(_showFeatures->isChecked())
|
||||||
|
{
|
||||||
|
drawKeypoints(&painter);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void Object::resizeEvent(QResizeEvent* event)
|
||||||
|
{
|
||||||
|
if(graphicsViewMode_)
|
||||||
|
{
|
||||||
|
graphicsView_->fitInView(graphicsView_->sceneRect(), Qt::KeepAspectRatio);
|
||||||
|
}
|
||||||
|
QWidget::resizeEvent(event);
|
||||||
|
}
|
||||||
|
|
||||||
|
void Object::contextMenuEvent(QContextMenuEvent * event)
|
||||||
|
{
|
||||||
|
QAction * action = _menu->exec(event->globalPos());
|
||||||
|
if(action == _saveImage)
|
||||||
|
{
|
||||||
|
QString text;
|
||||||
|
text = QFileDialog::getSaveFileName(this, tr("Save figure to ..."), _savedFileName, "*.png *.xpm *.jpg *.pdf");
|
||||||
|
if(!text.isEmpty())
|
||||||
|
{
|
||||||
|
if(!text.endsWith(".png") && !text.endsWith(".png") && !text.endsWith(".png") && !text.endsWith(".png"))
|
||||||
|
{
|
||||||
|
text.append(".png");//default
|
||||||
|
}
|
||||||
|
_savedFileName = text;
|
||||||
|
getSceneAsPixmap().save(text);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if(action == _showFeatures || action == _showImage)
|
||||||
|
{
|
||||||
|
if(graphicsViewMode_)
|
||||||
|
{
|
||||||
|
this->updateItemsShown();
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
this->update();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if(action == _mirrorView)
|
||||||
|
{
|
||||||
|
graphicsView_->setTransform(QTransform().scale(this->isMirrorView()?-1.0:1.0, 1.0));
|
||||||
|
if(graphicsViewMode_)
|
||||||
|
{
|
||||||
|
graphicsView_->fitInView(graphicsView_->sceneRect(), Qt::KeepAspectRatio);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
this->update();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if(action == _delete)
|
||||||
|
{
|
||||||
|
emit removalTriggered(this);
|
||||||
|
}
|
||||||
|
else if(action == _plainView)
|
||||||
|
{
|
||||||
|
this->setGraphicsViewMode(!_plainView->isChecked());
|
||||||
|
}
|
||||||
|
QWidget::contextMenuEvent(event);
|
||||||
|
}
|
||||||
|
|
||||||
|
QPixmap Object::getSceneAsPixmap()
|
||||||
|
{
|
||||||
|
if(graphicsViewMode_)
|
||||||
|
{
|
||||||
|
QPixmap img(graphicsView_->sceneRect().width(), graphicsView_->sceneRect().height());
|
||||||
|
QPainter p(&img);
|
||||||
|
graphicsView_->scene()->render(&p, graphicsView_->sceneRect(), graphicsView_->sceneRect());
|
||||||
|
return img;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
return QPixmap::grabWidget(this);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void Object::updateItemsShown()
|
||||||
|
{
|
||||||
|
QList<QGraphicsItem*> items = graphicsView_->scene()->items();
|
||||||
|
for(int i=0; i<items.size(); ++i)
|
||||||
|
{
|
||||||
|
if(qgraphicsitem_cast<KeypointItem*>(items.at(i)))
|
||||||
|
{
|
||||||
|
items.at(i)->setVisible(_showFeatures->isChecked());
|
||||||
|
}
|
||||||
|
else if(qgraphicsitem_cast<QGraphicsPixmapItem*>(items.at(i)))
|
||||||
|
{
|
||||||
|
items.at(i)->setVisible(_showImage->isChecked());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void Object::drawKeypoints(QPainter * painter)
|
||||||
|
{
|
||||||
|
QList<KeypointItem *> items;
|
||||||
|
KeypointItem * item = 0;
|
||||||
|
|
||||||
|
int i = 0;
|
||||||
|
for(std::vector<cv::KeyPoint>::const_iterator iter = keypoints_.begin(); iter != keypoints_.end(); ++iter, ++i )
|
||||||
|
{
|
||||||
|
const cv::KeyPoint & r = *iter;
|
||||||
|
float radius = 14*1.2/9.*2;//r.size*1.2/9.*2;
|
||||||
|
if(graphicsViewMode_)
|
||||||
|
{
|
||||||
|
QString info = QString( "ID = %1\n"
|
||||||
|
"Response = %2\n"
|
||||||
|
"Angle = %3\n"
|
||||||
|
"X = %4\n"
|
||||||
|
"Y = %5\n"
|
||||||
|
"Size = %6").arg(i+1).arg(r.response).arg(r.angle).arg(r.pt.x).arg(r.pt.y).arg(r.size);
|
||||||
|
// YELLOW = NEW and multiple times
|
||||||
|
item = new KeypointItem(i+1, r.pt.x-radius, r.pt.y-radius, radius*2, info, kptColors_.at(i));
|
||||||
|
item->setVisible(this->isFeaturesShown());
|
||||||
|
item->setZValue(1);
|
||||||
|
graphicsView_->scene()->addItem(item);
|
||||||
|
keypointItems_.append(item);
|
||||||
|
}
|
||||||
|
|
||||||
|
if(painter)
|
||||||
|
{
|
||||||
|
painter->save();
|
||||||
|
painter->setPen(kptColors_.at(i));
|
||||||
|
painter->setBrush(kptColors_.at(i));
|
||||||
|
painter->drawEllipse(r.pt.x-radius, r.pt.y-radius, radius*2, radius*2);
|
||||||
|
painter->restore();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
QColor Object::defaultColor() const
|
||||||
|
{
|
||||||
|
int alpha = 20*255/100;
|
||||||
|
return QColor(255, 255, 0, alpha);
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<cv::KeyPoint> Object::selectedKeypoints() const
|
||||||
|
{
|
||||||
|
std::vector<cv::KeyPoint> selected;
|
||||||
|
if(graphicsViewMode_)
|
||||||
|
{
|
||||||
|
QList<QGraphicsItem*> items = graphicsView_->scene()->selectedItems();
|
||||||
|
for(int i=0; i<items.size(); ++i)
|
||||||
|
{
|
||||||
|
if(qgraphicsitem_cast<KeypointItem*>(items.at(i)))
|
||||||
|
{
|
||||||
|
selected.push_back(keypoints_.at(((KeypointItem*)items.at(i))->id()-1)); // ids start at 1
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return selected;
|
||||||
|
}
|
||||||
|
|
||||||
|
void Object::setupGraphicsView()
|
||||||
|
{
|
||||||
|
graphicsView_->scene()->clear();
|
||||||
|
graphicsView_->scene()->setSceneRect(image_.rect());
|
||||||
|
QList<KeypointItem*> items;
|
||||||
|
if(image_.width() > 0 && image_.height() > 0)
|
||||||
|
{
|
||||||
|
QRectF sceneRect = graphicsView_->sceneRect();
|
||||||
|
|
||||||
|
QGraphicsPixmapItem * pixmapItem = graphicsView_->scene()->addPixmap(image_);
|
||||||
|
pixmapItem->setVisible(this->isImageShown());
|
||||||
|
this->drawKeypoints();
|
||||||
|
|
||||||
|
graphicsView_->fitInView(sceneRect, Qt::KeepAspectRatio);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
103
src/Object.h
Normal file
103
src/Object.h
Normal file
@ -0,0 +1,103 @@
|
|||||||
|
/*
|
||||||
|
* VisualObject.h
|
||||||
|
*
|
||||||
|
* Created on: 2011-10-21
|
||||||
|
* Author: matlab
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef OBJECT_H_
|
||||||
|
#define OBJECT_H_
|
||||||
|
|
||||||
|
#include <opencv2/features2d/features2d.hpp>
|
||||||
|
#include <QtGui/QWidget>
|
||||||
|
|
||||||
|
class KeypointItem;
|
||||||
|
class ImageKptsView;
|
||||||
|
class QAction;
|
||||||
|
class QMenu;
|
||||||
|
class QGraphicsView;
|
||||||
|
class QGraphicsScene;
|
||||||
|
|
||||||
|
class Object : public QWidget
|
||||||
|
{
|
||||||
|
Q_OBJECT
|
||||||
|
|
||||||
|
public:
|
||||||
|
Object(QWidget * parent = 0);
|
||||||
|
Object(int id,
|
||||||
|
const std::vector<cv::KeyPoint> & keypoints,
|
||||||
|
const cv::Mat & descriptors,
|
||||||
|
const IplImage * image,
|
||||||
|
const QString & detectorType = "NA",
|
||||||
|
const QString & descriptorType = "NA",
|
||||||
|
QWidget * parent = 0);
|
||||||
|
virtual ~Object();
|
||||||
|
|
||||||
|
void setId(int id);
|
||||||
|
void setData(const std::vector<cv::KeyPoint> & keypoints,
|
||||||
|
const cv::Mat & descriptors,
|
||||||
|
const IplImage * image);
|
||||||
|
void resetKptsColor();
|
||||||
|
void setKptColor(unsigned int index, const QColor & color);
|
||||||
|
void setGraphicsViewMode(bool on);
|
||||||
|
void setDeletable(bool deletable);
|
||||||
|
|
||||||
|
const std::vector<cv::KeyPoint> & keypoints() const {return keypoints_;}
|
||||||
|
const cv::Mat & descriptors() const {return descriptors_;}
|
||||||
|
const QPixmap & image() const {return image_;}
|
||||||
|
const IplImage * iplImage() const {return iplImage_;}
|
||||||
|
int id() const {return id_;}
|
||||||
|
QColor defaultColor() const;
|
||||||
|
bool isImageShown() const;
|
||||||
|
bool isFeaturesShown() const;
|
||||||
|
bool isMirrorView() const;
|
||||||
|
QGraphicsScene * scene() const;
|
||||||
|
std::vector<cv::KeyPoint> selectedKeypoints() const;
|
||||||
|
const QString & detectorType() const {return detectorType_;}
|
||||||
|
const QString & descriptorType() const {return descriptorType_;}
|
||||||
|
|
||||||
|
QPixmap getSceneAsPixmap();
|
||||||
|
|
||||||
|
void save(QDataStream & streamPtr) const;
|
||||||
|
void load(QDataStream & streamPtr);
|
||||||
|
|
||||||
|
protected:
|
||||||
|
virtual void paintEvent(QPaintEvent *event);
|
||||||
|
virtual void contextMenuEvent(QContextMenuEvent * event);
|
||||||
|
virtual void resizeEvent(QResizeEvent* event);
|
||||||
|
|
||||||
|
signals:
|
||||||
|
void removalTriggered(Object *);
|
||||||
|
|
||||||
|
private:
|
||||||
|
void setupGraphicsView();
|
||||||
|
void drawKeypoints(QPainter * painter = 0);
|
||||||
|
void setupUi();
|
||||||
|
void updateItemsShown();
|
||||||
|
|
||||||
|
private:
|
||||||
|
std::vector<cv::KeyPoint> keypoints_;
|
||||||
|
cv::Mat descriptors_;
|
||||||
|
QPixmap image_;
|
||||||
|
IplImage * iplImage_;
|
||||||
|
QList<KeypointItem*> keypointItems_;
|
||||||
|
QGraphicsView * graphicsView_;
|
||||||
|
int id_;
|
||||||
|
bool graphicsViewMode_;
|
||||||
|
QVector<QColor> kptColors_;
|
||||||
|
QString detectorType_;
|
||||||
|
QString descriptorType_;
|
||||||
|
|
||||||
|
// menu stuff
|
||||||
|
QString _savedFileName;
|
||||||
|
QMenu * _menu;
|
||||||
|
QAction * _showImage;
|
||||||
|
QAction * _showFeatures;
|
||||||
|
QAction * _saveImage;
|
||||||
|
QAction * _mirrorView;
|
||||||
|
QAction * _delete;
|
||||||
|
QAction * _plainView;
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
#endif /* OBJECT_H_ */
|
||||||
256
src/ParametersToolBox.cpp
Normal file
256
src/ParametersToolBox.cpp
Normal file
@ -0,0 +1,256 @@
|
|||||||
|
/*
|
||||||
|
* ParametersToolbox.cpp
|
||||||
|
*
|
||||||
|
* Created on: 2011-10-22
|
||||||
|
* Author: matlab
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "ParametersToolBox.h"
|
||||||
|
#include "Settings.h"
|
||||||
|
#include <QtGui/QComboBox>
|
||||||
|
#include <QtGui/QDoubleSpinBox>
|
||||||
|
#include <QtGui/QLineEdit>
|
||||||
|
#include <QtGui/QLabel>
|
||||||
|
#include <QtGui/QGroupBox>
|
||||||
|
#include <QtGui/QCheckBox>
|
||||||
|
#include <QtGui/QVBoxLayout>
|
||||||
|
#include <stdio.h>
|
||||||
|
|
||||||
|
ParametersToolBox::ParametersToolBox(QWidget *parent) :
|
||||||
|
QToolBox(parent)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
ParametersToolBox::~ParametersToolBox()
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
void ParametersToolBox::resetCurrentPage()
|
||||||
|
{
|
||||||
|
const QObjectList & children = this->widget(this->currentIndex())->children();
|
||||||
|
for(int j=0; j<children.size();++j)
|
||||||
|
{
|
||||||
|
QString key = children.at(j)->objectName();
|
||||||
|
QVariant value = Settings::getDefaultParameters().value(key, QVariant());
|
||||||
|
if(value.isValid())
|
||||||
|
{
|
||||||
|
if(qobject_cast<QComboBox*>(children.at(j)))
|
||||||
|
{
|
||||||
|
((QComboBox*)children.at(j))->setCurrentIndex(value.toString().split(':').first().toInt());
|
||||||
|
}
|
||||||
|
else if(qobject_cast<QSpinBox*>(children.at(j)))
|
||||||
|
{
|
||||||
|
((QSpinBox*)children.at(j))->setValue(value.toInt());
|
||||||
|
}
|
||||||
|
else if(qobject_cast<QDoubleSpinBox*>(children.at(j)))
|
||||||
|
{
|
||||||
|
((QDoubleSpinBox*)children.at(j))->setValue(value.toDouble());
|
||||||
|
}
|
||||||
|
else if(qobject_cast<QCheckBox*>(children.at(j)))
|
||||||
|
{
|
||||||
|
((QCheckBox*)children.at(j))->setChecked(value.toBool());
|
||||||
|
}
|
||||||
|
Settings::setParameter(key, value);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void ParametersToolBox::setupUi()
|
||||||
|
{
|
||||||
|
QWidget * currentItem = 0;
|
||||||
|
const ParametersMap & parameters = Settings::getParameters();
|
||||||
|
for(ParametersMap::const_iterator iter=parameters.constBegin();
|
||||||
|
iter!=parameters.constEnd();
|
||||||
|
++iter)
|
||||||
|
{
|
||||||
|
QStringList splitted = iter.key().split('/');
|
||||||
|
QString group = splitted.first();
|
||||||
|
QString name = splitted.last();
|
||||||
|
if(currentItem == 0 || currentItem->objectName().compare(group) != 0)
|
||||||
|
{
|
||||||
|
currentItem = new QWidget(this);
|
||||||
|
int index = this->addItem(currentItem, group);
|
||||||
|
currentItem->setObjectName(group);
|
||||||
|
QVBoxLayout * layout = new QVBoxLayout(currentItem);
|
||||||
|
currentItem->setLayout(layout);
|
||||||
|
layout->addSpacerItem(new QSpacerItem(0,0, QSizePolicy::Minimum, QSizePolicy::Expanding));
|
||||||
|
|
||||||
|
addParameter(layout, iter.key(), iter.value());
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
addParameter((QVBoxLayout*)currentItem->layout(), iter.key(), iter.value());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void ParametersToolBox::addParameter(QVBoxLayout * layout,
|
||||||
|
const QString & key,
|
||||||
|
const QVariant & value)
|
||||||
|
{
|
||||||
|
QString type = Settings::getParametersType().value(key);
|
||||||
|
if(type.compare("QString") == 0)
|
||||||
|
{
|
||||||
|
addParameter(layout, key, value.toString());
|
||||||
|
}
|
||||||
|
else if(type.compare("int") == 0)
|
||||||
|
{
|
||||||
|
addParameter(layout, key, value.toInt());
|
||||||
|
}
|
||||||
|
else if(type.compare("unsigned int") == 0)
|
||||||
|
{
|
||||||
|
addParameter(layout, key, value.toInt());
|
||||||
|
}
|
||||||
|
else if(type.compare("double") == 0)
|
||||||
|
{
|
||||||
|
addParameter(layout, key, value.toDouble());
|
||||||
|
}
|
||||||
|
else if(type.compare("float") == 0)
|
||||||
|
{
|
||||||
|
addParameter(layout, key, value.toDouble());
|
||||||
|
}
|
||||||
|
else if(type.compare("bool") == 0)
|
||||||
|
{
|
||||||
|
addParameter(layout, key, value.toBool());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void ParametersToolBox::addParameter(QVBoxLayout * layout,
|
||||||
|
const QString & key,
|
||||||
|
const QString & value)
|
||||||
|
{
|
||||||
|
if(value.contains(';'))
|
||||||
|
{
|
||||||
|
QComboBox * widget = new QComboBox(this);
|
||||||
|
widget->setObjectName(key);
|
||||||
|
QStringList splitted = value.split(':');
|
||||||
|
widget->addItems(splitted.last().split(';'));
|
||||||
|
widget->setCurrentIndex(splitted.first().toInt());
|
||||||
|
connect(widget, SIGNAL(currentIndexChanged(int)), this, SLOT(changeParameter(int)));
|
||||||
|
addParameter(layout, key.split('/').last(), widget);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
QLineEdit * widget = new QLineEdit(value, this);
|
||||||
|
widget->setObjectName(key);
|
||||||
|
connect(widget, SIGNAL(textChanged(const QString &)), this, SLOT(changeParameter(const QString &)));
|
||||||
|
addParameter(layout, key.split('/').last(), widget);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void ParametersToolBox::addParameter(QVBoxLayout * layout,
|
||||||
|
const QString & key,
|
||||||
|
const double & value)
|
||||||
|
{
|
||||||
|
QDoubleSpinBox * widget = new QDoubleSpinBox(this);
|
||||||
|
double def = Settings::getDefaultParameters().value(key).toDouble();
|
||||||
|
if(def<0.001)
|
||||||
|
{
|
||||||
|
widget->setDecimals(4);
|
||||||
|
}
|
||||||
|
else if(def<0.01)
|
||||||
|
{
|
||||||
|
widget->setDecimals(3);
|
||||||
|
}
|
||||||
|
|
||||||
|
if(def>0.0)
|
||||||
|
{
|
||||||
|
widget->setMaximum(def*10.0);
|
||||||
|
}
|
||||||
|
else if(def<0.0)
|
||||||
|
{
|
||||||
|
widget->setMinimum(def*10.0);
|
||||||
|
widget->setMaximum(0.0);
|
||||||
|
}
|
||||||
|
widget->setValue(value);
|
||||||
|
widget->setObjectName(key);
|
||||||
|
connect(widget, SIGNAL(editingFinished()), this, SLOT(changeParameter()));
|
||||||
|
addParameter(layout, key.split('/').last(), widget);
|
||||||
|
}
|
||||||
|
|
||||||
|
void ParametersToolBox::addParameter(QVBoxLayout * layout,
|
||||||
|
const QString & key,
|
||||||
|
const int & value)
|
||||||
|
{
|
||||||
|
QSpinBox * widget = new QSpinBox(this);
|
||||||
|
int def = Settings::getDefaultParameters().value(key).toInt();
|
||||||
|
|
||||||
|
if(def>0)
|
||||||
|
{
|
||||||
|
widget->setMaximum(def*10);
|
||||||
|
}
|
||||||
|
else if(def<0)
|
||||||
|
{
|
||||||
|
widget->setMinimum(def*10);
|
||||||
|
widget->setMaximum(0);
|
||||||
|
}
|
||||||
|
widget->setValue(value);
|
||||||
|
widget->setObjectName(key);
|
||||||
|
connect(widget, SIGNAL(editingFinished()), this, SLOT(changeParameter()));
|
||||||
|
addParameter(layout, key.split('/').last(), widget);
|
||||||
|
}
|
||||||
|
|
||||||
|
void ParametersToolBox::addParameter(QVBoxLayout * layout,
|
||||||
|
const QString & key,
|
||||||
|
const bool & value)
|
||||||
|
{
|
||||||
|
QCheckBox * widget = new QCheckBox(this);
|
||||||
|
widget->setChecked(value);
|
||||||
|
widget->setObjectName(key);
|
||||||
|
connect(widget, SIGNAL(stateChanged(int)), this, SLOT(changeParameter(int)));
|
||||||
|
addParameter(layout, key.split('/').last(), widget);
|
||||||
|
}
|
||||||
|
|
||||||
|
void ParametersToolBox::addParameter(QVBoxLayout * layout, const QString & name, QWidget * widget)
|
||||||
|
{
|
||||||
|
QHBoxLayout * hLayout = new QHBoxLayout();
|
||||||
|
layout->insertLayout(layout->count()-1, hLayout);
|
||||||
|
hLayout->addWidget(new QLabel(name, this));
|
||||||
|
hLayout->addWidget(widget);
|
||||||
|
}
|
||||||
|
|
||||||
|
void ParametersToolBox::changeParameter(const QString & value)
|
||||||
|
{
|
||||||
|
if(sender())
|
||||||
|
{
|
||||||
|
Settings::setParameter(sender()->objectName(), value);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
void ParametersToolBox::changeParameter()
|
||||||
|
{
|
||||||
|
if(sender())
|
||||||
|
{
|
||||||
|
QDoubleSpinBox * doubleSpinBox = qobject_cast<QDoubleSpinBox*>(sender());
|
||||||
|
QSpinBox * spinBox = qobject_cast<QSpinBox*>(sender());
|
||||||
|
if(doubleSpinBox)
|
||||||
|
{
|
||||||
|
Settings::setParameter(sender()->objectName(), doubleSpinBox->value());
|
||||||
|
}
|
||||||
|
else if(spinBox)
|
||||||
|
{
|
||||||
|
Settings::setParameter(sender()->objectName(), spinBox->value());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
void ParametersToolBox::changeParameter(const int & value)
|
||||||
|
{
|
||||||
|
if(sender())
|
||||||
|
{
|
||||||
|
QComboBox * comboBox = qobject_cast<QComboBox*>(sender());
|
||||||
|
QCheckBox * checkBox = qobject_cast<QCheckBox*>(sender());
|
||||||
|
if(comboBox)
|
||||||
|
{
|
||||||
|
QStringList items;
|
||||||
|
for(int i=0; i<comboBox->count(); ++i)
|
||||||
|
{
|
||||||
|
items.append(comboBox->itemText(i));
|
||||||
|
}
|
||||||
|
QString merged = QString::number(value) + QString(":") + items.join(";");
|
||||||
|
Settings::setParameter(sender()->objectName(), merged);
|
||||||
|
}
|
||||||
|
else if(checkBox)
|
||||||
|
{
|
||||||
|
Settings::setParameter(sender()->objectName(), value==Qt::Checked?true:false);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
42
src/ParametersToolBox.h
Normal file
42
src/ParametersToolBox.h
Normal file
@ -0,0 +1,42 @@
|
|||||||
|
/*
|
||||||
|
* ParametersToolbox.h
|
||||||
|
*
|
||||||
|
* Created on: 2011-10-22
|
||||||
|
* Author: matlab
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef PARAMETERSTOOLBOX_H_
|
||||||
|
#define PARAMETERSTOOLBOX_H_
|
||||||
|
|
||||||
|
#include <QtGui/QToolBox>
|
||||||
|
|
||||||
|
class QVBoxLayout;
|
||||||
|
class QAbstractButton;
|
||||||
|
|
||||||
|
class ParametersToolBox: public QToolBox
|
||||||
|
{
|
||||||
|
Q_OBJECT
|
||||||
|
|
||||||
|
public:
|
||||||
|
ParametersToolBox(QWidget *parent = 0);
|
||||||
|
virtual ~ParametersToolBox();
|
||||||
|
|
||||||
|
void setupUi();
|
||||||
|
|
||||||
|
private:
|
||||||
|
void addParameter(QVBoxLayout * layout, const QString & key, const QVariant & value);
|
||||||
|
void addParameter(QVBoxLayout * layout, const QString & key, const QString & value);
|
||||||
|
void addParameter(QVBoxLayout * layout, const QString & key, const int & value);
|
||||||
|
void addParameter(QVBoxLayout * layout, const QString & key, const double & value);
|
||||||
|
void addParameter(QVBoxLayout * layout, const QString & key, const bool & value);
|
||||||
|
void addParameter(QVBoxLayout * layout, const QString & name, QWidget * widget);
|
||||||
|
|
||||||
|
private slots:
|
||||||
|
void changeParameter();
|
||||||
|
void changeParameter(const QString & value);
|
||||||
|
void changeParameter(const int & value);
|
||||||
|
void resetCurrentPage();
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* PARAMETERSTOOLBOX_H_ */
|
||||||
285
src/Settings.cpp
Normal file
285
src/Settings.cpp
Normal file
@ -0,0 +1,285 @@
|
|||||||
|
/*
|
||||||
|
* Settings.cpp
|
||||||
|
*
|
||||||
|
* Created on: 2011-10-22
|
||||||
|
* Author: matlab
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
#include "Settings.h"
|
||||||
|
#include "Camera.h"
|
||||||
|
#include <QtCore/QSettings>
|
||||||
|
#include <QtCore/QStringList>
|
||||||
|
#include <stdio.h>
|
||||||
|
|
||||||
|
ParametersMap Settings::defaultParameters_;
|
||||||
|
ParametersMap Settings::parameters_;
|
||||||
|
ParametersType Settings::parametersType_;
|
||||||
|
Settings Settings::dummyInit_;
|
||||||
|
const char * Settings::iniDefaultFileName = "./" PROJECT_NAME ".ini";
|
||||||
|
|
||||||
|
void Settings::loadSettings(const QString & fileName, QByteArray * windowGeometry)
|
||||||
|
{
|
||||||
|
QSettings ini(fileName, QSettings::IniFormat);
|
||||||
|
for(ParametersMap::const_iterator iter = defaultParameters_.begin(); iter!=defaultParameters_.end(); ++iter)
|
||||||
|
{
|
||||||
|
const QString & key = iter.key();
|
||||||
|
QVariant value = ini.value(key, QVariant());
|
||||||
|
if(value.isValid())
|
||||||
|
{
|
||||||
|
setParameter(key, value);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if(windowGeometry)
|
||||||
|
{
|
||||||
|
QVariant value = ini.value("windowGeometry", QVariant());
|
||||||
|
if(value.isValid())
|
||||||
|
{
|
||||||
|
*windowGeometry = value.toByteArray();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
printf("Settings loaded from %s\n", fileName.toStdString().c_str());
|
||||||
|
}
|
||||||
|
|
||||||
|
void Settings::saveSettings(const QString & fileName, const QByteArray & windowGeometry)
|
||||||
|
{
|
||||||
|
QSettings ini(fileName, QSettings::IniFormat);
|
||||||
|
for(ParametersMap::const_iterator iter = parameters_.begin(); iter!=parameters_.end(); ++iter)
|
||||||
|
{
|
||||||
|
QString type = Settings::getParametersType().value(iter.key());
|
||||||
|
if(type.compare("float") == 0)
|
||||||
|
{
|
||||||
|
ini.setValue(iter.key(), QString::number(iter.value().toFloat(),'g',6));
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
ini.setValue(iter.key(), iter.value());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if(!windowGeometry.isEmpty())
|
||||||
|
{
|
||||||
|
ini.setValue("windowGeometry", windowGeometry);
|
||||||
|
}
|
||||||
|
printf("Settings saved to %s\n", fileName.toStdString().c_str());
|
||||||
|
}
|
||||||
|
|
||||||
|
cv::FeatureDetector * Settings::createFeaturesDetector()
|
||||||
|
{
|
||||||
|
cv::FeatureDetector * detector = 0;
|
||||||
|
QString str = getDetector_Type().toString();
|
||||||
|
QStringList split = str.split(':');
|
||||||
|
if(split.size()==2)
|
||||||
|
{
|
||||||
|
bool ok = false;
|
||||||
|
int index = split.first().toInt(&ok);
|
||||||
|
if(ok)
|
||||||
|
{
|
||||||
|
QStringList strategies = split.last().split(';');
|
||||||
|
if(strategies.size() == 8 && index>=0 && index<8)
|
||||||
|
{
|
||||||
|
switch(index)
|
||||||
|
{
|
||||||
|
case 0:
|
||||||
|
if(strategies.at(index).compare("Dense") == 0)
|
||||||
|
{
|
||||||
|
cv::DenseFeatureDetector::Params params;
|
||||||
|
params.initFeatureScale = getDense_initFeatureScale().toFloat();
|
||||||
|
params.featureScaleLevels = getDense_featureScaleLevels().toInt();
|
||||||
|
params.featureScaleMul = getDense_featureScaleMul().toFloat();
|
||||||
|
params.initXyStep = getDense_initXyStep().toInt();
|
||||||
|
params.initImgBound = getDense_initImgBound().toInt();
|
||||||
|
params.varyXyStepWithScale = getDense_varyXyStepWithScale().toBool();
|
||||||
|
params.varyImgBoundWithScale = getDense_varyImgBoundWithScale().toBool();
|
||||||
|
detector = new cv::DenseFeatureDetector(params);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case 1:
|
||||||
|
if(strategies.at(index).compare("Fast") == 0)
|
||||||
|
{
|
||||||
|
detector = new cv::FastFeatureDetector(
|
||||||
|
getFast_threshold().toInt(),
|
||||||
|
getFast_nonmaxSuppression().toBool());
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
if(strategies.at(index).compare("GoodFeaturesToTrack") == 0)
|
||||||
|
{
|
||||||
|
cv::GoodFeaturesToTrackDetector::Params params;
|
||||||
|
params.maxCorners = getGoodFeaturesToTrack_maxCorners().toInt();
|
||||||
|
params.qualityLevel = getGoodFeaturesToTrack_qualityLevel().toDouble();
|
||||||
|
params.minDistance = getGoodFeaturesToTrack_minDistance().toDouble();
|
||||||
|
params.blockSize = getGoodFeaturesToTrack_blockSize().toInt();
|
||||||
|
params.useHarrisDetector = getGoodFeaturesToTrack_useHarrisDetector().toBool();
|
||||||
|
params.k = getGoodFeaturesToTrack_k().toDouble();
|
||||||
|
detector = new cv::GoodFeaturesToTrackDetector(params);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case 3:
|
||||||
|
if(strategies.at(index).compare("Mser") == 0)
|
||||||
|
{
|
||||||
|
CvMSERParams params = cvMSERParams();
|
||||||
|
params.delta = getMser_delta().toInt();
|
||||||
|
params.maxArea = getMser_maxArea().toInt();
|
||||||
|
params.minArea = getMser_minArea().toInt();
|
||||||
|
params.maxVariation = getMser_maxVariation().toFloat();
|
||||||
|
params.minDiversity = getMser_minDiversity().toFloat();
|
||||||
|
params.maxEvolution = getMser_maxEvolution().toInt();
|
||||||
|
params.areaThreshold = getMser_areaThreshold().toDouble();
|
||||||
|
params.minMargin = getMser_minMargin().toDouble();
|
||||||
|
params.edgeBlurSize = getMser_edgeBlurSize().toInt();
|
||||||
|
detector = new cv::MserFeatureDetector(params);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case 4:
|
||||||
|
if(strategies.at(index).compare("Orb") == 0)
|
||||||
|
{
|
||||||
|
cv::ORB::CommonParams params;
|
||||||
|
params.scale_factor_ = getOrb_scaleFactor().toFloat();
|
||||||
|
params.n_levels_ = getOrb_nLevels().toUInt();
|
||||||
|
params.first_level_ = getOrb_firstLevel().toUInt();
|
||||||
|
params.edge_threshold_ = getOrb_edgeThreshold().toInt();
|
||||||
|
detector = new cv::OrbFeatureDetector(
|
||||||
|
getOrb_nFeatures().toUInt(),
|
||||||
|
params);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case 5:
|
||||||
|
if(strategies.at(index).compare("Sift") == 0)
|
||||||
|
{
|
||||||
|
cv::SIFT::DetectorParams detectorParams;
|
||||||
|
detectorParams.edgeThreshold = getSift_edgeThreshold().toDouble();
|
||||||
|
detectorParams.threshold = getSift_threshold().toDouble();
|
||||||
|
cv::SIFT::CommonParams commonParams;
|
||||||
|
commonParams.angleMode = getSift_angleMode().toInt();
|
||||||
|
commonParams.firstOctave = getSift_firstOctave().toInt();
|
||||||
|
commonParams.nOctaveLayers = getSift_nOctaveLayers().toInt();
|
||||||
|
commonParams.nOctaves = getSift_nOctaves().toInt();
|
||||||
|
detector = new cv::SiftFeatureDetector(
|
||||||
|
detectorParams,
|
||||||
|
commonParams);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case 6:
|
||||||
|
if(strategies.at(index).compare("Star") == 0)
|
||||||
|
{
|
||||||
|
CvStarDetectorParams params = cvStarDetectorParams();
|
||||||
|
params.lineThresholdBinarized = getStar_lineThresholdBinarized().toInt();
|
||||||
|
params.lineThresholdProjected = getStar_lineThresholdProjected().toInt();
|
||||||
|
params.maxSize = getStar_maxSize().toInt();
|
||||||
|
params.responseThreshold = getStar_responseThreshold().toInt();
|
||||||
|
params.suppressNonmaxSize = getStar_suppressNonmaxSize().toInt();
|
||||||
|
detector = new cv::StarFeatureDetector(params);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case 7:
|
||||||
|
if(strategies.at(index).compare("Surf") == 0)
|
||||||
|
{
|
||||||
|
detector = new cv::SurfFeatureDetector(
|
||||||
|
getSurf_hessianThreshold().toDouble(),
|
||||||
|
getSurf_octaves().toInt(),
|
||||||
|
getSurf_octaveLayers().toInt(),
|
||||||
|
getSurf_upright().toBool());
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return detector;
|
||||||
|
}
|
||||||
|
|
||||||
|
cv::DescriptorExtractor * Settings::createDescriptorsExtractor()
|
||||||
|
{
|
||||||
|
cv::DescriptorExtractor * extractor = 0;
|
||||||
|
QString str = getDescriptor_Type().toString();
|
||||||
|
QStringList split = str.split(':');
|
||||||
|
if(split.size()==2)
|
||||||
|
{
|
||||||
|
bool ok = false;
|
||||||
|
int index = split.first().toInt(&ok);
|
||||||
|
if(ok)
|
||||||
|
{
|
||||||
|
QStringList strategies = split.last().split(';');
|
||||||
|
if(strategies.size() == 4 && index>=0 && index<4)
|
||||||
|
{
|
||||||
|
switch(index)
|
||||||
|
{
|
||||||
|
case 0:
|
||||||
|
if(strategies.at(index).compare("Brief") == 0)
|
||||||
|
{
|
||||||
|
extractor = new cv::BriefDescriptorExtractor(
|
||||||
|
getBrief_bytes().toInt());
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case 1:
|
||||||
|
if(strategies.at(index).compare("Orb") == 0)
|
||||||
|
{
|
||||||
|
cv::ORB::CommonParams params;
|
||||||
|
params.scale_factor_ = getOrb_scaleFactor().toFloat();
|
||||||
|
params.n_levels_ = getOrb_nLevels().toUInt();
|
||||||
|
params.first_level_ = getOrb_firstLevel().toUInt();
|
||||||
|
params.edge_threshold_ = getOrb_edgeThreshold().toInt();
|
||||||
|
extractor = new cv::OrbDescriptorExtractor(params);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
if(strategies.at(index).compare("Sift") == 0)
|
||||||
|
{
|
||||||
|
cv::SIFT::DescriptorParams descriptorParams;
|
||||||
|
descriptorParams.isNormalize = getSift_isNormalize().toBool();
|
||||||
|
descriptorParams.magnification = getSift_magnification().toDouble();
|
||||||
|
descriptorParams.recalculateAngles = getSift_recalculateAngles().toBool();
|
||||||
|
cv::SIFT::CommonParams commonParams;
|
||||||
|
commonParams.angleMode = getSift_angleMode().toInt();
|
||||||
|
commonParams.firstOctave = getSift_firstOctave().toInt();
|
||||||
|
commonParams.nOctaveLayers = getSift_nOctaveLayers().toInt();
|
||||||
|
commonParams.nOctaves = getSift_nOctaves().toInt();
|
||||||
|
extractor = new cv::SiftDescriptorExtractor(
|
||||||
|
descriptorParams,
|
||||||
|
commonParams);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case 3:
|
||||||
|
if(strategies.at(index).compare("Surf") == 0)
|
||||||
|
{
|
||||||
|
extractor = new cv::SurfDescriptorExtractor(
|
||||||
|
getSurf_octaves().toInt(),
|
||||||
|
getSurf_octaveLayers().toInt(),
|
||||||
|
getSurf_extended().toBool(),
|
||||||
|
getSurf_upright().toBool());
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return extractor;
|
||||||
|
}
|
||||||
|
|
||||||
|
Camera * Settings::createCamera()
|
||||||
|
{
|
||||||
|
return new Camera(
|
||||||
|
getCamera_deviceId().toInt(),
|
||||||
|
getCamera_imageWidth().toInt(),
|
||||||
|
getCamera_imageHeight().toInt());
|
||||||
|
}
|
||||||
|
|
||||||
|
QString Settings::currentDetectorType()
|
||||||
|
{
|
||||||
|
int index = Settings::getDetector_Type().toString().split(':').first().toInt();
|
||||||
|
return getDetector_Type().toString().split(':').last().split(';').at(index);
|
||||||
|
}
|
||||||
|
|
||||||
|
QString Settings::currentDescriptorType()
|
||||||
|
{
|
||||||
|
int index = Settings::getDescriptor_Type().toString().split(':').first().toInt();
|
||||||
|
return getDescriptor_Type().toString().split(':').last().split(';').at(index);
|
||||||
|
}
|
||||||
|
|
||||||
150
src/Settings.h
Normal file
150
src/Settings.h
Normal file
@ -0,0 +1,150 @@
|
|||||||
|
/*
|
||||||
|
* Settings.h
|
||||||
|
*
|
||||||
|
* Created on: 2011-10-22
|
||||||
|
* Author: matlab
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef SETTINGS_H_
|
||||||
|
#define SETTINGS_H_
|
||||||
|
|
||||||
|
#include <QtCore/QMap>
|
||||||
|
#include <QtCore/QVariant>
|
||||||
|
#include <QtCore/QByteArray>
|
||||||
|
#include <opencv2/features2d/features2d.hpp>
|
||||||
|
|
||||||
|
class Camera;
|
||||||
|
|
||||||
|
typedef QMap<QString, QVariant> ParametersMap; // Key, value
|
||||||
|
typedef QMap<QString, QString> ParametersType; // Key, type
|
||||||
|
|
||||||
|
// MACRO BEGIN
|
||||||
|
#define PARAMETER(PREFIX, NAME, TYPE, DEFAULT_VALUE) \
|
||||||
|
public: \
|
||||||
|
static QString k##PREFIX##_##NAME() {return QString(#PREFIX "/" #NAME);} \
|
||||||
|
static TYPE default##PREFIX##_##NAME() {return DEFAULT_VALUE;} \
|
||||||
|
static QString type##PREFIX##_##NAME() {return QString(#TYPE);} \
|
||||||
|
static QVariant get##PREFIX##_##NAME() {return parameters_.value(#PREFIX "/" #NAME);} \
|
||||||
|
static void set##PREFIX##_##NAME(const TYPE & value) {parameters_[#PREFIX "/" #NAME] = value;} \
|
||||||
|
private: \
|
||||||
|
class Dummy##PREFIX##_##NAME { \
|
||||||
|
public: \
|
||||||
|
Dummy##PREFIX##_##NAME() { \
|
||||||
|
defaultParameters_.insert(#PREFIX "/" #NAME, QVariant(DEFAULT_VALUE)); \
|
||||||
|
parameters_.insert(#PREFIX "/" #NAME, DEFAULT_VALUE); \
|
||||||
|
parametersType_.insert(#PREFIX "/" #NAME, #TYPE);} \
|
||||||
|
}; \
|
||||||
|
Dummy##PREFIX##_##NAME dummy##PREFIX##_##NAME;
|
||||||
|
// MACRO END
|
||||||
|
|
||||||
|
class Settings
|
||||||
|
{
|
||||||
|
PARAMETER(Camera, deviceId, int, 0);
|
||||||
|
PARAMETER(Camera, imageWidth, int, 640);
|
||||||
|
PARAMETER(Camera, imageHeight, int, 480);
|
||||||
|
PARAMETER(Camera, imageRate, int, 5); // Hz
|
||||||
|
|
||||||
|
//List format : [Index:item0;item1;item3;...]
|
||||||
|
PARAMETER(Detector, Type, QString, "1:Dense;Fast;GoodFeaturesToTrack;Mser;Orb;Sift;Star;Surf");
|
||||||
|
PARAMETER(Descriptor, Type, QString, "0:Brief;Orb;Sift;Surf");
|
||||||
|
|
||||||
|
PARAMETER(Brief, bytes, int, 32);
|
||||||
|
|
||||||
|
PARAMETER(Dense, initFeatureScale, float, cv::DenseFeatureDetector::Params().initFeatureScale);
|
||||||
|
PARAMETER(Dense, featureScaleLevels, int, cv::DenseFeatureDetector::Params().featureScaleLevels);
|
||||||
|
PARAMETER(Dense, featureScaleMul, float, cv::DenseFeatureDetector::Params().featureScaleMul);
|
||||||
|
PARAMETER(Dense, initXyStep, int, cv::DenseFeatureDetector::Params().initXyStep);
|
||||||
|
PARAMETER(Dense, initImgBound, int, cv::DenseFeatureDetector::Params().initImgBound);
|
||||||
|
PARAMETER(Dense, varyXyStepWithScale, bool, cv::DenseFeatureDetector::Params().varyXyStepWithScale);
|
||||||
|
PARAMETER(Dense, varyImgBoundWithScale, bool, cv::DenseFeatureDetector::Params().varyImgBoundWithScale);
|
||||||
|
|
||||||
|
PARAMETER(Fast, threshold, int, 20);
|
||||||
|
PARAMETER(Fast, nonmaxSuppression, bool, true);
|
||||||
|
|
||||||
|
PARAMETER(GoodFeaturesToTrack, maxCorners, int, cv::GoodFeaturesToTrackDetector::Params().maxCorners);
|
||||||
|
PARAMETER(GoodFeaturesToTrack, qualityLevel, double, cv::GoodFeaturesToTrackDetector::Params().qualityLevel);
|
||||||
|
PARAMETER(GoodFeaturesToTrack, minDistance, double, cv::GoodFeaturesToTrackDetector::Params().minDistance);
|
||||||
|
PARAMETER(GoodFeaturesToTrack, blockSize, int, cv::GoodFeaturesToTrackDetector::Params().blockSize);
|
||||||
|
PARAMETER(GoodFeaturesToTrack, useHarrisDetector, bool, cv::GoodFeaturesToTrackDetector::Params().useHarrisDetector);
|
||||||
|
PARAMETER(GoodFeaturesToTrack, k, double, cv::GoodFeaturesToTrackDetector::Params().k);
|
||||||
|
|
||||||
|
PARAMETER(Orb, nFeatures, unsigned int, 700);
|
||||||
|
PARAMETER(Orb, scaleFactor, float, cv::ORB::CommonParams().scale_factor_);
|
||||||
|
PARAMETER(Orb, nLevels, unsigned int, cv::ORB::CommonParams().n_levels_);
|
||||||
|
PARAMETER(Orb, firstLevel, unsigned int, cv::ORB::CommonParams().first_level_);
|
||||||
|
PARAMETER(Orb, edgeThreshold, int, cv::ORB::CommonParams().edge_threshold_);
|
||||||
|
|
||||||
|
PARAMETER(Mser, delta, int, cvMSERParams().delta);
|
||||||
|
PARAMETER(Mser, minArea, int, cvMSERParams().minArea);
|
||||||
|
PARAMETER(Mser, maxArea, int, cvMSERParams().maxArea);
|
||||||
|
PARAMETER(Mser, maxVariation, float, cvMSERParams().maxVariation);
|
||||||
|
PARAMETER(Mser, minDiversity, float, cvMSERParams().minDiversity);
|
||||||
|
PARAMETER(Mser, maxEvolution, int, cvMSERParams().maxEvolution);
|
||||||
|
PARAMETER(Mser, areaThreshold, double, cvMSERParams().areaThreshold);
|
||||||
|
PARAMETER(Mser, minMargin, double, cvMSERParams().minMargin);
|
||||||
|
PARAMETER(Mser, edgeBlurSize, int, cvMSERParams().edgeBlurSize);
|
||||||
|
|
||||||
|
PARAMETER(Sift, threshold, double, cv::SIFT::DetectorParams::GET_DEFAULT_THRESHOLD());
|
||||||
|
PARAMETER(Sift, edgeThreshold, double, cv::SIFT::DetectorParams::GET_DEFAULT_EDGE_THRESHOLD());
|
||||||
|
PARAMETER(Sift, nOctaves, int, cv::SIFT::CommonParams::DEFAULT_NOCTAVES);
|
||||||
|
PARAMETER(Sift, nOctaveLayers, int, cv::SIFT::CommonParams::DEFAULT_NOCTAVE_LAYERS);
|
||||||
|
PARAMETER(Sift, firstOctave, int, cv::SIFT::CommonParams::DEFAULT_FIRST_OCTAVE);
|
||||||
|
PARAMETER(Sift, angleMode, int, cv::SIFT::CommonParams::FIRST_ANGLE);
|
||||||
|
PARAMETER(Sift, magnification, double, cv::SIFT::DescriptorParams::GET_DEFAULT_MAGNIFICATION());
|
||||||
|
PARAMETER(Sift, isNormalize, bool, cv::SIFT::DescriptorParams::DEFAULT_IS_NORMALIZE);
|
||||||
|
PARAMETER(Sift, recalculateAngles, bool, true);
|
||||||
|
|
||||||
|
PARAMETER(Star, maxSize, int, cvStarDetectorParams().maxSize);
|
||||||
|
PARAMETER(Star, responseThreshold, int, cvStarDetectorParams().responseThreshold);
|
||||||
|
PARAMETER(Star, lineThresholdProjected, int, cvStarDetectorParams().lineThresholdProjected);
|
||||||
|
PARAMETER(Star, lineThresholdBinarized, int, cvStarDetectorParams().lineThresholdBinarized);
|
||||||
|
PARAMETER(Star, suppressNonmaxSize, int, cvStarDetectorParams().suppressNonmaxSize);
|
||||||
|
|
||||||
|
PARAMETER(Surf, hessianThreshold, double, 400.0);
|
||||||
|
PARAMETER(Surf, octaves, int, 3);
|
||||||
|
PARAMETER(Surf, octaveLayers, int, 4);
|
||||||
|
PARAMETER(Surf, upright, bool, false);
|
||||||
|
PARAMETER(Surf, extended, bool, false);
|
||||||
|
|
||||||
|
PARAMETER(NN, nndrRatio, float, 0.8f); // NNDR RATIO
|
||||||
|
|
||||||
|
PARAMETER(General, nextObjID, unsigned int, 1);
|
||||||
|
|
||||||
|
PARAMETER(Homography, ransacReprojThr, double, 1.0);
|
||||||
|
PARAMETER(Homography, minimumInliers, int, 10);
|
||||||
|
|
||||||
|
public:
|
||||||
|
virtual ~Settings(){}
|
||||||
|
|
||||||
|
static const char * iniDefaultFileName; // "./" PROJECT_NAME ".ini"
|
||||||
|
|
||||||
|
static void loadSettings(const QString & fileName = iniDefaultFileName, QByteArray * windowGeometry = 0);
|
||||||
|
static void saveSettings(const QString & fileName = iniDefaultFileName, const QByteArray & windowGeometry = QByteArray());
|
||||||
|
|
||||||
|
static const ParametersMap & getDefaultParameters() {return defaultParameters_;}
|
||||||
|
static const ParametersMap & getParameters() {return parameters_;}
|
||||||
|
static const ParametersType & getParametersType() {return parametersType_;}
|
||||||
|
static void setParameter(const QString & key, const QVariant & value) {if(parameters_.contains(key))parameters_[key] = value;}
|
||||||
|
static void resetParameter(const QString & key) {if(defaultParameters_.contains(key)) parameters_.insert(key, defaultParameters_.value(key));}
|
||||||
|
static QVariant getParameter(const QString & key) {return parameters_.value(key, QVariant());}
|
||||||
|
|
||||||
|
static cv::FeatureDetector * createFeaturesDetector();
|
||||||
|
static cv::DescriptorExtractor * createDescriptorsExtractor();
|
||||||
|
|
||||||
|
static QString currentDescriptorType();
|
||||||
|
static QString currentDetectorType();
|
||||||
|
|
||||||
|
static Camera * createCamera();
|
||||||
|
|
||||||
|
private:
|
||||||
|
Settings(){}
|
||||||
|
|
||||||
|
private:
|
||||||
|
static ParametersMap defaultParameters_;
|
||||||
|
static ParametersMap parameters_;
|
||||||
|
static ParametersType parametersType_;
|
||||||
|
static Settings dummyInit_;
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
#endif /* SETTINGS_H_ */
|
||||||
18
src/main.cpp
Normal file
18
src/main.cpp
Normal file
@ -0,0 +1,18 @@
|
|||||||
|
#include <QtGui/QApplication>
|
||||||
|
#include "MainWindow.h"
|
||||||
|
|
||||||
|
int main(int argc, char* argv[])
|
||||||
|
{
|
||||||
|
/* Create tasks */
|
||||||
|
QApplication app(argc, argv);
|
||||||
|
MainWindow mainWindow;
|
||||||
|
|
||||||
|
mainWindow.showNormal();
|
||||||
|
|
||||||
|
// Now wait for application to finish
|
||||||
|
app.connect( &app, SIGNAL( lastWindowClosed() ),
|
||||||
|
&app, SLOT( quit() ) );
|
||||||
|
app.exec();// MUST be called by the Main Thread
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
30
src/qtipl.cpp
Normal file
30
src/qtipl.cpp
Normal file
@ -0,0 +1,30 @@
|
|||||||
|
|
||||||
|
#include "qtipl.h"
|
||||||
|
#include <opencv2/core/core_c.h>
|
||||||
|
|
||||||
|
// TODO : support only from gray 8bits ?
|
||||||
|
QImage Ipl2QImage(const IplImage *newImage)
|
||||||
|
{
|
||||||
|
QImage qtemp;
|
||||||
|
if (newImage && newImage->depth == IPL_DEPTH_8U && cvGetSize(newImage).width>0)
|
||||||
|
{
|
||||||
|
int x;
|
||||||
|
int y;
|
||||||
|
char* data = newImage->imageData;
|
||||||
|
|
||||||
|
qtemp= QImage(newImage->width, newImage->height,QImage::Format_RGB32 );
|
||||||
|
for( y = 0; y < newImage->height; y++, data +=newImage->widthStep )
|
||||||
|
{
|
||||||
|
for( x = 0; x < newImage->width; x++)
|
||||||
|
{
|
||||||
|
uint *p = (uint*)qtemp.scanLine (y) + x;
|
||||||
|
*p = qRgb(data[x * newImage->nChannels+2], data[x * newImage->nChannels+1],data[x * newImage->nChannels]);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
//Wrong IplImage format
|
||||||
|
}
|
||||||
|
return qtemp;
|
||||||
|
}
|
||||||
9
src/qtipl.h
Normal file
9
src/qtipl.h
Normal file
@ -0,0 +1,9 @@
|
|||||||
|
#ifndef QTIPL_H
|
||||||
|
#define QTIPL_H
|
||||||
|
|
||||||
|
#include <QtGui/QImage>
|
||||||
|
#include <opencv2/core/core.hpp>
|
||||||
|
|
||||||
|
QImage Ipl2QImage(const IplImage *newImage);
|
||||||
|
|
||||||
|
#endif
|
||||||
91
src/ui/addObjectDialog.ui
Normal file
91
src/ui/addObjectDialog.ui
Normal file
@ -0,0 +1,91 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<ui version="4.0">
|
||||||
|
<class>addObjectDialog</class>
|
||||||
|
<widget class="QDialog" name="addObjectDialog">
|
||||||
|
<property name="geometry">
|
||||||
|
<rect>
|
||||||
|
<x>0</x>
|
||||||
|
<y>0</y>
|
||||||
|
<width>527</width>
|
||||||
|
<height>420</height>
|
||||||
|
</rect>
|
||||||
|
</property>
|
||||||
|
<property name="windowTitle">
|
||||||
|
<string>Add object</string>
|
||||||
|
</property>
|
||||||
|
<layout class="QVBoxLayout" name="verticalLayout" stretch="0,1,0">
|
||||||
|
<item>
|
||||||
|
<widget class="QLabel" name="label_instruction">
|
||||||
|
<property name="text">
|
||||||
|
<string>(Instructions)</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
||||||
|
<item>
|
||||||
|
<widget class="Object" name="cameraView" native="true"/>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<widget class="Object" name="objectView" native="true"/>
|
||||||
|
</item>
|
||||||
|
</layout>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<layout class="QHBoxLayout" name="horizontalLayout">
|
||||||
|
<item>
|
||||||
|
<widget class="QPushButton" name="pushButton_cancel">
|
||||||
|
<property name="text">
|
||||||
|
<string>Cancel</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<spacer name="horizontalSpacer">
|
||||||
|
<property name="orientation">
|
||||||
|
<enum>Qt::Horizontal</enum>
|
||||||
|
</property>
|
||||||
|
<property name="sizeHint" stdset="0">
|
||||||
|
<size>
|
||||||
|
<width>40</width>
|
||||||
|
<height>20</height>
|
||||||
|
</size>
|
||||||
|
</property>
|
||||||
|
</spacer>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<widget class="QPushButton" name="pushButton_back">
|
||||||
|
<property name="text">
|
||||||
|
<string>Back</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<widget class="QPushButton" name="pushButton_takePicture">
|
||||||
|
<property name="text">
|
||||||
|
<string>Take picture</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<widget class="QPushButton" name="pushButton_next">
|
||||||
|
<property name="text">
|
||||||
|
<string>End</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
</layout>
|
||||||
|
</item>
|
||||||
|
</layout>
|
||||||
|
</widget>
|
||||||
|
<customwidgets>
|
||||||
|
<customwidget>
|
||||||
|
<class>Object</class>
|
||||||
|
<extends>QWidget</extends>
|
||||||
|
<header>Object.h</header>
|
||||||
|
<container>1</container>
|
||||||
|
</customwidget>
|
||||||
|
</customwidgets>
|
||||||
|
<resources/>
|
||||||
|
<connections/>
|
||||||
|
</ui>
|
||||||
450
src/ui/mainWindow.ui
Normal file
450
src/ui/mainWindow.ui
Normal file
@ -0,0 +1,450 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<ui version="4.0">
|
||||||
|
<class>mainWindow</class>
|
||||||
|
<widget class="QMainWindow" name="mainWindow">
|
||||||
|
<property name="geometry">
|
||||||
|
<rect>
|
||||||
|
<x>0</x>
|
||||||
|
<y>0</y>
|
||||||
|
<width>864</width>
|
||||||
|
<height>533</height>
|
||||||
|
</rect>
|
||||||
|
</property>
|
||||||
|
<property name="windowTitle">
|
||||||
|
<string>Find object</string>
|
||||||
|
</property>
|
||||||
|
<widget class="QWidget" name="centralwidget">
|
||||||
|
<layout class="QHBoxLayout" name="horizontalLayout" stretch="2">
|
||||||
|
<property name="spacing">
|
||||||
|
<number>0</number>
|
||||||
|
</property>
|
||||||
|
<property name="margin">
|
||||||
|
<number>0</number>
|
||||||
|
</property>
|
||||||
|
<item>
|
||||||
|
<layout class="QVBoxLayout" name="verticalLayout" stretch="0,1">
|
||||||
|
<property name="spacing">
|
||||||
|
<number>0</number>
|
||||||
|
</property>
|
||||||
|
<item>
|
||||||
|
<layout class="QHBoxLayout" name="horizontalLayout_2" stretch="0,0,0,0,0,0,0">
|
||||||
|
<item>
|
||||||
|
<widget class="QLabel" name="label_5">
|
||||||
|
<property name="font">
|
||||||
|
<font>
|
||||||
|
<weight>75</weight>
|
||||||
|
<bold>true</bold>
|
||||||
|
</font>
|
||||||
|
</property>
|
||||||
|
<property name="text">
|
||||||
|
<string>Camera</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<widget class="QLabel" name="label_timeRefreshRate">
|
||||||
|
<property name="text">
|
||||||
|
<string> (0 Hz - 0 Hz)</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<spacer name="horizontalSpacer_2">
|
||||||
|
<property name="orientation">
|
||||||
|
<enum>Qt::Horizontal</enum>
|
||||||
|
</property>
|
||||||
|
<property name="sizeHint" stdset="0">
|
||||||
|
<size>
|
||||||
|
<width>40</width>
|
||||||
|
<height>20</height>
|
||||||
|
</size>
|
||||||
|
</property>
|
||||||
|
</spacer>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<widget class="QLabel" name="label_detectorDescriptorType">
|
||||||
|
<property name="text">
|
||||||
|
<string/>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<spacer name="horizontalSpacer">
|
||||||
|
<property name="orientation">
|
||||||
|
<enum>Qt::Horizontal</enum>
|
||||||
|
</property>
|
||||||
|
<property name="sizeHint" stdset="0">
|
||||||
|
<size>
|
||||||
|
<width>40</width>
|
||||||
|
<height>20</height>
|
||||||
|
</size>
|
||||||
|
</property>
|
||||||
|
</spacer>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<widget class="QLabel" name="label_nfeatures">
|
||||||
|
<property name="text">
|
||||||
|
<string>0</string>
|
||||||
|
</property>
|
||||||
|
<property name="alignment">
|
||||||
|
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<widget class="QLabel" name="label_15">
|
||||||
|
<property name="text">
|
||||||
|
<string> features</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
</layout>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<widget class="QFrame" name="frame">
|
||||||
|
<property name="frameShape">
|
||||||
|
<enum>QFrame::StyledPanel</enum>
|
||||||
|
</property>
|
||||||
|
<property name="frameShadow">
|
||||||
|
<enum>QFrame::Raised</enum>
|
||||||
|
</property>
|
||||||
|
<layout class="QVBoxLayout" name="verticalLayout_3">
|
||||||
|
<property name="spacing">
|
||||||
|
<number>0</number>
|
||||||
|
</property>
|
||||||
|
<property name="margin">
|
||||||
|
<number>0</number>
|
||||||
|
</property>
|
||||||
|
<item>
|
||||||
|
<widget class="Object" name="imageView_source" native="true"/>
|
||||||
|
</item>
|
||||||
|
</layout>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
</layout>
|
||||||
|
</item>
|
||||||
|
</layout>
|
||||||
|
</widget>
|
||||||
|
<widget class="QMenuBar" name="menubar">
|
||||||
|
<property name="geometry">
|
||||||
|
<rect>
|
||||||
|
<x>0</x>
|
||||||
|
<y>0</y>
|
||||||
|
<width>864</width>
|
||||||
|
<height>25</height>
|
||||||
|
</rect>
|
||||||
|
</property>
|
||||||
|
<widget class="QMenu" name="menuFile">
|
||||||
|
<property name="title">
|
||||||
|
<string>File</string>
|
||||||
|
</property>
|
||||||
|
<addaction name="actionLoad_objects"/>
|
||||||
|
<addaction name="actionSave_objects"/>
|
||||||
|
<addaction name="separator"/>
|
||||||
|
<addaction name="actionExit"/>
|
||||||
|
</widget>
|
||||||
|
<widget class="QMenu" name="menuEdit">
|
||||||
|
<property name="title">
|
||||||
|
<string>Edit</string>
|
||||||
|
</property>
|
||||||
|
<addaction name="actionAdd_object"/>
|
||||||
|
<addaction name="actionStart_camera"/>
|
||||||
|
<addaction name="actionStop_camera"/>
|
||||||
|
</widget>
|
||||||
|
<widget class="QMenu" name="menuView">
|
||||||
|
<property name="title">
|
||||||
|
<string>View</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
<addaction name="menuFile"/>
|
||||||
|
<addaction name="menuEdit"/>
|
||||||
|
<addaction name="menuView"/>
|
||||||
|
</widget>
|
||||||
|
<widget class="QDockWidget" name="dockWidget_parameters">
|
||||||
|
<property name="minimumSize">
|
||||||
|
<size>
|
||||||
|
<width>300</width>
|
||||||
|
<height>180</height>
|
||||||
|
</size>
|
||||||
|
</property>
|
||||||
|
<property name="floating">
|
||||||
|
<bool>false</bool>
|
||||||
|
</property>
|
||||||
|
<property name="windowTitle">
|
||||||
|
<string>Parameters</string>
|
||||||
|
</property>
|
||||||
|
<attribute name="dockWidgetArea">
|
||||||
|
<number>2</number>
|
||||||
|
</attribute>
|
||||||
|
<widget class="QWidget" name="dockWidgetContents">
|
||||||
|
<layout class="QVBoxLayout" name="verticalLayout_4">
|
||||||
|
<item>
|
||||||
|
<widget class="ParametersToolBox" name="toolBox">
|
||||||
|
<property name="currentIndex">
|
||||||
|
<number>0</number>
|
||||||
|
</property>
|
||||||
|
<widget class="QWidget" name="page_1">
|
||||||
|
<property name="geometry">
|
||||||
|
<rect>
|
||||||
|
<x>0</x>
|
||||||
|
<y>0</y>
|
||||||
|
<width>282</width>
|
||||||
|
<height>401</height>
|
||||||
|
</rect>
|
||||||
|
</property>
|
||||||
|
<attribute name="label">
|
||||||
|
<string>Timings</string>
|
||||||
|
</attribute>
|
||||||
|
<layout class="QVBoxLayout" name="verticalLayout_5">
|
||||||
|
<item>
|
||||||
|
<layout class="QGridLayout" name="gridLayout" columnstretch="0,0,0">
|
||||||
|
<property name="horizontalSpacing">
|
||||||
|
<number>6</number>
|
||||||
|
</property>
|
||||||
|
<property name="verticalSpacing">
|
||||||
|
<number>0</number>
|
||||||
|
</property>
|
||||||
|
<property name="margin">
|
||||||
|
<number>0</number>
|
||||||
|
</property>
|
||||||
|
<item row="0" column="2">
|
||||||
|
<widget class="QLabel" name="label_3">
|
||||||
|
<property name="text">
|
||||||
|
<string>ms</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item row="1" column="1">
|
||||||
|
<widget class="QLabel" name="label_timeExtraction">
|
||||||
|
<property name="text">
|
||||||
|
<string>000</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item row="1" column="2">
|
||||||
|
<widget class="QLabel" name="label_4">
|
||||||
|
<property name="text">
|
||||||
|
<string>ms</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item row="1" column="0">
|
||||||
|
<widget class="QLabel" name="label_2">
|
||||||
|
<property name="text">
|
||||||
|
<string>Descriptors extraction</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item row="0" column="0">
|
||||||
|
<widget class="QLabel" name="label">
|
||||||
|
<property name="text">
|
||||||
|
<string>Features detection</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item row="0" column="1">
|
||||||
|
<widget class="QLabel" name="label_timeDetection">
|
||||||
|
<property name="text">
|
||||||
|
<string>000</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item row="3" column="0">
|
||||||
|
<widget class="QLabel" name="label_7">
|
||||||
|
<property name="text">
|
||||||
|
<string>Descriptors matching</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item row="2" column="0">
|
||||||
|
<widget class="QLabel" name="label_8">
|
||||||
|
<property name="text">
|
||||||
|
<string>Descriptors indexing</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item row="2" column="1">
|
||||||
|
<widget class="QLabel" name="label_timeIndexing">
|
||||||
|
<property name="text">
|
||||||
|
<string>000</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item row="3" column="1">
|
||||||
|
<widget class="QLabel" name="label_timeMatching">
|
||||||
|
<property name="text">
|
||||||
|
<string>000</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item row="2" column="2">
|
||||||
|
<widget class="QLabel" name="label_9">
|
||||||
|
<property name="text">
|
||||||
|
<string>ms</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item row="3" column="2">
|
||||||
|
<widget class="QLabel" name="label_10">
|
||||||
|
<property name="text">
|
||||||
|
<string>ms</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item row="4" column="0">
|
||||||
|
<widget class="QLabel" name="label_11">
|
||||||
|
<property name="text">
|
||||||
|
<string>Detect outliers and GUI</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item row="4" column="1">
|
||||||
|
<widget class="QLabel" name="label_timeGui">
|
||||||
|
<property name="text">
|
||||||
|
<string>000</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item row="4" column="2">
|
||||||
|
<widget class="QLabel" name="label_12">
|
||||||
|
<property name="text">
|
||||||
|
<string>ms</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
</layout>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<spacer name="verticalSpacer_2">
|
||||||
|
<property name="orientation">
|
||||||
|
<enum>Qt::Vertical</enum>
|
||||||
|
</property>
|
||||||
|
<property name="sizeHint" stdset="0">
|
||||||
|
<size>
|
||||||
|
<width>20</width>
|
||||||
|
<height>174</height>
|
||||||
|
</size>
|
||||||
|
</property>
|
||||||
|
</spacer>
|
||||||
|
</item>
|
||||||
|
</layout>
|
||||||
|
</widget>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<widget class="QPushButton" name="pushButton_restoreDefaults">
|
||||||
|
<property name="text">
|
||||||
|
<string>Restore defaults</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
</layout>
|
||||||
|
</widget>
|
||||||
|
</widget>
|
||||||
|
<widget class="QDockWidget" name="dockWidget_objects">
|
||||||
|
<property name="minimumSize">
|
||||||
|
<size>
|
||||||
|
<width>300</width>
|
||||||
|
<height>121</height>
|
||||||
|
</size>
|
||||||
|
</property>
|
||||||
|
<property name="windowTitle">
|
||||||
|
<string>Objects</string>
|
||||||
|
</property>
|
||||||
|
<attribute name="dockWidgetArea">
|
||||||
|
<number>1</number>
|
||||||
|
</attribute>
|
||||||
|
<widget class="QWidget" name="dockWidgetContents_2">
|
||||||
|
<layout class="QVBoxLayout" name="verticalLayout_6">
|
||||||
|
<item>
|
||||||
|
<widget class="QScrollArea" name="objects_area">
|
||||||
|
<property name="minimumSize">
|
||||||
|
<size>
|
||||||
|
<width>150</width>
|
||||||
|
<height>0</height>
|
||||||
|
</size>
|
||||||
|
</property>
|
||||||
|
<property name="widgetResizable">
|
||||||
|
<bool>true</bool>
|
||||||
|
</property>
|
||||||
|
<widget class="QWidget" name="scrollAreaWidgetContents">
|
||||||
|
<property name="geometry">
|
||||||
|
<rect>
|
||||||
|
<x>0</x>
|
||||||
|
<y>0</y>
|
||||||
|
<width>280</width>
|
||||||
|
<height>463</height>
|
||||||
|
</rect>
|
||||||
|
</property>
|
||||||
|
<layout class="QVBoxLayout" name="verticalLayout_objects">
|
||||||
|
<property name="margin">
|
||||||
|
<number>0</number>
|
||||||
|
</property>
|
||||||
|
<item>
|
||||||
|
<spacer name="verticalSpacer">
|
||||||
|
<property name="orientation">
|
||||||
|
<enum>Qt::Vertical</enum>
|
||||||
|
</property>
|
||||||
|
<property name="sizeHint" stdset="0">
|
||||||
|
<size>
|
||||||
|
<width>20</width>
|
||||||
|
<height>230</height>
|
||||||
|
</size>
|
||||||
|
</property>
|
||||||
|
</spacer>
|
||||||
|
</item>
|
||||||
|
</layout>
|
||||||
|
</widget>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
</layout>
|
||||||
|
</widget>
|
||||||
|
</widget>
|
||||||
|
<action name="actionExit">
|
||||||
|
<property name="text">
|
||||||
|
<string>Exit</string>
|
||||||
|
</property>
|
||||||
|
</action>
|
||||||
|
<action name="actionAdd_object">
|
||||||
|
<property name="text">
|
||||||
|
<string>Add object...</string>
|
||||||
|
</property>
|
||||||
|
</action>
|
||||||
|
<action name="actionStart_camera">
|
||||||
|
<property name="text">
|
||||||
|
<string>Start camera</string>
|
||||||
|
</property>
|
||||||
|
</action>
|
||||||
|
<action name="actionStop_camera">
|
||||||
|
<property name="text">
|
||||||
|
<string>Stop camera</string>
|
||||||
|
</property>
|
||||||
|
</action>
|
||||||
|
<action name="actionSave_objects">
|
||||||
|
<property name="text">
|
||||||
|
<string>Save objects...</string>
|
||||||
|
</property>
|
||||||
|
</action>
|
||||||
|
<action name="actionLoad_objects">
|
||||||
|
<property name="text">
|
||||||
|
<string>Load objects...</string>
|
||||||
|
</property>
|
||||||
|
</action>
|
||||||
|
</widget>
|
||||||
|
<customwidgets>
|
||||||
|
<customwidget>
|
||||||
|
<class>Object</class>
|
||||||
|
<extends>QWidget</extends>
|
||||||
|
<header>Object.h</header>
|
||||||
|
<container>1</container>
|
||||||
|
</customwidget>
|
||||||
|
<customwidget>
|
||||||
|
<class>ParametersToolBox</class>
|
||||||
|
<extends>QToolBox</extends>
|
||||||
|
<header>ParametersToolBox.h</header>
|
||||||
|
<container>1</container>
|
||||||
|
</customwidget>
|
||||||
|
</customwidgets>
|
||||||
|
<resources/>
|
||||||
|
<connections/>
|
||||||
|
</ui>
|
||||||
Loading…
x
Reference in New Issue
Block a user