Signature.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/core/Signature.h"
00029 #include "rtabmap/core/EpipolarGeometry.h"
00030 #include "rtabmap/core/Memory.h"
00031 #include "rtabmap/core/Compression.h"
00032 #include <opencv2/highgui/highgui.hpp>
00033 
00034 #include <rtabmap/utilite/UtiLite.h>
00035 
00036 namespace rtabmap
00037 {
00038 
00039 Signature::Signature() :
00040         _id(0), // invalid id
00041         _mapId(-1),
00042         _stamp(0.0),
00043         _weight(0),
00044         _saved(false),
00045         _modified(true),
00046         _linksModified(true),
00047         _enabled(false),
00048         _invalidWordsCount(0)
00049 {
00050 }
00051 
00052 Signature::Signature(
00053                 int id,
00054                 int mapId,
00055                 int weight,
00056                 double stamp,
00057                 const std::string & label,
00058                 const Transform & pose,
00059                 const Transform & groundTruthPose,
00060                 const SensorData & sensorData):
00061         _id(id),
00062         _mapId(mapId),
00063         _stamp(stamp),
00064         _weight(weight),
00065         _label(label),
00066         _saved(false),
00067         _modified(true),
00068         _linksModified(true),
00069         _enabled(false),
00070         _invalidWordsCount(0),
00071         _pose(pose),
00072         _groundTruthPose(groundTruthPose),
00073         _sensorData(sensorData)
00074 {
00075         if(_sensorData.id() == 0)
00076         {
00077                 _sensorData.setId(id);
00078         }
00079         UASSERT(_sensorData.id() == _id);
00080 }
00081 
00082 Signature::Signature(const SensorData & data) :
00083         _id(data.id()),
00084         _mapId(-1),
00085         _stamp(data.stamp()),
00086         _weight(0),
00087         _label(""),
00088         _saved(false),
00089         _modified(true),
00090         _linksModified(true),
00091         _enabled(false),
00092         _invalidWordsCount(0),
00093         _pose(Transform::getIdentity()),
00094         _groundTruthPose(data.groundTruth()),
00095         _sensorData(data)
00096 {
00097 
00098 }
00099 
00100 Signature::~Signature()
00101 {
00102         //UDEBUG("id=%d", _id);
00103 }
00104 
00105 void Signature::addLinks(const std::list<Link> & links)
00106 {
00107         for(std::list<Link>::const_iterator iter = links.begin(); iter!=links.end(); ++iter)
00108         {
00109                 addLink(*iter);
00110         }
00111 }
00112 void Signature::addLinks(const std::map<int, Link> & links)
00113 {
00114         for(std::map<int, Link>::const_iterator iter = links.begin(); iter!=links.end(); ++iter)
00115         {
00116                 addLink(iter->second);
00117         }
00118 }
00119 void Signature::addLink(const Link & link)
00120 {
00121         UDEBUG("Add link %d to %d (type=%d var=%f,%f)", link.to(), this->id(), (int)link.type(), link.transVariance(), link.rotVariance());
00122         UASSERT_MSG(link.from() == this->id(), uFormat("%d->%d for signature %d (type=%d)", link.from(), link.to(), this->id(), link.type()).c_str());
00123         UASSERT_MSG((link.to() != this->id()) || link.type()==Link::kPosePrior, uFormat("%d->%d for signature %d (type=%d)", link.from(), link.to(), this->id(), link.type()).c_str());
00124         std::pair<std::map<int, Link>::iterator, bool> pair = _links.insert(std::make_pair(link.to(), link));
00125         UASSERT_MSG(pair.second, uFormat("Link %d (type=%d) already added to signature %d!", link.to(), link.type(), this->id()).c_str());
00126         _linksModified = true;
00127 }
00128 
00129 bool Signature::hasLink(int idTo) const
00130 {
00131         return _links.find(idTo) != _links.end();
00132 }
00133 
00134 void Signature::changeLinkIds(int idFrom, int idTo)
00135 {
00136         std::map<int, Link>::iterator iter = _links.find(idFrom);
00137         if(iter != _links.end())
00138         {
00139                 Link link = iter->second;
00140                 _links.erase(iter);
00141                 link.setTo(idTo);
00142                 _links.insert(std::make_pair(idTo, link));
00143                 _linksModified = true;
00144                 UDEBUG("(%d) neighbor ids changed from %d to %d", _id, idFrom, idTo);
00145         }
00146 }
00147 
00148 void Signature::removeLinks()
00149 {
00150         if(_links.size())
00151                 _linksModified = true;
00152         _links.clear();
00153 }
00154 
00155 void Signature::removeLink(int idTo)
00156 {
00157         int count = (int)_links.erase(idTo);
00158         if(count)
00159         {
00160                 UDEBUG("Removed link %d from %d", idTo, this->id());
00161                 _linksModified = true;
00162         }
00163 }
00164 
00165 void Signature::removeVirtualLinks()
00166 {
00167         for(std::map<int, Link>::iterator iter=_links.begin(); iter!=_links.end();)
00168         {
00169                 if(iter->second.type() == Link::kVirtualClosure)
00170                 {
00171                         _links.erase(iter++);
00172                 }
00173                 else
00174                 {
00175                         ++iter;
00176                 }
00177         }
00178 }
00179 
00180 float Signature::compareTo(const Signature & s) const
00181 {
00182         float similarity = 0.0f;
00183         const std::multimap<int, cv::KeyPoint> & words = s.getWords();
00184 
00185         if(!s.isBadSignature() && !this->isBadSignature())
00186         {
00187                 std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > pairs;
00188                 int totalWords = ((int)_words.size()-_invalidWordsCount)>((int)words.size()-s.getInvalidWordsCount())?((int)_words.size()-_invalidWordsCount):((int)words.size()-s.getInvalidWordsCount());
00189                 UASSERT(totalWords > 0);
00190                 EpipolarGeometry::findPairs(words, _words, pairs);
00191 
00192                 similarity = float(pairs.size()) / float(totalWords);
00193         }
00194         return similarity;
00195 }
00196 
00197 void Signature::changeWordsRef(int oldWordId, int activeWordId)
00198 {
00199         std::list<cv::KeyPoint> kps = uValues(_words, oldWordId);
00200         if(kps.size())
00201         {
00202                 std::list<cv::Point3f> pts = uValues(_words3, oldWordId);
00203                 std::list<cv::Mat> descriptors = uValues(_wordsDescriptors, oldWordId);
00204                 if(oldWordId<=0)
00205                 {
00206                         _invalidWordsCount-=(int)_words.erase(oldWordId);
00207                         UASSERT(_invalidWordsCount>=0);
00208                 }
00209                 else
00210                 {
00211                         _words.erase(oldWordId);
00212                 }
00213                 _words3.erase(oldWordId);
00214                 _wordsDescriptors.erase(oldWordId);
00215                 _wordsChanged.insert(std::make_pair(oldWordId, activeWordId));
00216                 for(std::list<cv::KeyPoint>::const_iterator iter=kps.begin(); iter!=kps.end(); ++iter)
00217                 {
00218                         _words.insert(std::pair<int, cv::KeyPoint>(activeWordId, (*iter)));
00219                 }
00220                 for(std::list<cv::Point3f>::const_iterator iter=pts.begin(); iter!=pts.end(); ++iter)
00221                 {
00222                         _words3.insert(std::pair<int, cv::Point3f>(activeWordId, (*iter)));
00223                 }
00224                 for(std::list<cv::Mat>::const_iterator iter=descriptors.begin(); iter!=descriptors.end(); ++iter)
00225                 {
00226                         _wordsDescriptors.insert(std::pair<int, cv::Mat>(activeWordId, (*iter)));
00227                 }
00228         }
00229 }
00230 
00231 void Signature::setWords(const std::multimap<int, cv::KeyPoint> & words)
00232 {
00233         _enabled = false;
00234         _words = words;
00235         _invalidWordsCount = 0;
00236         for(std::multimap<int, cv::KeyPoint>::iterator iter=_words.begin(); iter!=_words.end(); ++iter)
00237         {
00238                 if(iter->first>0)
00239                 {
00240                         break;
00241                 }
00242                 ++_invalidWordsCount;
00243         }
00244 }
00245 
00246 bool Signature::isBadSignature() const
00247 {
00248         return _words.size()-_invalidWordsCount <= 0;
00249 }
00250 
00251 void Signature::removeAllWords()
00252 {
00253         _words.clear();
00254         _words3.clear();
00255         _wordsDescriptors.clear();
00256         _invalidWordsCount = 0;
00257 }
00258 
00259 void Signature::removeWord(int wordId)
00260 {
00261         if(wordId<=0)
00262         {
00263                 _invalidWordsCount-=(int)_words.erase(wordId);
00264                 UASSERT(_invalidWordsCount>=0);
00265         }
00266         else
00267         {
00268                 _words.erase(wordId);
00269         }
00270         _words3.erase(wordId);
00271         _wordsDescriptors.clear();
00272 }
00273 
00274 cv::Mat Signature::getPoseCovariance() const
00275 {
00276         cv::Mat covariance = cv::Mat::eye(6,6,CV_64FC1);
00277         if(_links.size())
00278         {
00279                 for(std::map<int, Link>::const_iterator iter = _links.begin(); iter!=_links.end(); ++iter)
00280                 {
00281                         if(iter->second.kNeighbor)
00282                         {
00283                                 //Assume the first neighbor to be the backward neighbor link
00284                                 if(iter->second.to() < iter->second.from())
00285                                 {
00286                                         covariance = iter->second.infMatrix().inv();
00287                                         break;
00288                                 }
00289                         }
00290                 }
00291         }
00292         return covariance;
00293 }
00294 
00295 long Signature::getMemoryUsed(bool withSensorData) const // Return memory usage in Bytes
00296 {
00297         long total =  _words.size() * sizeof(float) * 8 +
00298                                   _words3.size() * sizeof(float) * 4;
00299         if(!_wordsDescriptors.empty())
00300         {
00301                 total += _wordsDescriptors.size() * sizeof(int);
00302                 total += _wordsDescriptors.size() * _wordsDescriptors.begin()->second.total() * _wordsDescriptors.begin()->second.elemSize();
00303         }
00304         if(withSensorData)
00305         {
00306                 total+=_sensorData.getMemoryUsed();
00307         }
00308         return total;
00309 }
00310 
00311 } //namespace rtabmap


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