00001
00045 #include "mainwindow.h"
00046 #include "ui_mainwindow.h"
00047 #include "comthread.h"
00048 #include <ros/ros.h>
00049 #include <QListWidget>
00050 #include <QKeyEvent>
00051 #include <ros/service_client.h>
00052 #include <re_srvs/SetObject.h>
00053
00054 #include <QtCore>
00055 #include <QProgressDialog>
00056 #include <QFutureWatcher>
00057 #include <QFileDialog>
00058 #include <QTemporaryFile>
00059 #include <QDebug>
00060 #include <QMessageBox>
00061 #include <QDomDocument>
00062
00063 #include <cstdio>
00064
00065 #include "owldescriptioncreator.h"
00066 #include "re_object_recorder/qminizip.h"
00067 #include "uploadhelpers.h"
00068
00069 MainWindow::MainWindow(QWidget *parent) :
00070 QWidget(parent),
00071 ui(new Ui::MainWindow)
00072 {
00073 ui->setupUi(this);
00074 double boxsize_initial = 0.135;
00075 ui->boundingBoxSizeDoubleSpinBox->setValue(boxsize_initial);
00076 this->addAction(ui->actionDelete);
00077 ui->actionDelete->setShortcut(QKeySequence::Delete);
00078
00079 comthread = new ComThread;
00080 int maxScans = ui->maxScansSpinBox->value();
00081 comthread->maxScanNumberChanged(maxScans);
00082
00083 connect(ui->startstopbutton, SIGNAL(toggled(bool)), comthread, SLOT(recording(bool)));
00084 connect(ui->resetButton, SIGNAL(clicked()), comthread, SLOT(reset()));
00085 connect(ui->maxScansSpinBox, SIGNAL(valueChanged(int)), comthread, SLOT(maxScanNumberChanged(int)));
00086 connect(comthread, SIGNAL(addStatusMessage(QString)), this, SLOT(addStatusMessage(QString)));
00087 connect(comthread, SIGNAL(newCloudReceived(QString)), this, SLOT(insertCloud(QString)));
00088 connect(comthread, SIGNAL(finished()), this, SLOT(close()));
00089 connect(this, SIGNAL(changedBoxSize(double)), comthread, SLOT(changedBoxSize(double)));
00090
00091
00092 connect(ui->markerSizeDoubleSpinBox, SIGNAL(valueChanged(double)), comthread, SLOT(markerSizeChanged(double)));
00093 connect(ui->markerSpacingDoubleSpinBox, SIGNAL(valueChanged(double)), comthread, SLOT(markerSpacingChanged(double)));
00094
00095 Q_EMIT changedBoxSize(boxsize_initial);
00096
00097 comthread->start();
00098 updateOWL();
00099
00100 bool depth_registration_enabled = false;
00101 ros::param::get("/camera/driver/depth_registration", depth_registration_enabled);
00102 if (!depth_registration_enabled) {
00103 QMessageBox::warning(this, "Depth registration", "Depth registration is disabled in the openni driver."
00104 " This will probably lead to badly aligned pointclouds.");
00105 addStatusMessage("WARNING: Depth registration is disabled in the openni driver.");
00106 }
00107 }
00108
00109 MainWindow::~MainWindow() {
00110 delete ui;
00111 }
00112
00113 void MainWindow::closeEvent(QCloseEvent *) {
00114 ros::shutdown();
00115 comthread->wait();
00116 }
00117
00118 void MainWindow::addStatusMessage(QString msg) {
00119 ui->textEdit->append(msg);
00120 }
00121
00122 void MainWindow::insertCloud(QString id) {
00123 if (id.startsWith("-")) {
00124 while (ui->cloudListWidget->count()) {
00125 QListWidgetItem* item = ui->cloudListWidget->takeItem(0);
00126 if (item!=NULL)
00127 delete item;
00128 }
00129 } else
00130 ui->cloudListWidget->addItem(id);
00131 }
00132
00133 void MainWindow::on_cloudListWidget_itemSelectionChanged()
00134 {
00135 QStringList clouds;
00136 QList<QListWidgetItem*> items = ui->cloudListWidget->selectedItems();
00137 Q_FOREACH(QListWidgetItem* item, items)
00138 clouds.append(item->text());
00139 comthread->selectCloud(clouds);
00140 }
00141
00142 bool MainWindow::createZippedModel(QDir model_dir, const QString& zip_filename)
00143 {
00144 bool success = true;
00145 QMiniZip mz(zip_filename, QMiniZip::ZIP_CREATE);
00146
00147
00148 QDir dir = model_dir;
00149 dir.setFilter(QDir::Files | QDir::Hidden | QDir::NoSymLinks);
00150
00151 QFileInfoList list = dir.entryInfoList();
00152 Q_FOREACH(QFileInfo fi, list) {
00153 try {
00154 mz.addFile(fi, model_dir.dirName() + "/" + fi.fileName());
00155 } catch(const std::exception &e) {
00156 ui->textEdit->append("Error adding " + fi.fileName() + " to " + zip_filename + " (" + QString(e.what()) + ")");
00157 success = false;
00158 break;
00159 }
00160 }
00161 return success;
00162 }
00163
00164 void MainWindow::on_saveButton_clicked()
00165 {
00166 if (ui->startstopbutton->isChecked())
00167 ui->startstopbutton->click();
00168
00169 if (!checkInput())
00170 return;
00171
00172 QString parent_directory_str = QFileDialog::getExistingDirectory(this, "Select directory to store the point cloud", QString());
00173
00174 if (parent_directory_str.isEmpty())
00175 return;
00176
00177 QProgressDialog dlg(this);
00178 dlg.setCancelButton(NULL);
00179 dlg.setLabelText("Saving model");
00180 dlg.setWindowModality(Qt::WindowModal);
00181 dlg.setMinimumDuration(0);
00182 dlg.setMinimum(0);
00183 dlg.setMaximum(0);
00184 dlg.setCancelButton(NULL);
00185
00186 QFutureWatcher<bool> futureWatcher;
00187 QObject::connect(&futureWatcher, SIGNAL(finished()), &dlg, SLOT(reset()));
00188 QObject::connect(&dlg, SIGNAL(canceled()), &futureWatcher, SLOT(cancel()));
00189
00190 QFuture<bool> future = QtConcurrent::run(this, &MainWindow::saveModels, parent_directory_str, static_cast<QStringList*>(0));
00191 futureWatcher.setFuture(future);
00192
00193
00194 dlg.exec();
00195
00196 futureWatcher.waitForFinished();
00197
00198 if (!futureWatcher.result()) {
00199 addStatusMessage("Saving model to '" + parent_directory_str + "'' failed.");
00200 QMessageBox::warning(this, "Error", "Could not save model");
00201 }
00202 }
00203
00204 bool MainWindow::checkInput() {
00205 QString modelname = ui->objectNameEdit->text();
00206 static const QString msg = "Please specify name and class of the object prior to saving or uploading objects.";
00207 if (modelname == "") {
00208 QMessageBox::warning(this, "Insufficient Information", msg);
00209 ui->textEdit->append(msg);
00210 ui->tabWidget->setCurrentWidget(ui->uploadTab);
00211 ui->objectNameEdit->setFocus();
00212 return false;
00213 }
00214
00215 if (modelname.contains(" ")) {
00216 QMessageBox::warning(this, "Invalid model name", "Model names should not contain spaces.");
00217 ui->tabWidget->setCurrentWidget(ui->uploadTab);
00218 ui->objectNameEdit->setFocus();
00219 return false;
00220 }
00221 QString classname = ui->objectClassEdit->text();
00222 if (classname == "") {
00223 ui->textEdit->append(msg);
00224 ui->tabWidget->setCurrentWidget(ui->uploadTab);
00225 ui->objectClassEdit->setFocus();
00226 return false;
00227 }
00228 if (classname.contains(" ")) {
00229 QMessageBox::warning(this, "Invalid class name", "Class names should not contain spaces.");
00230 ui->tabWidget->setCurrentWidget(ui->uploadTab);
00231 ui->objectClassEdit->setFocus();
00232 return false;
00233 }
00234 return true;
00235 }
00236
00237 bool MainWindow::saveModels(QString parent_directory_str, QStringList *modelFiles) {
00238 if (modelFiles != NULL)
00239 modelFiles->clear();
00240
00241 QString classname = ui->objectClassEdit->text();
00242 QString modelname = ui->objectNameEdit->text();
00243
00244 QDir parent_dir(parent_directory_str);
00245
00246 try {
00247 parent_dir.mkdir(classname + "." + modelname);
00248 QDir model_dir = parent_dir;
00249 model_dir.cd(classname + "." + modelname);
00250 comthread->createRe_visionModel(model_dir, classname + "." + modelname);
00251 QString model_filename(parent_dir.absoluteFilePath("2dcammodel.zip"));
00252 bool success = createZippedModel(model_dir, model_filename);
00253 if (!success)
00254 return false;
00255 if (modelFiles != NULL)
00256 modelFiles->append(model_filename);
00257 } catch(const std::string& exception) {
00258 std::cerr << "caught exception: " << exception << std::endl;
00259 return false;
00260 } catch(...) {
00261 std::cerr << "caught exception" << std::endl;
00262 return false;
00263 }
00264
00265 try {
00266 parent_dir.mkdir(classname + "." + modelname + "_kinect");
00267 QDir model_dir = parent_dir;
00268 model_dir.cd(classname + "." + modelname + "_kinect");
00269 comthread->createKinectModel(model_dir, classname + "." + modelname);
00270 QString model_filename(parent_dir.absoluteFilePath("kinectmodel.zip"));
00271 bool success = createZippedModel(model_dir, model_filename);
00272 if (!success)
00273 return false;
00274 if (modelFiles != NULL)
00275 modelFiles->append(model_filename);
00276 } catch(...) {
00277 std::cerr << "caught exception" << std::endl;
00278 return false;
00279 }
00280
00281
00282 {
00283 bool created_preview = comthread->createPreview(parent_dir);
00284 if (created_preview && (modelFiles != NULL))
00285 modelFiles->append(parent_dir.filePath("preview.png"));
00286 }
00287
00288 return true;
00289 }
00290
00292 enum UploadResults {SUCCESS, NO_SERVICE, CHECK_FAILED, GENERIC_UPLOAD_FAILED};
00293 UploadResults uploadModels(UploadBase* uploadGeneric) {
00294 if (!uploadGeneric->waitForService())
00295 return NO_SERVICE;
00296 if (!uploadGeneric->check())
00297 return CHECK_FAILED;
00298
00299 if (!uploadGeneric->upload())
00300 return GENERIC_UPLOAD_FAILED;
00301 return SUCCESS;
00302 }
00303
00304 void MainWindow::on_reButton_clicked()
00305 {
00306 if (!checkInput())
00307 return;
00308 QString modelname = ui->objectNameEdit->text();
00309 QString classname = ui->objectClassEdit->text();
00310
00311
00312 QDir tempDir = QDir::tempPath();
00313 QString subdir_base = "object_recorder";
00314 int i=0;
00315 QString subdir_name = subdir_base + "_" + QString::number(i);
00316 while (tempDir.exists(subdir_name)) {
00317 i++;
00318 subdir_name = subdir_base + "_" + QString::number(i);
00319 }
00320
00321 tempDir.mkdir(subdir_name);
00322 QStringList model_files;
00323 {
00324 QProgressDialog dlg("Storing models...", "Cancel", 0, 0, this);
00325 dlg.setCancelButton(NULL);
00326 QFutureWatcher<bool> futureWatcher;
00327 QObject::connect(&futureWatcher, SIGNAL(finished()), &dlg, SLOT(reset()));
00328 QObject::connect(&dlg, SIGNAL(canceled()), &futureWatcher, SLOT(cancel()));
00329
00330 QFuture<bool> future = QtConcurrent::run(this, &MainWindow::saveModels, tempDir.filePath(subdir_name), &model_files);
00331 futureWatcher.setFuture(future);
00332
00333
00334 dlg.exec();
00335
00336 futureWatcher.waitForFinished();
00337 if (dlg.wasCanceled()) {
00338 addStatusMessage("Storing model files was cancelled by user");
00339 return;
00340 } else if (!future.result()) {
00341 qDebug() << "result = false";
00342 tempDir.rmdir(subdir_name);
00343 addStatusMessage("Could not store models");
00344 return;
00345 }
00346 }
00347
00348
00349 std::vector<re_msgs::File> fileMsgs;
00350 Q_FOREACH(const QString& model_filename, model_files) {
00351 re_msgs::File fileMsg;
00352 QString actualFilename = model_filename.split('/', QString::SkipEmptyParts).last();
00353 fileMsg.name = actualFilename.toStdString();
00354 QFile f(model_filename);
00355 if (!f.open(QIODevice::ReadOnly)) {
00356 addStatusMessage("Could not read model file '" + model_filename + "'.");
00357 continue;
00358 }
00359
00360 QByteArray data = f.readAll();
00361 fileMsg.data.resize(data.size());
00362 std::copy(data.data(), data.data()+data.size(), fileMsg.data.begin());
00363
00364 fileMsgs.push_back(fileMsg);
00365 }
00366
00367 UploadSetNewObject upload;
00368 upload.fillRequest(ui->apiKeyEdit->text().toStdString(), modelname.toStdString(), classname.toStdString(), ui->owlView->toPlainText().toStdString(),
00369 ui->objectDescriptionEdit->document()->toPlainText().toStdString(), fileMsgs);
00370
00371 QProgressDialog dlg(this);
00372 dlg.setCancelButton(NULL);
00373 dlg.setLabelText("Uploading models to RoboEarth...");
00374 dlg.setWindowModality(Qt::WindowModal);
00375 dlg.setMinimumDuration(0);
00376 dlg.setMinimum(0);
00377 dlg.setMaximum(0);
00378 dlg.setCancelButton(NULL);
00379
00380 QFutureWatcher<UploadResults> futureWatcher;
00381 QObject::connect(&futureWatcher, SIGNAL(finished()), &dlg, SLOT(reset()));
00382 QObject::connect(&dlg, SIGNAL(canceled()), &futureWatcher, SLOT(cancel()));
00383
00384 QFuture<UploadResults> future = QtConcurrent::run(&uploadModels, &upload);
00385 futureWatcher.setFuture(future);
00386
00387 dlg.exec();
00388 futureWatcher.waitForFinished();
00389
00390 UploadResults status = future.result();
00391 if (status == SUCCESS) {
00392 addStatusMessage("Successfully transmitted one object to roboearth database.");
00393 } else if (status == CHECK_FAILED) {
00394 static const QString msg = "Upload failed: A model of the same name is already in the database.";
00395 QMessageBox::warning(this, "Upload failed", msg);
00396 addStatusMessage(msg);
00397 } else if (status == NO_SERVICE) {
00398 static const QString msg = "Upload failed: No service found. Please make sure the re_comm is running.";
00399 QMessageBox::warning(this, "Upload failed", msg);
00400 addStatusMessage(msg);
00401 } else {
00402 static const QString msg = "Upload failed: Check re_comm output for more information. (Hint: Is your API key correct?)";
00403 QMessageBox::warning(this, "Upload failed", msg);
00404 addStatusMessage(msg);
00405 }
00406 }
00407
00408 void MainWindow::updateOWL() {
00409 QString model = ui->modelType->text();
00410 QString objectclass = ui->objectClassEdit->text();
00411 QString objectname = ui->objectNameEdit->text();
00412
00413 if (model.isEmpty() || objectclass.isEmpty() || objectname.isEmpty()) {
00414 ui->reButton->setEnabled(false);
00415 ui->owlView->setPlainText("");
00416 return;
00417 }
00418
00419 if (!ui->apiKeyEdit->text().isEmpty())
00420 ui->reButton->setEnabled(true);
00421 else
00422 ui->reButton->setEnabled(false);
00423 OWLDescriptionCreator odc(model, objectclass, QDateTime::currentDateTime());
00424 ui->owlView->setPlainText(odc.getOwlDescription());
00425 }
00426
00427 void MainWindow::on_objectClassEdit_textChanged(const QString &arg1) {
00428 updateOWL();
00429 }
00430
00431 void MainWindow::on_objectNameEdit_textChanged(const QString &arg1) {
00432 updateOWL();
00433 }
00434
00435 void MainWindow::on_boundingBoxSizeDoubleSpinBox_valueChanged(double val) {
00436 ros::param::set("boxsize", val);
00437 Q_EMIT changedBoxSize(val);
00438 }
00439
00440 void MainWindow::on_apiKeyEdit_textChanged(QString ) {
00441 updateOWL();
00442 }
00443
00444
00445 void MainWindow::on_startstopbutton_toggled(bool checked) {
00446 if (checked) {
00447 ui->startstopbutton->setText("Stop Recording");
00448 } else {
00449 ui->startstopbutton->setText("Start Recording");
00450 }
00451 }
00452
00453 void MainWindow::on_loadButton_clicked() {
00454
00455
00456
00457
00458
00459
00460 comthread->reset();
00461
00462 QString filename = QFileDialog::getOpenFileName(this, "Import stored model", QString(),
00463 "Stored Model (*.zip)");
00464 if (filename.isEmpty())
00465 return;
00466
00467 QMiniZip mz(filename, QMiniZip::UNZIP);
00468 QStringList extracted_files = mz.unzip(QDir::tempPath());
00469 QString metaFileName;
00470 Q_FOREACH(const QString& ef, extracted_files) {
00471 if (ef.toLower().endsWith("meta.xml")) {
00472 metaFileName = ef;
00473 break;
00474 }
00475 }
00476 if (metaFileName.isEmpty()) {
00477 addStatusMessage("Model file '" + filename + " does not contain a meta.xml file. aborting");
00478 return;
00479 }
00480
00481 QFile metaFile(metaFileName);
00482 if (!metaFile.open(QFile::ReadOnly | QFile::Text)) {
00483 addStatusMessage("could not open meta.xml!");
00484 return;
00485 }
00486
00487 QDomDocument doc;
00488 if (!doc.setContent(&metaFile)) {
00489 addStatusMessage( "could not parse meta.xml!");
00490 return;
00491 }
00492 QDomElement root = doc.documentElement();
00493 if (root.tagName() != "model") {
00494 addStatusMessage("meta.xml file in model '" + filename + "' is malformed.");
00495 }
00496 QDomElement typeEl = root.firstChildElement("type");
00497 if (typeEl.isNull()) {
00498 addStatusMessage("meta.xml file in model '" + filename + "' is malformed.");
00499 }
00500 if (typeEl.text() != "kinect_pcl") {
00501 QMessageBox::warning(this, "Error importing model", "The model file '" + filename + "' contains a model of type '" + typeEl.text() + "', whereas we need a model of type 'kinect_pcl'.");
00502 return;
00503 }
00504
00505 QDomElement nameEl = root.firstChildElement("name");
00506 if (nameEl.isNull()) {
00507 addStatusMessage("meta.xml file in model '" + filename + "' is malformed.");
00508 }
00509 QString class_model_name = nameEl.text();
00510
00511 if (class_model_name.count(".") != 1) {
00512 addStatusMessage("Cannot split '" + class_model_name + "' into class & model name. Please do so manually.");
00513 } else {
00514 QString modelname, classname;
00515 QStringList split = class_model_name.split('.');
00516 classname = split.at(0);
00517 modelname = split.at(1);
00518 ui->objectClassEdit->setText(classname);
00519 ui->objectNameEdit->setText(modelname);
00520 }
00521
00522 QDomElement facesEl = root.firstChildElement("faces");
00523 QString facesTxt = facesEl.text();
00524 bool conv_ok = false;
00525 int numFaces = facesTxt.toInt(&conv_ok);
00526 if (!conv_ok) {
00527 QMessageBox::warning(this, "Error importing model", "Could not read number of faces from '" + filename + "'.");
00528 return;
00529 }
00530
00531 QStringList facesFileNames;
00532 Q_FOREACH(const QString& ef, extracted_files) {
00533 if (ef.contains("dense_face_") && ef.endsWith(".pcd")) {
00534 facesFileNames.append(ef);
00535 }
00536 }
00537 if (facesFileNames.size() != numFaces) {
00538 QMessageBox::warning(this, "Error importing model", "Mismatch between number of faces in meta.xml and actual number of faces in model.");
00539 numFaces = facesFileNames.size();
00540 }
00541
00542 Q_FOREACH(const QString& fn, facesFileNames) {
00543 comthread->loadPointCloud(fn);
00544 }
00545 }
00546
00547
00548 void MainWindow::on_actionDelete_triggered()
00549 {
00550 QStringList clouds;
00551 QList<QListWidgetItem*> items = ui->cloudListWidget->selectedItems();
00552 Q_FOREACH(QListWidgetItem* item, items)
00553 clouds.append(item->text());
00554 comthread->removeCloud(clouds);
00555 Q_FOREACH(QListWidgetItem* item, items) {
00556 delete ui->cloudListWidget->takeItem(ui->cloudListWidget->row(item));
00557 }
00558 }