DataRecorder.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #include "rtabmap/gui/DataRecorder.h"
00029 
00030 #include <rtabmap/utilite/ULogger.h>
00031 #include <rtabmap/utilite/UTimer.h>
00032 #include <rtabmap/core/Memory.h>
00033 #include <rtabmap/core/Signature.h>
00034 #include <rtabmap/core/CameraEvent.h>
00035 #include <rtabmap/core/util3d.h>
00036 #include <rtabmap/gui/ImageView.h>
00037 #include <rtabmap/utilite/UCv2Qt.h>
00038 #include <QtCore/QMetaType>
00039 #include <QMessageBox>
00040 #include <QtGui/QCloseEvent>
00041 #include <QLabel>
00042 #include <QVBoxLayout>
00043 
00044 namespace rtabmap {
00045 
00046 
00047 DataRecorder::DataRecorder(QWidget * parent) :
00048                 QWidget(parent),
00049         memory_(0),
00050         imageView_(new ImageView(this)),
00051         label_(new QLabel(this)),
00052         processingImages_(false),
00053         count_(0),
00054         totalSizeKB_(0)
00055 {
00056         qRegisterMetaType<cv::Mat>("cv::Mat");
00057 
00058         imageView_->setImageDepthShown(true);
00059         imageView_->setMinimumSize(320, 240);
00060         QVBoxLayout * layout = new QVBoxLayout(this);
00061         layout->setMargin(0);
00062         layout->addWidget(imageView_);
00063         layout->addWidget(label_);
00064         layout->setStretch(0,1);
00065         this->setLayout(layout);
00066 }
00067 bool DataRecorder::init(const QString & path, bool recordInRAM)
00068 {
00069         UScopeMutex scope(memoryMutex_);
00070         if(!memory_)
00071         {
00072                 ParametersMap customParameters;
00073                 customParameters.insert(ParametersPair(Parameters::kMemRehearsalSimilarity(), "1.0")); // desactivate rehearsal
00074                 customParameters.insert(ParametersPair(Parameters::kKpMaxFeatures(), "-1")); // desactivate keypoints extraction
00075                 customParameters.insert(ParametersPair(Parameters::kMemBinDataKept(), "true")); // to keep images
00076                 customParameters.insert(ParametersPair(Parameters::kMemMapLabelsAdded(), "false")); // don't create map labels
00077                 customParameters.insert(ParametersPair(Parameters::kMemBadSignaturesIgnored(), "true")); // make usre memory cleanup is done
00078                 if(!recordInRAM)
00079                 {
00080                         customParameters.insert(ParametersPair(Parameters::kDbSqlite3InMemory(), "false"));
00081                 }
00082                 memory_ = new Memory();
00083                 if(!memory_->init(path.toStdString(), true, customParameters))
00084                 {
00085                         delete memory_;
00086                         memory_ = 0;
00087                         UERROR("Error initializing the memory.");
00088                         return false;
00089                 }
00090                 path_ = path;
00091                 return true;
00092         }
00093         else
00094         {
00095                 UERROR("Already initialized, close it first.");
00096                 return false;
00097         }
00098 }
00099 
00100 void DataRecorder::closeRecorder()
00101 {
00102         memoryMutex_.lock();
00103         if(memory_)
00104         {
00105                 delete memory_;
00106                 memory_ = 0;
00107                 UINFO("Data recorded to \"%s\".", this->path().toStdString().c_str());
00108         }
00109         memoryMutex_.unlock();
00110         processingImages_ = false;
00111         count_ = 0;
00112         totalSizeKB_ = 0;
00113         if(this->isVisible())
00114         {
00115                 QMessageBox::information(this, tr("Data recorder"), tr("Data recorded to \"%1\".").arg(this->path()));
00116         }
00117 }
00118 
00119 DataRecorder::~DataRecorder()
00120 {
00121         this->unregisterFromEventsManager();
00122         this->closeRecorder();
00123 }
00124 
00125 void DataRecorder::addData(const rtabmap::SensorData & data, const Transform & pose, const cv::Mat & covariance)
00126 {
00127         memoryMutex_.lock();
00128         if(memory_)
00129         {
00130                 if(memory_->getStMem().size() == 0 && data.id() > 0)
00131                 {
00132                         ParametersMap customParameters;
00133                         customParameters.insert(ParametersPair(Parameters::kMemGenerateIds(), "false")); // use id from data
00134                         memory_->parseParameters(customParameters);
00135                 }
00136 
00137                 //save to database
00138                 UTimer time;
00139                 memory_->update(data, pose, covariance);
00140                 const Signature * s = memory_->getLastWorkingSignature();
00141                 totalSizeKB_ += (int)s->sensorData().imageCompressed().total()/1000;
00142                 totalSizeKB_ += (int)s->sensorData().depthOrRightCompressed().total()/1000;
00143                 totalSizeKB_ += (int)s->sensorData().laserScanCompressed().total()/1000;
00144                 memory_->cleanup();
00145 
00146                 if(++count_ % 30)
00147                 {
00148                         memory_->emptyTrash();
00149                 }
00150                 UDEBUG("Time to process a message = %f s", time.ticks());
00151         }
00152         memoryMutex_.unlock();
00153 }
00154 
00155 void DataRecorder::showImage(const cv::Mat & image, const cv::Mat & depth)
00156 {
00157         processingImages_ = true;
00158         imageView_->setImage(uCvMat2QImage(image));
00159         imageView_->setImageDepth(uCvMat2QImage(depth));
00160         label_->setText(tr("Images=%1 (~%2 MB)").arg(count_).arg(totalSizeKB_/1000));
00161         processingImages_ = false;
00162 }
00163 
00164 void DataRecorder::closeEvent(QCloseEvent* event)
00165 {
00166         this->closeRecorder();
00167         event->accept();
00168 }
00169 
00170 void DataRecorder::handleEvent(UEvent * event)
00171 {
00172         if(memory_)
00173         {
00174                 if(event->getClassName().compare("CameraEvent") == 0)
00175                 {
00176                         CameraEvent * camEvent = (CameraEvent*)event;
00177                         if(camEvent->getCode() == CameraEvent::kCodeData)
00178                         {
00179                                 if(camEvent->data().isValid())
00180                                 {
00181                                         UINFO("Receiving rate = %f Hz", 1.0f/timer_.ticks());
00182                                         this->addData(camEvent->data());
00183 
00184                                         if(!processingImages_ && this->isVisible() && camEvent->data().isValid())
00185                                         {
00186                                                 processingImages_ = true;
00187                                                 QMetaObject::invokeMethod(this, "showImage",
00188                                                                 Q_ARG(cv::Mat, camEvent->data().imageRaw()),
00189                                                                 Q_ARG(cv::Mat, camEvent->data().depthOrRightRaw()));
00190                                         }
00191                                 }
00192                         }
00193                 }
00194         }
00195 }
00196 
00197 } /* namespace rtabmap */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:15