Added JSON optional output when in console mode (see --json option)
Added --scene option to process a single scene file Moved some apps in tools subfolder git-svn-id: http://find-object.googlecode.com/svn/trunk/find_object@362 620bd6b2-0a58-f614-fd9a-1bd335dccda9
This commit is contained in:
parent
43e855e822
commit
6a0136cc16
@ -12,6 +12,9 @@ ELSE ()
|
||||
ENDIF()
|
||||
#ADD_DEFINITIONS("-DUNICODE") # to test with UNICODE projects
|
||||
|
||||
####### local cmake modules #######
|
||||
SET(CMAKE_MODULE_PATH "${PROJECT_SOURCE_DIR}/cmake_modules")
|
||||
|
||||
#######################
|
||||
# VERSION
|
||||
#######################
|
||||
@ -78,7 +81,8 @@ set(INSTALL_CMAKE_DIR ${DEF_INSTALL_CMAKE_DIR} CACHE PATH
|
||||
|
||||
####### DEPENDENCIES #######
|
||||
FIND_PACKAGE(OpenCV REQUIRED) # tested on 2.3.1
|
||||
FIND_PACKAGE(Qt4 COMPONENTS QtCore QtGui QtNetwork) # tested on Qt4.7
|
||||
FIND_PACKAGE(Qt4 COMPONENTS QtCore QtGui QtNetwork REQUIRED) # tested on Qt4.8
|
||||
FIND_PACKAGE(JSONCPP)
|
||||
ADD_DEFINITIONS(-DQT_NO_KEYWORDS) # To avoid conflicts with boost signals used in ROS
|
||||
|
||||
####### OSX BUNDLE CMAKE_INSTALL_PREFIX #######
|
||||
@ -103,9 +107,7 @@ ENDIF(APPLE AND BUILD_AS_BUNDLE)
|
||||
ADD_SUBDIRECTORY( src )
|
||||
ADD_SUBDIRECTORY( app )
|
||||
ADD_SUBDIRECTORY( example )
|
||||
ADD_SUBDIRECTORY( tcpClient )
|
||||
ADD_SUBDIRECTORY( imagesTcpServer )
|
||||
ADD_SUBDIRECTORY( console_app )
|
||||
ADD_SUBDIRECTORY( tools )
|
||||
|
||||
|
||||
|
||||
@ -221,4 +223,9 @@ MESSAGE(STATUS " CMAKE_BUILD_TYPE = ${CMAKE_BUILD_TYPE}")
|
||||
IF(APPLE)
|
||||
MESSAGE(STATUS " BUILD_AS_BUNDLE = ${BUILD_AS_BUNDLE}")
|
||||
ENDIF(APPLE)
|
||||
IF(JSONCPP_FOUND)
|
||||
MESSAGE(STATUS " With JSONCPP = YES")
|
||||
ELSE()
|
||||
MESSAGE(STATUS " With JSONCPP = NO (libjsoncpp not found)")
|
||||
ENDIF()
|
||||
MESSAGE(STATUS "--------------------------------------------")
|
||||
|
||||
@ -12,6 +12,18 @@ SET(LIBRARIES
|
||||
${OpenCV_LIBS}
|
||||
)
|
||||
|
||||
IF(JSONCPP_FOUND)
|
||||
SET(INCLUDE_DIRS
|
||||
${INCLUDE_DIRS}
|
||||
${JSONCPP_INCLUDE_DIRS}
|
||||
)
|
||||
SET(LIBRARIES
|
||||
${LIBRARIES}
|
||||
${JSONCPP_LIBRARIES}
|
||||
)
|
||||
ADD_DEFINITIONS("-DWITH_JSONCPP")
|
||||
ENDIF(JSONCPP_FOUND)
|
||||
|
||||
#include files
|
||||
INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
|
||||
|
||||
|
||||
240
app/main.cpp
240
app/main.cpp
@ -8,6 +8,10 @@
|
||||
#include "find_object/TcpServer.h"
|
||||
#include "find_object/utilite/ULogger.h"
|
||||
|
||||
#ifdef WITH_JSONCPP
|
||||
#include <jsoncpp/json/writer.h>
|
||||
#endif
|
||||
|
||||
bool running = true;
|
||||
|
||||
#ifdef WIN32
|
||||
@ -66,15 +70,97 @@ void showUsage()
|
||||
" find_object [options]\n"
|
||||
#endif
|
||||
"Options:\n"
|
||||
" -console Don't use the GUI (by default the camera will be\n"
|
||||
" started automatically). Option -objs must also be\n"
|
||||
" --console Don't use the GUI (by default the camera will be\n"
|
||||
" started automatically). Option --objects must also be\n"
|
||||
" used with valid objects.\n"
|
||||
" -objs \"path\" Directory of the objects to detect.\n"
|
||||
" -config \"path\" Path to configuration file (default: %s).\n"
|
||||
" -help or --help Show usage.\n", Settings::iniDefaultPath().toStdString().c_str());
|
||||
" --objects \"path\" Directory of the objects to detect.\n"
|
||||
" --config \"path\" Path to configuration file (default: %s).\n"
|
||||
" --scene \"path\" Path to a scene image file.\n"
|
||||
#ifdef WITH_JSONCPP
|
||||
" --json \"path\" Path to an output JSON file (only in --console mode with --scene).\n"
|
||||
#endif
|
||||
" --help Show usage.\n", Settings::iniDefaultPath().toStdString().c_str());
|
||||
exit(-1);
|
||||
}
|
||||
|
||||
void writeJSON(const FindObject & findObject, const QString & path)
|
||||
{
|
||||
#ifdef WITH_JSONCPP
|
||||
if(!path.isEmpty())
|
||||
{
|
||||
Json::Value root;
|
||||
Json::Value detections;
|
||||
Json::Value matchesValues;
|
||||
|
||||
if(findObject.objectsDetected().size())
|
||||
{
|
||||
Q_ASSERT(objectsDetected.size() == findObject.inliers().size() &&
|
||||
objectsDetected.size() == findObject.outliers().size());
|
||||
|
||||
const QMultiMap<int,QPair<QRect,QTransform> > & objectsDetected = findObject.objectsDetected();
|
||||
QMultiMap<int, QMultiMap<int, int> >::const_iterator iterInliers = findObject.inliers().constBegin();
|
||||
QMultiMap<int, QMultiMap<int, int> >::const_iterator iterOutliers = findObject.outliers().constBegin();
|
||||
for(QMultiMap<int,QPair<QRect,QTransform> >::const_iterator iter = objectsDetected.constBegin();
|
||||
iter!= objectsDetected.end();)
|
||||
{
|
||||
char index = 'a';
|
||||
QMultiMap<int,QPair<QRect,QTransform> >::const_iterator jter = iter;
|
||||
for(;jter != objectsDetected.constEnd() && jter.key() == iter.key(); ++jter)
|
||||
{
|
||||
QString name = QString("object_%1%2").arg(jter.key()).arg(objectsDetected.count(jter.key())>1?QString(index++):"");
|
||||
detections.append(name.toStdString());
|
||||
|
||||
Json::Value homography;
|
||||
homography.append(jter.value().second.m11());
|
||||
homography.append(jter.value().second.m12());
|
||||
homography.append(jter.value().second.m13());
|
||||
homography.append(jter.value().second.m21());
|
||||
homography.append(jter.value().second.m22());
|
||||
homography.append(jter.value().second.m23());
|
||||
homography.append(jter.value().second.m31()); // dx
|
||||
homography.append(jter.value().second.m32()); // dy
|
||||
homography.append(jter.value().second.m33());
|
||||
root[name.toStdString()]["width"] = jter.value().first.width();
|
||||
root[name.toStdString()]["height"] = jter.value().first.height();
|
||||
root[name.toStdString()]["homography"] = homography;
|
||||
root[name.toStdString()]["inliers"] = iterInliers.value().size();
|
||||
root[name.toStdString()]["outliers"] = iterOutliers.value().size();
|
||||
|
||||
++iterInliers;
|
||||
++iterOutliers;
|
||||
}
|
||||
iter = jter;
|
||||
}
|
||||
}
|
||||
|
||||
const QMap<int, QMultiMap<int, int> > & matches = findObject.matches();
|
||||
for(QMap<int, QMultiMap<int, int> >::const_iterator iter = matches.constBegin();
|
||||
iter != matches.end();
|
||||
++iter)
|
||||
{
|
||||
QString name = QString("matches_%1").arg(iter.key());
|
||||
root[name.toStdString()] = iter.value().size();
|
||||
matchesValues.append(name.toStdString());
|
||||
}
|
||||
|
||||
root["objects"] = detections;
|
||||
root["matches"] = matchesValues;
|
||||
|
||||
// write in a nice readible way
|
||||
Json::StyledWriter styledWriter;
|
||||
//std::cout << styledWriter.write(root);
|
||||
QFile file(path);
|
||||
file.open(QIODevice::WriteOnly | QIODevice::Text);
|
||||
QTextStream out(&file);
|
||||
out << styledWriter.write(root).c_str();
|
||||
file.close();
|
||||
UINFO("JSON written to \"%s\"", path.toStdString().c_str());
|
||||
}
|
||||
#else
|
||||
UERROR("Not built with JSON support!");
|
||||
#endif
|
||||
}
|
||||
|
||||
int main(int argc, char* argv[])
|
||||
{
|
||||
ULogger::setType(ULogger::kTypeConsole);
|
||||
@ -87,11 +173,16 @@ int main(int argc, char* argv[])
|
||||
//////////////////////////
|
||||
bool guiMode = true;
|
||||
QString objectsPath = "";
|
||||
QString scenePath = "";
|
||||
QString configPath = Settings::iniDefaultPath();
|
||||
QString jsonPath;
|
||||
|
||||
for(int i=1; i<argc; ++i)
|
||||
{
|
||||
if(strcmp(argv[i], "-objs") == 0)
|
||||
if(strcmp(argv[i], "-objs") == 0 ||
|
||||
strcmp(argv[i], "--objs") == 0 ||
|
||||
strcmp(argv[i], "-objects") == 0 ||
|
||||
strcmp(argv[i], "--objects") == 0)
|
||||
{
|
||||
++i;
|
||||
if(i < argc)
|
||||
@ -103,7 +194,7 @@ int main(int argc, char* argv[])
|
||||
}
|
||||
if(!QDir(objectsPath).exists())
|
||||
{
|
||||
UERROR("Path not valid : %s", objectsPath.toStdString().c_str());
|
||||
UERROR("Objects path not valid : %s", objectsPath.toStdString().c_str());
|
||||
showUsage();
|
||||
}
|
||||
}
|
||||
@ -113,7 +204,31 @@ int main(int argc, char* argv[])
|
||||
}
|
||||
continue;
|
||||
}
|
||||
if(strcmp(argv[i], "-config") == 0)
|
||||
if(strcmp(argv[i], "-scene") == 0 ||
|
||||
strcmp(argv[i], "--scene") == 0)
|
||||
{
|
||||
++i;
|
||||
if(i < argc)
|
||||
{
|
||||
scenePath = argv[i];
|
||||
if(scenePath.contains('~'))
|
||||
{
|
||||
scenePath.replace('~', QDir::homePath());
|
||||
}
|
||||
if(!QFile(scenePath).exists())
|
||||
{
|
||||
UERROR("Scene path not valid : %s", scenePath.toStdString().c_str());
|
||||
showUsage();
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
showUsage();
|
||||
}
|
||||
continue;
|
||||
}
|
||||
if(strcmp(argv[i], "-config") == 0 ||
|
||||
strcmp(argv[i], "--config") == 0)
|
||||
{
|
||||
++i;
|
||||
if(i < argc)
|
||||
@ -135,12 +250,34 @@ int main(int argc, char* argv[])
|
||||
}
|
||||
continue;
|
||||
}
|
||||
if(strcmp(argv[i], "-console") == 0)
|
||||
#ifdef WITH_JSONCPP
|
||||
if(strcmp(argv[i], "-json") == 0 ||
|
||||
strcmp(argv[i], "--json") == 0)
|
||||
{
|
||||
++i;
|
||||
if(i < argc)
|
||||
{
|
||||
jsonPath = argv[i];
|
||||
if(jsonPath.contains('~'))
|
||||
{
|
||||
jsonPath.replace('~', QDir::homePath());
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
showUsage();
|
||||
}
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
if(strcmp(argv[i], "-console") == 0 ||
|
||||
strcmp(argv[i], "--console") == 0)
|
||||
{
|
||||
guiMode = false;
|
||||
continue;
|
||||
}
|
||||
if(strcmp(argv[i], "-help") == 0 || strcmp(argv[i], "--help") == 0)
|
||||
if(strcmp(argv[i], "-help") == 0 ||
|
||||
strcmp(argv[i], "--help") == 0)
|
||||
{
|
||||
showUsage();
|
||||
}
|
||||
@ -152,7 +289,11 @@ int main(int argc, char* argv[])
|
||||
UINFO("Options:");
|
||||
UINFO(" GUI mode = %s", guiMode?"true":"false");
|
||||
UINFO(" Objects path: \"%s\"", objectsPath.toStdString().c_str());
|
||||
UINFO(" Scene path: \"%s\"", scenePath.toStdString().c_str());
|
||||
UINFO(" Settings path: \"%s\"", configPath.toStdString().c_str());
|
||||
#ifdef WITH_JSONCPP
|
||||
UINFO(" JSON path: \"%s\"", configPath.toStdString().c_str());
|
||||
#endif
|
||||
|
||||
//////////////////////////
|
||||
// parse options END
|
||||
@ -174,6 +315,15 @@ int main(int argc, char* argv[])
|
||||
UWARN("No objects loaded from \"%s\"", objectsPath.toStdString().c_str());
|
||||
}
|
||||
}
|
||||
cv::Mat scene;
|
||||
if(!scenePath.isEmpty())
|
||||
{
|
||||
scene = cv::imread(scenePath.toStdString());
|
||||
if(scene.empty())
|
||||
{
|
||||
UERROR("Failed to load scene \"%s\"", scenePath.toStdString().c_str());
|
||||
}
|
||||
}
|
||||
|
||||
if(guiMode)
|
||||
{
|
||||
@ -183,7 +333,15 @@ int main(int argc, char* argv[])
|
||||
app.connect( &app, SIGNAL( lastWindowClosed() ), &app, SLOT( quit() ) );
|
||||
mainWindow.show();
|
||||
|
||||
if(!scene.empty())
|
||||
{
|
||||
mainWindow.update(scene);
|
||||
}
|
||||
|
||||
app.exec();
|
||||
|
||||
// Save settings
|
||||
Settings::saveSettings();
|
||||
}
|
||||
else
|
||||
{
|
||||
@ -195,43 +353,59 @@ int main(int argc, char* argv[])
|
||||
}
|
||||
|
||||
QCoreApplication app(argc, argv);
|
||||
Camera camera;
|
||||
|
||||
TcpServer tcpServer(Settings::getGeneral_port());
|
||||
printf("IP: %s\nport: %d\n", tcpServer.getHostAddress().toString().toStdString().c_str(), tcpServer.getPort());
|
||||
|
||||
// connect stuff:
|
||||
// [Camera] ---Image---> [FindObject] ---ObjectsDetected---> [TcpServer]
|
||||
QObject::connect(&camera, SIGNAL(imageReceived(const cv::Mat &)), findObject, SLOT(detect(const cv::Mat &)));
|
||||
// [FindObject] ---ObjectsDetected---> [TcpServer]
|
||||
QObject::connect(findObject, SIGNAL(objectsFound(QMultiMap<int,QPair<QRect,QTransform> >)), &tcpServer, SLOT(publishObjects(QMultiMap<int,QPair<QRect,QTransform> >)));
|
||||
|
||||
setupQuitSignal();
|
||||
|
||||
// start processing!
|
||||
while(running && !camera.start())
|
||||
if(!scene.empty())
|
||||
{
|
||||
if(Settings::getCamera_6useTcpCamera())
|
||||
// process the scene and exit
|
||||
findObject->detect(scene); // this will automatically emit objectsFound()
|
||||
|
||||
if(!jsonPath.isEmpty())
|
||||
{
|
||||
UWARN("Camera initialization failed! (with server %s:%d) Trying again in 1 second...",
|
||||
Settings::getCamera_7IP().toStdString().c_str(), Settings::getCamera_8port());
|
||||
Sleep(1000);
|
||||
}
|
||||
else
|
||||
{
|
||||
UERROR("Camera initialization failed!");
|
||||
running = false;
|
||||
writeJSON(*findObject, jsonPath);
|
||||
}
|
||||
}
|
||||
if(running)
|
||||
else
|
||||
{
|
||||
app.exec();
|
||||
Camera camera;
|
||||
|
||||
// [Camera] ---Image---> [FindObject]
|
||||
QObject::connect(&camera, SIGNAL(imageReceived(const cv::Mat &)), findObject, SLOT(detect(const cv::Mat &)));
|
||||
|
||||
//use camera in settings
|
||||
setupQuitSignal();
|
||||
|
||||
// start processing!
|
||||
while(running && !camera.start())
|
||||
{
|
||||
if(Settings::getCamera_6useTcpCamera())
|
||||
{
|
||||
UWARN("Camera initialization failed! (with server %s:%d) Trying again in 1 second...",
|
||||
Settings::getCamera_7IP().toStdString().c_str(), Settings::getCamera_8port());
|
||||
Sleep(1000);
|
||||
}
|
||||
else
|
||||
{
|
||||
UERROR("Camera initialization failed!");
|
||||
running = false;
|
||||
}
|
||||
}
|
||||
if(running)
|
||||
{
|
||||
app.exec();
|
||||
}
|
||||
|
||||
// cleanup
|
||||
camera.stop();
|
||||
}
|
||||
|
||||
// cleanup
|
||||
camera.stop();
|
||||
delete findObject;
|
||||
tcpServer.close();
|
||||
}
|
||||
|
||||
// Save settings
|
||||
Settings::saveSettings();
|
||||
}
|
||||
|
||||
29
cmake_modules/FindJSONCPP.cmake
Normal file
29
cmake_modules/FindJSONCPP.cmake
Normal file
@ -0,0 +1,29 @@
|
||||
# - Find JSONCPP
|
||||
# This module finds an installed JSONCPP package.
|
||||
#
|
||||
# It sets the following variables:
|
||||
# JSONCPP_FOUND - Set to false, or undefined, if JSONCPP isn't found.
|
||||
# JSONCPP_INCLUDE_DIRS - The JSONCPP include directory.
|
||||
# JSONCPP_LIBRARIES - The JSONCPP library to link against.
|
||||
|
||||
FIND_PATH(JSONCPP_INCLUDE_DIRS json/features.h PATH_SUFFIXES jsoncpp)
|
||||
|
||||
FIND_LIBRARY(JSONCPP_LIBRARY NAMES jsoncpp)
|
||||
|
||||
IF (JSONCPP_INCLUDE_DIRS AND JSONCPP_LIBRARY)
|
||||
SET(JSONCPP_FOUND TRUE)
|
||||
ENDIF (JSONCPP_INCLUDE_DIRS AND JSONCPP_LIBRARY)
|
||||
|
||||
IF (JSONCPP_FOUND)
|
||||
# show which JSONCPP was found only if not quiet
|
||||
SET(JSONCPP_LIBRARIES ${JSONCPP_LIBRARY})
|
||||
IF (NOT JSONCPP_FIND_QUIETLY)
|
||||
MESSAGE(STATUS "Found JSONCPP: ${JSONCPP_LIBRARIES}")
|
||||
ENDIF (NOT JSONCPP_FIND_QUIETLY)
|
||||
ELSE (JSONCPP_FOUND)
|
||||
# fatal error if JSONCPP is required but not found
|
||||
IF (JSONCPP_FIND_REQUIRED)
|
||||
MESSAGE(FATAL_ERROR "Could not find JSONCPP (libjsoncpp)")
|
||||
ENDIF (JSONCPP_FIND_REQUIRED)
|
||||
ENDIF (JSONCPP_FOUND)
|
||||
|
||||
@ -53,6 +53,7 @@ public:
|
||||
const QMap<int, ObjSignature*> & objects() const {return objects_;}
|
||||
const Vocabulary * vocabulary() const {return vocabulary_;}
|
||||
|
||||
const QMultiMap<int,QPair<QRect,QTransform> > & objectsDetected() const {return objectsDetected_;}
|
||||
const QMap<TimeStamp, float> & timeStamps() const {return timeStamps_;}
|
||||
const std::vector<cv::KeyPoint> & sceneKeypoints() const {return sceneKeypoints_;}
|
||||
const cv::Mat & sceneDescriptors() const {return sceneDescriptors_;}
|
||||
@ -66,7 +67,7 @@ public:
|
||||
float maxMatchedDistance() const {return maxMatchedDistance_;}
|
||||
|
||||
public Q_SLOTS:
|
||||
void detect(const cv::Mat & image);
|
||||
void detect(const cv::Mat & image); // emit objectsfound()
|
||||
|
||||
Q_SIGNALS:
|
||||
void objectsFound(const QMultiMap<int, QPair<QRect, QTransform> > &);
|
||||
@ -82,6 +83,7 @@ private:
|
||||
KeypointDetector * detector_;
|
||||
DescriptorExtractor * extractor_;
|
||||
|
||||
QMultiMap<int,QPair<QRect,QTransform> > objectsDetected_;
|
||||
QMap<TimeStamp, float> timeStamps_;
|
||||
std::vector<cv::KeyPoint> sceneKeypoints_;
|
||||
cv::Mat sceneDescriptors_;
|
||||
|
||||
@ -50,6 +50,7 @@ public Q_SLOTS:
|
||||
void startProcessing();
|
||||
void stopProcessing();
|
||||
void pauseProcessing();
|
||||
void update(const cv::Mat & image = cv::Mat());
|
||||
|
||||
private Q_SLOTS:
|
||||
void loadSettings();
|
||||
@ -67,7 +68,6 @@ private Q_SLOTS:
|
||||
void updateObjectsSize();
|
||||
void updateMirrorView();
|
||||
void showHideControls();
|
||||
void update(const cv::Mat & image = cv::Mat());
|
||||
void updateObjects();
|
||||
void notifyParametersChanged(const QStringList & param);
|
||||
void moveCameraFrame(int frame);
|
||||
|
||||
@ -594,6 +594,8 @@ private:
|
||||
|
||||
void FindObject::detect(const cv::Mat & image)
|
||||
{
|
||||
QTime time;
|
||||
time.start();
|
||||
QMultiMap<int,QPair<QRect,QTransform> > objects;
|
||||
this->detect(image, objects);
|
||||
if(objects.size() > 0 || Settings::getGeneral_sendNoObjDetectedEvents())
|
||||
@ -603,20 +605,23 @@ void FindObject::detect(const cv::Mat & image)
|
||||
|
||||
if(objects.size() > 1)
|
||||
{
|
||||
UINFO("(%s) %d objects detected!",
|
||||
UINFO("(%s) %d objects detected! (%d ms)",
|
||||
QTime::currentTime().toString("HH:mm:ss.zzz").toStdString().c_str(),
|
||||
(int)objects.size());
|
||||
(int)objects.size(),
|
||||
time.elapsed());
|
||||
}
|
||||
else if(objects.size() == 1)
|
||||
{
|
||||
UINFO("(%s) Object %d detected!",
|
||||
UINFO("(%s) Object %d detected! (%d ms)",
|
||||
QTime::currentTime().toString("HH:mm:ss.zzz").toStdString().c_str(),
|
||||
(int)objects.begin().key());
|
||||
(int)objects.begin().key(),
|
||||
time.elapsed());
|
||||
}
|
||||
else if(Settings::getGeneral_sendNoObjDetectedEvents())
|
||||
{
|
||||
UINFO("(%s) No objects detected.",
|
||||
QTime::currentTime().toString("HH:mm:ss.zzz").toStdString().c_str());
|
||||
UINFO("(%s) No objects detected. (%d ms)",
|
||||
QTime::currentTime().toString("HH:mm:ss.zzz").toStdString().c_str(),
|
||||
time.elapsed());
|
||||
}
|
||||
}
|
||||
|
||||
@ -626,6 +631,7 @@ bool FindObject::detect(const cv::Mat & image, QMultiMap<int,QPair<QRect,QTransf
|
||||
totalTime.start();
|
||||
|
||||
// reset statistics
|
||||
objectsDetected_.clear();
|
||||
timeStamps_.clear();
|
||||
sceneKeypoints_.clear();
|
||||
sceneDescriptors_ = cv::Mat();
|
||||
@ -934,6 +940,7 @@ bool FindObject::detect(const cv::Mat & image, QMultiMap<int,QPair<QRect,QTransf
|
||||
}
|
||||
}
|
||||
|
||||
objectsDetected_ = objectsDetected;
|
||||
timeStamps_.insert(kTimeTotal, totalTime.elapsed());
|
||||
|
||||
return success;
|
||||
|
||||
3
tools/CMakeLists.txt
Normal file
3
tools/CMakeLists.txt
Normal file
@ -0,0 +1,3 @@
|
||||
ADD_SUBDIRECTORY( tcpObjectsClient )
|
||||
ADD_SUBDIRECTORY( tcpImagesServer )
|
||||
ADD_SUBDIRECTORY( similarity )
|
||||
28
tools/similarity/CMakeLists.txt
Normal file
28
tools/similarity/CMakeLists.txt
Normal file
@ -0,0 +1,28 @@
|
||||
|
||||
|
||||
SET(SRC_FILES
|
||||
main.cpp
|
||||
)
|
||||
|
||||
SET(INCLUDE_DIRS
|
||||
${OpenCV_INCLUDE_DIRS}
|
||||
)
|
||||
|
||||
SET(LIBRARIES
|
||||
${OpenCV_LIBS}
|
||||
)
|
||||
|
||||
# Make sure the compiler can find include files from our library.
|
||||
INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
|
||||
|
||||
# Add binary called "similarity" that is built from the source file "main.cpp".
|
||||
# The extension is automatically found.
|
||||
ADD_EXECUTABLE(similarity ${SRC_FILES})
|
||||
TARGET_LINK_LIBRARIES(similarity ${LIBRARIES})
|
||||
|
||||
SET_TARGET_PROPERTIES( similarity
|
||||
PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-similarity)
|
||||
|
||||
INSTALL(TARGETS similarity
|
||||
RUNTIME DESTINATION bin COMPONENT runtime
|
||||
BUNDLE DESTINATION "${CMAKE_BUNDLE_LOCATION}" COMPONENT runtime)
|
||||
164
tools/similarity/main.cpp
Normal file
164
tools/similarity/main.cpp
Normal file
@ -0,0 +1,164 @@
|
||||
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
// OpenCV stuff
|
||||
#include <opencv2/core/core.hpp>
|
||||
#include <opencv2/highgui/highgui.hpp>
|
||||
#include <opencv2/features2d/features2d.hpp>
|
||||
#include <opencv2/nonfree/features2d.hpp>
|
||||
#include <opencv2/calib3d/calib3d.hpp> // for homography
|
||||
|
||||
void showUsage()
|
||||
{
|
||||
printf(
|
||||
"\n"
|
||||
"Return similarity between two images (the number of similar features between the images).\n"
|
||||
"Usage :\n"
|
||||
" ./find_object-similarity [option] object.png scene.png\n"
|
||||
"Options: \n"
|
||||
" -inliers return inliers percentage : inliers / (inliers + outliers)\n"
|
||||
" -quiet don't show messages\n");
|
||||
|
||||
exit(-1);
|
||||
}
|
||||
|
||||
enum {mTotal, mInliers};
|
||||
|
||||
int main(int argc, char * argv[])
|
||||
{
|
||||
bool quiet = false;
|
||||
int method = mTotal; //total matches
|
||||
if(argc<3)
|
||||
{
|
||||
printf("Two images required!\n");
|
||||
showUsage();
|
||||
}
|
||||
else if(argc>3)
|
||||
{
|
||||
for(int i=1; i<argc-2; ++i)
|
||||
{
|
||||
if(std::string(argv[i]).compare("-inliers") == 0)
|
||||
{
|
||||
method = mInliers;
|
||||
}
|
||||
else if(std::string(argv[i]).compare("-quiet") == 0)
|
||||
{
|
||||
quiet = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
printf("Option %s not recognized!", argv[1]);
|
||||
showUsage();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
//Load as grayscale
|
||||
cv::Mat objectImg = cv::imread(argv[argc-2], cv::IMREAD_GRAYSCALE);
|
||||
cv::Mat sceneImg = cv::imread(argv[argc-1], cv::IMREAD_GRAYSCALE);
|
||||
|
||||
int value = 0;
|
||||
if(!objectImg.empty() && !sceneImg.empty())
|
||||
{
|
||||
std::vector<cv::KeyPoint> objectKeypoints;
|
||||
std::vector<cv::KeyPoint> sceneKeypoints;
|
||||
cv::Mat objectDescriptors;
|
||||
cv::Mat sceneDescriptors;
|
||||
|
||||
////////////////////////////
|
||||
// EXTRACT KEYPOINTS
|
||||
////////////////////////////
|
||||
cv::SIFT sift;
|
||||
sift.detect(objectImg, objectKeypoints);
|
||||
sift.detect(sceneImg, sceneKeypoints);
|
||||
|
||||
////////////////////////////
|
||||
// EXTRACT DESCRIPTORS
|
||||
////////////////////////////
|
||||
sift.compute(objectImg, objectKeypoints, objectDescriptors);
|
||||
sift.compute(sceneImg, sceneKeypoints, sceneDescriptors);
|
||||
|
||||
////////////////////////////
|
||||
// NEAREST NEIGHBOR MATCHING USING FLANN LIBRARY (included in OpenCV)
|
||||
////////////////////////////
|
||||
cv::Mat results;
|
||||
cv::Mat dists;
|
||||
std::vector<std::vector<cv::DMatch> > matches;
|
||||
int k=2; // find the 2 nearest neighbors
|
||||
|
||||
// Create Flann KDTree index
|
||||
cv::flann::Index flannIndex(sceneDescriptors, cv::flann::KDTreeIndexParams(), cvflann::FLANN_DIST_EUCLIDEAN);
|
||||
results = cv::Mat(objectDescriptors.rows, k, CV_32SC1); // Results index
|
||||
dists = cv::Mat(objectDescriptors.rows, k, CV_32FC1); // Distance results are CV_32FC1
|
||||
|
||||
// search (nearest neighbor)
|
||||
flannIndex.knnSearch(objectDescriptors, results, dists, k, cv::flann::SearchParams() );
|
||||
|
||||
////////////////////////////
|
||||
// PROCESS NEAREST NEIGHBOR RESULTS
|
||||
////////////////////////////
|
||||
|
||||
// Find correspondences by NNDR (Nearest Neighbor Distance Ratio)
|
||||
float nndrRatio = 0.6;
|
||||
std::vector<cv::Point2f> mpts_1, mpts_2; // Used for homography
|
||||
std::vector<int> indexes_1, indexes_2; // Used for homography
|
||||
std::vector<uchar> outlier_mask; // Used for homography
|
||||
// Check if this descriptor matches with those of the objects
|
||||
|
||||
for(int i=0; i<objectDescriptors.rows; ++i)
|
||||
{
|
||||
// Apply NNDR
|
||||
if(dists.at<float>(i,0) <= nndrRatio * dists.at<float>(i,1))
|
||||
{
|
||||
mpts_1.push_back(objectKeypoints.at(i).pt);
|
||||
indexes_1.push_back(i);
|
||||
|
||||
mpts_2.push_back(sceneKeypoints.at(results.at<int>(i,0)).pt);
|
||||
indexes_2.push_back(results.at<int>(i,0));
|
||||
}
|
||||
}
|
||||
|
||||
if(method == mInliers)
|
||||
{
|
||||
// FIND HOMOGRAPHY
|
||||
unsigned int minInliers = 8;
|
||||
if(mpts_1.size() >= minInliers)
|
||||
{
|
||||
cv::Mat H = findHomography(mpts_1,
|
||||
mpts_2,
|
||||
cv::RANSAC,
|
||||
1.0,
|
||||
outlier_mask);
|
||||
int inliers=0, outliers=0;
|
||||
for(unsigned int k=0; k<mpts_1.size();++k)
|
||||
{
|
||||
if(outlier_mask.at(k))
|
||||
{
|
||||
++inliers;
|
||||
}
|
||||
else
|
||||
{
|
||||
++outliers;
|
||||
}
|
||||
}
|
||||
if(!quiet)
|
||||
printf("Total=%d Inliers=%d Outliers=%d\n", (int)mpts_1.size(), inliers, outliers);
|
||||
value = (inliers*100) / (inliers+outliers);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
value = mpts_1.size();
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
printf("Images are not valid!\n");
|
||||
showUsage();
|
||||
}
|
||||
if(!quiet)
|
||||
printf("Similarity = %d\n", value);
|
||||
return value;
|
||||
}
|
||||
@ -13,7 +13,7 @@ SET(SRC_FILES
|
||||
)
|
||||
|
||||
SET(INCLUDE_DIRS
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/../include
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/../../include
|
||||
${CMAKE_CURRENT_SOURCE_DIR}
|
||||
${OpenCV_INCLUDE_DIRS}
|
||||
)
|
||||
@ -30,13 +30,13 @@ INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
|
||||
|
||||
# Add binary called "example" that is built from the source file "main.cpp".
|
||||
# The extension is automatically found.
|
||||
ADD_EXECUTABLE(imagesTcpServer ${SRC_FILES})
|
||||
TARGET_LINK_LIBRARIES(imagesTcpServer find_object ${LIBRARIES})
|
||||
ADD_EXECUTABLE(tcpImagesServer ${SRC_FILES})
|
||||
TARGET_LINK_LIBRARIES(tcpImagesServer find_object ${LIBRARIES})
|
||||
|
||||
SET_TARGET_PROPERTIES( imagesTcpServer
|
||||
PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-imagesTcpServer)
|
||||
SET_TARGET_PROPERTIES( tcpImagesServer
|
||||
PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-tcpImagesServer)
|
||||
|
||||
INSTALL(TARGETS imagesTcpServer
|
||||
INSTALL(TARGETS tcpImagesServer
|
||||
RUNTIME DESTINATION bin COMPONENT runtime
|
||||
BUNDLE DESTINATION "${CMAKE_BUNDLE_LOCATION}" COMPONENT runtime)
|
||||
|
||||
@ -29,12 +29,12 @@ INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
|
||||
|
||||
# Add binary called "example" that is built from the source file "main.cpp".
|
||||
# The extension is automatically found.
|
||||
ADD_EXECUTABLE(tcpClient ${SRC_FILES})
|
||||
TARGET_LINK_LIBRARIES(tcpClient ${LIBRARIES})
|
||||
ADD_EXECUTABLE(tcpObjectsClient ${SRC_FILES})
|
||||
TARGET_LINK_LIBRARIES(tcpObjectsClient ${LIBRARIES})
|
||||
|
||||
SET_TARGET_PROPERTIES( tcpClient
|
||||
PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-tcpClient)
|
||||
SET_TARGET_PROPERTIES( tcpObjectsClient
|
||||
PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-tcpObjectsClient)
|
||||
|
||||
INSTALL(TARGETS tcpClient
|
||||
INSTALL(TARGETS tcpObjectsClient
|
||||
RUNTIME DESTINATION bin COMPONENT runtime
|
||||
BUNDLE DESTINATION "${CMAKE_BUNDLE_LOCATION}" COMPONENT runtime)
|
||||
Loading…
x
Reference in New Issue
Block a user