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 {
00049 }
00050 
00051 Signature::Signature(
00052                 int id,
00053                 int mapId,
00054                 int weight,
00055                 double stamp,
00056                 const std::string & label,
00057                 const Transform & pose,
00058                 const Transform & groundTruthPose,
00059                 const SensorData & sensorData):
00060         _id(id),
00061         _mapId(mapId),
00062         _stamp(stamp),
00063         _weight(weight),
00064         _label(label),
00065         _saved(false),
00066         _modified(true),
00067         _linksModified(true),
00068         _enabled(false),
00069         _pose(pose),
00070         _groundTruthPose(groundTruthPose),
00071         _sensorData(sensorData)
00072 {
00073         if(_sensorData.id() == 0)
00074         {
00075                 _sensorData.setId(id);
00076         }
00077         UASSERT(_sensorData.id() == _id);
00078 }
00079 
00080 Signature::Signature(const SensorData & data) :
00081         _id(data.id()),
00082         _mapId(-1),
00083         _stamp(data.stamp()),
00084         _weight(0),
00085         _label(""),
00086         _saved(false),
00087         _modified(true),
00088         _linksModified(true),
00089         _enabled(false),
00090         _pose(Transform::getIdentity()),
00091         _groundTruthPose(data.groundTruth()),
00092         _sensorData(data)
00093 {
00094 
00095 }
00096 
00097 Signature::~Signature()
00098 {
00099         //UDEBUG("id=%d", _id);
00100 }
00101 
00102 void Signature::addLinks(const std::list<Link> & links)
00103 {
00104         for(std::list<Link>::const_iterator iter = links.begin(); iter!=links.end(); ++iter)
00105         {
00106                 addLink(*iter);
00107         }
00108 }
00109 void Signature::addLinks(const std::map<int, Link> & links)
00110 {
00111         for(std::map<int, Link>::const_iterator iter = links.begin(); iter!=links.end(); ++iter)
00112         {
00113                 addLink(iter->second);
00114         }
00115 }
00116 void Signature::addLink(const Link & link)
00117 {
00118         UDEBUG("Add link %d to %d (type=%d)", link.to(), this->id(), (int)link.type());
00119         UASSERT_MSG(link.from() == this->id(), uFormat("%d->%d for signature %d (type=%d)", link.from(), link.to(), this->id(), link.type()).c_str());
00120         UASSERT_MSG(link.to() != this->id(), uFormat("%d->%d for signature %d (type=%d)", link.from(), link.to(), this->id(), link.type()).c_str());
00121         std::pair<std::map<int, Link>::iterator, bool> pair = _links.insert(std::make_pair(link.to(), link));
00122         UASSERT_MSG(pair.second, uFormat("Link %d (type=%d) already added to signature %d!", link.to(), link.type(), this->id()).c_str());
00123         _linksModified = true;
00124 }
00125 
00126 bool Signature::hasLink(int idTo) const
00127 {
00128         return _links.find(idTo) != _links.end();
00129 }
00130 
00131 void Signature::changeLinkIds(int idFrom, int idTo)
00132 {
00133         std::map<int, Link>::iterator iter = _links.find(idFrom);
00134         if(iter != _links.end())
00135         {
00136                 Link link = iter->second;
00137                 _links.erase(iter);
00138                 link.setTo(idTo);
00139                 _links.insert(std::make_pair(idTo, link));
00140                 _linksModified = true;
00141                 UDEBUG("(%d) neighbor ids changed from %d to %d", _id, idFrom, idTo);
00142         }
00143 }
00144 
00145 void Signature::removeLinks()
00146 {
00147         if(_links.size())
00148                 _linksModified = true;
00149         _links.clear();
00150 }
00151 
00152 void Signature::removeLink(int idTo)
00153 {
00154         int count = (int)_links.erase(idTo);
00155         if(count)
00156         {
00157                 UDEBUG("Removed link %d from %d", idTo, this->id());
00158                 _linksModified = true;
00159         }
00160 }
00161 
00162 void Signature::removeVirtualLinks()
00163 {
00164         for(std::map<int, Link>::iterator iter=_links.begin(); iter!=_links.end();)
00165         {
00166                 if(iter->second.type() == Link::kVirtualClosure)
00167                 {
00168                         _links.erase(iter++);
00169                 }
00170                 else
00171                 {
00172                         ++iter;
00173                 }
00174         }
00175 }
00176 
00177 float Signature::compareTo(const Signature & s) const
00178 {
00179         float similarity = 0.0f;
00180         const std::multimap<int, cv::KeyPoint> & words = s.getWords();
00181         if(words.size() != 0 && _words.size() != 0)
00182         {
00183                 std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > pairs;
00184                 unsigned int totalWords = _words.size()>words.size()?_words.size():words.size();
00185                 EpipolarGeometry::findPairs(words, _words, pairs);
00186 
00187                 similarity = float(pairs.size()) / float(totalWords);
00188         }
00189         return similarity;
00190 }
00191 
00192 void Signature::changeWordsRef(int oldWordId, int activeWordId)
00193 {
00194         std::list<cv::KeyPoint> kps = uValues(_words, oldWordId);
00195         if(kps.size())
00196         {
00197                 std::list<cv::Point3f> pts = uValues(_words3, oldWordId);
00198                 std::list<cv::Mat> descriptors = uValues(_wordsDescriptors, oldWordId);
00199                 _words.erase(oldWordId);
00200                 _words3.erase(oldWordId);
00201                 _wordsDescriptors.erase(oldWordId);
00202                 _wordsChanged.insert(std::make_pair(oldWordId, activeWordId));
00203                 for(std::list<cv::KeyPoint>::const_iterator iter=kps.begin(); iter!=kps.end(); ++iter)
00204                 {
00205                         _words.insert(std::pair<int, cv::KeyPoint>(activeWordId, (*iter)));
00206                 }
00207                 for(std::list<cv::Point3f>::const_iterator iter=pts.begin(); iter!=pts.end(); ++iter)
00208                 {
00209                         _words3.insert(std::pair<int, cv::Point3f>(activeWordId, (*iter)));
00210                 }
00211                 for(std::list<cv::Mat>::const_iterator iter=descriptors.begin(); iter!=descriptors.end(); ++iter)
00212                 {
00213                         _wordsDescriptors.insert(std::pair<int, cv::Mat>(activeWordId, (*iter)));
00214                 }
00215         }
00216 }
00217 
00218 bool Signature::isBadSignature() const
00219 {
00220         return !_words.size();
00221 }
00222 
00223 void Signature::removeAllWords()
00224 {
00225         _words.clear();
00226         _words3.clear();
00227         _wordsDescriptors.clear();
00228 }
00229 
00230 void Signature::removeWord(int wordId)
00231 {
00232         _words.erase(wordId);
00233         _words3.erase(wordId);
00234         _wordsDescriptors.clear();
00235 }
00236 
00237 cv::Mat Signature::getPoseCovariance() const
00238 {
00239         cv::Mat covariance = cv::Mat::eye(6,6,CV_64FC1);
00240         if(_links.size())
00241         {
00242                 for(std::map<int, Link>::const_iterator iter = _links.begin(); iter!=_links.end(); ++iter)
00243                 {
00244                         if(iter->second.kNeighbor)
00245                         {
00246                                 //Assume the first neighbor to be the backward neighbor link
00247                                 if(iter->second.to() < iter->second.from())
00248                                 {
00249                                         covariance = iter->second.infMatrix().inv();
00250                                         break;
00251                                 }
00252                         }
00253                 }
00254         }
00255         return covariance;
00256 }
00257 
00258 } //namespace rtabmap


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