New camera interface using signals/slots (for ROS nodes)
git-svn-id: http://find-object.googlecode.com/svn/trunk/find_object@34 620bd6b2-0a58-f614-fd9a-1bd335dccda9
This commit is contained in:
parent
45f6b9fd17
commit
acb12ac688
@ -5,6 +5,7 @@
|
|||||||
#include "KeypointItem.h"
|
#include "KeypointItem.h"
|
||||||
#include "Camera.h"
|
#include "Camera.h"
|
||||||
#include "qtipl.h"
|
#include "qtipl.h"
|
||||||
|
#include "Settings.h"
|
||||||
|
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
|
|
||||||
@ -15,19 +16,15 @@
|
|||||||
#include <opencv2/imgproc/imgproc_c.h>
|
#include <opencv2/imgproc/imgproc_c.h>
|
||||||
#include <opencv2/highgui/highgui_c.h>
|
#include <opencv2/highgui/highgui_c.h>
|
||||||
|
|
||||||
AddObjectDialog::AddObjectDialog(QList<ObjWidget*> * objects, QWidget * parent, Qt::WindowFlags f) :
|
AddObjectDialog::AddObjectDialog(Camera * camera, QList<ObjWidget*> * objects, QWidget * parent, Qt::WindowFlags f) :
|
||||||
QDialog(parent, f),
|
QDialog(parent, f),
|
||||||
camera_(0),
|
camera_(camera),
|
||||||
objects_(objects),
|
objects_(objects),
|
||||||
cvImage_(0)
|
cvImage_(0)
|
||||||
{
|
{
|
||||||
ui_ = new Ui_addObjectDialog();
|
ui_ = new Ui_addObjectDialog();
|
||||||
ui_->setupUi(this);
|
ui_->setupUi(this);
|
||||||
|
|
||||||
camera_ = Settings::createCamera();
|
|
||||||
|
|
||||||
connect(&cameraTimer_, SIGNAL(timeout()), this, SLOT(update()));
|
|
||||||
|
|
||||||
connect(ui_->pushButton_cancel, SIGNAL(clicked()), this, SLOT(cancel()));
|
connect(ui_->pushButton_cancel, SIGNAL(clicked()), this, SLOT(cancel()));
|
||||||
connect(ui_->pushButton_back, SIGNAL(clicked()), this, SLOT(back()));
|
connect(ui_->pushButton_back, SIGNAL(clicked()), this, SLOT(back()));
|
||||||
connect(ui_->pushButton_next, SIGNAL(clicked()), this, SLOT(next()));
|
connect(ui_->pushButton_next, SIGNAL(clicked()), this, SLOT(next()));
|
||||||
@ -44,15 +41,12 @@ AddObjectDialog::~AddObjectDialog()
|
|||||||
{
|
{
|
||||||
cvReleaseImage(&cvImage_);
|
cvReleaseImage(&cvImage_);
|
||||||
}
|
}
|
||||||
if(camera_)
|
|
||||||
{
|
|
||||||
delete camera_;
|
|
||||||
}
|
|
||||||
delete ui_;
|
delete ui_;
|
||||||
}
|
}
|
||||||
|
|
||||||
void AddObjectDialog::closeEvent(QCloseEvent* event)
|
void AddObjectDialog::closeEvent(QCloseEvent* event)
|
||||||
{
|
{
|
||||||
|
disconnect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)));
|
||||||
QDialog::closeEvent(event);
|
QDialog::closeEvent(event);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -102,20 +96,20 @@ void AddObjectDialog::setState(int state)
|
|||||||
ui_->cameraView->setVisible(true);
|
ui_->cameraView->setVisible(true);
|
||||||
ui_->objectView->setVisible(false);
|
ui_->objectView->setVisible(false);
|
||||||
ui_->cameraView->setGraphicsViewMode(false);
|
ui_->cameraView->setGraphicsViewMode(false);
|
||||||
if(!camera_->init())
|
if(!camera_ || !camera_->start())
|
||||||
{
|
{
|
||||||
QMessageBox::critical(this, tr("Camera error"), tr("Camera initialization failed! (with device %1)").arg(Settings::getCamera_deviceId().toInt()));
|
QMessageBox::critical(this, tr("Camera error"), tr("Camera is not started!"));
|
||||||
ui_->pushButton_takePicture->setEnabled(false);
|
ui_->pushButton_takePicture->setEnabled(false);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
cameraTimer_.start(1000/Settings::getCamera_imageRate().toInt());
|
connect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else if(state == kSelectFeatures)
|
else if(state == kSelectFeatures)
|
||||||
{
|
{
|
||||||
cameraTimer_.stop();
|
disconnect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)));
|
||||||
camera_->close();
|
camera_->stop();
|
||||||
|
|
||||||
ui_->pushButton_cancel->setEnabled(true);
|
ui_->pushButton_cancel->setEnabled(true);
|
||||||
ui_->pushButton_back->setEnabled(true);
|
ui_->pushButton_back->setEnabled(true);
|
||||||
@ -130,8 +124,8 @@ void AddObjectDialog::setState(int state)
|
|||||||
}
|
}
|
||||||
else if(state == kVerifySelection)
|
else if(state == kVerifySelection)
|
||||||
{
|
{
|
||||||
cameraTimer_.stop();
|
disconnect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)));
|
||||||
camera_->close();
|
camera_->stop();
|
||||||
|
|
||||||
ui_->pushButton_cancel->setEnabled(true);
|
ui_->pushButton_cancel->setEnabled(true);
|
||||||
ui_->pushButton_back->setEnabled(true);
|
ui_->pushButton_back->setEnabled(true);
|
||||||
@ -204,14 +198,15 @@ void AddObjectDialog::setState(int state)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void AddObjectDialog::update()
|
void AddObjectDialog::update(const cv::Mat & image)
|
||||||
{
|
{
|
||||||
if(cvImage_)
|
if(cvImage_)
|
||||||
{
|
{
|
||||||
cvReleaseImage(&cvImage_);
|
cvReleaseImage(&cvImage_);
|
||||||
cvImage_ = 0;
|
cvImage_ = 0;
|
||||||
}
|
}
|
||||||
cvImage_ = camera_->takeImage();
|
IplImage iplImage = image;
|
||||||
|
cvImage_ = cvCloneImage(& iplImage);
|
||||||
if(cvImage_)
|
if(cvImage_)
|
||||||
{
|
{
|
||||||
// convert to grayscale
|
// convert to grayscale
|
||||||
|
|||||||
@ -16,11 +16,11 @@ class AddObjectDialog : public QDialog {
|
|||||||
Q_OBJECT
|
Q_OBJECT
|
||||||
|
|
||||||
public:
|
public:
|
||||||
AddObjectDialog(QList<ObjWidget*> * objects, QWidget * parent = 0, Qt::WindowFlags f = 0);
|
AddObjectDialog(Camera * camera, QList<ObjWidget*> * objects, QWidget * parent = 0, Qt::WindowFlags f = 0);
|
||||||
virtual ~AddObjectDialog();
|
virtual ~AddObjectDialog();
|
||||||
|
|
||||||
private slots:
|
private slots:
|
||||||
void update();
|
void update(const cv::Mat &);
|
||||||
void next();
|
void next();
|
||||||
void back();
|
void back();
|
||||||
void cancel();
|
void cancel();
|
||||||
@ -36,7 +36,6 @@ private:
|
|||||||
private:
|
private:
|
||||||
Ui_addObjectDialog * ui_;
|
Ui_addObjectDialog * ui_;
|
||||||
Camera * camera_;
|
Camera * camera_;
|
||||||
QTimer cameraTimer_;
|
|
||||||
QList<ObjWidget*> * objects_;
|
QList<ObjWidget*> * objects_;
|
||||||
IplImage * cvImage_;
|
IplImage * cvImage_;
|
||||||
|
|
||||||
|
|||||||
@ -8,45 +8,23 @@
|
|||||||
#include "Camera.h"
|
#include "Camera.h"
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <opencv2/imgproc/imgproc_c.h>
|
#include <opencv2/imgproc/imgproc_c.h>
|
||||||
|
#include "Settings.h"
|
||||||
|
|
||||||
Camera::Camera(int deviceId,
|
Camera::Camera(QObject * parent) :
|
||||||
int imageWidth,
|
|
||||||
int imageHeight,
|
|
||||||
QObject * parent) :
|
|
||||||
QObject(parent),
|
QObject(parent),
|
||||||
capture_(0),
|
capture_(0)
|
||||||
deviceId_(deviceId),
|
|
||||||
imageWidth_(imageWidth),
|
|
||||||
imageHeight_(imageHeight)
|
|
||||||
{
|
{
|
||||||
|
connect(&cameraTimer_, SIGNAL(timeout()), this, SLOT(takeImage()));
|
||||||
}
|
}
|
||||||
|
|
||||||
Camera::~Camera()
|
Camera::~Camera()
|
||||||
{
|
{
|
||||||
this->close();
|
this->stop();
|
||||||
}
|
}
|
||||||
|
|
||||||
bool Camera::init()
|
void Camera::stop()
|
||||||
{
|
|
||||||
if(!capture_)
|
|
||||||
{
|
|
||||||
capture_ = cvCaptureFromCAM(deviceId_);
|
|
||||||
if(capture_)
|
|
||||||
{
|
|
||||||
cvSetCaptureProperty(capture_, CV_CAP_PROP_FRAME_WIDTH, double(imageWidth_));
|
|
||||||
cvSetCaptureProperty(capture_, CV_CAP_PROP_FRAME_HEIGHT, double(imageHeight_));
|
|
||||||
}
|
|
||||||
}
|
|
||||||
if(!capture_)
|
|
||||||
{
|
|
||||||
printf("Failed to create a capture object!\n");
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
void Camera::close()
|
|
||||||
{
|
{
|
||||||
|
cameraTimer_.stop();
|
||||||
if(capture_)
|
if(capture_)
|
||||||
{
|
{
|
||||||
cvReleaseCapture(&capture_);
|
cvReleaseCapture(&capture_);
|
||||||
@ -54,11 +32,11 @@ void Camera::close()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
IplImage * Camera::takeImage()
|
void Camera::takeImage()
|
||||||
{
|
{
|
||||||
IplImage * img = 0;
|
|
||||||
if(capture_)
|
if(capture_)
|
||||||
{
|
{
|
||||||
|
IplImage * img = 0;
|
||||||
if(cvGrabFrame(capture_)) // capture a frame
|
if(cvGrabFrame(capture_)) // capture a frame
|
||||||
{
|
{
|
||||||
img = cvRetrieveFrame(capture_); // retrieve the captured frame
|
img = cvRetrieveFrame(capture_); // retrieve the captured frame
|
||||||
@ -67,29 +45,57 @@ IplImage * Camera::takeImage()
|
|||||||
{
|
{
|
||||||
printf("CameraVideo: Could not grab a frame, the end of the feed may be reached...\n");
|
printf("CameraVideo: Could not grab a frame, the end of the feed may be reached...\n");
|
||||||
}
|
}
|
||||||
}
|
|
||||||
|
|
||||||
//resize
|
//resize
|
||||||
if(img &&
|
if(img &&
|
||||||
imageWidth_ &&
|
Settings::getCamera_imageWidth().toInt() &&
|
||||||
imageHeight_ &&
|
Settings::getCamera_imageHeight().toInt() &&
|
||||||
imageWidth_ != (unsigned int)img->width &&
|
Settings::getCamera_imageWidth().toInt() != (unsigned int)img->width &&
|
||||||
imageHeight_ != (unsigned int)img->height)
|
Settings::getCamera_imageHeight().toInt() != (unsigned int)img->height)
|
||||||
{
|
{
|
||||||
// declare a destination IplImage object with correct size, depth and channels
|
// declare a destination IplImage object with correct size, depth and channels
|
||||||
IplImage * resampledImg = cvCreateImage( cvSize(imageWidth_, imageHeight_),
|
cv::Mat imgMat(cvSize(Settings::getCamera_imageWidth().toInt(), Settings::getCamera_imageHeight().toInt()),
|
||||||
img->depth,
|
img->depth,
|
||||||
img->nChannels );
|
img->nChannels );
|
||||||
|
|
||||||
//use cvResize to resize source to a destination image (linear interpolation)
|
//use cvResize to resize source to a destination image (linear interpolation)
|
||||||
cvResize(img, resampledImg);
|
IplImage resampledImg = imgMat;
|
||||||
img = resampledImg;
|
cvResize(img, &resampledImg);
|
||||||
|
emit imageReceived(imgMat);
|
||||||
}
|
}
|
||||||
else if(img)
|
else
|
||||||
{
|
{
|
||||||
img = cvCloneImage(img);
|
emit imageReceived(cv::Mat(img, true));
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
return img;
|
bool Camera::start()
|
||||||
|
{
|
||||||
|
if(!capture_)
|
||||||
|
{
|
||||||
|
if(!capture_)
|
||||||
|
{
|
||||||
|
capture_ = cvCaptureFromCAM(Settings::getCamera_deviceId().toInt());
|
||||||
|
if(capture_)
|
||||||
|
{
|
||||||
|
cvSetCaptureProperty(capture_, CV_CAP_PROP_FRAME_WIDTH, double(Settings::getCamera_imageWidth().toInt()));
|
||||||
|
cvSetCaptureProperty(capture_, CV_CAP_PROP_FRAME_HEIGHT, double(Settings::getCamera_imageHeight().toInt()));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if(!capture_)
|
||||||
|
{
|
||||||
|
printf("Failed to create a capture object!\n");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
cameraTimer_.start(1000/Settings::getCamera_imageRate().toInt());
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void Camera::updateImageRate()
|
||||||
|
{
|
||||||
|
cameraTimer_.setInterval(1000/Settings::getCamera_imageRate().toInt());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
31
src/Camera.h
31
src/Camera.h
@ -10,38 +10,29 @@
|
|||||||
|
|
||||||
#include <opencv2/highgui/highgui.hpp>
|
#include <opencv2/highgui/highgui.hpp>
|
||||||
#include <QtCore/QObject>
|
#include <QtCore/QObject>
|
||||||
#include "Settings.h"
|
#include <QtCore/QTimer>
|
||||||
|
|
||||||
class Camera : public QObject {
|
class Camera : public QObject {
|
||||||
Q_OBJECT
|
Q_OBJECT
|
||||||
public:
|
public:
|
||||||
Camera(int deviceId = Settings::defaultCamera_deviceId(),
|
Camera(QObject * parent = 0);
|
||||||
int width = Settings::defaultCamera_imageWidth(),
|
|
||||||
int height = Settings::defaultCamera_imageHeight(),
|
|
||||||
QObject * parent = 0);
|
|
||||||
virtual ~Camera();
|
virtual ~Camera();
|
||||||
|
|
||||||
void setDeviceId(int deviceId) {deviceId_=deviceId;}
|
virtual bool start();
|
||||||
void setImageWidth(int imageWidth) {imageWidth_=imageWidth;}
|
virtual void stop();
|
||||||
void setImageHeight(int imageHeight) {imageHeight_=imageHeight;}
|
|
||||||
|
|
||||||
int getDeviceId() const {return deviceId_;}
|
|
||||||
int getImageWidth() const {return imageWidth_;}
|
|
||||||
int getImageHeight() const {return imageHeight_;}
|
|
||||||
|
|
||||||
signals:
|
signals:
|
||||||
void ready();
|
void imageReceived(const cv::Mat & image);
|
||||||
|
|
||||||
public:
|
public slots:
|
||||||
bool init();
|
void updateImageRate();
|
||||||
void close();
|
|
||||||
IplImage * takeImage();
|
private slots:
|
||||||
|
void takeImage();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
CvCapture * capture_;
|
CvCapture * capture_;
|
||||||
int deviceId_;
|
QTimer cameraTimer_;
|
||||||
int imageWidth_;
|
|
||||||
int imageHeight_;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* CAMERA_H_ */
|
#endif /* CAMERA_H_ */
|
||||||
|
|||||||
@ -21,21 +21,34 @@
|
|||||||
#include <QtGui/QMessageBox>
|
#include <QtGui/QMessageBox>
|
||||||
#include <QtGui/QGraphicsScene>
|
#include <QtGui/QGraphicsScene>
|
||||||
#include <QtGui/QGraphicsRectItem>
|
#include <QtGui/QGraphicsRectItem>
|
||||||
|
#include <QtGui/QSpinBox>
|
||||||
|
|
||||||
MainWindow::MainWindow(QWidget * parent) :
|
// Camera ownership transferred
|
||||||
|
MainWindow::MainWindow(Camera * camera, QWidget * parent) :
|
||||||
QMainWindow(parent),
|
QMainWindow(parent),
|
||||||
camera_(0)
|
camera_(camera)
|
||||||
{
|
{
|
||||||
ui_ = new Ui_mainWindow();
|
ui_ = new Ui_mainWindow();
|
||||||
ui_->setupUi(this);
|
ui_->setupUi(this);
|
||||||
|
|
||||||
connect(&cameraTimer_, SIGNAL(timeout()), this, SLOT(update()));
|
if(!camera_)
|
||||||
|
{
|
||||||
|
camera_ = new Camera(this);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
camera_->setParent(this);
|
||||||
|
}
|
||||||
|
|
||||||
QByteArray geometry;
|
QByteArray geometry;
|
||||||
Settings::loadSettings(Settings::iniDefaultPath(), &geometry);
|
Settings::loadSettings(Settings::iniDefaultPath(), &geometry);
|
||||||
this->restoreGeometry(geometry);
|
this->restoreGeometry(geometry);
|
||||||
|
|
||||||
ui_->toolBox->setupUi();
|
ui_->toolBox->setupUi();
|
||||||
|
connect((QSpinBox*)ui_->toolBox->getParameterWidget(Settings::kCamera_imageRate()),
|
||||||
|
SIGNAL(editingFinished()),
|
||||||
|
camera_,
|
||||||
|
SLOT(updateImageRate()));
|
||||||
ui_->dockWidget_parameters->hide();
|
ui_->dockWidget_parameters->hide();
|
||||||
ui_->menuView->addAction(ui_->dockWidget_parameters->toggleViewAction());
|
ui_->menuView->addAction(ui_->dockWidget_parameters->toggleViewAction());
|
||||||
ui_->menuView->addAction(ui_->dockWidget_objects->toggleViewAction());
|
ui_->menuView->addAction(ui_->dockWidget_objects->toggleViewAction());
|
||||||
@ -59,12 +72,8 @@ MainWindow::MainWindow(QWidget * parent) :
|
|||||||
|
|
||||||
MainWindow::~MainWindow()
|
MainWindow::~MainWindow()
|
||||||
{
|
{
|
||||||
this->stopCamera();
|
disconnect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)));
|
||||||
if(camera_)
|
camera_->stop();
|
||||||
{
|
|
||||||
delete camera_;
|
|
||||||
camera_ = 0;
|
|
||||||
}
|
|
||||||
dataTree_ = cv::Mat();
|
dataTree_ = cv::Mat();
|
||||||
qDeleteAll(objects_.begin(), objects_.end());
|
qDeleteAll(objects_.begin(), objects_.end());
|
||||||
objects_.clear();
|
objects_.clear();
|
||||||
@ -145,7 +154,7 @@ void MainWindow::removeObject(ObjWidget * object)
|
|||||||
void MainWindow::addObject()
|
void MainWindow::addObject()
|
||||||
{
|
{
|
||||||
this->stopCamera();
|
this->stopCamera();
|
||||||
AddObjectDialog dialog(&objects_, this);
|
AddObjectDialog dialog(camera_, &objects_, this);
|
||||||
if(dialog.exec() == QDialog::Accepted)
|
if(dialog.exec() == QDialog::Accepted)
|
||||||
{
|
{
|
||||||
showObject(objects_.last());
|
showObject(objects_.last());
|
||||||
@ -248,16 +257,9 @@ void MainWindow::updateData()
|
|||||||
|
|
||||||
void MainWindow::startCamera()
|
void MainWindow::startCamera()
|
||||||
{
|
{
|
||||||
if(camera_)
|
if(camera_->start())
|
||||||
{
|
{
|
||||||
camera_->close();
|
connect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)));
|
||||||
delete camera_;
|
|
||||||
}
|
|
||||||
camera_ = Settings::createCamera();
|
|
||||||
connect(camera_, SIGNAL(ready()), this, SLOT(update()));
|
|
||||||
if(camera_->init())
|
|
||||||
{
|
|
||||||
cameraTimer_.start(1000/Settings::getCamera_imageRate().toInt());
|
|
||||||
ui_->actionStop_camera->setEnabled(true);
|
ui_->actionStop_camera->setEnabled(true);
|
||||||
ui_->actionStart_camera->setEnabled(false);
|
ui_->actionStart_camera->setEnabled(false);
|
||||||
}
|
}
|
||||||
@ -271,16 +273,14 @@ void MainWindow::stopCamera()
|
|||||||
{
|
{
|
||||||
if(camera_)
|
if(camera_)
|
||||||
{
|
{
|
||||||
cameraTimer_.stop();
|
disconnect(camera_, SIGNAL(imageReceived(const cv::Mat &)), this, SLOT(update(const cv::Mat &)));
|
||||||
camera_->close();
|
camera_->stop();
|
||||||
delete camera_;
|
|
||||||
camera_ = 0;
|
|
||||||
}
|
}
|
||||||
ui_->actionStop_camera->setEnabled(false);
|
ui_->actionStop_camera->setEnabled(false);
|
||||||
ui_->actionStart_camera->setEnabled(true);
|
ui_->actionStart_camera->setEnabled(true);
|
||||||
}
|
}
|
||||||
|
|
||||||
void MainWindow::update()
|
void MainWindow::update(const cv::Mat & image)
|
||||||
{
|
{
|
||||||
// reset objects color
|
// reset objects color
|
||||||
for(int i=0; i<objects_.size(); ++i)
|
for(int i=0; i<objects_.size(); ++i)
|
||||||
@ -288,20 +288,19 @@ void MainWindow::update()
|
|||||||
objects_[i]->resetKptsColor();
|
objects_[i]->resetKptsColor();
|
||||||
}
|
}
|
||||||
|
|
||||||
if(camera_)
|
if(!image.empty())
|
||||||
{
|
|
||||||
IplImage * cvImage = camera_->takeImage();
|
|
||||||
if(cvImage)
|
|
||||||
{
|
{
|
||||||
|
IplImage iplImage = image;
|
||||||
|
|
||||||
QTime time;
|
QTime time;
|
||||||
time.start();
|
time.start();
|
||||||
|
|
||||||
//Convert to grayscale
|
//Convert to grayscale
|
||||||
IplImage * imageGrayScale = 0;
|
IplImage * imageGrayScale = 0;
|
||||||
if(cvImage->nChannels != 1 || cvImage->depth != IPL_DEPTH_8U)
|
if(iplImage.nChannels != 1 || iplImage.depth != IPL_DEPTH_8U)
|
||||||
{
|
{
|
||||||
imageGrayScale = cvCreateImage(cvSize(cvImage->width,cvImage->height), IPL_DEPTH_8U, 1);
|
imageGrayScale = cvCreateImage(cvSize(iplImage.width,iplImage.height), IPL_DEPTH_8U, 1);
|
||||||
cvCvtColor(cvImage, imageGrayScale, CV_BGR2GRAY);
|
cvCvtColor(&iplImage, imageGrayScale, CV_BGR2GRAY);
|
||||||
}
|
}
|
||||||
cv::Mat img;
|
cv::Mat img;
|
||||||
if(imageGrayScale)
|
if(imageGrayScale)
|
||||||
@ -310,7 +309,7 @@ void MainWindow::update()
|
|||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
img = cv::Mat(cvImage);
|
img = cv::Mat(&iplImage);
|
||||||
}
|
}
|
||||||
|
|
||||||
// EXTRACT KEYPOINTS
|
// EXTRACT KEYPOINTS
|
||||||
@ -355,7 +354,7 @@ void MainWindow::update()
|
|||||||
|
|
||||||
|
|
||||||
// PROCESS RESULTS
|
// PROCESS RESULTS
|
||||||
ui_->imageView_source->setData(keypoints, cv::Mat(), cvImage);
|
ui_->imageView_source->setData(keypoints, cv::Mat(), &iplImage);
|
||||||
int j=0;
|
int j=0;
|
||||||
std::vector<cv::Point2f> mpts_1, mpts_2;
|
std::vector<cv::Point2f> mpts_1, mpts_2;
|
||||||
std::vector<int> indexes_1, indexes_2;
|
std::vector<int> indexes_1, indexes_2;
|
||||||
@ -454,7 +453,7 @@ void MainWindow::update()
|
|||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
ui_->imageView_source->setData(keypoints, cv::Mat(), cvImage);
|
ui_->imageView_source->setData(keypoints, cv::Mat(), &iplImage);
|
||||||
}
|
}
|
||||||
|
|
||||||
//Update object pictures
|
//Update object pictures
|
||||||
@ -466,10 +465,7 @@ void MainWindow::update()
|
|||||||
ui_->label_nfeatures->setText(QString::number(keypoints.size()));
|
ui_->label_nfeatures->setText(QString::number(keypoints.size()));
|
||||||
ui_->imageView_source->update();
|
ui_->imageView_source->update();
|
||||||
ui_->label_timeGui->setText(QString::number(time.restart()));
|
ui_->label_timeGui->setText(QString::number(time.restart()));
|
||||||
|
|
||||||
cvReleaseImage(&cvImage);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
ui_->label_detectorDescriptorType->setText(QString("%1/%2").arg(Settings::currentDetectorType()).arg(Settings::currentDescriptorType()));
|
ui_->label_detectorDescriptorType->setText(QString("%1/%2").arg(Settings::currentDetectorType()).arg(Settings::currentDescriptorType()));
|
||||||
ui_->label_timeRefreshRate->setText(QString("(%1 Hz - %2 Hz)").arg(QString::number(1000/cameraTimer_.interval())).arg(QString::number(int(1000.0f/(float)(updateRate_.restart()) + 1))));
|
ui_->label_timeRefreshRate->setText(QString("(%1 Hz - %2 Hz)").arg(QString::number(Settings::getCamera_imageRate().toInt())).arg(QString::number(int(1000.0f/(float)(updateRate_.restart()) + 1))));
|
||||||
}
|
}
|
||||||
|
|||||||
@ -23,7 +23,7 @@ class MainWindow : public QMainWindow
|
|||||||
Q_OBJECT
|
Q_OBJECT
|
||||||
|
|
||||||
public:
|
public:
|
||||||
MainWindow(QWidget * parent = 0);
|
MainWindow(Camera * camera = 0, QWidget * parent = 0);
|
||||||
virtual ~MainWindow();
|
virtual ~MainWindow();
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
@ -35,7 +35,7 @@ private slots:
|
|||||||
void stopCamera();
|
void stopCamera();
|
||||||
void loadObjects();
|
void loadObjects();
|
||||||
void saveObjects();
|
void saveObjects();
|
||||||
void update();
|
void update(const cv::Mat & image);
|
||||||
void updateData();
|
void updateData();
|
||||||
void removeObject(ObjWidget * object);
|
void removeObject(ObjWidget * object);
|
||||||
|
|
||||||
@ -46,7 +46,6 @@ private:
|
|||||||
Ui_mainWindow * ui_;
|
Ui_mainWindow * ui_;
|
||||||
Camera * camera_;
|
Camera * camera_;
|
||||||
QList<ObjWidget*> objects_;
|
QList<ObjWidget*> objects_;
|
||||||
QTimer cameraTimer_;
|
|
||||||
cv::Mat dataTree_;
|
cv::Mat dataTree_;
|
||||||
QList<int> dataRange_;
|
QList<int> dataRange_;
|
||||||
QTime updateRate_;
|
QTime updateRate_;
|
||||||
|
|||||||
@ -1,17 +1,3 @@
|
|||||||
/*
|
|
||||||
* Object.cpp
|
|
||||||
*
|
|
||||||
* Created on: 2011-10-23
|
|
||||||
* Author: matlab
|
|
||||||
*/
|
|
||||||
|
|
||||||
|
|
||||||
/*
|
|
||||||
* VisualObject.h
|
|
||||||
*
|
|
||||||
* Created on: 2011-10-21
|
|
||||||
* Author: matlab
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include "ObjWidget.h"
|
#include "ObjWidget.h"
|
||||||
#include "KeypointItem.h"
|
#include "KeypointItem.h"
|
||||||
|
|||||||
@ -25,6 +25,11 @@ ParametersToolBox::~ParametersToolBox()
|
|||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
QWidget * ParametersToolBox::getParameterWidget(const QString & key)
|
||||||
|
{
|
||||||
|
return this->findChild<QWidget*>(key);
|
||||||
|
}
|
||||||
|
|
||||||
void ParametersToolBox::resetCurrentPage()
|
void ParametersToolBox::resetCurrentPage()
|
||||||
{
|
{
|
||||||
const QObjectList & children = this->widget(this->currentIndex())->children();
|
const QObjectList & children = this->widget(this->currentIndex())->children();
|
||||||
|
|||||||
@ -22,6 +22,7 @@ public:
|
|||||||
virtual ~ParametersToolBox();
|
virtual ~ParametersToolBox();
|
||||||
|
|
||||||
void setupUi();
|
void setupUi();
|
||||||
|
QWidget * getParameterWidget(const QString & key);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
void addParameter(QVBoxLayout * layout, const QString & key, const QVariant & value);
|
void addParameter(QVBoxLayout * layout, const QString & key, const QVariant & value);
|
||||||
@ -36,7 +37,6 @@ private slots:
|
|||||||
void changeParameter(const QString & value);
|
void changeParameter(const QString & value);
|
||||||
void changeParameter(const int & value);
|
void changeParameter(const int & value);
|
||||||
void resetCurrentPage();
|
void resetCurrentPage();
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* PARAMETERSTOOLBOX_H_ */
|
#endif /* PARAMETERSTOOLBOX_H_ */
|
||||||
|
|||||||
@ -291,14 +291,6 @@ cv::DescriptorExtractor * Settings::createDescriptorsExtractor()
|
|||||||
return extractor;
|
return extractor;
|
||||||
}
|
}
|
||||||
|
|
||||||
Camera * Settings::createCamera()
|
|
||||||
{
|
|
||||||
return new Camera(
|
|
||||||
getCamera_deviceId().toInt(),
|
|
||||||
getCamera_imageWidth().toInt(),
|
|
||||||
getCamera_imageHeight().toInt());
|
|
||||||
}
|
|
||||||
|
|
||||||
QString Settings::currentDetectorType()
|
QString Settings::currentDetectorType()
|
||||||
{
|
{
|
||||||
int index = Settings::getDetector_Type().toString().split(':').first().toInt();
|
int index = Settings::getDetector_Type().toString().split(':').first().toInt();
|
||||||
|
|||||||
@ -136,8 +136,6 @@ public:
|
|||||||
static QString currentDescriptorType();
|
static QString currentDescriptorType();
|
||||||
static QString currentDetectorType();
|
static QString currentDetectorType();
|
||||||
|
|
||||||
static Camera * createCamera();
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
Settings(){}
|
Settings(){}
|
||||||
|
|
||||||
|
|||||||
Loading…
x
Reference in New Issue
Block a user