Moved all non-gui stuff outside the GUI

Added FindObject and ObjSignature classes
Added ULogger from utilite for pretty log

git-svn-id: http://find-object.googlecode.com/svn/trunk/find_object@356 620bd6b2-0a58-f614-fd9a-1bd335dccda9
This commit is contained in:
matlabbe 2014-07-31 19:02:31 +00:00
parent 79b4f319f1
commit 680b1740b1
33 changed files with 3364 additions and 1447 deletions

View File

@ -5,7 +5,9 @@ SET(headers_ui
../src/MainWindow.h ../src/MainWindow.h
../src/AddObjectDialog.h ../src/AddObjectDialog.h
../src/ObjWidget.h ../src/ObjWidget.h
../src/FindObject.h
../src/Camera.h ../src/Camera.h
../src/CameraTcpClient.h
../src/ParametersToolBox.h ../src/ParametersToolBox.h
../src/AboutDialog.h ../src/AboutDialog.h
../src/TcpServer.h ../src/TcpServer.h
@ -43,12 +45,15 @@ SET(SRC_FILES
../src/RectItem.cpp ../src/RectItem.cpp
../src/QtOpenCV.cpp ../src/QtOpenCV.cpp
../src/Camera.cpp ../src/Camera.cpp
../src/CameraTcpClient.cpp
../src/ParametersToolBox.cpp ../src/ParametersToolBox.cpp
../src/Settings.cpp ../src/Settings.cpp
../src/ObjWidget.cpp ../src/ObjWidget.cpp
../src/FindObject.cpp
../src/AboutDialog.cpp ../src/AboutDialog.cpp
../src/TcpServer.cpp ../src/TcpServer.cpp
../src/Vocabulary.cpp ../src/Vocabulary.cpp
../src/utilite/ULogger.cpp
../src/utilite/UPlot.cpp ../src/utilite/UPlot.cpp
../src/utilite/UDirectory.cpp ../src/utilite/UDirectory.cpp
../src/utilite/UFile.cpp ../src/utilite/UFile.cpp

View File

@ -3,6 +3,12 @@
#include <QtCore/QFile> #include <QtCore/QFile>
#include "MainWindow.h" #include "MainWindow.h"
#include "Settings.h" #include "Settings.h"
#include "FindObject.h"
#include "Camera.h"
#include "TcpServer.h"
#include "utilite/ULogger.h"
bool running = true;
#ifdef WIN32 #ifdef WIN32
#include <windows.h> #include <windows.h>
@ -11,19 +17,47 @@ BOOL WINAPI my_handler(DWORD signal)
if (signal == CTRL_C_EVENT) if (signal == CTRL_C_EVENT)
{ {
printf("\nCtrl-C caught! Quitting application...\n"); printf("\nCtrl-C caught! Quitting application...\n");
QApplication::quit(); QCoreApplication::quit();
} }
return TRUE; return TRUE;
running = false;
} }
#else #else
#include <signal.h> #include <signal.h>
void my_handler(int s) void my_handler(int s)
{ {
printf("\nCtrl-C caught! Quitting application...\n"); printf("\nCtrl-C caught! Quitting application...\n");
QApplication::quit(); QCoreApplication::quit();
running = false;
}
inline void Sleep(unsigned int ms)
{
struct timespec req;
struct timespec rem;
req.tv_sec = ms / 1000;
req.tv_nsec = (ms - req.tv_sec * 1000) * 1000 * 1000;
nanosleep (&req, &rem);
} }
#endif #endif
void setupQuitSignal()
{
// Catch ctrl-c to close Qt
#ifdef WIN32
if (!SetConsoleCtrlHandler(my_handler, TRUE))
{
printf("\nERROR: Could not set control handler");
return 1;
}
#else
struct sigaction sigIntHandler;
sigIntHandler.sa_handler = my_handler;
sigemptyset(&sigIntHandler.sa_mask);
sigIntHandler.sa_flags = 0;
sigaction(SIGINT, &sigIntHandler, NULL);
#endif
}
void showUsage() void showUsage()
{ {
printf("\nUsage:\n" printf("\nUsage:\n"
@ -44,9 +78,14 @@ void showUsage()
int main(int argc, char* argv[]) int main(int argc, char* argv[])
{ {
QApplication app(argc, argv); ULogger::setType(ULogger::kTypeConsole);
ULogger::setLevel(ULogger::kInfo);
ULogger::setPrintWhere(false);
ULogger::setPrintTime(false);
// parse options //////////////////////////
// parse options BEGIN
//////////////////////////
bool guiMode = true; bool guiMode = true;
QString objectsPath = ""; QString objectsPath = "";
QString configPath = Settings::iniDefaultPath(); QString configPath = Settings::iniDefaultPath();
@ -65,7 +104,7 @@ int main(int argc, char* argv[])
} }
if(!QDir(objectsPath).exists()) if(!QDir(objectsPath).exists())
{ {
printf("[ERROR] Path not valid : %s\n", objectsPath.toStdString().c_str()); UERROR("Path not valid : %s", objectsPath.toStdString().c_str());
showUsage(); showUsage();
} }
} }
@ -87,7 +126,7 @@ int main(int argc, char* argv[])
} }
if(!QFile::exists(configPath)) if(!QFile::exists(configPath))
{ {
printf("[ERROR] Configuration file doesn't exist : %s\n", configPath.toStdString().c_str()); UERROR("Configuration file doesn't exist : %s", configPath.toStdString().c_str());
showUsage(); showUsage();
} }
} }
@ -107,61 +146,93 @@ int main(int argc, char* argv[])
showUsage(); showUsage();
} }
printf("[ERROR] Unrecognized option : %s\n", argv[i]); UERROR("Unrecognized option : %s", argv[i]);
showUsage(); showUsage();
} }
printf("Options:\n"); UINFO("Options:");
printf(" GUI mode = %s\n", guiMode?"true":"false"); UINFO(" GUI mode = %s", guiMode?"true":"false");
printf(" Objects path: \"%s\"\n", objectsPath.toStdString().c_str()); UINFO(" Objects path: \"%s\"", objectsPath.toStdString().c_str());
printf(" Settings path: \"%s\"\n", configPath.toStdString().c_str()); UINFO(" Settings path: \"%s\"", configPath.toStdString().c_str());
//////////////////////////
// parse options END
//////////////////////////
MainWindow mainWindow(0, configPath); // Load settings, should be loaded before creating other objects
Settings::init(configPath);
// Create FindObject
FindObject * findObject = new FindObject();
// Load objects if path is set
int objectsLoaded = 0; int objectsLoaded = 0;
if(!objectsPath.isEmpty()) if(!objectsPath.isEmpty())
{ {
objectsLoaded = mainWindow.loadObjects(objectsPath); objectsLoaded = findObject->loadObjects(objectsPath);
if(!objectsLoaded) if(!objectsLoaded)
{ {
printf("[WARNING] No objects loaded from \"%s\"\n", objectsPath.toStdString().c_str()); UWARN("No objects loaded from \"%s\"", objectsPath.toStdString().c_str());
} }
} }
if(objectsLoaded == 0 && !guiMode)
{
printf("[ERROR] In console mode, at least one object must be loaded! See -console option.\n");
showUsage();
}
if(guiMode) if(guiMode)
{ {
QApplication app(argc, argv);
MainWindow mainWindow(findObject, 0); // ownership transfered
app.connect( &app, SIGNAL( lastWindowClosed() ), &app, SLOT( quit() ) ); app.connect( &app, SIGNAL( lastWindowClosed() ), &app, SLOT( quit() ) );
mainWindow.show(); mainWindow.show();
app.exec();
} }
else else
{ {
mainWindow.startProcessing(); if(objectsLoaded == 0)
}
if(!guiMode)
{
// Catch ctrl-c to close the gui
#ifdef WIN32
if (!SetConsoleCtrlHandler(my_handler, TRUE))
{ {
printf("\nERROR: Could not set control handler"); UERROR("In console mode, at least one object must be loaded! See -console option.");
return 1; delete findObject;
showUsage();
} }
#else
struct sigaction sigIntHandler; QCoreApplication app(argc, argv);
sigIntHandler.sa_handler = my_handler; Camera camera;
sigemptyset(&sigIntHandler.sa_mask); TcpServer tcpServer(Settings::getGeneral_port());
sigIntHandler.sa_flags = 0; printf("IP: %s\nport: %d\n", tcpServer.getHostAddress().toString().toStdString().c_str(), tcpServer.getPort());
sigaction(SIGINT, &sigIntHandler, NULL);
#endif // connect stuff:
// [Camera] ---Image---> [FindObject] ---ObjectsDetected---> [TcpServer]
QObject::connect(&camera, SIGNAL(imageReceived(const cv::Mat &)), findObject, SLOT(detect(const cv::Mat &)));
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(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();
delete findObject;
tcpServer.close();
} }
return app.exec(); // Save settings
Settings::saveSettings();
} }

View File

@ -2,6 +2,7 @@
SET(headers_ui SET(headers_ui
../src/ObjWidget.h ../src/ObjWidget.h
../src/Camera.h ../src/Camera.h
../src/CameraTcpClient.h
) )
#This will generate moc_* for Qt #This will generate moc_* for Qt
QT4_WRAP_CPP(moc_srcs ${headers_ui}) QT4_WRAP_CPP(moc_srcs ${headers_ui})
@ -14,8 +15,11 @@ SET(SRC_FILES
../src/QtOpenCV.cpp ../src/QtOpenCV.cpp
../src/Settings.cpp ../src/Settings.cpp
../src/Camera.cpp ../src/Camera.cpp
../src/CameraTcpClient.cpp
../src/utilite/UDirectory.cpp ../src/utilite/UDirectory.cpp
../src/utilite/UFile.cpp ../src/utilite/UFile.cpp
../src/utilite/ULogger.cpp
../src/utilite/UConversion.cpp
${moc_srcs} ${moc_srcs}
) )

View File

@ -151,8 +151,8 @@ int main(int argc, char * argv[])
// PROCESS NEAREST NEIGHBOR RESULTS // PROCESS NEAREST NEIGHBOR RESULTS
//////////////////////////// ////////////////////////////
// Set gui data // Set gui data
objWidget.setData(objectKeypoints, objectDescriptors, objectImg, "", ""); objWidget.setData(objectKeypoints, cvtCvMat2QImage(objectImg));
sceneWidget.setData(sceneKeypoints, sceneDescriptors, sceneImg, "", ""); sceneWidget.setData(sceneKeypoints, cvtCvMat2QImage(sceneImg));
// Find correspondences by NNDR (Nearest Neighbor Distance Ratio) // Find correspondences by NNDR (Nearest Neighbor Distance Ratio)
float nndrRatio = 0.8; float nndrRatio = 0.8;

View File

@ -1,6 +1,7 @@
### Qt Gui stuff ### ### Qt Gui stuff ###
SET(headers_ui SET(headers_ui
../src/Camera.h ../src/Camera.h
../src/CameraTcpClient.h
ImagesTcpServer.h ImagesTcpServer.h
) )
#This will generate moc_* for Qt #This will generate moc_* for Qt
@ -9,10 +10,13 @@ QT4_WRAP_CPP(moc_srcs ${headers_ui})
SET(SRC_FILES SET(SRC_FILES
../src/Camera.cpp ../src/Camera.cpp
../src/CameraTcpClient.cpp
../src/Settings.cpp ../src/Settings.cpp
../src/QtOpenCV.cpp ../src/QtOpenCV.cpp
../src/utilite/UDirectory.cpp ../src/utilite/UDirectory.cpp
../src/utilite/UFile.cpp ../src/utilite/UFile.cpp
../src/utilite/ULogger.cpp
../src/utilite/UConversion.cpp
ImagesTcpServer.cpp ImagesTcpServer.cpp
main.cpp main.cpp
${moc_srcs} ${moc_srcs}

View File

@ -9,6 +9,8 @@
#include "Camera.h" #include "Camera.h"
#include "QtOpenCV.h" #include "QtOpenCV.h"
#include "Settings.h" #include "Settings.h"
#include "ObjSignature.h"
#include "utilite/ULogger.h"
#include <stdio.h> #include <stdio.h>
@ -22,7 +24,8 @@
AddObjectDialog::AddObjectDialog(Camera * camera, const cv::Mat & image, bool mirrorView, QWidget * parent, Qt::WindowFlags f) : AddObjectDialog::AddObjectDialog(Camera * camera, const cv::Mat & image, bool mirrorView, QWidget * parent, Qt::WindowFlags f) :
QDialog(parent, f), QDialog(parent, f),
camera_(camera), camera_(camera),
object_(0) objWidget_(0),
objSignature_(0)
{ {
ui_ = new Ui_addObjectDialog(); ui_ = new Ui_addObjectDialog();
ui_->setupUi(this); ui_->setupUi(this);
@ -38,7 +41,7 @@ AddObjectDialog::AddObjectDialog(Camera * camera, const cv::Mat & image, bool mi
connect(ui_->comboBox_selection, SIGNAL(currentIndexChanged(int)), this, SLOT(changeSelectionMode())); connect(ui_->comboBox_selection, SIGNAL(currentIndexChanged(int)), this, SLOT(changeSelectionMode()));
connect(ui_->cameraView, SIGNAL(selectionChanged()), this, SLOT(updateNextButton())); connect(ui_->cameraView, SIGNAL(selectionChanged()), this, SLOT(updateNextButton()));
connect(ui_->cameraView, SIGNAL(roiChanged(const QRect &)), this, SLOT(updateNextButton(const QRect &))); connect(ui_->cameraView, SIGNAL(roiChanged(const cv::Rect &)), this, SLOT(updateNextButton(const cv::Rect &)));
ui_->cameraView->setMirrorView(mirrorView); ui_->cameraView->setMirrorView(mirrorView);
if((camera_ && camera_->isRunning()) || image.empty()) if((camera_ && camera_->isRunning()) || image.empty())
@ -56,13 +59,27 @@ AddObjectDialog::~AddObjectDialog()
{ {
delete detector_; delete detector_;
delete extractor_; delete extractor_;
if(object_) if(objWidget_)
{ {
delete object_; delete objWidget_;
objWidget_ = 0;
}
if(objSignature_)
{
delete objSignature_;
objSignature_ = 0;
} }
delete ui_; delete ui_;
} }
void AddObjectDialog::retrieveObject(ObjWidget ** widget, ObjSignature ** signature)
{
*widget = objWidget_;
objWidget_= 0;
*signature = objSignature_;
objSignature_ = 0;
}
void AddObjectDialog::closeEvent(QCloseEvent* event) void AddObjectDialog::closeEvent(QCloseEvent* event)
{ {
if(camera_) if(camera_)
@ -91,40 +108,40 @@ void AddObjectDialog::takePicture()
void AddObjectDialog::updateNextButton() void AddObjectDialog::updateNextButton()
{ {
updateNextButton(QRect()); updateNextButton(cv::Rect());
} }
void AddObjectDialog::updateNextButton(const QRect & rect) void AddObjectDialog::updateNextButton(const cv::Rect & rect)
{ {
roi_ = rect; roi_ = rect;
if(roi_.isValid() && ui_->cameraView->cvImage().cols) if(roi_.height && roi_.width && cameraImage_.cols)
{ {
//clip roi //clip roi
if( roi_.x() >= ui_->cameraView->cvImage().cols || if( roi_.x >= cameraImage_.cols ||
roi_.x()+roi_.width() <= 0 || roi_.x+roi_.width <= 0 ||
roi_.y() >= ui_->cameraView->cvImage().rows || roi_.y >= cameraImage_.rows ||
roi_.y()+roi_.height() <= 0) roi_.y+roi_.height <= 0)
{ {
//Not valid... //Not valid...
roi_ = QRect(); roi_ = cv::Rect();
} }
else else
{ {
if(roi_.x() < 0) if(roi_.x < 0)
{ {
roi_.setX(0); roi_.x = 0;
} }
if(roi_.x() + roi_.width() > ui_->cameraView->cvImage().cols) if(roi_.x + roi_.width > cameraImage_.cols)
{ {
roi_.setWidth(ui_->cameraView->cvImage().cols - roi_.x()); roi_.width = cameraImage_.cols - roi_.x;
} }
if(roi_.y() < 0) if(roi_.y < 0)
{ {
roi_.setY(0); roi_.y = 0;
} }
if(roi_.y() + roi_.height() > ui_->cameraView->cvImage().rows) if(roi_.y + roi_.height > cameraImage_.rows)
{ {
roi_.setHeight(ui_->cameraView->cvImage().rows - roi_.y()); roi_.height = cameraImage_.rows - roi_.y;
} }
} }
} }
@ -143,7 +160,7 @@ void AddObjectDialog::updateNextButton(const QRect & rect)
} }
else else
{ {
if(roi_.isNull()) if(roi_.width == 0 || roi_.height == 0)
{ {
ui_->pushButton_next->setEnabled(false); ui_->pushButton_next->setEnabled(false);
} }
@ -214,7 +231,7 @@ void AddObjectDialog::setState(int state)
ui_->label_instruction->setText(tr("Select region representing the object.")); ui_->label_instruction->setText(tr("Select region representing the object."));
ui_->cameraView->setGraphicsViewMode(false); ui_->cameraView->setGraphicsViewMode(false);
} }
updateNextButton(QRect()); updateNextButton(cv::Rect());
} }
else if(state == kVerifySelection) else if(state == kVerifySelection)
{ {
@ -245,32 +262,25 @@ void AddObjectDialog::setState(int state)
std::vector<cv::KeyPoint> selectedKeypoints = ui_->cameraView->selectedKeypoints(); std::vector<cv::KeyPoint> selectedKeypoints = ui_->cameraView->selectedKeypoints();
// Select keypoints // Select keypoints
if(!cvImage_.empty() && if(!cameraImage_.empty() &&
((ui_->comboBox_selection->currentIndex() == 1 && selectedKeypoints.size()) || ((ui_->comboBox_selection->currentIndex() == 1 && selectedKeypoints.size()) ||
(ui_->comboBox_selection->currentIndex() == 0 && !roi_.isNull()))) (ui_->comboBox_selection->currentIndex() == 0 && roi_.width && roi_.height)))
{ {
cv::Rect roi;
if(ui_->comboBox_selection->currentIndex() == 1) if(ui_->comboBox_selection->currentIndex() == 1)
{ {
roi = computeROI(selectedKeypoints); roi_ = computeROI(selectedKeypoints);
} }
else
{ cv::Mat imgRoi(cameraImage_, roi_);
roi.x = roi_.x();
roi.y = roi_.y();
roi.width = roi_.width();
roi.height = roi_.height();
}
cv::Mat imgRoi(cvImage_, roi);
if(ui_->comboBox_selection->currentIndex() == 1) if(ui_->comboBox_selection->currentIndex() == 1)
{ {
if(roi.x != 0 || roi.y != 0) if(roi_.x != 0 || roi_.y != 0)
{ {
for(unsigned int i=0; i<selectedKeypoints.size(); ++i) for(unsigned int i=0; i<selectedKeypoints.size(); ++i)
{ {
selectedKeypoints.at(i).pt.x -= roi.x; selectedKeypoints.at(i).pt.x -= roi_.x;
selectedKeypoints.at(i).pt.y -= roi.y; selectedKeypoints.at(i).pt.y -= roi_.y;
} }
} }
} }
@ -280,14 +290,14 @@ void AddObjectDialog::setState(int state)
selectedKeypoints.clear(); selectedKeypoints.clear();
detector_->detect(imgRoi, selectedKeypoints); detector_->detect(imgRoi, selectedKeypoints);
} }
ui_->objectView->setData(selectedKeypoints, cv::Mat(), imgRoi, Settings::currentDetectorType(), ""); ui_->objectView->setData(selectedKeypoints, cvtCvMat2QImage(imgRoi.clone()));
ui_->objectView->setMinimumSize(roi.width, roi.height); ui_->objectView->setMinimumSize(roi_.width, roi_.height);
ui_->objectView->update(); ui_->objectView->update();
ui_->pushButton_next->setEnabled(true); ui_->pushButton_next->setEnabled(true);
} }
else else
{ {
printf("Please select items\n"); UINFO("Please select items");
ui_->pushButton_next->setEnabled(false); ui_->pushButton_next->setEnabled(false);
} }
ui_->label_instruction->setText(tr("Selection : %1 features").arg(selectedKeypoints.size())); ui_->label_instruction->setText(tr("Selection : %1 features").arg(selectedKeypoints.size()));
@ -296,26 +306,34 @@ void AddObjectDialog::setState(int state)
{ {
std::vector<cv::KeyPoint> keypoints = ui_->objectView->keypoints(); std::vector<cv::KeyPoint> keypoints = ui_->objectView->keypoints();
if((ui_->comboBox_selection->currentIndex() == 1 && keypoints.size()) || if((ui_->comboBox_selection->currentIndex() == 1 && keypoints.size()) ||
(ui_->comboBox_selection->currentIndex() == 0 && !roi_.isNull())) (ui_->comboBox_selection->currentIndex() == 0 && roi_.width && roi_.height))
{ {
cv::Mat descriptors; cv::Mat descriptors;
cv::Mat imgRoi(cameraImage_, roi_);
if(keypoints.size()) if(keypoints.size())
{ {
// Extract descriptors // Extract descriptors
extractor_->compute(ui_->objectView->cvImage(), keypoints, descriptors); extractor_->compute(imgRoi, keypoints, descriptors);
if(keypoints.size() != (unsigned int)descriptors.rows) if(keypoints.size() != (unsigned int)descriptors.rows)
{ {
printf("ERROR : keypoints=%d != descriptors=%d\n", (int)keypoints.size(), descriptors.rows); UERROR("keypoints=%d != descriptors=%d", (int)keypoints.size(), descriptors.rows);
} }
} }
if(object_) if(objWidget_)
{ {
delete object_; delete objWidget_;
object_ = 0; objWidget_ = 0;
} }
object_ = new ObjWidget(0, keypoints, descriptors, ui_->objectView->cvImage(), Settings::currentDetectorType(), Settings::currentDescriptorType()); if(objSignature_)
{
delete objSignature_;
objSignature_ = 0;
}
objSignature_ = new ObjSignature(0, imgRoi.clone());
objSignature_->setData(keypoints, descriptors, Settings::currentDetectorType(), Settings::currentDescriptorType());
objWidget_ = new ObjWidget(0, keypoints, cvtCvMat2QImage(imgRoi.clone()));
this->accept(); this->accept();
} }
@ -324,24 +342,24 @@ void AddObjectDialog::setState(int state)
void AddObjectDialog::update(const cv::Mat & image) void AddObjectDialog::update(const cv::Mat & image)
{ {
cvImage_ = cv::Mat(); cameraImage_ = cv::Mat();
if(!image.empty()) if(!image.empty())
{ {
// convert to grayscale // convert to grayscale
if(image.channels() != 1 || image.depth() != CV_8U) if(image.channels() != 1 || image.depth() != CV_8U)
{ {
cv::cvtColor(image, cvImage_, CV_BGR2GRAY); cv::cvtColor(image, cameraImage_, CV_BGR2GRAY);
} }
else else
{ {
cvImage_ = image; cameraImage_ = image.clone();
} }
// Extract keypoints // Extract keypoints
cv::vector<cv::KeyPoint> keypoints; cv::vector<cv::KeyPoint> keypoints;
detector_->detect(cvImage_, keypoints); detector_->detect(cameraImage_, keypoints);
ui_->cameraView->setData(keypoints, cv::Mat(), cvImage_, Settings::currentDetectorType(), ""); ui_->cameraView->setData(keypoints, cvtCvMat2QImage(cameraImage_));
ui_->cameraView->update(); ui_->cameraView->update();
} }
} }
@ -383,8 +401,8 @@ cv::Rect AddObjectDialog::computeROI(const std::vector<cv::KeyPoint> & kpts)
roi.y = h1; roi.y = h1;
roi.width = x2-x1; roi.width = x2-x1;
roi.height = h2-h1; roi.height = h2-h1;
//printf("ptx=%d, pty=%d\n", (int)kpts.at(i).pt.x, (int)kpts.at(i).pt.y); //UINFO("ptx=%d, pty=%d", (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); //UINFO("x=%d, y=%d, w=%d, h=%d", roi.x, roi.y, roi.width, roi.height);
} }
return roi; return roi;

View File

@ -16,6 +16,7 @@ class Camera;
class KeypointItem; class KeypointItem;
class KeypointDetector; class KeypointDetector;
class DescriptorExtractor; class DescriptorExtractor;
class ObjSignature;
class AddObjectDialog : public QDialog { class AddObjectDialog : public QDialog {
@ -26,7 +27,7 @@ public:
virtual ~AddObjectDialog(); virtual ~AddObjectDialog();
// ownership transferred to caller // ownership transferred to caller
ObjWidget * retrieveObject() {ObjWidget * obj = object_; object_=0; return obj;} void retrieveObject(ObjWidget ** widget, ObjSignature ** signature);
private Q_SLOTS: private Q_SLOTS:
void update(const cv::Mat &); void update(const cv::Mat &);
@ -35,7 +36,7 @@ private Q_SLOTS:
void cancel(); void cancel();
void takePicture(); void takePicture();
void updateNextButton(); void updateNextButton();
void updateNextButton(const QRect &); void updateNextButton(const cv::Rect &);
void changeSelectionMode(); void changeSelectionMode();
protected: protected:
@ -47,14 +48,15 @@ private:
private: private:
Ui_addObjectDialog * ui_; Ui_addObjectDialog * ui_;
Camera * camera_; Camera * camera_;
ObjWidget * object_; ObjWidget * objWidget_;
cv::Mat cvImage_; ObjSignature * objSignature_;
cv::Mat cameraImage_;
cv::Rect roi_;
KeypointDetector * detector_; KeypointDetector * detector_;
DescriptorExtractor * extractor_; DescriptorExtractor * extractor_;
enum State{kTakePicture, kSelectFeatures, kVerifySelection, kClosing}; enum State{kTakePicture, kSelectFeatures, kVerifySelection, kClosing};
int state_; int state_;
QRect roi_;
}; };
#endif /* ADDOBJECTDIALOG_H_ */ #endif /* ADDOBJECTDIALOG_H_ */

View File

@ -8,93 +8,9 @@
#include "Settings.h" #include "Settings.h"
#include <QtCore/QFile> #include <QtCore/QFile>
#include "utilite/UDirectory.h" #include "utilite/UDirectory.h"
#include "utilite/ULogger.h"
#include "QtOpenCV.h" #include "QtOpenCV.h"
CameraTcpClient::CameraTcpClient(QObject *parent) :
QTcpSocket(parent),
blockSize_(0)
{
connect(this, SIGNAL(readyRead()), this, SLOT(readReceivedData()));
connect(this, SIGNAL(error(QAbstractSocket::SocketError)), this, SLOT(displayError(QAbstractSocket::SocketError)));
connect(this, SIGNAL(disconnected()), this, SLOT(connectionLost()));
}
cv::Mat CameraTcpClient::getImage()
{
cv::Mat img;
if(images_.size())
{
// if queue changed after tcp connection ended with images still in the buffer
int queue = Settings::getCamera_9queueSize();
while(queue > 0 && images_.size() > queue)
{
images_.pop_front();
}
img = images_.front();
images_.pop_front();
}
return img;
}
void CameraTcpClient::readReceivedData()
{
QDataStream in(this);
in.setVersion(QDataStream::Qt_4_0);
if (blockSize_ == 0)
{
if (this->bytesAvailable() < (int)sizeof(quint64))
{
return;
}
in >> blockSize_;
}
if (this->bytesAvailable() < (int)blockSize_)
{
return;
}
std::vector<unsigned char> buf(blockSize_);
in.readRawData((char*)buf.data(), blockSize_);
images_.push_back(cv::imdecode(buf, cv::IMREAD_UNCHANGED));
int queue = Settings::getCamera_9queueSize();
while(queue > 0 && images_.size() > queue)
{
images_.pop_front();
}
blockSize_ = 0;
}
void CameraTcpClient::displayError(QAbstractSocket::SocketError socketError)
{
switch (socketError)
{
case QAbstractSocket::RemoteHostClosedError:
break;
case QAbstractSocket::HostNotFoundError:
printf("[ERROR] CameraTcp: Tcp error: The host was not found. Please "
"check the host name and port settings.\n");
break;
case QAbstractSocket::ConnectionRefusedError:
printf("[ERROR] CameraTcp: The connection was refused by the peer. "
"Make sure your images server is running, "
"and check that the host name and port "
"settings are correct.\n");
break;
default:
printf("The following error occurred: %s.\n", this->errorString().toStdString().c_str());
break;
}
}
void CameraTcpClient::connectionLost()
{
//printf("[WARNING] CameraTcp: Connection lost!\n");
}
Camera::Camera(QObject * parent) : Camera::Camera(QObject * parent) :
QObject(parent), QObject(parent),
currentImageIndex_(0) currentImageIndex_(0)
@ -179,7 +95,7 @@ void Camera::takeImage()
img = cameraTcpClient_.getImage(); img = cameraTcpClient_.getImage();
if(cameraTcpClient_.imagesBuffered() > 0 && Settings::getCamera_9queueSize() == 0) if(cameraTcpClient_.imagesBuffered() > 0 && Settings::getCamera_9queueSize() == 0)
{ {
printf("[Warning] %d images buffered so far...\n", cameraTcpClient_.imagesBuffered()); UWARN("%d images buffered so far...", cameraTcpClient_.imagesBuffered());
} }
while(img.empty() && cameraTcpClient_.waitForReadyRead()) while(img.empty() && cameraTcpClient_.waitForReadyRead())
{ {
@ -189,7 +105,7 @@ void Camera::takeImage()
{ {
if(!cameraTcpClient_.waitForConnected()) if(!cameraTcpClient_.waitForConnected())
{ {
printf("Connection is lost, trying to reconnect to server (%s:%d)... (at the rate of the camera: %d ms)\n", UWARN("Connection is lost, trying to reconnect to server (%s:%d)... (at the rate of the camera: %d ms)",
Settings::getCamera_7IP().toStdString().c_str(), Settings::getCamera_7IP().toStdString().c_str(),
Settings::getCamera_8port(), Settings::getCamera_8port(),
cameraTimer_.interval()); cameraTimer_.interval());
@ -200,7 +116,7 @@ void Camera::takeImage()
if(img.empty()) if(img.empty())
{ {
printf("Camera: Could not grab a frame, the end of the feed may be reached...\n"); UWARN("Camera: Could not grab a frame, the end of the feed may be reached...");
} }
else else
{ {
@ -234,7 +150,7 @@ bool Camera::start()
cameraTcpClient_.connectToHost(Settings::getCamera_7IP(), Settings::getCamera_8port()); cameraTcpClient_.connectToHost(Settings::getCamera_7IP(), Settings::getCamera_8port());
if(!cameraTcpClient_.waitForConnected()) if(!cameraTcpClient_.waitForConnected())
{ {
printf("[WARNING] Camera: Cannot connect to server \"%s:%d\"\n", UWARN("Camera: Cannot connect to server \"%s:%d\"",
Settings::getCamera_7IP().toStdString().c_str(), Settings::getCamera_7IP().toStdString().c_str(),
Settings::getCamera_8port()); Settings::getCamera_8port());
cameraTcpClient_.close(); cameraTcpClient_.close();
@ -258,12 +174,12 @@ bool Camera::start()
{ {
images_.append(path.toStdString() + UDirectory::separator() + *iter); images_.append(path.toStdString() + UDirectory::separator() + *iter);
} }
printf("Camera: Reading %d images from directory \"%s\"...\n", (int)images_.size(), path.toStdString().c_str()); UINFO("Camera: Reading %d images from directory \"%s\"...", (int)images_.size(), path.toStdString().c_str());
if(images_.isEmpty()) if(images_.isEmpty())
{ {
printf("[WARNING] Camera: Directory \"%s\" is empty (no images matching the \"%s\" extensions). " UWARN("Camera: Directory \"%s\" is empty (no images matching the \"%s\" extensions). "
"If you want to disable loading automatically this directory, " "If you want to disable loading automatically this directory, "
"clear the Camera/mediaPath parameter. By default, webcam will be used instead of the directory.\n", "clear the Camera/mediaPath parameter. By default, webcam will be used instead of the directory.",
path.toStdString().c_str(), path.toStdString().c_str(),
ext.toStdString().c_str()); ext.toStdString().c_str());
} }
@ -274,11 +190,13 @@ bool Camera::start()
capture_.open(path.toStdString().c_str()); capture_.open(path.toStdString().c_str());
if(!capture_.isOpened()) if(!capture_.isOpened())
{ {
printf("[WARNING] Camera: Cannot open file \"%s\". If you want to disable loading automatically this video file, clear the Camera/mediaPath parameter. By default, webcam will be used instead of the file.\n", path.toStdString().c_str()); UWARN("Camera: Cannot open file \"%s\". If you want to disable loading "
"automatically this video file, clear the Camera/mediaPath parameter. "
"By default, webcam will be used instead of the file.", path.toStdString().c_str());
} }
else else
{ {
printf("Camera: Reading from video file \"%s\"...\n", path.toStdString().c_str()); UINFO("Camera: Reading from video file \"%s\"...", path.toStdString().c_str());
} }
} }
if(!capture_.isOpened() && images_.empty()) if(!capture_.isOpened() && images_.empty())
@ -290,13 +208,13 @@ bool Camera::start()
capture_.set(CV_CAP_PROP_FRAME_WIDTH, double(Settings::getCamera_2imageWidth())); capture_.set(CV_CAP_PROP_FRAME_WIDTH, double(Settings::getCamera_2imageWidth()));
capture_.set(CV_CAP_PROP_FRAME_HEIGHT, double(Settings::getCamera_3imageHeight())); capture_.set(CV_CAP_PROP_FRAME_HEIGHT, double(Settings::getCamera_3imageHeight()));
} }
printf("Camera: Reading from camera device %d...\n", Settings::getCamera_1deviceId()); UINFO("Camera: Reading from camera device %d...", Settings::getCamera_1deviceId());
} }
} }
} }
if(!capture_.isOpened() && images_.empty() && !cameraTcpClient_.isOpen()) if(!capture_.isOpened() && images_.empty() && !cameraTcpClient_.isOpen())
{ {
printf("[ERROR] Camera: Failed to open a capture object!\n"); UERROR("Camera: Failed to open a capture object!");
return false; return false;
} }

View File

@ -9,25 +9,7 @@
#include <QtCore/QObject> #include <QtCore/QObject>
#include <QtCore/QTimer> #include <QtCore/QTimer>
#include <QtGui/QImage> #include <QtGui/QImage>
#include <QtNetwork/QTcpSocket> #include "CameraTcpClient.h"
class CameraTcpClient : public QTcpSocket
{
Q_OBJECT;
public:
CameraTcpClient(QObject * parent = 0);
cv::Mat getImage();
int imagesBuffered() const {return images_.size();}
private Q_SLOTS:
void readReceivedData();
void displayError(QAbstractSocket::SocketError socketError);
void connectionLost();
private:
quint64 blockSize_;
QVector<cv::Mat> images_;
};
class Camera : public QObject { class Camera : public QObject {
Q_OBJECT Q_OBJECT

95
src/CameraTcpClient.cpp Normal file
View File

@ -0,0 +1,95 @@
/*
* CameraTcpClient.cpp
*
* Created on: 2014-07-31
* Author: mathieu
*/
#include "CameraTcpClient.h"
#include "Settings.h"
#include "utilite/ULogger.h"
CameraTcpClient::CameraTcpClient(QObject *parent) :
QTcpSocket(parent),
blockSize_(0)
{
connect(this, SIGNAL(readyRead()), this, SLOT(readReceivedData()));
connect(this, SIGNAL(error(QAbstractSocket::SocketError)), this, SLOT(displayError(QAbstractSocket::SocketError)));
connect(this, SIGNAL(disconnected()), this, SLOT(connectionLost()));
}
cv::Mat CameraTcpClient::getImage()
{
cv::Mat img;
if(images_.size())
{
// if queue changed after tcp connection ended with images still in the buffer
int queue = Settings::getCamera_9queueSize();
while(queue > 0 && images_.size() > queue)
{
images_.pop_front();
}
img = images_.front();
images_.pop_front();
}
return img;
}
void CameraTcpClient::readReceivedData()
{
QDataStream in(this);
in.setVersion(QDataStream::Qt_4_0);
if (blockSize_ == 0)
{
if (this->bytesAvailable() < (int)sizeof(quint64))
{
return;
}
in >> blockSize_;
}
if (this->bytesAvailable() < (int)blockSize_)
{
return;
}
std::vector<unsigned char> buf(blockSize_);
in.readRawData((char*)buf.data(), blockSize_);
images_.push_back(cv::imdecode(buf, cv::IMREAD_UNCHANGED));
int queue = Settings::getCamera_9queueSize();
while(queue > 0 && images_.size() > queue)
{
images_.pop_front();
}
blockSize_ = 0;
}
void CameraTcpClient::displayError(QAbstractSocket::SocketError socketError)
{
switch (socketError)
{
case QAbstractSocket::RemoteHostClosedError:
break;
case QAbstractSocket::HostNotFoundError:
UWARN("CameraTcp: Tcp error: The host was not found. Please "
"check the host name and port settings.\n");
break;
case QAbstractSocket::ConnectionRefusedError:
UWARN("CameraTcp: The connection was refused by the peer. "
"Make sure your images server is running, "
"and check that the host name and port "
"settings are correct.");
break;
default:
UERROR("The following error occurred: %s.", this->errorString().toStdString().c_str());
break;
}
}
void CameraTcpClient::connectionLost()
{
//printf("[WARNING] CameraTcp: Connection lost!\n");
}

32
src/CameraTcpClient.h Normal file
View File

@ -0,0 +1,32 @@
/*
* CameraTcpClient.h
*
* Created on: 2014-07-31
* Author: mathieu
*/
#ifndef CAMERATCPCLIENT_H_
#define CAMERATCPCLIENT_H_
#include <QtNetwork/QTcpSocket>
#include <opencv2/opencv.hpp>
class CameraTcpClient : public QTcpSocket
{
Q_OBJECT;
public:
CameraTcpClient(QObject * parent = 0);
cv::Mat getImage();
int imagesBuffered() const {return images_.size();}
private Q_SLOTS:
void readReceivedData();
void displayError(QAbstractSocket::SocketError socketError);
void connectionLost();
private:
quint64 blockSize_;
QVector<cv::Mat> images_;
};
#endif /* CAMERATCPCLIENT_H_ */

939
src/FindObject.cpp Normal file
View File

@ -0,0 +1,939 @@
/*
* FindObject.cpp
*
* Created on: 2014-07-30
* Author: mathieu
*/
#include "FindObject.h"
#include "ObjSignature.h"
#include "Settings.h"
#include "utilite/UDirectory.h"
#include "utilite/ULogger.h"
#include "Vocabulary.h"
#include <QtCore/QThread>
#include <QtCore/QFileInfo>
#include <QtCore/QStringList>
#include <QtCore/QTime>
#include <stdio.h>
FindObject::FindObject(QObject * parent) :
QObject(parent),
vocabulary_(new Vocabulary()),
detector_(Settings::createKeypointDetector()),
extractor_(Settings::createDescriptorExtractor()),
minMatchedDistance_(-1),
maxMatchedDistance_(-1)
{
Q_ASSERT(detector_ != 0 && extractor_ != 0);
}
FindObject::~FindObject() {
delete detector_;
delete extractor_;
delete vocabulary_;
objectsDescriptors_.clear();
}
int FindObject::loadObjects(const QString & dirPath)
{
int loadedObjects = 0;
QString formats = Settings::getGeneral_imageFormats().remove('*').remove('.');
UDirectory dir(dirPath.toStdString(), formats.toStdString());
if(dir.isValid())
{
const std::list<std::string> & names = dir.getFileNames(); // sorted in natural order
for(std::list<std::string>::const_iterator iter=names.begin(); iter!=names.end(); ++iter)
{
this->addObject((dirPath.toStdString()+dir.separator()+*iter).c_str());
}
if(names.size())
{
this->updateObjects();
this->updateVocabulary();
}
loadedObjects = (int)names.size();
}
return loadedObjects;
}
const ObjSignature * FindObject::addObject(const QString & filePath)
{
UINFO("Load file %s", filePath.toStdString().c_str());
if(!filePath.isNull())
{
cv::Mat img = cv::imread(filePath.toStdString().c_str(), cv::IMREAD_GRAYSCALE);
if(!img.empty())
{
int id = 0;
QFileInfo file(filePath);
QStringList list = file.fileName().split('.');
if(list.size())
{
bool ok = false;
id = list.front().toInt(&ok);
if(ok && id>0)
{
if(objects_.contains(id))
{
UWARN("Object %d already added, a new ID will be generated (new id=%d).", id, Settings::getGeneral_nextObjID());
id = 0;
}
}
else
{
id = 0;
}
}
return this->addObject(img, id);
}
}
return 0;
}
const ObjSignature * FindObject::addObject(const cv::Mat & image, int id)
{
Q_ASSERT(id >= 0);
ObjSignature * s = new ObjSignature(id, image);
if(!this->addObject(s))
{
delete s;
return 0;
}
return s;
}
bool FindObject::addObject(ObjSignature * obj)
{
Q_ASSERT(obj != 0 && obj->id() >= 0);
if(obj->id() && objects_.contains(obj->id()))
{
UERROR("object with id %d already added!", obj->id());
return false;
}
else if(obj->id() == 0)
{
obj->setId(Settings::getGeneral_nextObjID());
}
Settings::setGeneral_nextObjID(obj->id()+1);
objects_.insert(obj->id(), obj);
clearVocabulary();
return true;
}
void FindObject::removeObject(int id)
{
if(objects_.contains(id))
{
delete objects_.value(id);
objects_.remove(id);
clearVocabulary();
}
}
void FindObject::removeAllObjects()
{
qDeleteAll(objects_);
objects_.clear();
clearVocabulary();
}
void FindObject::updateDetectorExtractor()
{
delete detector_;
delete extractor_;
detector_ = Settings::createKeypointDetector();
extractor_ = Settings::createDescriptorExtractor();
Q_ASSERT(detector_ != 0 && extractor_ != 0);
}
std::vector<cv::KeyPoint> limitKeypoints(const std::vector<cv::KeyPoint> & keypoints, int maxKeypoints)
{
std::vector<cv::KeyPoint> kptsKept;
if(maxKeypoints > 0 && (int)keypoints.size() > maxKeypoints)
{
// Sort words by response
std::multimap<float, int> reponseMap; // <response,id>
for(unsigned int i = 0; i <keypoints.size(); ++i)
{
//Keep track of the data, to be easier to manage the data in the next step
reponseMap.insert(std::pair<float, int>(fabs(keypoints[i].response), i));
}
// Remove them
std::multimap<float, int>::reverse_iterator iter = reponseMap.rbegin();
kptsKept.resize(maxKeypoints);
for(unsigned int k=0; k < kptsKept.size() && iter!=reponseMap.rend(); ++k, ++iter)
{
kptsKept[k] = keypoints[iter->second];
}
}
else
{
kptsKept = keypoints;
}
return kptsKept;
}
class ExtractFeaturesThread : public QThread
{
public:
ExtractFeaturesThread(int objectId, const cv::Mat & image) :
objectId_(objectId),
image_(image)
{
}
int objectId() const {return objectId_;}
const cv::Mat & image() const {return image_;}
const std::vector<cv::KeyPoint> & keypoints() const {return keypoints_;}
const cv::Mat & descriptors() const {return descriptors_;}
protected:
virtual void run()
{
QTime time;
time.start();
UINFO("Extracting descriptors from object %d...", objectId_);
KeypointDetector * detector = Settings::createKeypointDetector();
keypoints_.clear();
descriptors_ = cv::Mat();
detector->detect(image_, keypoints_);
delete detector;
if(keypoints_.size())
{
int maxFeatures = Settings::getFeature2D_3MaxFeatures();
if(maxFeatures > 0 && (int)keypoints_.size() > maxFeatures)
{
int previousCount = (int)keypoints_.size();
keypoints_ = limitKeypoints(keypoints_, maxFeatures);
UINFO("obj=%d, %d keypoints removed, (kept %d), min/max response=%f/%f", objectId_, previousCount-(int)keypoints_.size(), (int)keypoints_.size(), keypoints_.size()?keypoints_.back().response:0.0f, keypoints_.size()?keypoints_.front().response:0.0f);
}
DescriptorExtractor * extractor = Settings::createDescriptorExtractor();
extractor->compute(image_, keypoints_, descriptors_);
delete extractor;
if((int)keypoints_.size() != descriptors_.rows)
{
UERROR("obj=%d kpt=%d != descriptors=%d", objectId_, (int)keypoints_.size(), descriptors_.rows);
}
}
else
{
UWARN("no features detected in object %d !?!", objectId_);
}
UINFO("%d descriptors extracted from object %d (in %d ms)", descriptors_.rows, objectId_, time.elapsed());
}
private:
int objectId_;
cv::Mat image_;
std::vector<cv::KeyPoint> keypoints_;
cv::Mat descriptors_;
};
void FindObject::updateObjects()
{
if(objects_.size())
{
int threadCounts = Settings::getGeneral_threads();
if(threadCounts == 0)
{
threadCounts = objects_.size();
}
QTime time;
time.start();
UINFO("Features extraction from %d objects...", objects_.size());
QList<ObjSignature*> objectsList = objects_.values();
for(int i=0; i<objectsList.size(); i+=threadCounts)
{
QVector<ExtractFeaturesThread*> threads;
for(int k=i; k<i+threadCounts && k<objectsList.size(); ++k)
{
threads.push_back(new ExtractFeaturesThread(objectsList.at(k)->id(), objectsList.at(k)->image()));
threads.back()->start();
}
for(int j=0; j<threads.size(); ++j)
{
threads[j]->wait();
int id = threads[j]->objectId();
objects_.value(id)->setData(
threads[j]->keypoints(),
threads[j]->descriptors(),
Settings::currentDetectorType(),
Settings::currentDescriptorType());
}
}
UINFO("Features extraction from %d objects... done! (%d ms)", objects_.size(), time.elapsed());
}
else
{
UINFO("No objects to update...");
}
}
void FindObject::clearVocabulary()
{
objectsDescriptors_.clear();
dataRange_.clear();
vocabulary_->clear();
}
void FindObject::updateVocabulary()
{
clearVocabulary();
int count = 0;
int dim = -1;
int type = -1;
// Get the total size and verify descriptors
QList<ObjSignature*> objectsList = objects_.values();
for(int i=0; i<objectsList.size(); ++i)
{
if(!objectsList.at(i)->descriptors().empty())
{
if(dim >= 0 && objectsList.at(i)->descriptors().cols != dim)
{
UERROR("Descriptors of the objects are not all the same size! Objects "
"opened must have all the same size (and from the same descriptor extractor).");
return;
}
dim = objectsList.at(i)->descriptors().cols;
if(type >= 0 && objectsList.at(i)->descriptors().type() != type)
{
UERROR("Descriptors of the objects are not all the same type! Objects opened "
"must have been processed by the same descriptor extractor.");
return;
}
type = objectsList.at(i)->descriptors().type();
count += objectsList.at(i)->descriptors().rows;
}
}
// Copy data
if(count)
{
UINFO("Updating global descriptors matrix: Objects=%d, total descriptors=%d, dim=%d, type=%d",
(int)objects_.size(), count, dim, type);
if(Settings::getGeneral_invertedSearch() || Settings::getGeneral_threads() == 1)
{
// If only one thread, put all descriptors in the same cv::Mat
objectsDescriptors_.insert(0, cv::Mat(count, dim, type));
int row = 0;
for(int i=0; i<objectsList.size(); ++i)
{
if(objectsList.at(i)->descriptors().rows)
{
cv::Mat dest(objectsDescriptors_.begin().value(), cv::Range(row, row+objectsList.at(i)->descriptors().rows));
objectsList.at(i)->descriptors().copyTo(dest);
row += objectsList.at(i)->descriptors().rows;
// dataRange contains the upper_bound for each
// object (the last descriptors position in the
// global object descriptors matrix)
if(objectsList.at(i)->descriptors().rows)
{
dataRange_.insert(row-1, objectsList.at(i)->id());
}
}
}
if(Settings::getGeneral_invertedSearch())
{
QTime time;
time.start();
bool incremental = Settings::getGeneral_vocabularyIncremental();
if(incremental)
{
UINFO("Creating incremental vocabulary...");
}
else
{
UINFO("Creating vocabulary...");
}
QTime localTime;
localTime.start();
int updateVocabularyMinWords = Settings::getGeneral_vocabularyUpdateMinWords();
int addedWords = 0;
for(int i=0; i<objectsList.size(); ++i)
{
QMultiMap<int, int> words = vocabulary_->addWords(objectsList[i]->descriptors(), objectsList.at(i)->id(), incremental);
objectsList[i]->setWords(words);
addedWords += words.uniqueKeys().size();
bool updated = false;
if(incremental && addedWords && addedWords >= updateVocabularyMinWords)
{
vocabulary_->update();
addedWords = 0;
updated = true;
}
UINFO("Object %d, %d words from %d descriptors (%d words, %d ms) %s",
objectsList[i]->id(),
words.uniqueKeys().size(),
objectsList[i]->descriptors().rows,
vocabulary_->size(),
localTime.restart(),
updated?"updated":"");
}
if(addedWords)
{
vocabulary_->update();
}
if(incremental)
{
UINFO("Creating incremental vocabulary... done! size=%d (%d ms)", vocabulary_->size(), time.elapsed());
}
else
{
UINFO("Creating vocabulary... done! size=%d (%d ms)", vocabulary_->size(), time.elapsed());
}
}
}
else
{
for(int i=0; i<objectsList.size(); ++i)
{
objectsDescriptors_.insert(objectsList.at(i)->id(), objectsList.at(i)->descriptors());
}
}
}
}
class SearchThread: public QThread
{
public:
SearchThread(Vocabulary * vocabulary, int objectId, const cv::Mat * descriptors, const QMultiMap<int, int> * sceneWords) :
vocabulary_(vocabulary),
objectId_(objectId),
descriptors_(descriptors),
sceneWords_(sceneWords),
minMatchedDistance_(-1.0f),
maxMatchedDistance_(-1.0f)
{
Q_ASSERT(index && descriptors);
}
virtual ~SearchThread() {}
int getObjectId() const {return objectId_;}
float getMinMatchedDistance() const {return minMatchedDistance_;}
float getMaxMatchedDistance() const {return maxMatchedDistance_;}
const QMultiMap<int, int> & getMatches() const {return matches_;}
protected:
virtual void run()
{
//QTime time;
//time.start();
cv::Mat results;
cv::Mat dists;
//match objects to scene
int k = Settings::getNearestNeighbor_3nndrRatioUsed()?2:1;
results = cv::Mat(descriptors_->rows, k, CV_32SC1); // results index
dists = cv::Mat(descriptors_->rows, k, CV_32FC1); // Distance results are CV_32FC1
vocabulary_->search(*descriptors_, results, dists, k);
// PROCESS RESULTS
// Get all matches for each object
for(int i=0; i<dists.rows; ++i)
{
// Check if this descriptor matches with those of the objects
bool matched = false;
if(Settings::getNearestNeighbor_3nndrRatioUsed() &&
dists.at<float>(i,0) <= Settings::getNearestNeighbor_4nndrRatio() * dists.at<float>(i,1))
{
matched = true;
}
if((matched || !Settings::getNearestNeighbor_3nndrRatioUsed()) &&
Settings::getNearestNeighbor_5minDistanceUsed())
{
if(dists.at<float>(i,0) <= Settings::getNearestNeighbor_6minDistance())
{
matched = true;
}
else
{
matched = false;
}
}
if(!matched && !Settings::getNearestNeighbor_3nndrRatioUsed() && !Settings::getNearestNeighbor_5minDistanceUsed())
{
matched = true; // no criterion, match to the nearest descriptor
}
if(minMatchedDistance_ == -1 || minMatchedDistance_ > dists.at<float>(i,0))
{
minMatchedDistance_ = dists.at<float>(i,0);
}
if(maxMatchedDistance_ == -1 || maxMatchedDistance_ < dists.at<float>(i,0))
{
maxMatchedDistance_ = dists.at<float>(i,0);
}
int wordId = results.at<int>(i,0);
if(matched && sceneWords_->count(wordId) == 1)
{
matches_.insert(i, sceneWords_->value(wordId));
matches_.insert(i, results.at<int>(i,0));
}
}
//UINFO("Search Object %d time=%d ms", objectIndex_, time.elapsed());
}
private:
Vocabulary * vocabulary_; // would be const but flann search() method is not const!?
int objectId_;
const cv::Mat * descriptors_;
const QMultiMap<int, int> * sceneWords_; // <word id, keypoint indexes>
float minMatchedDistance_;
float maxMatchedDistance_;
QMultiMap<int, int> matches_;
};
class HomographyThread: public QThread
{
public:
HomographyThread(
const QMultiMap<int, int> * matches, // <object, scene>
int objectId,
const std::vector<cv::KeyPoint> * kptsA,
const std::vector<cv::KeyPoint> * kptsB) :
matches_(matches),
objectId_(objectId),
kptsA_(kptsA),
kptsB_(kptsB)
{
Q_ASSERT(matches && kptsA && kptsB);
}
virtual ~HomographyThread() {}
int getObjectId() const {return objectId_;}
const std::vector<int> & getIndexesA() const {return indexesA_;}
const std::vector<int> & getIndexesB() const {return indexesB_;}
const std::vector<uchar> & getOutlierMask() const {return outlierMask_;}
QMultiMap<int, int> getInliers() const {return inliers_;}
QMultiMap<int, int> getOutliers() const {return outliers_;}
const cv::Mat & getHomography() const {return h_;}
protected:
virtual void run()
{
//QTime time;
//time.start();
std::vector<cv::Point2f> mpts_1(matches_->size());
std::vector<cv::Point2f> mpts_2(matches_->size());
indexesA_.resize(matches_->size());
indexesB_.resize(matches_->size());
int j=0;
for(QMultiMap<int, int>::const_iterator iter = matches_->begin(); iter!=matches_->end(); ++iter)
{
mpts_1[j] = kptsA_->at(iter.key()).pt;
indexesA_[j] = iter.key();
mpts_2[j] = kptsB_->at(iter.value()).pt;
indexesB_[j] = iter.value();
++j;
}
if((int)mpts_1.size() >= Settings::getHomography_minimumInliers())
{
h_ = findHomography(mpts_1,
mpts_2,
Settings::getHomographyMethod(),
Settings::getHomography_ransacReprojThr(),
outlierMask_);
for(unsigned int k=0; k<mpts_1.size();++k)
{
if(outlierMask_.at(k))
{
inliers_.insert(indexesA_[k], indexesB_[k]);
}
else
{
outliers_.insert(indexesA_[k], indexesB_[k]);
}
}
// ignore homography when all features are inliers
if(inliers_.size() == (int)outlierMask_.size() && !h_.empty())
{
if(Settings::getHomography_ignoreWhenAllInliers() || cv::countNonZero(h_) < 1)
{
h_ = cv::Mat();
}
}
}
//UINFO("Homography Object %d time=%d ms", objectIndex_, time.elapsed());
}
private:
const QMultiMap<int, int> * matches_;
int objectId_;
const std::vector<cv::KeyPoint> * kptsA_;
const std::vector<cv::KeyPoint> * kptsB_;
std::vector<int> indexesA_;
std::vector<int> indexesB_;
std::vector<uchar> outlierMask_;
QMultiMap<int, int> inliers_;
QMultiMap<int, int> outliers_;
cv::Mat h_;
};
void FindObject::detect(const cv::Mat & image)
{
QMultiMap<int,QPair<QRect,QTransform> > objects;
this->detect(image, objects);
if(objects.size() > 0 || Settings::getGeneral_sendNoObjDetectedEvents())
{
Q_EMIT objectsFound(objects);
}
if(objects.size() > 1)
{
UINFO("(%s) %d objects detected!",
QTime::currentTime().toString("HH:mm:ss.zzz").toStdString().c_str(),
(int)objects.size());
}
else if(objects.size() == 1)
{
UINFO("(%s) Object %d detected!",
QTime::currentTime().toString("HH:mm:ss.zzz").toStdString().c_str(),
(int)objects.begin().key());
}
else if(Settings::getGeneral_sendNoObjDetectedEvents())
{
UINFO("(%s) No objects detected.",
QTime::currentTime().toString("HH:mm:ss.zzz").toStdString().c_str());
}
}
bool FindObject::detect(const cv::Mat & image, QMultiMap<int,QPair<QRect,QTransform> > & objectsDetected)
{
QTime totalTime;
totalTime.start();
// reset statistics
timeStamps_.clear();
sceneKeypoints_.clear();
sceneDescriptors_ = cv::Mat();
sceneWords_.clear();
matches_.clear();
inliers_.clear();
outliers_.clear();
minMatchedDistance_ = -1.0f;
maxMatchedDistance_ = -1.0f;
bool success = false;
if(!image.empty())
{
//Convert to grayscale
cv::Mat grayscaleImg;
if(image.channels() != 1 || image.depth() != CV_8U)
{
cv::cvtColor(image, grayscaleImg, cv::COLOR_BGR2GRAY);
}
else
{
grayscaleImg = image;
}
QTime time;
time.start();
// EXTRACT KEYPOINTS
detector_->detect(grayscaleImg, sceneKeypoints_);
timeStamps_.insert(kTimeKeypointDetection, time.restart());
if(sceneKeypoints_.size())
{
int maxFeatures = Settings::getFeature2D_3MaxFeatures();
if(maxFeatures > 0 && (int)sceneKeypoints_.size() > maxFeatures)
{
sceneKeypoints_ = limitKeypoints(sceneKeypoints_, maxFeatures);
}
// EXTRACT DESCRIPTORS
extractor_->compute(grayscaleImg, sceneKeypoints_, sceneDescriptors_);
if((int)sceneKeypoints_.size() != sceneDescriptors_.rows)
{
UERROR("kpt=%d != descriptors=%d\n", (int)sceneKeypoints_.size(), sceneDescriptors_.rows);
}
}
else
{
UWARN("no features detected !?!\n");
}
timeStamps_.insert(kTimeDescriptorExtraction, time.restart());
bool consistentNNData = (vocabulary_->size()!=0 && vocabulary_->wordToObjects().begin().value()!=-1 && Settings::getGeneral_invertedSearch()) ||
((vocabulary_->size()==0 || vocabulary_->wordToObjects().begin().value()==-1) && !Settings::getGeneral_invertedSearch());
// COMPARE
if(!objectsDescriptors_.empty() &&
sceneKeypoints_.size() &&
consistentNNData &&
objectsDescriptors_.begin().value().cols == sceneDescriptors_.cols &&
objectsDescriptors_.begin().value().type() == sceneDescriptors_.type()) // binary descriptor issue, if the dataTree is not yet updated with modified settings
{
success = true;
QMultiMap<int, int> words;
if(!Settings::getGeneral_invertedSearch())
{
// CREATE INDEX for the scene
vocabulary_->clear();
words = vocabulary_->addWords(sceneDescriptors_, -1, Settings::getGeneral_vocabularyIncremental());
if(!Settings::getGeneral_vocabularyIncremental())
{
vocabulary_->update();
}
timeStamps_.insert(kTimeIndexing, time.restart());
}
for(QMap<int, ObjSignature*>::iterator iter=objects_.begin(); iter!=objects_.end(); ++iter)
{
matches_.insert(iter.key(), QMultiMap<int, int>());
}
if(Settings::getGeneral_invertedSearch() || Settings::getGeneral_threads() == 1)
{
cv::Mat results;
cv::Mat dists;
// DO NEAREST NEIGHBOR
int k = Settings::getNearestNeighbor_3nndrRatioUsed()?2:1;
if(!Settings::getGeneral_invertedSearch())
{
//match objects to scene
results = cv::Mat(objectsDescriptors_.begin().value().rows, k, CV_32SC1); // results index
dists = cv::Mat(objectsDescriptors_.begin().value().rows, k, CV_32FC1); // Distance results are CV_32FC1
vocabulary_->search(objectsDescriptors_.begin().value(), results, dists, k);
}
else
{
//match scene to objects
results = cv::Mat(sceneDescriptors_.rows, k, CV_32SC1); // results index
dists = cv::Mat(sceneDescriptors_.rows, k, CV_32FC1); // Distance results are CV_32FC1
vocabulary_->search(sceneDescriptors_, results, dists, k);
}
// PROCESS RESULTS
// Get all matches for each object
for(int i=0; i<dists.rows; ++i)
{
// Check if this descriptor matches with those of the objects
bool matched = false;
if(Settings::getNearestNeighbor_3nndrRatioUsed() &&
dists.at<float>(i,0) <= Settings::getNearestNeighbor_4nndrRatio() * dists.at<float>(i,1))
{
matched = true;
}
if((matched || !Settings::getNearestNeighbor_3nndrRatioUsed()) &&
Settings::getNearestNeighbor_5minDistanceUsed())
{
if(dists.at<float>(i,0) <= Settings::getNearestNeighbor_6minDistance())
{
matched = true;
}
else
{
matched = false;
}
}
if(!matched && !Settings::getNearestNeighbor_3nndrRatioUsed() && !Settings::getNearestNeighbor_5minDistanceUsed())
{
matched = true; // no criterion, match to the nearest descriptor
}
if(minMatchedDistance_ == -1 || minMatchedDistance_ > dists.at<float>(i,0))
{
minMatchedDistance_ = dists.at<float>(i,0);
}
if(maxMatchedDistance_ == -1 || maxMatchedDistance_ < dists.at<float>(i,0))
{
maxMatchedDistance_ = dists.at<float>(i,0);
}
if(matched)
{
if(Settings::getGeneral_invertedSearch())
{
int wordId = results.at<int>(i,0);
QList<int> objIds = vocabulary_->wordToObjects().values(wordId);
for(int j=0; j<objIds.size(); ++j)
{
// just add unique matches
if(vocabulary_->wordToObjects().count(wordId, objIds[j]) == 1)
{
matches_.find(objIds[j]).value().insert(objects_.value(objIds[j])->words().value(wordId), i);
}
}
}
else
{
QMap<int, int>::iterator iter = dataRange_.lowerBound(i);
int objectId = iter.value();
int fisrtObjectDescriptorIndex = (iter == dataRange_.begin())?0:(--iter).key()+1;
int objectDescriptorIndex = i - fisrtObjectDescriptorIndex;
int wordId = results.at<int>(i,0);
if(words.count(wordId) == 1)
{
matches_.find(objectId).value().insert(objectDescriptorIndex, words.value(wordId));
}
}
}
}
}
else
{
//multi-threaded, match objects to scene
int threadCounts = Settings::getGeneral_threads();
if(threadCounts == 0)
{
threadCounts = (int)objectsDescriptors_.size();
}
QList<int> objectsDescriptorsId = objectsDescriptors_.keys();
QList<cv::Mat> objectsDescriptorsMat = objectsDescriptors_.values();
for(int j=0; j<objectsDescriptorsMat.size(); j+=threadCounts)
{
QVector<SearchThread*> threads;
for(int k=j; k<j+threadCounts && k<objectsDescriptorsMat.size(); ++k)
{
threads.push_back(new SearchThread(vocabulary_, objectsDescriptorsId[k], &objectsDescriptorsMat[k], &words));
threads.back()->start();
}
for(int k=0; k<threads.size(); ++k)
{
threads[k]->wait();
matches_[threads[k]->getObjectId()] = threads[k]->getMatches();
if(minMatchedDistance_ == -1 || minMatchedDistance_ > threads[k]->getMinMatchedDistance())
{
minMatchedDistance_ = threads[k]->getMinMatchedDistance();
}
if(maxMatchedDistance_ == -1 || maxMatchedDistance_ < threads[k]->getMaxMatchedDistance())
{
maxMatchedDistance_ = threads[k]->getMaxMatchedDistance();
}
delete threads[k];
}
}
}
timeStamps_.insert(kTimeMatching, time.restart());
// Homographies
if(Settings::getHomography_homographyComputed())
{
// HOMOGRAPHY
int threadCounts = Settings::getGeneral_threads();
if(threadCounts == 0)
{
threadCounts = matches_.size();
}
QList<int> matchesId = matches_.keys();
QList<QMultiMap<int, int> > matchesList = matches_.values();
for(int i=0; i<matchesList.size(); i+=threadCounts)
{
QVector<HomographyThread*> threads;
for(int k=i; k<i+threadCounts && k<matchesList.size(); ++k)
{
int objectId = matchesId[k];
threads.push_back(new HomographyThread(&matchesList[k], objectId, &objects_.value(objectId)->keypoints(), &sceneKeypoints_));
threads.back()->start();
}
for(int j=0; j<threads.size(); ++j)
{
threads[j]->wait();
int id = threads[j]->getObjectId();
if(!threads[j]->getHomography().empty())
{
if(threads[j]->getInliers().size() >= Settings::getHomography_minimumInliers())
{
const cv::Mat & H = threads[j]->getHomography();
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));
int distance = Settings::getGeneral_multiDetectionRadius(); // in pixels
if(Settings::getGeneral_multiDetection())
{
// Get the outliers and recompute homography with them
matchesList.push_back(threads[j]->getOutliers());
matchesId.push_back(id);
// compute distance from previous added same objects...
QMultiMap<int, QPair<QRect, QTransform> >::iterator objIter = objectsDetected.find(id);
for(;objIter!=objectsDetected.end() && objIter.key() == id; ++objIter)
{
qreal dx = objIter.value().second.m31() - hTransform.m31();
qreal dy = objIter.value().second.m32() - hTransform.m32();
int d = (int)sqrt(dx*dx + dy*dy);
if(d < distance)
{
distance = d;
}
}
}
if(distance >= Settings::getGeneral_multiDetectionRadius())
{
QRect rect = objects_.value(id)->rect();
objectsDetected.insert(id, QPair<QRect, QTransform>(rect, hTransform));
inliers_.insert(id, threads[j]->getInliers());
outliers_.insert(id, threads[j]->getOutliers());
}
else
{
rejectedInliers_.insert(id, threads[j]->getInliers());
rejectedOutliers_.insert(id, threads[j]->getOutliers());
}
}
else
{
rejectedInliers_.insert(id, threads[j]->getInliers());
rejectedOutliers_.insert(id, threads[j]->getOutliers());
}
}
else
{
rejectedInliers_.insert(id, threads[j]->getInliers());
rejectedOutliers_.insert(id, threads[j]->getOutliers());
}
}
}
timeStamps_.insert(kTimeHomography, time.restart());
}
}
else if(!objectsDescriptors_.empty() && sceneKeypoints_.size())
{
UWARN("Cannot search, objects must be updated");
}
}
timeStamps_.insert(kTimeTotal, totalTime.elapsed());
return success;
}

96
src/FindObject.h Normal file
View File

@ -0,0 +1,96 @@
/*
* FindObject.h
*
* Created on: 2014-07-30
* Author: mathieu
*/
#ifndef FINDOBJECT_H_
#define FINDOBJECT_H_
#include <QtCore/QObject>
#include <QtCore/QString>
#include <QtCore/QMap>
#include <QtCore/QMultiMap>
#include <QtCore/QPair>
#include <QtCore/QVector>
#include <QtGui/QTransform>
#include <QtCore/QRect>
#include <opencv2/opencv.hpp>
#include <vector>
class ObjSignature;
class Vocabulary;
class KeypointDetector;
class DescriptorExtractor;
class FindObject : public QObject
{
Q_OBJECT;
public:
enum TimeStamp{kTimeKeypointDetection, kTimeDescriptorExtraction, kTimeIndexing, kTimeMatching, kTimeHomography, kTimeTotal};
public:
FindObject(QObject * parent = 0);
virtual ~FindObject();
int loadObjects(const QString & dirPath); // call updateObjects()
const ObjSignature * addObject(const QString & filePath);
const ObjSignature * addObject(const cv::Mat & image, int id=0);
bool addObject(ObjSignature * obj); // take ownership when true is returned
void removeObject(int id);
void removeAllObjects();
bool detect(const cv::Mat & image, QMultiMap<int,QPair<QRect,QTransform> > & objectsDetected);
void updateDetectorExtractor();
void updateObjects();
void updateVocabulary();
const QMap<int, ObjSignature*> & objects() const {return objects_;}
const Vocabulary * vocabulary() const {return vocabulary_;}
const QMap<TimeStamp, float> & timeStamps() const {return timeStamps_;}
const std::vector<cv::KeyPoint> & sceneKeypoints() const {return sceneKeypoints_;}
const cv::Mat & sceneDescriptors() const {return sceneDescriptors_;}
const QMultiMap<int, int> & sceneWords() const {return sceneWords_;}
const QMap<int, QMultiMap<int, int> > & matches() const {return matches_;}
const QMultiMap<int, QMultiMap<int, int> > & inliers() const {return inliers_;}
const QMultiMap<int, QMultiMap<int, int> > & outliers() const {return outliers_;}
const QMultiMap<int, QMultiMap<int, int> > & rejectedInliers() const {return rejectedInliers_;}
const QMultiMap<int, QMultiMap<int, int> > & rejectedOutliers() const {return rejectedOutliers_;}
float minMatchedDistance() const {return minMatchedDistance_;}
float maxMatchedDistance() const {return maxMatchedDistance_;}
public Q_SLOTS:
void detect(const cv::Mat & image);
Q_SIGNALS:
void objectsFound(const QMultiMap<int, QPair<QRect, QTransform> > &);
private:
void clearVocabulary();
private:
QMap<int, ObjSignature*> objects_;
Vocabulary * vocabulary_;
QMap<int, cv::Mat> objectsDescriptors_;
QMap<int, int> dataRange_; // <last id of object's descriptor, id>
KeypointDetector * detector_;
DescriptorExtractor * extractor_;
QMap<TimeStamp, float> timeStamps_;
std::vector<cv::KeyPoint> sceneKeypoints_;
cv::Mat sceneDescriptors_;
QMultiMap<int, int> sceneWords_;
QMap<int, QMultiMap<int, int> > matches_; // ObjectID Map< ObjectDescriptorIndex, SceneDescriptorIndex >, match the number of objects
QMultiMap<int, QMultiMap<int, int> > inliers_; // ObjectID Map< ObjectDescriptorIndex, SceneDescriptorIndex >, match the number of detected objects
QMultiMap<int, QMultiMap<int, int> > outliers_; // ObjectID Map< ObjectDescriptorIndex, SceneDescriptorIndex >, match the number of detected objects
QMultiMap<int, QMultiMap<int, int> > rejectedInliers_; // ObjectID Map< ObjectDescriptorIndex, SceneDescriptorIndex >
QMultiMap<int, QMultiMap<int, int> > rejectedOutliers_; // ObjectID Map< ObjectDescriptorIndex, SceneDescriptorIndex >
float minMatchedDistance_;
float maxMatchedDistance_;
};
#endif /* FINDOBJECT_H_ */

File diff suppressed because it is too large Load Diff

View File

@ -24,6 +24,7 @@ class TcpServer;
class KeypointDetector; class KeypointDetector;
class DescriptorExtractor; class DescriptorExtractor;
class Vocabulary; class Vocabulary;
class FindObject;
namespace rtabmap namespace rtabmap
{ {
@ -35,15 +36,9 @@ class MainWindow : public QMainWindow
Q_OBJECT Q_OBJECT
public: public:
MainWindow(Camera * camera = 0, const QString & settings = "", QWidget * parent = 0); MainWindow(FindObject * findObject, Camera * camera = 0, QWidget * parent = 0);
virtual ~MainWindow(); virtual ~MainWindow();
bool loadSettings(const QString & path);
bool saveSettings(const QString & path);
int loadObjects(const QString & dirPath);
void saveObjects(const QString & dirPath);
void setSourceImageText(const QString & text); void setSourceImageText(const QString & text);
protected: protected:
@ -70,7 +65,7 @@ private Q_SLOTS:
void updateObjectsSize(); void updateObjectsSize();
void updateMirrorView(); void updateMirrorView();
void showHideControls(); void showHideControls();
void update(const cv::Mat & image); void update(const cv::Mat & image = cv::Mat());
void updateObjects(); void updateObjects();
void notifyParametersChanged(const QStringList & param); void notifyParametersChanged(const QStringList & param);
void moveCameraFrame(int frame); void moveCameraFrame(int frame);
@ -80,32 +75,32 @@ Q_SIGNALS:
void objectsFound(const QMultiMap<int, QPair<QRect, QTransform> > &); void objectsFound(const QMultiMap<int, QPair<QRect, QTransform> > &);
private: private:
bool loadSettings(const QString & path);
bool saveSettings(const QString & path);
int loadObjects(const QString & dirPath);
int saveObjects(const QString & dirPath);
void setupTCPServer(); void setupTCPServer();
void addObjectFromFile(const QString & filePath); bool addObjectFromFile(const QString & filePath);
void showObject(ObjWidget * obj); void showObject(ObjWidget * obj);
void updateData();
void updateObjectSize(ObjWidget * obj); void updateObjectSize(ObjWidget * obj);
void updateVocabulary();
private: private:
Ui_mainWindow * ui_; Ui_mainWindow * ui_;
Camera * camera_; Camera * camera_;
QString settings_; FindObject * findObject_;
rtabmap::PdfPlotCurve * likelihoodCurve_; rtabmap::PdfPlotCurve * likelihoodCurve_;
rtabmap::PdfPlotCurve * inliersCurve_; rtabmap::PdfPlotCurve * inliersCurve_;
AboutDialog * aboutDialog_; AboutDialog * aboutDialog_;
QList<ObjWidget*> objects_; QMap<int, ObjWidget*> objWidgets_;
std::vector<cv::Mat> objectsDescriptors_;
Vocabulary * vocabulary_;
QMap<int, int> dataRange_; // <last id of object's descriptor, id>
QTime updateRate_; QTime updateRate_;
QTime refreshStartTime_; QTime refreshStartTime_;
int lowestRefreshRate_; int lowestRefreshRate_;
bool objectsModified_; bool objectsModified_;
QMap<int, QByteArray> imagesMap_; QMap<int, QByteArray> imagesMap_;
TcpServer * tcpServer_;
QMap<QString, QVariant> lastObjectsUpdateParameters_; // ParametersMap QMap<QString, QVariant> lastObjectsUpdateParameters_; // ParametersMap
KeypointDetector * detector_; TcpServer * tcpServer_;
DescriptorExtractor * extractor_; cv::Mat sceneImage_;
}; };
#endif /* MainWindow_H_ */ #endif /* MainWindow_H_ */

57
src/ObjSignature.h Normal file
View File

@ -0,0 +1,57 @@
/*
* ObjSignature.h
*
* Created on: 2014-07-30
* Author: mathieu
*/
#ifndef OBJSIGNATURE_H_
#define OBJSIGNATURE_H_
#include <opencv2/opencv.hpp>
#include <QtCore/QString>
#include <QtCore/QMultiMap>
#include <QtCore/QRect>
class ObjSignature {
public:
ObjSignature(int id, const cv::Mat & image) :
id_(id),
image_(image)
{}
virtual ~ObjSignature() {}
void setData(const std::vector<cv::KeyPoint> & keypoints,
const cv::Mat & descriptors,
const QString & detectorType,
const QString & descriptorType)
{
keypoints_ = keypoints;
descriptors_ = descriptors;
detectorType_ = detectorType;
descriptorType_ = descriptorType;
}
void setWords(const QMultiMap<int, int> & words) {words_ = words;}
void setId(int id) {id_ = id;}
QRect rect() const {return QRect(0,0,image_.cols, image_.rows);}
int id() const {return id_;}
const cv::Mat & image() const {return image_;}
const std::vector<cv::KeyPoint> & keypoints() const {return keypoints_;}
const cv::Mat & descriptors() const {return descriptors_;}
const QMultiMap<int, int> & words() const {return words_;}
const QString & detectorType() const {return detectorType_;}
const QString & descriptorType() const {return descriptorType_;}
private:
int id_;
cv::Mat image_;
std::vector<cv::KeyPoint> keypoints_;
cv::Mat descriptors_;
QMultiMap<int, int> words_; // <word id, keypoint indexes>
QString detectorType_;
QString descriptorType_;
};
#endif /* OBJSIGNATURE_H_ */

View File

@ -6,6 +6,7 @@
#include "KeypointItem.h" #include "KeypointItem.h"
#include "QtOpenCV.h" #include "QtOpenCV.h"
#include "Settings.h" #include "Settings.h"
#include "utilite/ULogger.h"
#include <opencv2/highgui/highgui.hpp> #include <opencv2/highgui/highgui.hpp>
@ -29,32 +30,22 @@
ObjWidget::ObjWidget(QWidget * parent) : ObjWidget::ObjWidget(QWidget * parent) :
QWidget(parent), QWidget(parent),
graphicsView_(0),
id_(0), id_(0),
detectorType_("NA"), graphicsView_(0),
descriptorType_("NA"),
graphicsViewInitialized_(false), graphicsViewInitialized_(false),
alpha_(100) alpha_(100)
{ {
setupUi(); setupUi();
} }
ObjWidget::ObjWidget(int id, ObjWidget::ObjWidget(int id, const std::vector<cv::KeyPoint> & keypoints, const QImage & image, QWidget * parent) :
const std::vector<cv::KeyPoint> & keypoints,
const cv::Mat & descriptors,
const cv::Mat & image,
const QString & detectorType,
const QString & descriptorType,
QWidget * parent) :
QWidget(parent), QWidget(parent),
graphicsView_(0),
id_(id), id_(id),
detectorType_("NA"), graphicsView_(0),
descriptorType_("NA"),
graphicsViewInitialized_(false), graphicsViewInitialized_(false),
alpha_(100) alpha_(100)
{ {
setupUi(); setupUi();
this->setData(keypoints, descriptors, image, detectorType, descriptorType); this->setData(keypoints, image);
} }
ObjWidget::~ObjWidget() ObjWidget::~ObjWidget()
{ {
@ -240,38 +231,24 @@ void ObjWidget::setTextLabel(const QString & text)
label_->setText(text); label_->setText(text);
} }
void ObjWidget::setData(const std::vector<cv::KeyPoint> & keypoints, void ObjWidget::setData(const std::vector<cv::KeyPoint> & keypoints, const QImage & image)
const cv::Mat & descriptors,
const cv::Mat & image,
const QString & detectorType,
const QString & descriptorType)
{ {
keypoints_ = keypoints; keypoints_ = keypoints;
descriptors_ = descriptors;
kptColors_ = QVector<QColor>((int)keypoints.size(), defaultColor()); kptColors_ = QVector<QColor>((int)keypoints.size(), defaultColor());
keypointItems_.clear(); keypointItems_.clear();
rectItems_.clear(); rectItems_.clear();
graphicsView_->scene()->clear(); graphicsView_->scene()->clear();
graphicsViewInitialized_ = false; graphicsViewInitialized_ = false;
detectorType_ = detectorType;
descriptorType_ = descriptorType;
mouseCurrentPos_ = mousePressedPos_; // this will reset roi selection mouseCurrentPos_ = mousePressedPos_; // this will reset roi selection
cvImage_ = image.clone(); pixmap_ = QPixmap::fromImage(image);
pixmap_ = QPixmap::fromImage(cvtCvMat2QImage(cvImage_));
//this->setMinimumSize(image_.size()); //this->setMinimumSize(image_.size());
if(graphicsViewMode_->isChecked()) if(graphicsViewMode_->isChecked())
{ {
this->setupGraphicsView(); this->setupGraphicsView();
} }
label_->setVisible(image.empty()); label_->setVisible(image.isNull());
}
void ObjWidget::setWords(const QMultiMap<int, int> & words)
{
Q_ASSERT(words.size() == keypoints_.size());
words_ = words;
} }
void ObjWidget::resetKptsColor() void ObjWidget::resetKptsColor()
@ -296,7 +273,7 @@ void ObjWidget::setKptColor(int index, const QColor & color)
} }
else else
{ {
printf("PROBLEM index =%d > size=%d\n", index, kptColors_.size()); UWARN("PROBLEM index =%d > size=%d\n", index, kptColors_.size());
} }
if(graphicsViewMode_->isChecked()) if(graphicsViewMode_->isChecked())
@ -381,64 +358,6 @@ void ObjWidget::setFeaturesShown(bool shown)
} }
} }
void ObjWidget::save(QDataStream & streamPtr) const
{
streamPtr << id_ << detectorType_ << descriptorType_;
streamPtr << (int)keypoints_.size();
for(unsigned 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 << pixmap_;
}
void ObjWidget::load(QDataStream & streamPtr)
{
std::vector<cv::KeyPoint> kpts;
cv::Mat descriptors;
int nKpts;
QString detectorType, descriptorType;
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 >> pixmap_;
this->setData(kpts, descriptors, cv::Mat(), detectorType, descriptorType);
cvImage_ = cvtQImage2CvMat(pixmap_.toImage());
//this->setMinimumSize(image_.size());
}
void ObjWidget::computeScaleOffsets(float & scale, float & offsetX, float & offsetY) void ObjWidget::computeScaleOffsets(float & scale, float & offsetX, float & offsetY)
{ {
scale = 1.0f; scale = 1.0f;
@ -598,7 +517,7 @@ void ObjWidget::mouseReleaseEvent(QMouseEvent * event)
right = qAbs(l - pixmap_.width()); right = qAbs(l - pixmap_.width());
} }
Q_EMIT roiChanged(QRect(left, top, right-left, bottom-top)); Q_EMIT roiChanged(cv::Rect(left, top, right-left, bottom-top));
} }
QWidget::mouseReleaseEvent(event); QWidget::mouseReleaseEvent(event);
} }

View File

@ -25,22 +25,11 @@ class ObjWidget : public QWidget
public: public:
ObjWidget(QWidget * parent = 0); ObjWidget(QWidget * parent = 0);
ObjWidget(int id, ObjWidget(int id, const std::vector<cv::KeyPoint> & keypoints, const QImage & image, QWidget * parent = 0);
const std::vector<cv::KeyPoint> & keypoints,
const cv::Mat & descriptors,
const cv::Mat & image,
const QString & detectorType = "NA",
const QString & descriptorType = "NA",
QWidget * parent = 0);
virtual ~ObjWidget(); virtual ~ObjWidget();
void setId(int id); void setId(int id);
void setData(const std::vector<cv::KeyPoint> & keypoints, void setData(const std::vector<cv::KeyPoint> & keypoints, const QImage & image);
const cv::Mat & descriptors,
const cv::Mat & image,
const QString & detectorType,
const QString & descriptorType);
void setWords(const QMultiMap<int, int> & words);
void setTextLabel(const QString & text); void setTextLabel(const QString & text);
void resetKptsColor(); void resetKptsColor();
void setKptColor(int index, const QColor & color); void setKptColor(int index, const QColor & color);
@ -55,12 +44,9 @@ public:
void addRect(QGraphicsRectItem * rect); void addRect(QGraphicsRectItem * rect);
void clearRoiSelection() {mousePressedPos_ = mouseCurrentPos_ = QPoint();update();} void clearRoiSelection() {mousePressedPos_ = mouseCurrentPos_ = QPoint();update();}
const QMultiMap<int, int> & words() const {return words_;}
const std::vector<cv::KeyPoint> & keypoints() const {return keypoints_;}
const cv::Mat & descriptors() const {return descriptors_;}
const QPixmap & pixmap() const {return pixmap_;}
const cv::Mat & cvImage() const {return cvImage_;}
int id() const {return id_;} int id() const {return id_;}
const std::vector<cv::KeyPoint> keypoints() const {return keypoints_;}
const QPixmap & pixmap() const {return pixmap_;}
QColor defaultColor() const; QColor defaultColor() const;
bool isImageShown() const; bool isImageShown() const;
bool isFeaturesShown() const; bool isFeaturesShown() const;
@ -68,15 +54,10 @@ public:
bool isMirrorView() const; bool isMirrorView() const;
//QGraphicsScene * scene() const; //QGraphicsScene * scene() const;
std::vector<cv::KeyPoint> selectedKeypoints() const; std::vector<cv::KeyPoint> selectedKeypoints() const;
const QString & detectorType() const {return detectorType_;}
const QString & descriptorType() const {return descriptorType_;}
QList<QGraphicsItem*> selectedItems() const; QList<QGraphicsItem*> selectedItems() const;
QPixmap getSceneAsPixmap(); QPixmap getSceneAsPixmap();
void save(QDataStream & streamPtr) const;
void load(QDataStream & streamPtr);
protected: protected:
virtual void paintEvent(QPaintEvent *event); virtual void paintEvent(QPaintEvent *event);
virtual void contextMenuEvent(QContextMenuEvent * event); virtual void contextMenuEvent(QContextMenuEvent * event);
@ -88,7 +69,7 @@ protected:
Q_SIGNALS: Q_SIGNALS:
void removalTriggered(ObjWidget *); void removalTriggered(ObjWidget *);
void selectionChanged(); void selectionChanged();
void roiChanged(const QRect &); void roiChanged(const cv::Rect &);
private: private:
void setupGraphicsView(); void setupGraphicsView();
@ -98,17 +79,12 @@ private:
void computeScaleOffsets(float & scale, float & offsetX, float & offsetY); void computeScaleOffsets(float & scale, float & offsetX, float & offsetY);
private: private:
int id_;
std::vector<cv::KeyPoint> keypoints_; std::vector<cv::KeyPoint> keypoints_;
cv::Mat descriptors_;
QMultiMap<int, int> words_; // <word id, keypoint indexes>
QPixmap pixmap_; QPixmap pixmap_;
cv::Mat cvImage_;
QList<KeypointItem*> keypointItems_; QList<KeypointItem*> keypointItems_;
QGraphicsView * graphicsView_; QGraphicsView * graphicsView_;
int id_;
QVector<QColor> kptColors_; QVector<QColor> kptColors_;
QString detectorType_;
QString descriptorType_;
QList<QGraphicsRectItem*> rectItems_; QList<QGraphicsRectItem*> rectItems_;
bool graphicsViewInitialized_; bool graphicsViewInitialized_;
int alpha_; int alpha_;

View File

@ -6,25 +6,46 @@
#include <opencv2/core/core_c.h> #include <opencv2/core/core_c.h>
#include <stdio.h> #include <stdio.h>
QImage cvtCvMat2QImage(const cv::Mat & image) QImage cvtCvMat2QImage(const cv::Mat & image, bool isBgr)
{ {
QImage qtemp; QImage qtemp;
if(!image.empty() && image.depth() == CV_8U) if(!image.empty() && image.depth() == CV_8U)
{ {
const unsigned char * data = image.data; if(image.channels()==3)
qtemp = QImage(image.cols, image.rows, QImage::Format_RGB32);
for(int y = 0; y < image.rows; ++y, data += image.cols*image.elemSize())
{ {
for(int x = 0; x < image.cols; ++x) const unsigned char * data = image.data;
if(image.channels() == 3)
{ {
QRgb * p = ((QRgb*)qtemp.scanLine (y)) + x; qtemp = QImage(image.cols, image.rows, QImage::Format_RGB32);
*p = qRgb(data[x * image.channels()+2], data[x * image.channels()+1], data[x * image.channels()]); for(int y = 0; y < image.rows; ++y, data += image.cols*image.elemSize())
{
for(int x = 0; x < image.cols; ++x)
{
QRgb * p = ((QRgb*)qtemp.scanLine (y)) + x;
if(isBgr)
{
*p = qRgb(data[x * image.channels()+2], data[x * image.channels()+1], data[x * image.channels()]);
}
else
{
*p = qRgb(data[x * image.channels()], data[x * image.channels()+1], data[x * image.channels()+2]);
}
}
}
} }
} }
} else if(image.channels() == 1)
else if(!image.empty() && image.depth() != CV_8U) {
{ // mono grayscale
printf("Wrong image format, must be 8_bits\n"); qtemp = QImage(image.data, image.cols, image.rows, image.cols, QImage::Format_Indexed8).copy();
QVector<QRgb> my_table;
for(int i = 0; i < 256; i++) my_table.push_back(qRgb(i,i,i));
qtemp.setColorTable(my_table);
}
else
{
printf("Wrong image format, must have 1 or 3 channels\n");
}
} }
return qtemp; return qtemp;
} }

View File

@ -9,7 +9,7 @@
#include <opencv2/core/core.hpp> #include <opencv2/core/core.hpp>
// Convert OpenCV matrix to QImage // Convert OpenCV matrix to QImage
QImage cvtCvMat2QImage(const cv::Mat & image); QImage cvtCvMat2QImage(const cv::Mat & image, bool isBgr = true);
// Convert QImage to OpenCV matrix // Convert QImage to OpenCV matrix
cv::Mat cvtQImage2CvMat(const QImage & image); cv::Mat cvtQImage2CvMat(const QImage & image);

View File

@ -4,6 +4,7 @@
#include "Settings.h" #include "Settings.h"
#include "Camera.h" #include "Camera.h"
#include "utilite/ULogger.h"
#include <QtCore/QSettings> #include <QtCore/QSettings>
#include <QtCore/QStringList> #include <QtCore/QStringList>
#include <QtCore/QDir> #include <QtCore/QDir>
@ -20,6 +21,7 @@ ParametersMap Settings::parameters_;
ParametersType Settings::parametersType_; ParametersType Settings::parametersType_;
DescriptionsMap Settings::descriptions_; DescriptionsMap Settings::descriptions_;
Settings Settings::dummyInit_; Settings Settings::dummyInit_;
QString Settings::iniPath_;
QString Settings::workingDirectory() QString Settings::workingDirectory()
{ {
@ -39,12 +41,31 @@ QString Settings::iniDefaultPath()
#endif #endif
} }
void Settings::loadSettings(const QString & fileName, QByteArray * windowGeometry, QByteArray * windowState) QString Settings::iniPath()
{
if(!iniPath_.isNull())
{
return iniPath_;
}
return iniDefaultPath();
}
void Settings::init(const QString & fileName)
{
iniPath_ = fileName;
if(fileName.isEmpty())
{
iniPath_ = iniDefaultPath();
}
loadSettings(iniPath_);
}
void Settings::loadSettings(const QString & fileName)
{ {
QString path = fileName; QString path = fileName;
if(fileName.isEmpty()) if(fileName.isEmpty())
{ {
path = iniDefaultPath(); path = iniPath();
} }
QSettings ini(path, QSettings::IniFormat); QSettings ini(path, QSettings::IniFormat);
for(ParametersMap::const_iterator iter = defaultParameters_.begin(); iter!=defaultParameters_.end(); ++iter) for(ParametersMap::const_iterator iter = defaultParameters_.begin(); iter!=defaultParameters_.end(); ++iter)
@ -62,38 +83,53 @@ void Settings::loadSettings(const QString & fileName, QByteArray * windowGeometr
str = getParameter(key).toString(); str = getParameter(key).toString();
str[0] = index.toAscii(); str[0] = index.toAscii();
value = QVariant(str); value = QVariant(str);
printf("Updated list of parameter \"%s\"\n", key.toStdString().c_str()); UINFO("Updated list of parameter \"%s\"", key.toStdString().c_str());
} }
setParameter(key, value); setParameter(key, value);
} }
} }
if(windowGeometry) if(cv::gpu::getCudaEnabledDeviceCount() == 0)
{ {
QVariant value = ini.value("windowGeometry", QVariant()); Settings::setFeature2D_SURF_gpu(false);
if(value.isValid()) Settings::setFeature2D_Fast_gpu(false);
{ Settings::setFeature2D_ORB_gpu(false);
*windowGeometry = value.toByteArray();
}
}
if(windowState)
{
QVariant value = ini.value("windowState", QVariant());
if(value.isValid())
{
*windowState = value.toByteArray();
}
} }
printf("Settings loaded from %s\n", path.toStdString().c_str()); UINFO("Settings loaded from %s", path.toStdString().c_str());
} }
void Settings::saveSettings(const QString & fileName, const QByteArray & windowGeometry, const QByteArray & windowState) void Settings::loadWindowSettings(QByteArray & windowGeometry, QByteArray & windowState, const QString & fileName)
{ {
QString path = fileName; QString path = fileName;
if(fileName.isEmpty()) if(fileName.isEmpty())
{ {
path = iniDefaultPath(); path = iniPath();
}
QSettings ini(path, QSettings::IniFormat);
QVariant value = ini.value("windowGeometry", QVariant());
if(value.isValid())
{
windowGeometry = value.toByteArray();
}
value = ini.value("windowState", QVariant());
if(value.isValid())
{
windowState = value.toByteArray();
}
UINFO("Window settings loaded from %s", path.toStdString().c_str());
}
void Settings::saveSettings(const QString & fileName)
{
QString path = fileName;
if(fileName.isEmpty())
{
path = iniPath();
} }
QSettings ini(path, QSettings::IniFormat); QSettings ini(path, QSettings::IniFormat);
for(ParametersMap::const_iterator iter = parameters_.begin(); iter!=parameters_.end(); ++iter) for(ParametersMap::const_iterator iter = parameters_.begin(); iter!=parameters_.end(); ++iter)
@ -108,6 +144,17 @@ void Settings::saveSettings(const QString & fileName, const QByteArray & windowG
ini.setValue(iter.key(), iter.value()); ini.setValue(iter.key(), iter.value());
} }
} }
UINFO("Settings saved to %s", path.toStdString().c_str());
}
void Settings::saveWindowSettings(const QByteArray & windowGeometry, const QByteArray & windowState, const QString & fileName)
{
QString path = fileName;
if(fileName.isEmpty())
{
path = iniPath();
}
QSettings ini(path, QSettings::IniFormat);
if(!windowGeometry.isEmpty()) if(!windowGeometry.isEmpty())
{ {
ini.setValue("windowGeometry", windowGeometry); ini.setValue("windowGeometry", windowGeometry);
@ -116,7 +163,7 @@ void Settings::saveSettings(const QString & fileName, const QByteArray & windowG
{ {
ini.setValue("windowState", windowState); ini.setValue("windowState", windowState);
} }
printf("Settings saved to %s\n", path.toStdString().c_str()); UINFO("Window settings saved to %s", path.toStdString().c_str());
} }
class GPUFeature2D class GPUFeature2D
@ -161,7 +208,8 @@ public:
} }
catch(cv::Exception &e) catch(cv::Exception &e)
{ {
printf("GPUSURF error: %s \n(If something about layer_rows, parameter nOctaves=%d of SURF is too high for the size of the image (%d,%d).)\n", UERROR("GPUSURF error: %s \n(If something about layer_rows, parameter nOctaves=%d of SURF "
"is too high for the size of the image (%d,%d).)",
e.msg.c_str(), e.msg.c_str(),
surf_.nOctaves, surf_.nOctaves,
image.cols, image.cols,
@ -182,7 +230,8 @@ public:
} }
catch(cv::Exception &e) catch(cv::Exception &e)
{ {
printf("GPUSURF error: %s \n(If something about layer_rows, parameter nOctaves=%d of SURF is too high for the size of the image (%d,%d).)\n", UERROR("GPUSURF error: %s \n(If something about layer_rows, parameter nOctaves=%d of SURF "
"is too high for the size of the image (%d,%d).)",
e.msg.c_str(), e.msg.c_str(),
surf_.nOctaves, surf_.nOctaves,
image.cols, image.cols,
@ -226,7 +275,7 @@ protected:
std::vector<cv::KeyPoint>& keypoints, std::vector<cv::KeyPoint>& keypoints,
cv::Mat& descriptors) cv::Mat& descriptors)
{ {
printf("GPUFAST:computeDescriptors() Should not be used!\n"); UERROR("GPUFAST:computeDescriptors() Should not be used!");
} }
private: private:
@ -269,7 +318,7 @@ protected:
} }
catch(cv::Exception &e) catch(cv::Exception &e)
{ {
printf("GPUORB error: %s \n(If something about matrix size, the image/object may be too small (%d,%d).)\n", UERROR("GPUORB error: %s \n(If something about matrix size, the image/object may be too small (%d,%d).)",
e.msg.c_str(), e.msg.c_str(),
image.cols, image.cols,
image.rows); image.rows);
@ -289,7 +338,7 @@ protected:
} }
catch(cv::Exception &e) catch(cv::Exception &e)
{ {
printf("GPUORB error: %s \n(If something about matrix size, the image/object may be too small (%d,%d).)\n", UERROR("GPUORB error: %s \n(If something about matrix size, the image/object may be too small (%d,%d).)",
e.msg.c_str(), e.msg.c_str(),
image.cols, image.cols,
image.rows); image.rows);
@ -759,7 +808,7 @@ cv::flann::IndexParams * Settings::createFlannIndexParams()
} }
if(!params) if(!params)
{ {
printf("ERROR: NN strategy not found !? Using default KDTRee...\n"); UERROR("NN strategy not found !? Using default KDTRee...");
params = new cv::flann::KDTreeIndexParams(); params = new cv::flann::KDTreeIndexParams();
} }
return params ; return params ;

View File

@ -206,9 +206,14 @@ public:
static QString workingDirectory(); static QString workingDirectory();
static QString iniDefaultPath(); static QString iniDefaultPath();
static QString iniDefaultFileName() {return "config.ini";} static QString iniDefaultFileName() {return "config.ini";}
static QString iniPath();
static void loadSettings(const QString & fileName = QString(), QByteArray * windowGeometry = 0, QByteArray * windowState = 0); static void init(const QString & fileName = QString());
static void saveSettings(const QString & fileName = QString(), const QByteArray & windowGeometry = QByteArray(), const QByteArray & windowState = QByteArray());
static void loadSettings(const QString & fileName = QString());
static void loadWindowSettings(QByteArray & windowGeometry, QByteArray & windowState, const QString & fileName = QString());
static void saveSettings(const QString & fileName = QString());
static void saveWindowSettings(const QByteArray & windowGeometry, const QByteArray & windowState, const QString & fileName = QString());
static const ParametersMap & getDefaultParameters() {return defaultParameters_;} static const ParametersMap & getDefaultParameters() {return defaultParameters_;}
static const ParametersMap & getParameters() {return parameters_;} static const ParametersMap & getParameters() {return parameters_;}
@ -240,6 +245,7 @@ private:
static ParametersType parametersType_; static ParametersType parametersType_;
static DescriptionsMap descriptions_; static DescriptionsMap descriptions_;
static Settings dummyInit_; static Settings dummyInit_;
static QString iniPath_;
}; };
class KeypointDetector class KeypointDetector

View File

@ -6,6 +6,7 @@
*/ */
#include "TcpServer.h" #include "TcpServer.h"
#include "utilite/ULogger.h"
#include <QtNetwork/QNetworkInterface> #include <QtNetwork/QNetworkInterface>
#include <QtNetwork/QTcpSocket> #include <QtNetwork/QTcpSocket>
@ -16,7 +17,7 @@ TcpServer::TcpServer(quint16 port, QObject * parent) :
{ {
if (!this->listen(QHostAddress::Any, port)) if (!this->listen(QHostAddress::Any, port))
{ {
printf("ERROR: Unable to start the TCP server: %s\n", this->errorString().toStdString().c_str()); UERROR("Unable to start the TCP server: %s", this->errorString().toStdString().c_str());
return; return;
} }

View File

@ -22,10 +22,11 @@ public:
QHostAddress getHostAddress() const; QHostAddress getHostAddress() const;
quint16 getPort() const; quint16 getPort() const;
public Q_SLOTS:
void publishObjects(const QMultiMap<int, QPair<QRect, QTransform> > & objects);
private Q_SLOTS: private Q_SLOTS:
void addClient(); void addClient();
void publishObjects(const QMultiMap<int, QPair<QRect, QTransform> > & objects);
}; };
#endif /* TCPSERVER_H_ */ #endif /* TCPSERVER_H_ */

View File

@ -26,7 +26,7 @@ void Vocabulary::clear()
notIndexedWordIds_.clear(); notIndexedWordIds_.clear();
} }
QMultiMap<int, int> Vocabulary::addWords(const cv::Mat & descriptors, int objectIndex, bool incremental) QMultiMap<int, int> Vocabulary::addWords(const cv::Mat & descriptors, int objectId, bool incremental)
{ {
QMultiMap<int, int> words; QMultiMap<int, int> words;
if (descriptors.empty()) if (descriptors.empty())
@ -141,7 +141,7 @@ QMultiMap<int, int> Vocabulary::addWords(const cv::Mat & descriptors, int object
if(match) if(match)
{ {
words.insert(fullResults.begin().value(), i); words.insert(fullResults.begin().value(), i);
wordToObjects_.insert(fullResults.begin().value(), objectIndex); wordToObjects_.insert(fullResults.begin().value(), objectId);
++matches; ++matches;
} }
else else
@ -150,7 +150,7 @@ QMultiMap<int, int> Vocabulary::addWords(const cv::Mat & descriptors, int object
notIndexedWordIds_.push_back(indexedDescriptors_.rows + notIndexedDescriptors_.rows); notIndexedWordIds_.push_back(indexedDescriptors_.rows + notIndexedDescriptors_.rows);
notIndexedDescriptors_.push_back(descriptors.row(i)); notIndexedDescriptors_.push_back(descriptors.row(i));
words.insert(notIndexedWordIds_.back(), i); words.insert(notIndexedWordIds_.back(), i);
wordToObjects_.insert(notIndexedWordIds_.back(), objectIndex); wordToObjects_.insert(notIndexedWordIds_.back(), objectId);
} }
} }
} }
@ -158,7 +158,7 @@ QMultiMap<int, int> Vocabulary::addWords(const cv::Mat & descriptors, int object
{ {
for(int i = 0; i < descriptors.rows; ++i) for(int i = 0; i < descriptors.rows; ++i)
{ {
wordToObjects_.insert(indexedDescriptors_.rows + notIndexedDescriptors_.rows+i, objectIndex); wordToObjects_.insert(indexedDescriptors_.rows + notIndexedDescriptors_.rows+i, objectId);
words.insert(indexedDescriptors_.rows + notIndexedDescriptors_.rows+i, i); words.insert(indexedDescriptors_.rows + notIndexedDescriptors_.rows+i, i);
notIndexedWordIds_.push_back(indexedDescriptors_.rows + notIndexedDescriptors_.rows+i); notIndexedWordIds_.push_back(indexedDescriptors_.rows + notIndexedDescriptors_.rows+i);
} }

View File

@ -18,7 +18,7 @@ public:
virtual ~Vocabulary(); virtual ~Vocabulary();
void clear(); void clear();
QMultiMap<int, int> addWords(const cv::Mat & descriptors, int objectIndex, bool incremental); QMultiMap<int, int> addWords(const cv::Mat & descriptors, int objectId, bool incremental);
void update(); void update();
void search(const cv::Mat & descriptors, cv::Mat & results, cv::Mat & dists, int k); void search(const cv::Mat & descriptors, cv::Mat & results, cv::Mat & dists, int k);
int size() const {return indexedDescriptors_.rows + notIndexedDescriptors_.rows;} int size() const {return indexedDescriptors_.rows + notIndexedDescriptors_.rows;}
@ -28,7 +28,7 @@ private:
cv::flann::Index flannIndex_; cv::flann::Index flannIndex_;
cv::Mat indexedDescriptors_; cv::Mat indexedDescriptors_;
cv::Mat notIndexedDescriptors_; cv::Mat notIndexedDescriptors_;
QMultiMap<int, int> wordToObjects_; QMultiMap<int, int> wordToObjects_; // <wordId, ObjectId>
QVector<int> notIndexedWordIds_; QVector<int> notIndexedWordIds_;
}; };

View File

@ -119,7 +119,7 @@ void PdfPlotCurve::clear()
UPlotCurve::clear(); UPlotCurve::clear();
} }
void PdfPlotCurve::setData(const QMap<int, float> & dataMap, const QMap<int, int> & weightsMap) void PdfPlotCurve::setData(const QMap<int, int> & dataMap, const QMap<int, int> & weightsMap)
{ {
ULOGGER_DEBUG("dataMap=%d, weightsMap=%d", dataMap.size(), weightsMap.size()); ULOGGER_DEBUG("dataMap=%d, weightsMap=%d", dataMap.size(), weightsMap.size());
if(dataMap.size() > 0) if(dataMap.size() > 0)
@ -146,7 +146,7 @@ void PdfPlotCurve::setData(const QMap<int, float> & dataMap, const QMap<int, int
// update values // update values
QList<QGraphicsItem*>::iterator iter = _items.begin(); QList<QGraphicsItem*>::iterator iter = _items.begin();
QMap<int, int>::const_iterator j=weightsMap.begin(); QMap<int, int>::const_iterator j=weightsMap.begin();
for(QMap<int, float>::const_iterator i=dataMap.begin(); i!=dataMap.end(); ++i, ++j) for(QMap<int, int>::const_iterator i=dataMap.begin(); i!=dataMap.end(); ++i, ++j)
{ {
((PdfPlotItem*)*iter)->setLikelihood(i.key(), i.value(), j!=weightsMap.end()?j.value():-1); ((PdfPlotItem*)*iter)->setLikelihood(i.key(), i.value(), j!=weightsMap.end()?j.value():-1);
//2 times... //2 times...

View File

@ -58,7 +58,7 @@ public:
virtual ~PdfPlotCurve(); virtual ~PdfPlotCurve();
virtual void clear(); virtual void clear();
void setData(const QMap<int, float> & dataMap, const QMap<int, int> & weightsMap); void setData(const QMap<int, int> & dataMap, const QMap<int, int> & weightsMap);
private: private:
const QMap<int, QByteArray> * _imagesMapRef; const QMap<int, QByteArray> * _imagesMapRef;

77
src/utilite/UDestroyer.h Normal file
View File

@ -0,0 +1,77 @@
/*
* utilite is a cross-platform library with
* useful utilities for fast and small developing.
* Copyright (C) 2010 Mathieu Labbe
*
* utilite is free library: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* utilite is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef UDESTROYER_H
#define UDESTROYER_H
//#include "utilite/UtiLiteExp.h" // DLL export/import defines
/**
* This class is used to delete a dynamically created
* objects. It was mainly designed to remove dynamically created Singleton.
* Created on the stack of a Singleton, when the
* application is finished, his destructor make sure that the
* Singleton is deleted.
*
*/
template <class T>
class UDestroyer
{
public:
/**
* The constructor. Set the doomed object (take ownership of the object). The object is deleted
* when this object is deleted.
*/
UDestroyer(T* doomed = 0) : doomed_(doomed) {}
~UDestroyer()
{
if(doomed_)
{
delete doomed_;
doomed_ = 0;
}
}
/**
* Set the doomed object. If a doomed object is already set, the function returns false.
* @param doomed the doomed object
* @return false if an object is already set and the new object is not null, otherwise true
*/
bool setDoomed(T* doomed)
{
if(doomed_ && doomed)
{
return false;
}
doomed_ = doomed;
return true;
}
private:
// Prevent users from making copies of a
// Destroyer to avoid double deletion:
UDestroyer(const UDestroyer<T>&);
void operator=(const UDestroyer<T>&);
private:
T* doomed_;
};
#endif // UDESTROYER_H

590
src/utilite/ULogger.cpp Normal file
View File

@ -0,0 +1,590 @@
/*
* utilite is a cross-platform library with
* useful utilities for fast and small developing.
* Copyright (C) 2010 Mathieu Labbe
*
* utilite is free library: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* utilite is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "utilite/ULogger.h"
#include "utilite/UConversion.h"
#include "utilite/UFile.h"
#include "utilite/UStl.h"
#include <fstream>
#include <string>
#include <string.h>
#ifndef WIN32
#include <sys/time.h>
#endif
#ifdef WIN32
#include <Windows.h>
#define COLOR_NORMAL FOREGROUND_BLUE | FOREGROUND_GREEN | FOREGROUND_RED
#define COLOR_RED FOREGROUND_RED | FOREGROUND_INTENSITY
#define COLOR_GREEN FOREGROUND_GREEN
#define COLOR_YELLOW FOREGROUND_GREEN | FOREGROUND_RED
#else
#define COLOR_NORMAL "\033[0m"
#define COLOR_RED "\033[31m"
#define COLOR_GREEN "\033[32m"
#define COLOR_YELLOW "\033[33m"
#endif
bool ULogger::append_ = true;
bool ULogger::printTime_ = true;
bool ULogger::printLevel_ = true;
bool ULogger::printEndline_ = true;
bool ULogger::printColored_ = true;
bool ULogger::printWhere_ = true;
bool ULogger::printWhereFullPath_ = false;
bool ULogger::limitWhereLength_ = false;
bool ULogger::buffered_ = false;
bool ULogger::exitingState_ = false;
ULogger::Level ULogger::level_ = kInfo; // By default, we show all info msgs + upper level (Warning, Error)
ULogger::Level ULogger::exitLevel_ = kFatal;
ULogger::Level ULogger::eventLevel_ = kFatal;
const char * ULogger::levelName_[5] = {"DEBUG", " INFO", " WARN", "ERROR", "FATAL"};
ULogger* ULogger::instance_ = 0;
UDestroyer<ULogger> ULogger::destroyer_;
ULogger::Type ULogger::type_ = ULogger::kTypeNoLog; // Default nothing
UMutex ULogger::loggerMutex_;
const std::string ULogger::kDefaultLogFileName = "./ULog.txt";
std::string ULogger::logFileName_;
std::string ULogger::bufferedMsgs_;
/**
* This class is used to write logs in the console. This class cannot
* be directly used, use ULogger::setType() to console type to print in
* console and use macro UDEBUG(), UINFO()... to print messages.
* @see ULogger
*/
class UConsoleLogger : public ULogger
{
public :
virtual ~UConsoleLogger() {this->_flush();}
protected:
/**
* Only the Logger can create inherited
* loggers according to the Abstract factory patterns.
*/
friend class ULogger;
UConsoleLogger() {}
private:
virtual void _write(const char* msg, va_list arg)
{
vprintf(msg, arg);
}
virtual void _writeStr(const char* msg)
{
printf("%s", msg);
}
};
/**
* This class is used to write logs in a file. This class cannot
* be directly used, use ULogger::setType() to file type to print in
* a file and use macro UDEBUG(), UINFO()... to print messages.
* @see ULogger
*/
class UFileLogger : public ULogger
{
public:
virtual ~UFileLogger()
{
this->_flush();
if(fout_)
{
fclose(fout_);
}
}
protected:
/**
* Only the Logger can create inherited
* loggers according to the Abstract factory patterns.
*/
friend class ULogger;
/**
* The UFileLogger constructor.
* @param fileName the file name
* @param append if true append logs in the file,
* ortherwise it overrides the file.
*
*/
UFileLogger(const std::string &fileName, bool append)
{
fileName_ = fileName;
if(!append) {
std::ofstream fileToClear(fileName_.c_str(), std::ios::out);
fileToClear.clear();
fileToClear.close();
}
#ifdef _MSC_VER
fopen_s(&fout_, fileName_.c_str(), "a");
#else
fout_ = fopen(fileName_.c_str(), "a");
#endif
if(!fout_) {
printf("FileLogger : Cannot open file : %s\n", fileName_.c_str()); // TODO send Event instead, or return error code
return;
}
}
private:
virtual void _write(const char* msg, va_list arg)
{
if(fout_)
{
vfprintf(fout_, msg, arg);
}
}
virtual void _writeStr(const char* msg)
{
if(fout_)
{
fprintf(fout_, "%s", msg);
}
}
private:
std::string fileName_; ///< the file name
FILE* fout_;
std::string bufferedMsgs_;
};
void ULogger::setType(Type type, const std::string &fileName, bool append)
{
ULogger::flush();
loggerMutex_.lock();
{
// instance not yet created
if(!instance_)
{
type_ = type;
logFileName_ = fileName;
append_ = append;
instance_ = createInstance();
}
// type changed
else if(type_ != type || (type_ == kTypeFile && logFileName_.compare(fileName)!=0))
{
destroyer_.setDoomed(0);
delete instance_;
instance_ = 0;
type_ = type;
logFileName_ = fileName;
append_ = append;
instance_ = createInstance();
}
}
loggerMutex_.unlock();
}
void ULogger::reset()
{
ULogger::setType(ULogger::kTypeNoLog);
append_ = true;
printTime_ = true;
printLevel_ = true;
printEndline_ = true;
printColored_ = true;
printWhere_ = true;
printWhereFullPath_ = false;
limitWhereLength_ = false;
level_ = kInfo; // By default, we show all info msgs + upper level (Warning, Error)
logFileName_ = ULogger::kDefaultLogFileName;
}
void ULogger::setBuffered(bool buffered)
{
if(!buffered)
{
ULogger::flush();
}
buffered_ = buffered;
}
void ULogger::flush()
{
loggerMutex_.lock();
if(!instance_ || bufferedMsgs_.size()==0)
{
loggerMutex_.unlock();
return;
}
instance_->_flush();
loggerMutex_.unlock();
}
void ULogger::_flush()
{
ULogger::getInstance()->_writeStr(bufferedMsgs_.c_str());
bufferedMsgs_.clear();
}
void ULogger::write(const char* msg, ...)
{
loggerMutex_.lock();
if(!instance_)
{
loggerMutex_.unlock();
return;
}
std::string endline = "";
if(printEndline_) {
endline = "\r\n";
}
std::string time = "";
if(printTime_)
{
getTime(time);
time.append(" - ");
}
if(printTime_)
{
if(buffered_)
{
bufferedMsgs_.append(time.c_str());
}
else
{
ULogger::getInstance()->_writeStr(time.c_str());
}
}
va_list args;
va_start(args, msg);
if(buffered_)
{
bufferedMsgs_.append(uFormatv(msg, args));
}
else
{
ULogger::getInstance()->_write(msg, args);
}
va_end(args);
if(printEndline_)
{
if(buffered_)
{
bufferedMsgs_.append(endline.c_str());
}
else
{
ULogger::getInstance()->_writeStr(endline.c_str());
}
}
loggerMutex_.unlock();
}
void ULogger::write(ULogger::Level level,
const char * file,
int line,
const char * function,
const char* msg,
...)
{
if(exitingState_)
{
// Ignore messages after a fatal exit...
return;
}
loggerMutex_.lock();
if(type_ == kTypeNoLog && level < kFatal)
{
loggerMutex_.unlock();
return;
}
if(strlen(msg) == 0 && !printWhere_ && level < exitLevel_)
{
loggerMutex_.unlock();
// No need to show an empty message if we don't print where.
return;
}
if(level >= level_)
{
#ifdef WIN32
int color = 0;
#else
const char* color = NULL;
#endif
switch(level)
{
case kDebug:
color = COLOR_GREEN;
break;
case kInfo:
color = COLOR_NORMAL;
break;
case kWarning:
color = COLOR_YELLOW;
break;
case kError:
case kFatal:
color = COLOR_RED;
break;
default:
break;
}
std::string endline = "";
if(printEndline_) {
endline = "\r\n";
}
std::string time = "";
if(printTime_)
{
time.append("(");
getTime(time);
time.append(") ");
}
std::string levelStr = "";
if(printLevel_)
{
const int bufSize = 30;
char buf[bufSize] = {0};
#ifdef _MSC_VER
sprintf_s(buf, bufSize, "[%s]", levelName_[level]);
#else
snprintf(buf, bufSize, "[%s]", levelName_[level]);
#endif
levelStr = buf;
levelStr.append(" ");
}
std::string whereStr = "";
if(printWhere_)
{
whereStr.append("");
//File
if(printWhereFullPath_)
{
whereStr.append(file);
}
else
{
std::string fileName = UFile::getName(file);
if(limitWhereLength_ && fileName.size() > 8)
{
fileName.erase(8);
fileName.append("~");
}
whereStr.append(fileName);
}
//Line
whereStr.append(":");
std::string lineStr = uNumber2Str(line);
whereStr.append(lineStr);
//Function
whereStr.append("::");
std::string funcStr = function;
if(!printWhereFullPath_ && limitWhereLength_ && funcStr.size() > 8)
{
funcStr.erase(8);
funcStr.append("~");
}
funcStr.append("()");
whereStr.append(funcStr);
whereStr.append(" ");
}
va_list args;
if(type_ != kTypeNoLog)
{
va_start(args, msg);
#ifdef WIN32
HANDLE H = GetStdHandle(STD_OUTPUT_HANDLE);
#endif
if(type_ == ULogger::kTypeConsole && printColored_)
{
#ifdef WIN32
SetConsoleTextAttribute(H,color);
#else
if(buffered_)
{
bufferedMsgs_.append(color);
}
else
{
ULogger::getInstance()->_writeStr(color);
}
#endif
}
if(buffered_)
{
bufferedMsgs_.append(levelStr.c_str());
bufferedMsgs_.append(time.c_str());
bufferedMsgs_.append(whereStr.c_str());
bufferedMsgs_.append(uFormatv(msg, args));
}
else
{
ULogger::getInstance()->_writeStr(levelStr.c_str());
ULogger::getInstance()->_writeStr(time.c_str());
ULogger::getInstance()->_writeStr(whereStr.c_str());
ULogger::getInstance()->_write(msg, args);
}
if(type_ == ULogger::kTypeConsole && printColored_)
{
#ifdef WIN32
SetConsoleTextAttribute(H,COLOR_NORMAL);
#else
if(buffered_)
{
bufferedMsgs_.append(COLOR_NORMAL);
}
else
{
ULogger::getInstance()->_writeStr(COLOR_NORMAL);
}
#endif
}
if(buffered_)
{
bufferedMsgs_.append(endline.c_str());
}
else
{
ULogger::getInstance()->_writeStr(endline.c_str());
}
va_end (args);
}
if(level >= exitLevel_)
{
printf("\n*******\n%s message occurred! Application will now exit.\n", levelName_[level]);
if(type_ != kTypeConsole)
{
printf(" %s%s%s\n", levelStr.c_str(), time.c_str(), whereStr.c_str());
va_start(args, msg);
vprintf(msg, args);
va_end(args);
}
printf("*******\n");
destroyer_.setDoomed(0);
delete instance_; // If a FileLogger is used, this will close the file.
instance_ = 0;
//========================================================================
// EXIT APPLICATION
exit(1);
//========================================================================
}
}
loggerMutex_.unlock();
}
int ULogger::getTime(std::string &timeStr)
{
if(!printTime_) {
return 0;
}
struct tm timeinfo;
const int bufSize = 30;
char buf[bufSize] = {0};
#if _MSC_VER
time_t rawtime;
time(&rawtime);
localtime_s (&timeinfo, &rawtime );
int result = sprintf_s(buf, bufSize, "%d-%s%d-%s%d %s%d:%s%d:%s%d",
timeinfo.tm_year+1900,
(timeinfo.tm_mon+1) < 10 ? "0":"", timeinfo.tm_mon+1,
(timeinfo.tm_mday) < 10 ? "0":"", timeinfo.tm_mday,
(timeinfo.tm_hour) < 10 ? "0":"", timeinfo.tm_hour,
(timeinfo.tm_min) < 10 ? "0":"", timeinfo.tm_min,
(timeinfo.tm_sec) < 10 ? "0":"", timeinfo.tm_sec);
#elif WIN32
time_t rawtime;
time(&rawtime);
timeinfo = *localtime (&rawtime);
int result = snprintf(buf, bufSize, "%d-%s%d-%s%d %s%d:%s%d:%s%d",
timeinfo.tm_year+1900,
(timeinfo.tm_mon+1) < 10 ? "0":"", timeinfo.tm_mon+1,
(timeinfo.tm_mday) < 10 ? "0":"", timeinfo.tm_mday,
(timeinfo.tm_hour) < 10 ? "0":"", timeinfo.tm_hour,
(timeinfo.tm_min) < 10 ? "0":"", timeinfo.tm_min,
(timeinfo.tm_sec) < 10 ? "0":"", timeinfo.tm_sec);
#else
struct timeval rawtime;
gettimeofday(&rawtime, NULL);
localtime_r (&rawtime.tv_sec, &timeinfo);
int result = snprintf(buf, bufSize, "%d-%s%d-%s%d %s%d:%s%d:%s%d.%s%d",
timeinfo.tm_year+1900,
(timeinfo.tm_mon+1) < 10 ? "0":"", timeinfo.tm_mon+1,
(timeinfo.tm_mday) < 10 ? "0":"", timeinfo.tm_mday,
(timeinfo.tm_hour) < 10 ? "0":"", timeinfo.tm_hour,
(timeinfo.tm_min) < 10 ? "0":"", timeinfo.tm_min,
(timeinfo.tm_sec) < 10 ? "0":"", timeinfo.tm_sec,
(rawtime.tv_usec/1000) < 10 ? "00":(rawtime.tv_usec/1000) < 100?"0":"", int(rawtime.tv_usec/1000));
#endif
if(result)
{
timeStr.append(buf);
}
return result;
}
ULogger* ULogger::getInstance()
{
if(!instance_)
{
instance_ = createInstance();
}
return instance_;
}
ULogger* ULogger::createInstance()
{
ULogger* instance = 0;
if(type_ == ULogger::kTypeConsole)
{
instance = new UConsoleLogger();
}
else if(type_ == ULogger::kTypeFile)
{
instance = new UFileLogger(logFileName_, append_);
}
destroyer_.setDoomed(instance);
return instance;
}
ULogger::~ULogger()
{
instance_ = 0;
//printf("Logger is destroyed...\n\r");
}

531
src/utilite/ULogger.h Normal file
View File

@ -0,0 +1,531 @@
/*
* utilite is a cross-platform library with
* useful utilities for fast and small developing.
* Copyright (C) 2010 Mathieu Labbe
*
* utilite is free library: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* utilite is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef ULOGGER_H
#define ULOGGER_H
//#include "utilite/UtiLiteExp.h" // DLL export/import defines
#include "utilite/UMutex.h"
#include "utilite/UDestroyer.h"
#include <stdio.h>
#include <time.h>
#include <string>
#include <vector>
#include <stdarg.h>
/**
* \file ULogger.h
* \brief ULogger class and convenient macros
*
* This contains macros useful for logging a message anywhere in the
* application. Once the ULogger is set, use these macros like a printf to
* print debug messages.
*/
/*
* Convenient macros for logging...
*/
#define ULOGGER_LOG(level, ...) ULogger::write(level, __FILE__, __LINE__, __FUNCTION__, __VA_ARGS__)
#define ULOGGER_DEBUG(...) ULOGGER_LOG(ULogger::kDebug, __VA_ARGS__)
#define ULOGGER_INFO(...) ULOGGER_LOG(ULogger::kInfo, __VA_ARGS__)
#define ULOGGER_WARN(...) ULOGGER_LOG(ULogger::kWarning, __VA_ARGS__)
#define ULOGGER_ERROR(...) ULOGGER_LOG(ULogger::kError, __VA_ARGS__)
#define ULOGGER_FATAL(...) ULOGGER_LOG(ULogger::kFatal, __VA_ARGS__)
#define UDEBUG(...) ULOGGER_DEBUG(__VA_ARGS__)
#define UINFO(...) ULOGGER_INFO(__VA_ARGS__)
#define UWARN(...) ULOGGER_WARN(__VA_ARGS__)
#define UERROR(...) ULOGGER_ERROR(__VA_ARGS__)
#define UFATAL(...) ULOGGER_FATAL(__VA_ARGS__)
#define UASSERT(condition) if(!(condition)) ULogger::write(ULogger::kFatal, __FILE__, __LINE__, __FUNCTION__, "Condition (%s) not met!", #condition)
#define UASSERT_MSG(condition, msg_str) if(!(condition)) ULogger::write(ULogger::kFatal, __FILE__, __LINE__, __FUNCTION__, "Condition (%s) not met! [%s]", #condition, msg_str)
/**
* \def UDEBUG(...)
* Print a debug level message in the logger. Format is the same as a printf:
* @code
* UDEBUG("This is a debug message with the number %d", 42);
* @endcode
*/
/**
* \def UINFO(...)
* Print a information level message in the logger. Format is the same as a printf:
* @code
* UINFO("This is a information message with the number %d", 42);
* @endcode
*/
/**
* \def UWARN(...)
* Print a warning level message in the logger. Format is the same as a printf:
* @code
* UWARN("This is a warning message with the number %d", 42);
* @endcode
*/
/**
* \def UERROR(...)
* Print an error level message in the logger. Format is the same as a printf:
* @code
* UERROR("This is an error message with the number %d", 42);
* @endcode
*/
/**
* \def UFATAL(...)
* Print a fatal error level message in the logger. The application will exit on
* fatal error. Format is the same as a printf:
* @code
* UFATAL("This is a fatal error message with the number %d", 42);
* @endcode
*/
/**
* \def UASSERT(condition, ...)
* Print a fatal error level message in the logger if condition is not met. The application will exit on
* fatal error. Format is the same as a printf:
* @code
* UASSERT(a!=42, "This is a fatal error message with the number %d", 42);
* @endcode
*/
/**
* This class is used to log messages with time on a console, in a file
* and/or with an event. At the start of the application, call
* ULogger::setType() with the type of the logger you want (see ULogger::Type, the type of the output
* can be changed at the run-time.). To use it,
* simply call the convenient macros UDEBUG(), UINFO(), UWARN(), UERROR(), UFATAL() depending of
* the severity of the message. You can disable some messages by setting the logger
* level ULogger::setLevel() to severity you want, defined by ULogger::Level. A fatal message
* will make the application to exit, printing the message on console (whatever the logger type) and
* posting a ULogEvent (synchronously... see UEventsManager::post()) before exiting.
*
* The display of the logged messages can be modified:
* - If you don't want the level label, set ULogger::setPrintLevel() to false.
* - If you don't want the time label, set ULogger::setPrintTime() to false.
* - If you don't want the end of line added, set ULogger::setPrintEndline() to false.
* - If you don't the full path of the message, set ULogger::setPrintWhereFullPath() to false.
* - If you don't the path of the message, set ULogger::setPrintWhere() to false.
*
* When using a file logger (kTypeLogger), it can be useful in some
* application to buffer messages before writing them to hard drive (avoiding
* hard drive latencies). You can set ULogger::setBuffered() to true to do that. When the
* buffered messages will be written to file on appllciation exit (ULogger destructor) or when
* ULogger::flush() is called.
*
* If you want the application to exit on a lower severity level than kFatal,
* you can set ULogger::setExitLevel() to any ULogger::Type you want.
*
* Example:
* @code
* #include <utilite/ULogger.h>
* int main(int argc, char * argv[])
* {
* // Set the logger type. The choices are kTypeConsole,
* // kTypeFile or kTypeNoLog (nothing is logged).
* ULogger::setType(ULogger::kTypeConsole);
*
* // Set the logger severity level (kDebug, kInfo, kWarning, kError, kFatal).
* // All log entries under the severity level are not logged. Here,
* // only debug messages are not logged.
* ULogger::setLevel(ULogger::kInfo);
*
* // Use a predefined Macro to easy logging. It can be
* // called anywhere in the application as the logger is
* // a Singleton.
* UDEBUG("This message won't be logged because the "
* "severity level of the logger is set to kInfo.");
*
* UINFO("This message is logged.");
*
* UWARN("A warning message...");
*
* UERROR("An error message with code %d.", 42);
*
* return 0;
* }
* @endcode
* Output:
* @code
* [ INFO] (2010-09-25 18:08:20) main.cpp:18::main() This message is logged.
* [ WARN] (2010-09-25 18:08:20) main.cpp:20::main() A warning message...
* [ERROR] (2010-09-25 18:08:20) main.cpp:22::main() An error message with code 42.
* @endcode
*
* Another useful form of the ULogger is to use it with the UTimer class. Here an example:
* @code
* #include <utilite/ULogger.h>
* #include <utilite/UTimer.h>
* ...
* UTimer timer; // automatically starts
* // do some works for part A
* UINFO("Time for part A = %f s", timer.ticks());
* // do some works for part B
* UINFO("Time for part B = %f s", timer.ticks());
* // do some works for part C
* UINFO("Time for part C = %f s", timer.ticks());
* ...
* @endcode
*
* @see setType()
* @see setLevel()
* @see UDEBUG(), UINFO(), UWARN(), UERROR(), UFATAL()
*
*/
class ULogger
{
public:
/**
* The default log file name.
*/
static const std::string kDefaultLogFileName;
/**
* Loggers available:
* @code
* kTypeNoLog, kTypeConsole, kTypeFile
* @endcode
*/
enum Type{kTypeNoLog, kTypeConsole, kTypeFile};
/**
* Logger levels, from lowest severity to highest:
* @code
* kDebug, kInfo, kWarning, kError, kFatal
* @endcode
*/
enum Level{kDebug, kInfo, kWarning, kError, kFatal};
/**
* Set the type of the logger. When using kTypeFile, the parameter "fileName" would be
* changed (default is "./ULog.txt"), and optionally "append" if we want the
* logger to append messages to file or to overwrite the file.
* @param type the ULogger::Type of the logger.
* @param fileName file name used with a file logger type.
* @param append if true, the file isn't overwritten, otherwise it is.
*
* TODO : Can it be useful to have 2 or more types at the same time ? Print
* in console and file at the same time.
*/
static void setType(Type type, const std::string &fileName = kDefaultLogFileName, bool append = true);
static Type type() {return type_;}
// Setters
/**
* Print time: default true.
* @param printTime true to print time, otherwise set to false.
*/
static void setPrintTime(bool printTime) {printTime_ = printTime;}
static bool isPrintTime() {return printTime_;}
/**
* Print level: default true.
* @param printLevel true to print level, otherwise set to false.
*/
static void setPrintLevel(bool printLevel) {printLevel_ = printLevel;}
static bool isPrintLevel() {return printLevel_;}
/**
* Print end of line: default true.
* @param printLevel true to print end of line, otherwise set to false.
*/
static void setPrintEndline(bool printEndline) {printEndline_ = printEndline;}
static bool isPrintEndLine() {return printEndline_;}
/**
* Print text with color: default true.
* Dark green for Debug, white for Info, yellow for Warning, red for Error and Fatal.
* @param printColored true to print text with color, otherwise set to false.
*/
static void setPrintColored(bool printColored) {printColored_ = printColored;}
static bool isPrintColored() {return printColored_;}
/**
* Print where is this message in source code: default true.
* @param printWhere true to print where, otherwise set to false.
*/
static void setPrintWhere(bool printWhere) {printWhere_ = printWhere;}
static bool isPrintWhere() {return printWhere_;}
/**
* Print the full path: default true. ULogger::setPrintWhere() must be true to have path printed.
* @param printWhereFullPath true to print the full path, otherwise set to false.
*/
static void setPrintWhereFullPath(bool printWhereFullPath) {printWhereFullPath_ = printWhereFullPath;}
static bool isPrintWhereFullPath() {return printWhereFullPath_;}
/**
* Set is the logger buffers messages, default false. When true, the messages are
* buffered until the application is closed or ULogger::flush() is called.
* @see ULogger::flush()
* @param buffered true to buffer messages, otherwise set to false.
*/
static void setBuffered(bool buffered);
static bool isBuffered() {return buffered_;}
/**
* Set logger level: default kInfo. All messages over the severity set
* are printed, other are ignored. The severity is from the lowest to
* highest:
* - kDebug
* - kInfo
* - kWarning
* - kError
* - kFatal
* @param level the minimum level of the messages printed.
*/
static void setLevel(ULogger::Level level) {level_ = level;}
static ULogger::Level level() {return level_;}
/**
* Make application to exit when a log with level is written (useful for debugging). The message is printed to
* console (whatever the logger type) and an ULogEvent is sent (synchronously... see UEventsManager::post()) before exiting.
*
* Note : A kFatal level will always exit whatever the level specified here.
*/
static void setExitLevel(ULogger::Level exitLevel) {exitLevel_ = exitLevel;}
static ULogger::Level exitLevel() {return exitLevel_;}
/**
* An ULogEvent is sent on each message logged at the specified level.
* Note : On message with level >= exitLevel, the event is sent synchronously (see UEventsManager::post()).
* @see ULogEvent
* @see setExitLevel()
*/
static void setEventLevel(ULogger::Level eventSentLevel) {eventLevel_ = eventSentLevel;}
static ULogger::Level eventLevel() {return eventLevel_;}
/**
* Reset to default parameters.
*/
static void reset();
/**
* Flush buffered messages.
* @see setBuffered()
*/
static void flush();
/**
* Write a message directly to logger without level handling.
* @param msg the message to write.
* @param ... the variable arguments
* @deprecated use UDEBUG(), UINFO(), UWARN(), UERROR() or UFATAL()
*/
static void write(const char* msg, ...);
/*
* Write a message to logger: use UDEBUG(), UINFO(), UWARN(), UERROR() or UFATAL() instead.
* @param level the log level of this message
* @param file the file path
* @param line the line in the file
* @param function the function name in which the message is logged
* @param msg the message to write
* @param ... the variable arguments
*/
static void write(ULogger::Level level,
const char * file,
int line,
const char *function,
const char* msg,
...);
/**
* Get the time in the format "2008-7-13 12:23:44".
* @param timeStr string were the time will be copied.
* @return the number of characters written, or 0 if an error occurred.
*/
static int getTime(std::string &timeStr);
protected:
/*
* This method is used to have a reference on the
* Logger. When no Logger exists, one is
* created. There is only one instance in the application.
* Must be protected by loggerMutex_.
* See the Singleton pattern for further explanation.
*
* @return the reference on the Logger
*/
static ULogger* getInstance();
/*
* Called only once in getInstance(). It can't be instanciated
* by the user.
*
* @see getInstance()
*/
ULogger() {}
/*
* Only called by a Destroyer.
* @see Destroyer
*/
virtual ~ULogger();
/*
* Flush buffered messages
*/
void _flush();
/*
* A Destroyer is used to remove a dynamicaly created
* Singleton. It is friend here to have access to the
* destructor.
*
* @see Destroyer
*/
friend class UDestroyer<ULogger>;
/*
* The log file name.
*/
static std::string logFileName_;
/*
* Default true, it doesn't overwrite the file.
*/
static bool append_;
private:
/*
* Create an instance according to type. See the Abstract factory
* pattern for further explanation.
* @see type_
* @return the reference on the new logger
*/
static ULogger* createInstance();
/*
* Write a message on the output with the format :
* "A message". Inherited class
* must override this method to output the message. It
* does nothing by default.
* @param msg the message to write.
* @param arg the variable arguments
*/
virtual void _write(const char* msg, va_list arg) {} // Do nothing by default
virtual void _writeStr(const char* msg) {} // Do nothing by default
private:
/*
* The Logger instance pointer.
*/
static ULogger* instance_;
/*
* The Logger's destroyer
*/
static UDestroyer<ULogger> destroyer_;
/*
* If the logger prints the time for each message.
* Default is true.
*/
static bool printTime_;
/*
* If the logger prints the level for each message.
* Default is true.
*/
static bool printLevel_;
/*
* If the logger prints the end line for each message.
* Default is true.
*/
static bool printEndline_;
/*
* If the logger prints text with color.
* Default is true.
*/
static bool printColored_;
/*
* If the logger prints where the message is logged (fileName::function():line).
* Default is true.
*/
static bool printWhere_;
/*
* If the logger prints the full path of the source file
* where the message is written. Only works when
* "printWhere_" is true.
* Default is false.
*/
static bool printWhereFullPath_;
/*
* If the logger limit the size of the "where" path to
* characters. If the path is over 8 characters, a "~"
* is added. Only works when "printWhereFullPath_" is false.
* Default is false.
*/
static bool limitWhereLength_;
/*
* The type of the logger.
*/
static Type type_;
/*
* The severity of the log.
*/
static Level level_;
/*
* The severity at which the application exits.
* Note : A FATAL level will always exit whatever the level specified here.
*/
static Level exitLevel_;
/*
* The severity at which the message is also sent in a ULogEvent.
*/
static Level eventLevel_;
static const char * levelName_[5];
/*
* Mutex used when accessing public functions.
*/
static UMutex loggerMutex_;
/*
* If the logger prints messages only when ULogger::flush() is called.
* Default is false.
*/
static bool buffered_;
static std::string bufferedMsgs_;
/*
* State attribute. This state happens when an exit level
* message is received.
* Messages received during this state are not logged.
* @see exitLevel_
*/
static bool exitingState_;
};
#endif // ULOGGER_H

179
src/utilite/UMutex.h Normal file
View File

@ -0,0 +1,179 @@
/*
* utilite is a cross-platform library with
* useful utilities for fast and small developing.
* Copyright (C) 2010 Mathieu Labbe
*
* utilite is free library: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* utilite is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef UMUTEX_H
#define UMUTEX_H
#include <errno.h>
#ifdef WIN32
#include "utilite/UWin32.h"
#else
#include <pthread.h>
#endif
/**
* A mutex class.
*
* On a lock() call, the calling thread is blocked if the
* UMutex was previously locked by another thread. It is unblocked when unlock() is called.
*
* On Unix (not yet tested on Windows), UMutex is recursive: the same thread can
* call multiple times lock() without being blocked.
*
* Example:
* @code
* UMutex m; // Mutex shared with another thread(s).
* ...
* m.lock();
* // Data is protected here from the second thread
* //(assuming the second one protects also with the same mutex the same data).
* m.unlock();
*
* @endcode
*
* @see USemaphore
*/
class UMutex
{
public:
/**
* The constructor.
*/
UMutex()
{
#ifdef WIN32
InitializeCriticalSection(&C);
#else
pthread_mutexattr_t attr;
pthread_mutexattr_init(&attr);
pthread_mutexattr_settype(&attr,PTHREAD_MUTEX_RECURSIVE);
pthread_mutex_init(&M,&attr);
pthread_mutexattr_destroy(&attr);
#endif
}
virtual ~UMutex()
{
#ifdef WIN32
DeleteCriticalSection(&C);
#else
pthread_mutex_unlock(&M); pthread_mutex_destroy(&M);
#endif
}
/**
* Lock the mutex.
*/
int lock() const
{
#ifdef WIN32
EnterCriticalSection(&C); return 0;
#else
return pthread_mutex_lock(&M);
#endif
}
#ifdef WIN32
#if(_WIN32_WINNT >= 0x0400)
int lockTry() const
{
return (TryEnterCriticalSection(&C)?0:EBUSY);
}
#endif
#else
int lockTry() const
{
return pthread_mutex_trylock(&M);
}
#endif
/**
* Unlock the mutex.
*/
int unlock() const
{
#ifdef WIN32
LeaveCriticalSection(&C); return 0;
#else
return pthread_mutex_unlock(&M);
#endif
}
private:
#ifdef WIN32
mutable CRITICAL_SECTION C;
#else
mutable pthread_mutex_t M;
#endif
void operator=(UMutex &M) {}
UMutex( const UMutex &M ) {}
};
/**
* Automatically lock the referenced mutex on constructor and unlock mutex on destructor.
*
* Example:
* @code
* UMutex m; // Mutex shared with another thread(s).
* ...
* int myMethod()
* {
* UScopeMutex sm(m); // automatically lock the mutex m
* if(cond1)
* {
* return 1; // automatically unlock the mutex m
* }
* else if(cond2)
* {
* return 2; // automatically unlock the mutex m
* }
* return 0; // automatically unlock the mutex m
* }
*
* @endcode
*
* @see UMutex
*/
class UScopeMutex
{
public:
UScopeMutex(const UMutex & mutex) :
mutex_(mutex)
{
mutex_.lock();
}
// backward compatibility
UScopeMutex(UMutex * mutex) :
mutex_(*mutex)
{
mutex_.lock();
}
~UScopeMutex()
{
mutex_.unlock();
}
private:
const UMutex & mutex_;
};
#endif // UMUTEX_H

64
src/utilite/UWin32.h Normal file
View File

@ -0,0 +1,64 @@
/////////////////////////////////////////////////////////////////////
// Written by Phillip Sitbon
// Copyright 2003
//
// Win32.h
// - Windows includes
//
/////////////////////////////////////////////////////////////////////
#ifndef _U_Win32_
#define _U_Win32_
#include "utilite/UtiLiteExp.h"
#if !defined(_WINDOWS_)
// WIN32 Excludes
#ifdef WIN32_LEAN_AND_MEAN
# define VC_EXTRALEAN
# define WIN32_LEAN_AND_MEAN
# define _PRSHT_H_
# define NOGDICAPMASKS // CC_*, LC_*, PC_*, CP_*, TC_*, RC_
# define NOVIRTUALKEYCODES // VK_*
# define NOWINMESSAGES // WM_*, EM_*, LB_*, CB_*
# define NOWINSTYLES // WS_*, CS_*, ES_*, LBS_*, SBS_*, CBS_*
# define NOSYSMETRICS // SM_*
# define NOMENUS // MF_*
# define NOICONS // IDI_*
# define NOKEYSTATES // MK_*
# define NOSYSCOMMANDS // SC_*
# define NORASTEROPS // Binary and Tertiary raster ops
# define NOSHOWWINDOW // SW_*
# define OEMRESOURCE // OEM Resource values
# define NOATOM // Atom Manager routines
# define NOCLIPBOARD // Clipboard routines
# define NOCOLOR // Screen colors
# define NOCTLMGR // Control and Dialog routines
# define NODRAWTEXT // DrawText() and DT_*
# define NOGDI // All GDI defines and routines
# define NOKERNEL // All KERNEL defines and routines
# define NOUSER // All USER defines and routines
# define NONLS // All NLS defines and routines
# define NOMB // MB_* and MessageBox()
# define NOMEMMGR // GMEM_*, LMEM_*, GHND, LHND, associated routines
# define NOMETAFILE // typedef METAFILEPICT
# define NOMINMAX // Macros min(a,b) and max(a,b)
# define NOMSG // typedef MSG and associated routines
# define NOOPENFILE // OpenFile(), OemToAnsi, AnsiToOem, and OF_*
# define NOSCROLL // SB_* and scrolling routines
# define NOSERVICE // All Service Controller routines, SERVICE_ equates, etc.
# define NOSOUND // Sound driver routines
# define NOTEXTMETRIC // typedef TEXTMETRIC and associated routines
# define NOWH // SetWindowsHook and WH_*
# define NOWINOFFSETS // GWL_*, GCL_*, associated routines
# define NOCOMM // COMM driver routines
# define NOKANJI // Kanji support stuff.
# define NOHELP // Help engine interface.
# define NOPROFILER // Profiler interface.
# define NODEFERWINDOWPOS // DeferWindowPos routines
# define NOMCX // Modem Configuration Extensions
#endif // WIN32_LEAN_AND_MEAN
//
# include <windows.h>
#endif
#endif // !_U_Win32_