From f16595d505131089011d02347785b2eec5ea6665 Mon Sep 17 00:00:00 2001 From: matlabbe Date: Wed, 6 Aug 2014 14:09:55 +0000 Subject: [PATCH] Added find_object namespace prefix to all signals and slots git-svn-id: http://find-object.googlecode.com/svn/trunk/find_object@381 620bd6b2-0a58-f614-fd9a-1bd335dccda9 --- app/main.cpp | 50 +++++++++++------------ include/find_object/FindObject.h | 4 +- include/find_object/MainWindow.h | 12 +++--- include/find_object/ObjWidget.h | 2 +- include/find_object/TcpServer.h | 2 +- src/FindObject.cpp | 4 +- src/MainWindow.cpp | 6 +-- tools/tcpClient/TcpClient.cpp | 4 +- tools/tcpImagesServer/ImagesTcpServer.cpp | 6 +-- tools/tcpRequest/main.cpp | 10 ++--- 10 files changed, 46 insertions(+), 54 deletions(-) diff --git a/app/main.cpp b/app/main.cpp index 44e5d431..0080df1e 100644 --- a/app/main.cpp +++ b/app/main.cpp @@ -38,8 +38,6 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include "find_object/JsonWriter.h" #include "find_object/utilite/ULogger.h" -using namespace find_object; - bool running = true; #ifdef WIN32 @@ -108,8 +106,8 @@ void showUsage() " --My/Parameter \"value\" Set find-Object's parameter (look --params for parameters' name).\n" " It will override the one in --config. Example to set 4 threads:\n" " $ find_object --General/threads 4\n" - " --help Show usage.\n", Settings::iniDefaultPath().toStdString().c_str()); - if(JsonWriter::available()) + " --help Show usage.\n", find_object::Settings::iniDefaultPath().toStdString().c_str()); + if(find_object::JsonWriter::available()) { printf(" --json \"path\" Path to an output JSON file (only in --console mode with --scene).\n"); } @@ -129,9 +127,9 @@ int main(int argc, char* argv[]) bool guiMode = true; QString objectsPath = ""; QString scenePath = ""; - QString configPath = Settings::iniDefaultPath(); + QString configPath = find_object::Settings::iniDefaultPath(); QString jsonPath; - ParametersMap customParameters; + find_object::ParametersMap customParameters; for(int i=1; i 2) { @@ -287,11 +285,11 @@ int main(int argc, char* argv[]) UINFO(" Objects path: \"%s\"", objectsPath.toStdString().c_str()); UINFO(" Scene path: \"%s\"", scenePath.toStdString().c_str()); UINFO(" Settings path: \"%s\"", configPath.toStdString().c_str()); - if(JsonWriter::available()) + if(find_object::JsonWriter::available()) { UINFO(" JSON path: \"%s\"", jsonPath.toStdString().c_str()); } - for(ParametersMap::iterator iter= customParameters.begin(); iter!=customParameters.end(); ++iter) + for(find_object::ParametersMap::iterator iter= customParameters.begin(); iter!=customParameters.end(); ++iter) { UINFO(" Param \"%s\"=\"%s\"", iter.key().toStdString().c_str(), iter.value().toString().toStdString().c_str()); } @@ -301,16 +299,16 @@ int main(int argc, char* argv[]) ////////////////////////// // Load settings, should be loaded before creating other objects - Settings::init(configPath); + find_object::Settings::init(configPath); // Override custom parameters: - for(ParametersMap::iterator iter= customParameters.begin(); iter!=customParameters.end(); ++iter) + for(find_object::ParametersMap::iterator iter= customParameters.begin(); iter!=customParameters.end(); ++iter) { - Settings::setParameter(iter.key(), iter.value()); + find_object::Settings::setParameter(iter.key(), iter.value()); } // Create FindObject - FindObject * findObject = new FindObject(); + find_object::FindObject * findObject = new find_object::FindObject(); // Load objects if path is set int objectsLoaded = 0; @@ -335,7 +333,7 @@ int main(int argc, char* argv[]) if(guiMode) { QApplication app(argc, argv); - MainWindow mainWindow(findObject, 0); // ownership transfered + find_object::MainWindow mainWindow(findObject, 0); // ownership transfered app.connect( &app, SIGNAL( lastWindowClosed() ), &app, SLOT( quit() ) ); mainWindow.show(); @@ -348,7 +346,7 @@ int main(int argc, char* argv[]) app.exec(); // Save settings - Settings::saveSettings(); + find_object::Settings::saveSettings(); } else { @@ -366,7 +364,7 @@ int main(int argc, char* argv[]) // process the scene and exit QTime time; time.start(); - DetectionInfo info; + find_object::DetectionInfo info; findObject->detect(scene, info); if(info.objDetected_.size() > 1) @@ -377,26 +375,26 @@ int main(int argc, char* argv[]) { UINFO("Object %d detected! (%d ms)", (int)info.objDetected_.begin().key(), time.elapsed()); } - else if(Settings::getGeneral_sendNoObjDetectedEvents()) + else if(find_object::Settings::getGeneral_sendNoObjDetectedEvents()) { UINFO("No objects detected. (%d ms)", time.elapsed()); } - if(!jsonPath.isEmpty() && JsonWriter::available()) + if(!jsonPath.isEmpty() && find_object::JsonWriter::available()) { - JsonWriter::write(info, jsonPath); + find_object::JsonWriter::write(info, jsonPath); UINFO("JSON written to \"%s\"", jsonPath.toStdString().c_str()); } } else { - Camera camera; - TcpServer tcpServer(Settings::getGeneral_port()); + find_object::Camera camera; + find_object::TcpServer tcpServer(find_object::Settings::getGeneral_port()); UINFO("Detection sent on port: %d (IP=%s)", tcpServer.getPort(), tcpServer.getHostAddress().toString().toStdString().c_str()); // connect stuff: // [FindObject] ---ObjectsDetected---> [TcpServer] - QObject::connect(findObject, SIGNAL(objectsFound(DetectionInfo)), &tcpServer, SLOT(publishDetectionInfo(DetectionInfo))); + QObject::connect(findObject, SIGNAL(objectsFound(find_object::DetectionInfo)), &tcpServer, SLOT(publishDetectionInfo(find_object::DetectionInfo))); // [Camera] ---Image---> [FindObject] QObject::connect(&camera, SIGNAL(imageReceived(const cv::Mat &)), findObject, SLOT(detect(const cv::Mat &))); diff --git a/include/find_object/FindObject.h b/include/find_object/FindObject.h index 3e4c5cf9..ee929106 100644 --- a/include/find_object/FindObject.h +++ b/include/find_object/FindObject.h @@ -65,7 +65,7 @@ public: void removeObject(int id); void removeAllObjects(); - bool detect(const cv::Mat & image, DetectionInfo & info); + bool detect(const cv::Mat & image, find_object::DetectionInfo & info); void updateDetectorExtractor(); void updateObjects(); @@ -78,7 +78,7 @@ public Q_SLOTS: void detect(const cv::Mat & image); // emit objectsFound() Q_SIGNALS: - void objectsFound(const DetectionInfo &); + void objectsFound(const find_object::DetectionInfo &); private: void clearVocabulary(); diff --git a/include/find_object/MainWindow.h b/include/find_object/MainWindow.h index c27864e4..7264749d 100644 --- a/include/find_object/MainWindow.h +++ b/include/find_object/MainWindow.h @@ -66,7 +66,7 @@ class FINDOBJECT_EXP MainWindow : public QMainWindow Q_OBJECT public: - MainWindow(FindObject * findObject, Camera * camera = 0, QWidget * parent = 0); + MainWindow(find_object::FindObject * findObject, find_object::Camera * camera = 0, QWidget * parent = 0); virtual ~MainWindow(); void setSourceImageText(const QString & text); @@ -91,7 +91,7 @@ private Q_SLOTS: void setupCameraFromVideoFile(); void setupCameraFromImagesDirectory(); void setupCameraFromTcpIp(); - void removeObject(ObjWidget * object); + void removeObject(find_object::ObjWidget * object); void removeAllObjects(); void updateObjectsSize(); void updateMirrorView(); @@ -102,7 +102,7 @@ private Q_SLOTS: void rectHovered(int objId); Q_SIGNALS: - void objectsFound(const DetectionInfo &); + void objectsFound(const find_object::DetectionInfo &); private: bool loadSettings(const QString & path); @@ -111,8 +111,8 @@ private: int saveObjects(const QString & dirPath); void setupTCPServer(); bool addObjectFromFile(const QString & filePath); - void showObject(ObjWidget * obj); - void updateObjectSize(ObjWidget * obj); + void showObject(find_object::ObjWidget * obj); + void updateObjectSize(find_object::ObjWidget * obj); void updateVocabulary(); private: @@ -122,7 +122,7 @@ private: rtabmap::PdfPlotCurve * likelihoodCurve_; rtabmap::PdfPlotCurve * inliersCurve_; AboutDialog * aboutDialog_; - QMap objWidgets_; + QMap objWidgets_; QTime updateRate_; QTime refreshStartTime_; int lowestRefreshRate_; diff --git a/include/find_object/ObjWidget.h b/include/find_object/ObjWidget.h index 73ac7af9..04591570 100644 --- a/include/find_object/ObjWidget.h +++ b/include/find_object/ObjWidget.h @@ -96,7 +96,7 @@ protected: virtual void mouseReleaseEvent(QMouseEvent * event); Q_SIGNALS: - void removalTriggered(ObjWidget *); + void removalTriggered(find_object::ObjWidget *); void selectionChanged(); void roiChanged(const cv::Rect &); diff --git a/include/find_object/TcpServer.h b/include/find_object/TcpServer.h index acee1dd9..a5ee8a17 100644 --- a/include/find_object/TcpServer.h +++ b/include/find_object/TcpServer.h @@ -49,7 +49,7 @@ public: quint16 getPort() const; public Q_SLOTS: - void publishDetectionInfo(const DetectionInfo & info); + void publishDetectionInfo(const find_object::DetectionInfo & info); private Q_SLOTS: void addClient(); diff --git a/src/FindObject.cpp b/src/FindObject.cpp index d2e433cb..c9e82b41 100644 --- a/src/FindObject.cpp +++ b/src/FindObject.cpp @@ -48,7 +48,7 @@ FindObject::FindObject(QObject * parent) : detector_(Settings::createKeypointDetector()), extractor_(Settings::createDescriptorExtractor()) { - qRegisterMetaType("DetectionInfo"); + qRegisterMetaType("find_object::DetectionInfo"); Q_ASSERT(detector_ != 0 && extractor_ != 0); } @@ -655,7 +655,7 @@ void FindObject::detect(const cv::Mat & image) } } -bool FindObject::detect(const cv::Mat & image, DetectionInfo & info) +bool FindObject::detect(const cv::Mat & image, find_object::DetectionInfo & info) { QTime totalTime; totalTime.start(); diff --git a/src/MainWindow.cpp b/src/MainWindow.cpp index 8ff6d818..05ac6346 100644 --- a/src/MainWindow.cpp +++ b/src/MainWindow.cpp @@ -294,7 +294,7 @@ void MainWindow::setupTCPServer() delete tcpServer_; } tcpServer_ = new TcpServer(Settings::getGeneral_port(), this); - connect(this, SIGNAL(objectsFound(DetectionInfo)), tcpServer_, SLOT(publishDetectionInfo(DetectionInfo))); + connect(this, SIGNAL(objectsFound(find_object::DetectionInfo)), tcpServer_, SLOT(publishDetectionInfo(find_object::DetectionInfo))); ui_->label_ipAddress->setText(tcpServer_->getHostAddress().toString()); ui_->label_port->setNum(tcpServer_->getPort()); UINFO("Detection sent on port: %d (IP=%s)", tcpServer_->getPort(), tcpServer_->getHostAddress().toString().toStdString().c_str()); @@ -446,7 +446,7 @@ bool MainWindow::saveObjects() return false; } -void MainWindow::removeObject(ObjWidget * object) +void MainWindow::removeObject(find_object::ObjWidget * object) { if(object) { @@ -735,7 +735,7 @@ void MainWindow::showObject(ObjWidget * obj) vLayout->addLayout(hLayout); vLayout->addWidget(obj); obj->setDeletable(true); - connect(obj, SIGNAL(removalTriggered(ObjWidget*)), this, SLOT(removeObject(ObjWidget*))); + connect(obj, SIGNAL(removalTriggered(find_object::ObjWidget*)), this, SLOT(removeObject(find_object::ObjWidget*))); connect(obj, SIGNAL(destroyed(QObject *)), title, SLOT(deleteLater())); connect(obj, SIGNAL(destroyed(QObject *)), detectedLabel, SLOT(deleteLater())); connect(obj, SIGNAL(destroyed(QObject *)), detectorDescriptorType, SLOT(deleteLater())); diff --git a/tools/tcpClient/TcpClient.cpp b/tools/tcpClient/TcpClient.cpp index 7c0ef363..decf5d9b 100644 --- a/tools/tcpClient/TcpClient.cpp +++ b/tools/tcpClient/TcpClient.cpp @@ -32,8 +32,6 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include -using namespace find_object; - TcpClient::TcpClient(QObject *parent) : QTcpSocket(parent), blockSize_(0) @@ -65,7 +63,7 @@ void TcpClient::readReceivedData() blockSize_ = 0; - DetectionInfo info; + find_object::DetectionInfo info; in >> info; printf("---\n"); diff --git a/tools/tcpImagesServer/ImagesTcpServer.cpp b/tools/tcpImagesServer/ImagesTcpServer.cpp index f9bbcbe1..115bffd1 100644 --- a/tools/tcpImagesServer/ImagesTcpServer.cpp +++ b/tools/tcpImagesServer/ImagesTcpServer.cpp @@ -33,14 +33,12 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include -using namespace find_object; - ImagesTcpServer::ImagesTcpServer(float hz, const QString & path, QObject * parent) : QTcpSocket(parent) { // Set camera parameters - Settings::setCamera_4imageRate(hz); - Settings::setCamera_5mediaPath(path); + find_object::Settings::setCamera_4imageRate(hz); + find_object::Settings::setCamera_5mediaPath(path); connect(&camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(publishImage(const cv::Mat &))); connect(this, SIGNAL(connected()), this, SLOT(startCamera())); diff --git a/tools/tcpRequest/main.cpp b/tools/tcpRequest/main.cpp index edfe7564..533a6b76 100644 --- a/tools/tcpRequest/main.cpp +++ b/tools/tcpRequest/main.cpp @@ -33,8 +33,6 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include "TcpResponse.h" #include "find_object/JsonWriter.h" -using namespace find_object; - void showUsage() { printf("\ntcpRequest [options] --scene image.png --out # --in #\n" @@ -42,7 +40,7 @@ void showUsage() " \"in\" is the port from which the detection is received.\n" " Options:\n" " --host #.#.#.# Set host address.\n"); - if(JsonWriter::available()) + if(find_object::JsonWriter::available()) { printf(" --json \"path\" Path to an output JSON file.\n"); } @@ -116,7 +114,7 @@ int main(int argc, char * argv[]) continue; } - if(JsonWriter::available()) + if(find_object::JsonWriter::available()) { if(strcmp(argv[i], "--json") == 0 || strcmp(argv[i], "-json") == 0) { @@ -236,9 +234,9 @@ int main(int argc, char * argv[]) printf("No objects detected.\n"); } // write json - if(!jsonPath.isEmpty() && JsonWriter::available()) + if(!jsonPath.isEmpty() && find_object::JsonWriter::available()) { - JsonWriter::write(response.info(), jsonPath); + find_object::JsonWriter::write(response.info(), jsonPath); printf("JSON written to \"%s\"\n", jsonPath.toStdString().c_str()); } }