Added parameter General/sendNoObjDetectedEvents

git-svn-id: http://find-object.googlecode.com/svn/trunk/find_object@284 620bd6b2-0a58-f614-fd9a-1bd335dccda9
This commit is contained in:
matlabbe 2014-05-22 17:47:00 +00:00
parent 9422df9965
commit 6478e78899
4 changed files with 91 additions and 81 deletions

View File

@ -1716,12 +1716,16 @@ void MainWindow::update(const cv::Mat & image)
QTime::currentTime().toString("HH:mm:ss.zzz").toStdString().c_str(),
(int)objectsDetected.begin().key());
}
else
else if(Settings::getGeneral_sendNoObjDetectedEvents())
{
printf("(%s) No objects detected.\n",
QTime::currentTime().toString("HH:mm:ss.zzz").toStdString().c_str());
}
emit objectsFound(objectsDetected);
if(objectsDetected.size() > 0 || Settings::getGeneral_sendNoObjDetectedEvents())
{
emit objectsFound(objectsDetected);
}
ui_->label_objectsDetected->setNum(objectsDetected.size());
}
else

View File

@ -183,6 +183,7 @@ class Settings
PARAMETER(General, autoScroll, bool, true, "Auto scroll to detected object in Objects panel.");
PARAMETER(General, vocabularyIncremental, bool, false, "The vocabulary is created incrementally. When new objects are added, their descriptors are compared to those already in vocabulary to find if the visual word already exist or not. \"NearestNeighbor/nndrRatio\" is used to compare descriptors.");
PARAMETER(General, vocabularyUpdateMinWords, int, 2000, "When the vocabulary is incremental (see \"General/vocabularyIncremental\"), after X words added to vocabulary, the internal index is updated with new words. This parameter lets avoiding to reconstruct the whole nearest neighbor index after each time descriptors of an object are added to vocabulary. 0 means no incremental update.");
PARAMETER(General, sendNoObjDetectedEvents, bool, true, "When there are no objects detected, send an empty object detection event.");
PARAMETER(Homography, homographyComputed, bool, true, "Compute homography? On ROS, this is required to publish objects detected.");
PARAMETER(Homography, method, QString, "1:LMEDS;RANSAC", "Type of the robust estimation algorithm: least-median algorithm or RANSAC algorithm.");

View File

@ -54,40 +54,37 @@ quint16 TcpServer::getPort() const
void TcpServer::publishObjects(const QMultiMap<int, QPair<QRect, QTransform> > & objects)
{
if(objects.size())
QList<QTcpSocket*> clients = this->findChildren<QTcpSocket*>();
if(clients.size())
{
QList<QTcpSocket*> clients = this->findChildren<QTcpSocket*>();
if(clients.size())
QVector<float> data(objects.size()*12);
int i=0;
for(QMultiMap<int, QPair<QRect, QTransform> >::const_iterator iter=objects.constBegin(); iter!=objects.constEnd(); ++iter)
{
QVector<float> data(objects.size()*12);
int i=0;
for(QMultiMap<int, QPair<QRect, QTransform> >::const_iterator iter=objects.constBegin(); iter!=objects.constEnd(); ++iter)
{
data[i++] = iter.key();
data[i++] = iter.value().first.width();
data[i++] = iter.value().first.height();
data[i++] = iter.value().second.m11();
data[i++] = iter.value().second.m12();
data[i++] = iter.value().second.m13();
data[i++] = iter.value().second.m21();
data[i++] = iter.value().second.m22();
data[i++] = iter.value().second.m23();
data[i++] = iter.value().second.m31(); // dx
data[i++] = iter.value().second.m32(); // dy
data[i++] = iter.value().second.m33();
}
data[i++] = iter.key();
data[i++] = iter.value().first.width();
data[i++] = iter.value().first.height();
data[i++] = iter.value().second.m11();
data[i++] = iter.value().second.m12();
data[i++] = iter.value().second.m13();
data[i++] = iter.value().second.m21();
data[i++] = iter.value().second.m22();
data[i++] = iter.value().second.m23();
data[i++] = iter.value().second.m31(); // dx
data[i++] = iter.value().second.m32(); // dy
data[i++] = iter.value().second.m33();
}
for(QList<QTcpSocket*>::iterator iter = clients.begin(); iter!=clients.end(); ++iter)
{
QByteArray block;
QDataStream out(&block, QIODevice::WriteOnly);
out.setVersion(QDataStream::Qt_4_0);
out << (quint16)0;
out << data;
out.device()->seek(0);
out << (quint16)(block.size() - sizeof(quint16));
(*iter)->write(block);
}
for(QList<QTcpSocket*>::iterator iter = clients.begin(); iter!=clients.end(); ++iter)
{
QByteArray block;
QDataStream out(&block, QIODevice::WriteOnly);
out.setVersion(QDataStream::Qt_4_0);
out << (quint16)0;
out << data;
out.device()->seek(0);
out << (quint16)(block.size() - sizeof(quint16));
(*iter)->write(block);
}
}
}

View File

@ -49,59 +49,67 @@ void TcpClient::readData()
in >> data;
printf("---\n");
for(int i=0; i<data.size(); i+=12)
if(data.size() == 0)
{
// get data
int id = (int)data[i];
float objectWidth = data[i+1];
float objectHeight = data[i+2];
// Find corners Qt
QTransform qtHomography(data[i+3], data[i+4], data[i+5],
data[i+6], data[i+7], data[i+8],
data[i+9], data[i+10], data[i+11]);
QPointF qtTopLeft = qtHomography.map(QPointF(0,0));
QPointF qtTopRight = qtHomography.map(QPointF(objectWidth,0));
QPointF qtBottomLeft = qtHomography.map(QPointF(0,objectHeight));
QPointF qtBottomRight = qtHomography.map(QPointF(objectWidth,objectHeight));
printf("(%s) Object %d detected, Qt corners at (%f,%f) (%f,%f) (%f,%f) (%f,%f)\n",
QTime::currentTime().toString("HH:mm:ss.zzz").toStdString().c_str(),
id,
qtTopLeft.x(), qtTopLeft.y(),
qtTopRight.x(), qtTopRight.y(),
qtBottomLeft.x(), qtBottomLeft.y(),
qtBottomRight.x(), qtBottomRight.y());
// Example with OpenCV
if(0)
printf("(%s) No objects detected.\n",
QTime::currentTime().toString("HH:mm:ss.zzz").toStdString().c_str());
}
else
{
for(int i=0; i<data.size(); i+=12)
{
// Find corners OpenCV
cv::Mat cvHomography(3, 3, CV_32F);
cvHomography.at<float>(0,0) = data[i+3];
cvHomography.at<float>(1,0) = data[i+4];
cvHomography.at<float>(2,0) = data[i+5];
cvHomography.at<float>(0,1) = data[i+6];
cvHomography.at<float>(1,1) = data[i+7];
cvHomography.at<float>(2,1) = data[i+8];
cvHomography.at<float>(0,2) = data[i+9];
cvHomography.at<float>(1,2) = data[i+10];
cvHomography.at<float>(2,2) = data[i+11];
std::vector<cv::Point2f> inPts, outPts;
inPts.push_back(cv::Point2f(0,0));
inPts.push_back(cv::Point2f(objectWidth,0));
inPts.push_back(cv::Point2f(0,objectHeight));
inPts.push_back(cv::Point2f(objectWidth,objectHeight));
cv::perspectiveTransform(inPts, outPts, cvHomography);
// get data
int id = (int)data[i];
float objectWidth = data[i+1];
float objectHeight = data[i+2];
printf("(%s) Object %d detected, CV corners at (%f,%f) (%f,%f) (%f,%f) (%f,%f)\n",
// Find corners Qt
QTransform qtHomography(data[i+3], data[i+4], data[i+5],
data[i+6], data[i+7], data[i+8],
data[i+9], data[i+10], data[i+11]);
QPointF qtTopLeft = qtHomography.map(QPointF(0,0));
QPointF qtTopRight = qtHomography.map(QPointF(objectWidth,0));
QPointF qtBottomLeft = qtHomography.map(QPointF(0,objectHeight));
QPointF qtBottomRight = qtHomography.map(QPointF(objectWidth,objectHeight));
printf("(%s) Object %d detected, Qt corners at (%f,%f) (%f,%f) (%f,%f) (%f,%f)\n",
QTime::currentTime().toString("HH:mm:ss.zzz").toStdString().c_str(),
id,
outPts.at(0).x, outPts.at(0).y,
outPts.at(1).x, outPts.at(1).y,
outPts.at(2).x, outPts.at(2).y,
outPts.at(3).x, outPts.at(3).y);
qtTopLeft.x(), qtTopLeft.y(),
qtTopRight.x(), qtTopRight.y(),
qtBottomLeft.x(), qtBottomLeft.y(),
qtBottomRight.x(), qtBottomRight.y());
// Example with OpenCV
if(0)
{
// Find corners OpenCV
cv::Mat cvHomography(3, 3, CV_32F);
cvHomography.at<float>(0,0) = data[i+3];
cvHomography.at<float>(1,0) = data[i+4];
cvHomography.at<float>(2,0) = data[i+5];
cvHomography.at<float>(0,1) = data[i+6];
cvHomography.at<float>(1,1) = data[i+7];
cvHomography.at<float>(2,1) = data[i+8];
cvHomography.at<float>(0,2) = data[i+9];
cvHomography.at<float>(1,2) = data[i+10];
cvHomography.at<float>(2,2) = data[i+11];
std::vector<cv::Point2f> inPts, outPts;
inPts.push_back(cv::Point2f(0,0));
inPts.push_back(cv::Point2f(objectWidth,0));
inPts.push_back(cv::Point2f(0,objectHeight));
inPts.push_back(cv::Point2f(objectWidth,objectHeight));
cv::perspectiveTransform(inPts, outPts, cvHomography);
printf("(%s) Object %d detected, CV corners at (%f,%f) (%f,%f) (%f,%f) (%f,%f)\n",
QTime::currentTime().toString("HH:mm:ss.zzz").toStdString().c_str(),
id,
outPts.at(0).x, outPts.at(0).y,
outPts.at(1).x, outPts.at(1).y,
outPts.at(2).x, outPts.at(2).y,
outPts.at(3).x, outPts.at(3).y);
}
}
}
}