Fixed some crash issues between descriptor type / nearest neighbor strategy required data type / nearest neighbor distance type.
Added selective update on objects when parameters are changed. git-svn-id: http://find-object.googlecode.com/svn/trunk/find_object@112 620bd6b2-0a58-f614-fd9a-1bd335dccda9
This commit is contained in:
parent
3ba8c95284
commit
a6dc94a31d
@ -32,6 +32,7 @@
|
|||||||
#include <QtGui/QProgressDialog>
|
#include <QtGui/QProgressDialog>
|
||||||
#include <QtGui/QCloseEvent>
|
#include <QtGui/QCloseEvent>
|
||||||
#include <QtGui/QCheckBox>
|
#include <QtGui/QCheckBox>
|
||||||
|
#include <QtGui/QScrollBar>
|
||||||
|
|
||||||
#include "utilite/UDirectory.h"
|
#include "utilite/UDirectory.h"
|
||||||
|
|
||||||
@ -48,8 +49,8 @@ MainWindow::MainWindow(Camera * camera, QWidget * parent) :
|
|||||||
aboutDialog_ = new AboutDialog(this);
|
aboutDialog_ = new AboutDialog(this);
|
||||||
this->setStatusBar(new QStatusBar());
|
this->setStatusBar(new QStatusBar());
|
||||||
|
|
||||||
likelihoodCurve_ = new rtabmap::PdfPlotCurve("Likelihood", &imagesMap_);
|
likelihoodCurve_ = new rtabmap::PdfPlotCurve("Likelihood", &imagesMap_, this);
|
||||||
ui_->likelihoodPlot->addCurve(likelihoodCurve_); // ownership transfered
|
ui_->likelihoodPlot->addCurve(likelihoodCurve_, false);
|
||||||
ui_->likelihoodPlot->setGraphicsView(true);
|
ui_->likelihoodPlot->setGraphicsView(true);
|
||||||
|
|
||||||
if(!camera_)
|
if(!camera_)
|
||||||
@ -79,7 +80,7 @@ MainWindow::MainWindow(Camera * camera, QWidget * parent) :
|
|||||||
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());
|
||||||
ui_->menuView->addAction(ui_->dockWidget_plot->toggleViewAction());
|
ui_->menuView->addAction(ui_->dockWidget_plot->toggleViewAction());
|
||||||
connect(ui_->toolBox, SIGNAL(parametersChanged()), this, SLOT(notifyParametersChanged()));
|
connect(ui_->toolBox, SIGNAL(parametersChanged(const QStringList &)), this, SLOT(notifyParametersChanged(const QStringList &)));
|
||||||
|
|
||||||
ui_->imageView_source->setGraphicsViewMode(false);
|
ui_->imageView_source->setGraphicsViewMode(false);
|
||||||
ui_->imageView_source->setTextLabel(tr("Press \"space\" to start camera..."));
|
ui_->imageView_source->setTextLabel(tr("Press \"space\" to start camera..."));
|
||||||
@ -637,7 +638,7 @@ void MainWindow::updateData()
|
|||||||
if(count)
|
if(count)
|
||||||
{
|
{
|
||||||
objectsDescriptors_ = cv::Mat(count, dim, type);
|
objectsDescriptors_ = cv::Mat(count, dim, type);
|
||||||
printf("Total descriptors=%d, dim=%d, type=%d\n",count, dim, type);
|
printf("Updating global descriptors matrix: Total descriptors=%d, dim=%d, type=%d\n",count, dim, type);
|
||||||
int row = 0;
|
int row = 0;
|
||||||
for(int i=0; i<objects_.size(); ++i)
|
for(int i=0; i<objects_.size(); ++i)
|
||||||
{
|
{
|
||||||
@ -654,14 +655,16 @@ void MainWindow::updateData()
|
|||||||
}
|
}
|
||||||
if(Settings::getGeneral_invertedSearch())
|
if(Settings::getGeneral_invertedSearch())
|
||||||
{
|
{
|
||||||
|
printf("Creating FLANN index (%s) with objects' descriptors...\n", Settings::currentNearestNeighborType().toStdString().c_str());
|
||||||
// CREATE INDEX
|
// CREATE INDEX
|
||||||
QTime time;
|
QTime time;
|
||||||
time.start();
|
time.start();
|
||||||
cv::flann::IndexParams * params = Settings::createFlannIndexParams();
|
cv::flann::IndexParams * params = Settings::createFlannIndexParams();
|
||||||
flannIndex_.build(objectsDescriptors_, *params, Settings::getFlannDistanceType());
|
flannIndex_.build(objectsDescriptors_, *params, Settings::getFlannDistanceType());
|
||||||
delete params;
|
delete params;
|
||||||
ui_->label_timeIndexing->setNum(time.restart());
|
ui_->label_timeIndexing->setNum(time.elapsed());
|
||||||
ui_->label_vocabularySize->setNum(objectsDescriptors_.rows);
|
ui_->label_vocabularySize->setNum(objectsDescriptors_.rows);
|
||||||
|
printf("Creating FLANN index (%s) with objects' descriptors... done! (%d ms)\n", Settings::currentNearestNeighborType().toStdString().c_str(), time.elapsed());
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -839,6 +842,7 @@ void MainWindow::update(const cv::Mat & image)
|
|||||||
if(!Settings::getGeneral_invertedSearch())
|
if(!Settings::getGeneral_invertedSearch())
|
||||||
{
|
{
|
||||||
// CREATE INDEX
|
// CREATE INDEX
|
||||||
|
//printf("Creating FLANN index (%s)\n", Settings::currentNearestNeighborType().toStdString().c_str());
|
||||||
cv::flann::IndexParams * params = Settings::createFlannIndexParams();
|
cv::flann::IndexParams * params = Settings::createFlannIndexParams();
|
||||||
flannIndex_.build(descriptors, *params, Settings::getFlannDistanceType());
|
flannIndex_.build(descriptors, *params, Settings::getFlannDistanceType());
|
||||||
delete params;
|
delete params;
|
||||||
@ -933,6 +937,8 @@ void MainWindow::update(const cv::Mat & image)
|
|||||||
}
|
}
|
||||||
|
|
||||||
QMap<int, float> scores;
|
QMap<int, float> scores;
|
||||||
|
int maxScoreId = -1;
|
||||||
|
int maxScore = 0;
|
||||||
// For each object
|
// For each object
|
||||||
for(int i=0; i<matches.size(); ++i)
|
for(int i=0; i<matches.size(); ++i)
|
||||||
{
|
{
|
||||||
@ -1052,6 +1058,11 @@ void MainWindow::update(const cv::Mat & image)
|
|||||||
}
|
}
|
||||||
|
|
||||||
scores.insert(objects_.at(i)->id(), matches[i].size());
|
scores.insert(objects_.at(i)->id(), matches[i].size());
|
||||||
|
if(maxScoreId == -1 || maxScore < matches[i].size())
|
||||||
|
{
|
||||||
|
maxScoreId = objects_.at(i)->id();
|
||||||
|
maxScore = matches[i].size();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
//update likelihood plot
|
//update likelihood plot
|
||||||
@ -1064,6 +1075,17 @@ void MainWindow::update(const cv::Mat & image)
|
|||||||
ui_->label_minMatchedDistance->setNum(minMatchedDistance);
|
ui_->label_minMatchedDistance->setNum(minMatchedDistance);
|
||||||
ui_->label_maxMatchedDistance->setNum(maxMatchedDistance);
|
ui_->label_maxMatchedDistance->setNum(maxMatchedDistance);
|
||||||
|
|
||||||
|
//Scroll objects slider to the best score
|
||||||
|
if(maxScoreId>=0)
|
||||||
|
{
|
||||||
|
QLabel * label = ui_->dockWidget_objects->findChild<QLabel*>(QString("%1title").arg(maxScoreId));
|
||||||
|
if(label)
|
||||||
|
{
|
||||||
|
ui_->objects_area->verticalScrollBar()->setValue(label->pos().y());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Emit homographies
|
||||||
if(objectsDetected.size())
|
if(objectsDetected.size())
|
||||||
{
|
{
|
||||||
emit objectsFound(objectsDetected);
|
emit objectsFound(objectsDetected);
|
||||||
@ -1120,13 +1142,49 @@ void MainWindow::update(const cv::Mat & image)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void MainWindow::notifyParametersChanged()
|
void MainWindow::notifyParametersChanged(const QStringList & paramChanged)
|
||||||
{
|
{
|
||||||
printf("Parameters changed...\n");
|
|
||||||
|
//Selective update (to not update all objects for a simple camera's parameter modification)
|
||||||
|
bool detectorDescriptorParamsChanged = false;
|
||||||
|
bool nearestNeighborParamsChanged = false;
|
||||||
|
QString currentDetectorType = Settings::currentDetectorType();
|
||||||
|
QString currentDescriptorType = Settings::currentDescriptorType();
|
||||||
|
QString currentNNType = Settings::currentNearestNeighborType();
|
||||||
|
//printf("currentDescriptorType: %s\n", currentDescriptorType.toStdString().c_str());
|
||||||
|
//printf("currentNNType: %s\n", currentNNType.toStdString().c_str());
|
||||||
|
for(QStringList::const_iterator iter = paramChanged.begin(); iter!=paramChanged.end(); ++iter)
|
||||||
|
{
|
||||||
|
printf("Parameter changed: %s\n", iter->toStdString().c_str());
|
||||||
|
if(!detectorDescriptorParamsChanged &&
|
||||||
|
( iter->contains(currentDetectorType) ||
|
||||||
|
iter->contains(currentDescriptorType) ||
|
||||||
|
iter->compare(Settings::kDetector_Descriptor_1Detector()) == 0 ||
|
||||||
|
iter->compare(Settings::kDetector_Descriptor_2Descriptor()) == 0 ))
|
||||||
|
{
|
||||||
|
detectorDescriptorParamsChanged = true;
|
||||||
|
}
|
||||||
|
else if(!nearestNeighborParamsChanged &&
|
||||||
|
( iter->contains(currentNNType) ||
|
||||||
|
iter->compare(Settings::kGeneral_invertedSearch()) == 0 ||
|
||||||
|
iter->compare(Settings::kNearestNeighbor_1Strategy()) == 0 ||
|
||||||
|
iter->compare(Settings::kNearestNeighbor_2Distance_type()) == 0))
|
||||||
|
{
|
||||||
|
nearestNeighborParamsChanged = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
if(Settings::getGeneral_autoUpdateObjects())
|
if(Settings::getGeneral_autoUpdateObjects())
|
||||||
|
{
|
||||||
|
if(detectorDescriptorParamsChanged)
|
||||||
{
|
{
|
||||||
this->updateObjects();
|
this->updateObjects();
|
||||||
}
|
}
|
||||||
|
else if(nearestNeighborParamsChanged)
|
||||||
|
{
|
||||||
|
this->updateData();
|
||||||
|
}
|
||||||
|
}
|
||||||
else if(objects_.size())
|
else if(objects_.size())
|
||||||
{
|
{
|
||||||
this->statusBar()->showMessage(tr("A parameter has changed... \"Update objects\" may be required."));
|
this->statusBar()->showMessage(tr("A parameter has changed... \"Update objects\" may be required."));
|
||||||
|
|||||||
@ -65,7 +65,7 @@ private slots:
|
|||||||
void showHideControls();
|
void showHideControls();
|
||||||
void update(const cv::Mat & image);
|
void update(const cv::Mat & image);
|
||||||
void updateObjects();
|
void updateObjects();
|
||||||
void notifyParametersChanged();
|
void notifyParametersChanged(const QStringList & param);
|
||||||
void moveCameraFrame(int frame);
|
void moveCameraFrame(int frame);
|
||||||
|
|
||||||
signals:
|
signals:
|
||||||
|
|||||||
@ -28,8 +28,9 @@ QWidget * ParametersToolBox::getParameterWidget(const QString & key)
|
|||||||
return this->findChild<QWidget*>(key);
|
return this->findChild<QWidget*>(key);
|
||||||
}
|
}
|
||||||
|
|
||||||
void ParametersToolBox::resetPage(int index)
|
QStringList ParametersToolBox::resetPage(int index)
|
||||||
{
|
{
|
||||||
|
QStringList paramChanged;
|
||||||
const QObjectList & children = this->widget(index)->children();
|
const QObjectList & children = this->widget(index)->children();
|
||||||
for(int j=0; j<children.size();++j)
|
for(int j=0; j<children.size();++j)
|
||||||
{
|
{
|
||||||
@ -40,49 +41,72 @@ void ParametersToolBox::resetPage(int index)
|
|||||||
QVariant value = Settings::getDefaultParameters().value(key, QVariant());
|
QVariant value = Settings::getDefaultParameters().value(key, QVariant());
|
||||||
if(value.isValid())
|
if(value.isValid())
|
||||||
{
|
{
|
||||||
|
Settings::setParameter(key, value);
|
||||||
|
|
||||||
if(qobject_cast<QComboBox*>(children.at(j)))
|
if(qobject_cast<QComboBox*>(children.at(j)))
|
||||||
|
{
|
||||||
|
if(((QComboBox*)children.at(j))->currentIndex() != value.toString().split(':').first().toInt())
|
||||||
{
|
{
|
||||||
((QComboBox*)children.at(j))->setCurrentIndex(value.toString().split(':').first().toInt());
|
((QComboBox*)children.at(j))->setCurrentIndex(value.toString().split(':').first().toInt());
|
||||||
|
paramChanged.append(key);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
else if(qobject_cast<QSpinBox*>(children.at(j)))
|
else if(qobject_cast<QSpinBox*>(children.at(j)))
|
||||||
|
{
|
||||||
|
if(((QSpinBox*)children.at(j))->value() != value.toInt())
|
||||||
{
|
{
|
||||||
((QSpinBox*)children.at(j))->setValue(value.toInt());
|
((QSpinBox*)children.at(j))->setValue(value.toInt());
|
||||||
|
paramChanged.append(key);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
else if(qobject_cast<QDoubleSpinBox*>(children.at(j)))
|
else if(qobject_cast<QDoubleSpinBox*>(children.at(j)))
|
||||||
|
{
|
||||||
|
if(((QDoubleSpinBox*)children.at(j))->value() != value.toDouble())
|
||||||
{
|
{
|
||||||
((QDoubleSpinBox*)children.at(j))->setValue(value.toDouble());
|
((QDoubleSpinBox*)children.at(j))->setValue(value.toDouble());
|
||||||
|
paramChanged.append(key);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
else if(qobject_cast<QCheckBox*>(children.at(j)))
|
else if(qobject_cast<QCheckBox*>(children.at(j)))
|
||||||
|
{
|
||||||
|
if(((QCheckBox*)children.at(j))->isChecked() != value.toBool())
|
||||||
{
|
{
|
||||||
((QCheckBox*)children.at(j))->setChecked(value.toBool());
|
((QCheckBox*)children.at(j))->setChecked(value.toBool());
|
||||||
|
paramChanged.append(key);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
else if(qobject_cast<QLineEdit*>(children.at(j)))
|
else if(qobject_cast<QLineEdit*>(children.at(j)))
|
||||||
|
{
|
||||||
|
if(((QLineEdit*)children.at(j))->text().compare(value.toString()) != 0)
|
||||||
{
|
{
|
||||||
((QLineEdit*)children.at(j))->setText(value.toString());
|
((QLineEdit*)children.at(j))->setText(value.toString());
|
||||||
}
|
paramChanged.append(key);
|
||||||
Settings::setParameter(key, value);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
return paramChanged;
|
||||||
|
}
|
||||||
|
|
||||||
void ParametersToolBox::resetCurrentPage()
|
void ParametersToolBox::resetCurrentPage()
|
||||||
{
|
{
|
||||||
this->blockSignals(true);
|
this->blockSignals(true);
|
||||||
this->resetPage(this->currentIndex());
|
QStringList paramChanged = this->resetPage(this->currentIndex());
|
||||||
this->blockSignals(false);
|
this->blockSignals(false);
|
||||||
emit parametersChanged();
|
emit parametersChanged(paramChanged);
|
||||||
}
|
}
|
||||||
|
|
||||||
void ParametersToolBox::resetAllPages()
|
void ParametersToolBox::resetAllPages()
|
||||||
{
|
{
|
||||||
|
QStringList paramChanged;
|
||||||
this->blockSignals(true);
|
this->blockSignals(true);
|
||||||
for(int i=0; i< this->count(); ++i)
|
for(int i=0; i< this->count(); ++i)
|
||||||
{
|
{
|
||||||
this->resetPage(i);
|
paramChanged.append(this->resetPage(i));
|
||||||
}
|
}
|
||||||
this->blockSignals(false);
|
this->blockSignals(false);
|
||||||
emit parametersChanged();
|
emit parametersChanged(paramChanged);
|
||||||
}
|
}
|
||||||
|
|
||||||
void ParametersToolBox::setupUi()
|
void ParametersToolBox::setupUi()
|
||||||
@ -300,7 +324,9 @@ void ParametersToolBox::changeParameter(const QString & value)
|
|||||||
if(sender())
|
if(sender())
|
||||||
{
|
{
|
||||||
Settings::setParameter(sender()->objectName(), value);
|
Settings::setParameter(sender()->objectName(), value);
|
||||||
emit parametersChanged();
|
QStringList paramChanged;
|
||||||
|
paramChanged.append(sender()->objectName());
|
||||||
|
emit parametersChanged(paramChanged);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
void ParametersToolBox::changeParameter()
|
void ParametersToolBox::changeParameter()
|
||||||
@ -322,21 +348,25 @@ void ParametersToolBox::changeParameter()
|
|||||||
{
|
{
|
||||||
Settings::setParameter(sender()->objectName(), lineEdit->text());
|
Settings::setParameter(sender()->objectName(), lineEdit->text());
|
||||||
}
|
}
|
||||||
emit parametersChanged();
|
QStringList paramChanged;
|
||||||
|
paramChanged.append(sender()->objectName());
|
||||||
|
emit parametersChanged(paramChanged);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
void ParametersToolBox::changeParameter(const int & value)
|
void ParametersToolBox::changeParameter(const int & value)
|
||||||
{
|
{
|
||||||
if(sender())
|
if(sender())
|
||||||
{
|
{
|
||||||
|
QStringList paramChanged;
|
||||||
QComboBox * comboBox = qobject_cast<QComboBox*>(sender());
|
QComboBox * comboBox = qobject_cast<QComboBox*>(sender());
|
||||||
QCheckBox * checkBox = qobject_cast<QCheckBox*>(sender());
|
QCheckBox * checkBox = qobject_cast<QCheckBox*>(sender());
|
||||||
if(comboBox)
|
if(comboBox)
|
||||||
{
|
{
|
||||||
|
bool nnStrategyChanged = false;
|
||||||
|
//verify binary issue with nearest neighbor strategy
|
||||||
if(comboBox->objectName().compare(Settings::kDetector_Descriptor_2Descriptor()) == 0 ||
|
if(comboBox->objectName().compare(Settings::kDetector_Descriptor_2Descriptor()) == 0 ||
|
||||||
comboBox->objectName().compare(Settings::kNearestNeighbor_1Strategy()) == 0)
|
comboBox->objectName().compare(Settings::kNearestNeighbor_1Strategy()) == 0)
|
||||||
{
|
{
|
||||||
//verify binary issue
|
|
||||||
QComboBox * descriptorBox = (QComboBox*)this->getParameterWidget(Settings::kDetector_Descriptor_2Descriptor());
|
QComboBox * descriptorBox = (QComboBox*)this->getParameterWidget(Settings::kDetector_Descriptor_2Descriptor());
|
||||||
QComboBox * nnBox = (QComboBox*)this->getParameterWidget(Settings::kNearestNeighbor_1Strategy());
|
QComboBox * nnBox = (QComboBox*)this->getParameterWidget(Settings::kNearestNeighbor_1Strategy());
|
||||||
bool isBinaryDescriptor = descriptorBox->currentText().compare("ORB") == 0 || descriptorBox->currentText().compare("Brief") == 0;
|
bool isBinaryDescriptor = descriptorBox->currentText().compare("ORB") == 0 || descriptorBox->currentText().compare("Brief") == 0;
|
||||||
@ -351,12 +381,15 @@ void ParametersToolBox::changeParameter(const int & value)
|
|||||||
QString tmp = Settings::getNearestNeighbor_1Strategy();
|
QString tmp = Settings::getNearestNeighbor_1Strategy();
|
||||||
*tmp.begin() = '5'; // set index
|
*tmp.begin() = '5'; // set index
|
||||||
Settings::setNearestNeighbor_1Strategy(tmp);
|
Settings::setNearestNeighbor_1Strategy(tmp);
|
||||||
|
nnBox->blockSignals(true);
|
||||||
this->updateParameter(Settings::kNearestNeighbor_1Strategy());
|
this->updateParameter(Settings::kNearestNeighbor_1Strategy());
|
||||||
|
nnBox->blockSignals(false);
|
||||||
if(sender() == nnBox)
|
if(sender() == nnBox)
|
||||||
{
|
{
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
nnStrategyChanged = true;
|
||||||
|
paramChanged.append(Settings::kNearestNeighbor_1Strategy());
|
||||||
}
|
}
|
||||||
else if(!isBinaryDescriptor && nnBox->currentText().compare("Lsh") == 0)
|
else if(!isBinaryDescriptor && nnBox->currentText().compare("Lsh") == 0)
|
||||||
{
|
{
|
||||||
@ -369,11 +402,44 @@ void ParametersToolBox::changeParameter(const int & value)
|
|||||||
QString tmp = Settings::getNearestNeighbor_1Strategy();
|
QString tmp = Settings::getNearestNeighbor_1Strategy();
|
||||||
*tmp.begin() = '1'; // set index
|
*tmp.begin() = '1'; // set index
|
||||||
Settings::setNearestNeighbor_1Strategy(tmp);
|
Settings::setNearestNeighbor_1Strategy(tmp);
|
||||||
|
nnBox->blockSignals(true);
|
||||||
this->updateParameter(Settings::kNearestNeighbor_1Strategy());
|
this->updateParameter(Settings::kNearestNeighbor_1Strategy());
|
||||||
|
nnBox->blockSignals(false);
|
||||||
if(sender() == nnBox)
|
if(sender() == nnBox)
|
||||||
{
|
{
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
nnStrategyChanged = true;
|
||||||
|
paramChanged.append(Settings::kNearestNeighbor_1Strategy());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Distance issue when using nearest neighbor strategy using CV_32F type, though Lsh support all type (doesn't crash at least)
|
||||||
|
if(nnStrategyChanged ||
|
||||||
|
comboBox->objectName().compare(Settings::kNearestNeighbor_1Strategy()) == 0 ||
|
||||||
|
comboBox->objectName().compare(Settings::kNearestNeighbor_2Distance_type()) == 0)
|
||||||
|
{
|
||||||
|
QComboBox * nnBox = (QComboBox*)this->getParameterWidget(Settings::kNearestNeighbor_1Strategy());
|
||||||
|
QComboBox * distBox = (QComboBox*)this->getParameterWidget(Settings::kNearestNeighbor_2Distance_type());
|
||||||
|
if(nnBox->currentText().compare("Lsh") != 0 && distBox->currentIndex() > 1)
|
||||||
|
{
|
||||||
|
QMessageBox::warning(this,
|
||||||
|
tr("Error"),
|
||||||
|
tr("Current selected nearest neighbor strategy type (\"%1\") cannot handle distance strategy (\"%2\").\n"
|
||||||
|
"Falling back to \"EUCLIDEAN_L2\" distance strategy (by default).")
|
||||||
|
.arg(nnBox->currentText())
|
||||||
|
.arg(distBox->currentText()));
|
||||||
|
QString tmp = Settings::getNearestNeighbor_2Distance_type();
|
||||||
|
*tmp.begin() = '0'; // set index
|
||||||
|
Settings::setNearestNeighbor_2Distance_type(tmp);
|
||||||
|
distBox->blockSignals(true);
|
||||||
|
this->updateParameter(Settings::kNearestNeighbor_2Distance_type());
|
||||||
|
distBox->blockSignals(false);
|
||||||
|
if(sender() == distBox)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
paramChanged.append(Settings::kNearestNeighbor_2Distance_type());
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -389,6 +455,7 @@ void ParametersToolBox::changeParameter(const int & value)
|
|||||||
{
|
{
|
||||||
Settings::setParameter(sender()->objectName(), value==Qt::Checked?true:false);
|
Settings::setParameter(sender()->objectName(), value==Qt::Checked?true:false);
|
||||||
}
|
}
|
||||||
emit parametersChanged();
|
paramChanged.append(sender()->objectName());
|
||||||
|
emit parametersChanged(paramChanged);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@ -31,7 +31,7 @@ private:
|
|||||||
void addParameter(QVBoxLayout * layout, const QString & name, QWidget * widget);
|
void addParameter(QVBoxLayout * layout, const QString & name, QWidget * widget);
|
||||||
|
|
||||||
signals:
|
signals:
|
||||||
void parametersChanged();
|
void parametersChanged(const QStringList & name);
|
||||||
|
|
||||||
private slots:
|
private slots:
|
||||||
void changeParameter();
|
void changeParameter();
|
||||||
@ -41,7 +41,7 @@ private slots:
|
|||||||
void resetAllPages();
|
void resetAllPages();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
void resetPage(int index);
|
QStringList resetPage(int index);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* PARAMETERSTOOLBOX_H_ */
|
#endif /* PARAMETERSTOOLBOX_H_ */
|
||||||
|
|||||||
@ -1,4 +1,4 @@
|
|||||||
// Taken from RTAB-Map library r605 [www.rtabmap.googlecode.com]
|
// Taken from RTAB-Map library r606 [www.rtabmap.googlecode.com]
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Copyright (C) 2010-2011, Mathieu Labbe and IntRoLab - Universite de Sherbrooke
|
* Copyright (C) 2010-2011, Mathieu Labbe and IntRoLab - Universite de Sherbrooke
|
||||||
|
|||||||
@ -1,4 +1,4 @@
|
|||||||
// Taken from RTAB-Map library r605 [www.rtabmap.googlecode.com]
|
// Taken from RTAB-Map library r606 [www.rtabmap.googlecode.com]
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Copyright (C) 2010-2011, Mathieu Labbe and IntRoLab - Universite de Sherbrooke
|
* Copyright (C) 2010-2011, Mathieu Labbe and IntRoLab - Universite de Sherbrooke
|
||||||
|
|||||||
@ -223,14 +223,13 @@
|
|||||||
<addaction name="actionAdd_objects_from_files"/>
|
<addaction name="actionAdd_objects_from_files"/>
|
||||||
<addaction name="separator"/>
|
<addaction name="separator"/>
|
||||||
<addaction name="actionLoad_scene_from_file"/>
|
<addaction name="actionLoad_scene_from_file"/>
|
||||||
|
<addaction name="actionCamera_from_directory_of_images"/>
|
||||||
|
<addaction name="actionCamera_from_video_file"/>
|
||||||
<addaction name="separator"/>
|
<addaction name="separator"/>
|
||||||
<addaction name="actionStart_camera"/>
|
<addaction name="actionStart_camera"/>
|
||||||
<addaction name="actionPause_camera"/>
|
<addaction name="actionPause_camera"/>
|
||||||
<addaction name="actionStop_camera"/>
|
<addaction name="actionStop_camera"/>
|
||||||
<addaction name="separator"/>
|
<addaction name="separator"/>
|
||||||
<addaction name="actionCamera_from_directory_of_images"/>
|
|
||||||
<addaction name="actionCamera_from_video_file"/>
|
|
||||||
<addaction name="separator"/>
|
|
||||||
<addaction name="actionRestore_all_default_settings"/>
|
<addaction name="actionRestore_all_default_settings"/>
|
||||||
<addaction name="separator"/>
|
<addaction name="separator"/>
|
||||||
<addaction name="actionRemove_all_objects"/>
|
<addaction name="actionRemove_all_objects"/>
|
||||||
@ -665,7 +664,7 @@
|
|||||||
</action>
|
</action>
|
||||||
<action name="actionLoad_scene_from_file">
|
<action name="actionLoad_scene_from_file">
|
||||||
<property name="text">
|
<property name="text">
|
||||||
<string>Load scene from file...</string>
|
<string>Camera from single file...</string>
|
||||||
</property>
|
</property>
|
||||||
</action>
|
</action>
|
||||||
<action name="actionPause_camera">
|
<action name="actionPause_camera">
|
||||||
|
|||||||
@ -1,4 +1,4 @@
|
|||||||
// Taken from UtiLite library r185 [www.utilite.googlecode.com]
|
// Taken from UtiLite library r186 [www.utilite.googlecode.com]
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* utilite is a cross-platform library with
|
* utilite is a cross-platform library with
|
||||||
@ -296,7 +296,6 @@ void UPlotCurve::attach(UPlot * plot)
|
|||||||
{
|
{
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
this->setParent(plot);
|
|
||||||
if(_plot)
|
if(_plot)
|
||||||
{
|
{
|
||||||
_plot->removeCurve(this);
|
_plot->removeCurve(this);
|
||||||
@ -1738,7 +1737,7 @@ UPlotCurve * UPlot::addCurve(const QString & curveName, const QColor & color)
|
|||||||
return curve;
|
return curve;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool UPlot::addCurve(UPlotCurve * curve)
|
bool UPlot::addCurve(UPlotCurve * curve, bool ownershipTransferred)
|
||||||
{
|
{
|
||||||
if(curve)
|
if(curve)
|
||||||
{
|
{
|
||||||
@ -1757,7 +1756,11 @@ bool UPlot::addCurve(UPlotCurve * curve)
|
|||||||
|
|
||||||
// add curve
|
// add curve
|
||||||
_curves.append(curve);
|
_curves.append(curve);
|
||||||
curve->attach(this); // ownership is transferred
|
curve->attach(this);
|
||||||
|
if(ownershipTransferred)
|
||||||
|
{
|
||||||
|
curve->setParent(this);
|
||||||
|
}
|
||||||
this->updateAxis(curve);
|
this->updateAxis(curve);
|
||||||
curve->setXStart(_axisMaximums[1]);
|
curve->setXStart(_axisMaximums[1]);
|
||||||
|
|
||||||
|
|||||||
@ -1,4 +1,4 @@
|
|||||||
// Taken from UtiLite library r185 [www.utilite.googlecode.com]
|
// Taken from UtiLite library r186 [www.utilite.googlecode.com]
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* utilite is a cross-platform library with
|
* utilite is a cross-platform library with
|
||||||
@ -141,7 +141,6 @@ public:
|
|||||||
void setData(const std::vector<float> & y);
|
void setData(const std::vector<float> & y);
|
||||||
void getData(QVector<float> & x, QVector<float> & y) const; // only call in Qt MainThread
|
void getData(QVector<float> & x, QVector<float> & y) const; // only call in Qt MainThread
|
||||||
void draw(QPainter * painter);
|
void draw(QPainter * painter);
|
||||||
const QVector<float> & getMinMax() const {return _minMax;}
|
|
||||||
|
|
||||||
public slots:
|
public slots:
|
||||||
/**
|
/**
|
||||||
@ -225,6 +224,7 @@ protected:
|
|||||||
void attach(UPlot * plot);
|
void attach(UPlot * plot);
|
||||||
void detach(UPlot * plot);
|
void detach(UPlot * plot);
|
||||||
void updateMinMax();
|
void updateMinMax();
|
||||||
|
const QVector<float> & getMinMax() const {return _minMax;}
|
||||||
int removeItem(int index);
|
int removeItem(int index);
|
||||||
void _addValue(UPlotItem * data);;
|
void _addValue(UPlotItem * data);;
|
||||||
virtual bool isMinMaxValid() const {return _minMax.size();}
|
virtual bool isMinMaxValid() const {return _minMax.size();}
|
||||||
@ -475,11 +475,9 @@ public:
|
|||||||
*/
|
*/
|
||||||
UPlotCurve * addCurve(const QString & curveName, const QColor & color = QColor());
|
UPlotCurve * addCurve(const QString & curveName, const QColor & color = QColor());
|
||||||
/**
|
/**
|
||||||
* Add a curve. Ownership is transferred to UPlot.
|
* Add a curve. Ownership is transferred to UPlot if ownershipTransferred=true.
|
||||||
* If you add the curve to more than one UPlot, the ownership is transferred
|
|
||||||
* to the last UPlot.
|
|
||||||
*/
|
*/
|
||||||
bool addCurve(UPlotCurve * curve);
|
bool addCurve(UPlotCurve * curve, bool ownershipTransferred = true);
|
||||||
/**
|
/**
|
||||||
* Get all curve names.
|
* Get all curve names.
|
||||||
*/
|
*/
|
||||||
|
|||||||
Loading…
x
Reference in New Issue
Block a user