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")); // deactivate rehearsal
00074                 customParameters.insert(ParametersPair(Parameters::kKpMaxFeatures(), "-1")); // deactivate 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 sure memory cleanup is done
00078                 customParameters.insert(ParametersPair(Parameters::kMemIntermediateNodeDataKept(), "true"));
00079                 if(!recordInRAM)
00080                 {
00081                         customParameters.insert(ParametersPair(Parameters::kDbSqlite3InMemory(), "false"));
00082                 }
00083                 memory_ = new Memory();
00084                 if(!memory_->init(path.toStdString(), true, customParameters))
00085                 {
00086                         delete memory_;
00087                         memory_ = 0;
00088                         UERROR("Error initializing the memory.");
00089                         return false;
00090                 }
00091                 path_ = path;
00092                 return true;
00093         }
00094         else
00095         {
00096                 UERROR("Already initialized, close it first.");
00097                 return false;
00098         }
00099 }
00100 
00101 void DataRecorder::closeRecorder()
00102 {
00103         memoryMutex_.lock();
00104         if(memory_)
00105         {
00106                 delete memory_;
00107                 memory_ = 0;
00108                 UINFO("Data recorded to \"%s\".", this->path().toStdString().c_str());
00109         }
00110         memoryMutex_.unlock();
00111         processingImages_ = false;
00112         count_ = 0;
00113         totalSizeKB_ = 0;
00114         if(this->isVisible())
00115         {
00116                 QMessageBox::information(this, tr("Data recorder"), tr("Data recorded to \"%1\".").arg(this->path()));
00117         }
00118 }
00119 
00120 DataRecorder::~DataRecorder()
00121 {
00122         this->unregisterFromEventsManager();
00123         this->closeRecorder();
00124 }
00125 
00126 void DataRecorder::addData(const rtabmap::SensorData & data, const Transform & pose, const cv::Mat & covariance)
00127 {
00128         memoryMutex_.lock();
00129         if(memory_)
00130         {
00131                 if(memory_->getStMem().size() == 0 && data.id() > 0)
00132                 {
00133                         ParametersMap customParameters;
00134                         customParameters.insert(ParametersPair(Parameters::kMemGenerateIds(), "false")); // use id from data
00135                         memory_->parseParameters(customParameters);
00136                 }
00137 
00138                 //save to database
00139                 UTimer time;
00140                 memory_->update(data, pose, covariance);
00141                 const Signature * s = memory_->getLastWorkingSignature();
00142                 totalSizeKB_ += (int)s->sensorData().imageCompressed().total()/1000;
00143                 totalSizeKB_ += (int)s->sensorData().depthOrRightCompressed().total()/1000;
00144                 totalSizeKB_ += (int)s->sensorData().laserScanCompressed().data().total()/1000;
00145                 memory_->cleanup();
00146 
00147                 if(++count_ % 30)
00148                 {
00149                         memory_->emptyTrash();
00150                 }
00151                 UDEBUG("Time to process a message = %f s, totalSizeKB_=%d", time.ticks(), totalSizeKB_);
00152         }
00153         memoryMutex_.unlock();
00154 }
00155 
00156 void DataRecorder::showImage(const cv::Mat & image, const cv::Mat & depth)
00157 {
00158         processingImages_ = true;
00159         imageView_->setImage(uCvMat2QImage(image));
00160         imageView_->setImageDepth(depth);
00161         label_->setText(tr("Images=%1 (~%2 MB)").arg(count_).arg(totalSizeKB_/1000));
00162         processingImages_ = false;
00163 }
00164 
00165 void DataRecorder::closeEvent(QCloseEvent* event)
00166 {
00167         this->closeRecorder();
00168         event->accept();
00169 }
00170 
00171 bool DataRecorder::handleEvent(UEvent * event)
00172 {
00173         if(memory_)
00174         {
00175                 if(event->getClassName().compare("CameraEvent") == 0)
00176                 {
00177                         CameraEvent * camEvent = (CameraEvent*)event;
00178                         if(camEvent->getCode() == CameraEvent::kCodeData)
00179                         {
00180                                 if(camEvent->data().isValid())
00181                                 {
00182                                         UINFO("Receiving rate = %f Hz", 1.0f/timer_.ticks());
00183                                         this->addData(
00184                                                         camEvent->data(),
00185                                                         camEvent->info().odomPose,
00186                                                         camEvent->info().odomCovariance.empty()?cv::Mat::eye(6,6,CV_64FC1):camEvent->info().odomCovariance);
00187 
00188                                         if(!processingImages_ && this->isVisible() && camEvent->data().isValid())
00189                                         {
00190                                                 processingImages_ = true;
00191                                                 QMetaObject::invokeMethod(this, "showImage",
00192                                                                 Q_ARG(cv::Mat, camEvent->data().imageRaw()),
00193                                                                 Q_ARG(cv::Mat, camEvent->data().depthOrRightRaw()));
00194                                         }
00195                                 }
00196                         }
00197                 }
00198         }
00199         return false;
00200 }
00201 
00202 } /* namespace rtabmap */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:19