Signature.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2014, 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(-1),
00044         _saved(false),
00045         _modified(true),
00046         _linksModified(true),
00047         _enabled(false),
00048         _fx(0.0f),
00049         _fy(0.0f),
00050         _cx(0.0f),
00051         _cy(0.0f),
00052         _laserScanMaxPts(0)
00053 {
00054 }
00055 
00056 Signature::Signature(
00057                 int id,
00058                 int mapId,
00059                 int weight,
00060                 double stamp,
00061                 const std::string & label,
00062                 const std::multimap<int, cv::KeyPoint> & words,
00063                 const std::multimap<int, pcl::PointXYZ> & words3, // in base_link frame (localTransform applied)
00064                 const Transform & pose,
00065                 const std::vector<unsigned char> & userData,
00066                 const cv::Mat & laserScanCompressed, // in base_link frame
00067                 const cv::Mat & imageCompressed, // in camera_link frame
00068                 const cv::Mat & depthCompressed, // in camera_link frame
00069                 float fx,
00070                 float fy,
00071                 float cx,
00072                 float cy,
00073                 const Transform & localTransform,
00074                 int laserScanMaxPts) :
00075         _id(id),
00076         _mapId(mapId),
00077         _stamp(stamp),
00078         _weight(weight),
00079         _label(label),
00080         _userData(userData),
00081         _saved(false),
00082         _modified(true),
00083         _linksModified(true),
00084         _words(words),
00085         _enabled(false),
00086         _imageCompressed(imageCompressed),
00087         _depthCompressed(depthCompressed),
00088         _laserScanCompressed(laserScanCompressed),
00089         _fx(fx),
00090         _fy(fy),
00091         _cx(cx),
00092         _cy(cy),
00093         _pose(pose),
00094         _localTransform(localTransform),
00095         _words3(words3),
00096         _laserScanMaxPts(laserScanMaxPts)
00097 {
00098 }
00099 
00100 Signature::~Signature()
00101 {
00102         //UDEBUG("id=%d", _id);
00103 }
00104 
00105 void Signature::setUserData(const std::vector<unsigned char> & data)
00106 {
00107         if(!_userData.empty() && !data.empty())
00108         {
00109                 UWARN("Node %d: Current user data (%d bytes) overwritten by new data (%d bytes)",
00110                                 _id, (int)_userData.size(), (int)data.size());
00111         }
00112 
00113         _modified = true;
00114         _userData = data;
00115 }
00116 
00117 void Signature::addLinks(const std::list<Link> & links)
00118 {
00119         for(std::list<Link>::const_iterator iter = links.begin(); iter!=links.end(); ++iter)
00120         {
00121                 addLink(*iter);
00122         }
00123 }
00124 void Signature::addLinks(const std::map<int, Link> & links)
00125 {
00126         for(std::map<int, Link>::const_iterator iter = links.begin(); iter!=links.end(); ++iter)
00127         {
00128                 addLink(iter->second);
00129         }
00130 }
00131 void Signature::addLink(const Link & link)
00132 {
00133         UDEBUG("Add link %d to %d (type=%d)", link.to(), this->id(), (int)link.type());
00134         UASSERT(link.from() == this->id());
00135         std::pair<std::map<int, Link>::iterator, bool> pair = _links.insert(std::make_pair(link.to(), link));
00136         UASSERT_MSG(pair.second, uFormat("Link %d (type=%d) already added to signature %d!", link.to(), link.type(), this->id()).c_str());
00137         _linksModified = true;
00138 }
00139 
00140 bool Signature::hasLink(int idTo) const
00141 {
00142         return _links.find(idTo) != _links.end();
00143 }
00144 
00145 void Signature::changeLinkIds(int idFrom, int idTo)
00146 {
00147         std::map<int, Link>::iterator iter = _links.find(idFrom);
00148         if(iter != _links.end())
00149         {
00150                 Link link = iter->second;
00151                 _links.erase(iter);
00152                 link.setTo(idTo);
00153                 _links.insert(std::make_pair(idTo, link));
00154                 _linksModified = true;
00155                 UDEBUG("(%d) neighbor ids changed from %d to %d", _id, idFrom, idTo);
00156         }
00157 }
00158 
00159 void Signature::removeLinks()
00160 {
00161         if(_links.size())
00162                 _linksModified = true;
00163         _links.clear();
00164 }
00165 
00166 void Signature::removeLink(int idTo)
00167 {
00168         int count = (int)_links.erase(idTo);
00169         if(count)
00170         {
00171                 _linksModified = true;
00172         }
00173 }
00174 
00175 void Signature::removeVirtualLinks()
00176 {
00177         for(std::map<int, Link>::iterator iter=_links.begin(); iter!=_links.end();)
00178         {
00179                 if(iter->second.type() == Link::kVirtualClosure)
00180                 {
00181                         _links.erase(iter++);
00182                 }
00183                 else
00184                 {
00185                         ++iter;
00186                 }
00187         }
00188 }
00189 
00190 float Signature::compareTo(const Signature & s) const
00191 {
00192         float similarity = 0.0f;
00193         const std::multimap<int, cv::KeyPoint> & words = s.getWords();
00194         if(words.size() != 0 && _words.size() != 0)
00195         {
00196                 std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > pairs;
00197                 unsigned int totalWords = _words.size()>words.size()?_words.size():words.size();
00198                 EpipolarGeometry::findPairs(words, _words, pairs);
00199 
00200                 similarity = float(pairs.size()) / float(totalWords);
00201         }
00202         return similarity;
00203 }
00204 
00205 void Signature::changeWordsRef(int oldWordId, int activeWordId)
00206 {
00207         std::list<cv::KeyPoint> kps = uValues(_words, oldWordId);
00208         if(kps.size())
00209         {
00210                 std::list<pcl::PointXYZ> pts = uValues(_words3, oldWordId);
00211                 _words.erase(oldWordId);
00212                 _words3.erase(oldWordId);
00213                 _wordsChanged.insert(std::make_pair(oldWordId, activeWordId));
00214                 for(std::list<cv::KeyPoint>::const_iterator iter=kps.begin(); iter!=kps.end(); ++iter)
00215                 {
00216                         _words.insert(std::pair<int, cv::KeyPoint>(activeWordId, (*iter)));
00217                 }
00218                 for(std::list<pcl::PointXYZ>::const_iterator iter=pts.begin(); iter!=pts.end(); ++iter)
00219                 {
00220                         _words3.insert(std::pair<int, pcl::PointXYZ>(activeWordId, (*iter)));
00221                 }
00222         }
00223 }
00224 
00225 bool Signature::isBadSignature() const
00226 {
00227         return !_words.size();
00228 }
00229 
00230 void Signature::removeAllWords()
00231 {
00232         _words.clear();
00233         _words3.clear();
00234 }
00235 
00236 void Signature::removeWord(int wordId)
00237 {
00238         _words.erase(wordId);
00239         _words3.erase(wordId);
00240 }
00241 
00242 void Signature::setDepthCompressed(const cv::Mat & bytes, float fx, float fy, float cx, float cy)
00243 {
00244         UASSERT_MSG(bytes.empty() || (!bytes.empty() && fx > 0.0f && fy > 0.0f && cx >= 0.0f && cy >= 0.0f), uFormat("fx=%f fy=%f cx=%f cy=%f",fx,fy,cx,cy).c_str());
00245         _depthCompressed = bytes;
00246         _fx=fx;
00247         _fy=fy;
00248         _cx=cx;
00249         _cy=cy;
00250 }
00251 
00252 float Signature::getDepthFx() const {return getFx();}
00253 float Signature::getDepthFy() const {return getFy();}
00254 float Signature::getDepthCx() const {return getCx();}
00255 float Signature::getDepthCy() const {return getCy();}
00256 
00257 void Signature::getPoseVariance(float & rotVariance, float & transVariance) const
00258 {
00259         rotVariance = 1.0f;
00260         transVariance = 1.0f;
00261         if(_links.size())
00262         {
00263                 for(std::map<int, Link>::const_iterator iter = _links.begin(); iter!=_links.end(); ++iter)
00264                 {
00265                         if(iter->second.kNeighbor)
00266                         {
00267                                 //Assume the first neighbor to be the backward neighbor link
00268                                 if(iter->second.to() < iter->second.from())
00269                                 {
00270                                         rotVariance = iter->second.rotVariance();
00271                                         transVariance = iter->second.transVariance();
00272                                         break;
00273                                 }
00274                         }
00275                 }
00276         }
00277 }
00278 
00279 SensorData Signature::toSensorData()
00280 {
00281         this->uncompressData();
00282         float rotVariance = 1.0f;
00283         float transVariance = 1.0f;
00284         this->getPoseVariance(rotVariance, transVariance);
00285 
00286         return SensorData(_laserScanRaw,
00287                         _laserScanMaxPts,
00288                         _imageRaw,
00289                         _depthRaw,
00290                         _fx,
00291                         _fy,
00292                         _cx,
00293                         _cy,
00294                         _localTransform,
00295                         _pose,
00296                         rotVariance,
00297                         transVariance,
00298                         _id,
00299                         _stamp,
00300                         _userData);
00301 }
00302 
00303 void Signature::uncompressData()
00304 {
00305         uncompressData(&_imageRaw, &_depthRaw, &_laserScanRaw);
00306 }
00307 
00308 void Signature::uncompressData(cv::Mat * imageRaw, cv::Mat * depthRaw, cv::Mat * laserScanRaw)
00309 {
00310         uncompressDataConst(imageRaw, depthRaw, laserScanRaw);
00311         if(imageRaw && !imageRaw->empty() && _imageRaw.empty())
00312         {
00313                 _imageRaw = *imageRaw;
00314         }
00315         if(depthRaw && !depthRaw->empty() && _depthRaw.empty())
00316         {
00317                 _depthRaw = *depthRaw;
00318         }
00319         if(laserScanRaw && !laserScanRaw->empty() && _laserScanRaw.empty())
00320         {
00321                 _laserScanRaw = *laserScanRaw;
00322         }
00323 }
00324 
00325 void Signature::uncompressDataConst(cv::Mat * imageRaw, cv::Mat * depthRaw, cv::Mat * laserScanRaw) const
00326 {
00327         if(imageRaw)
00328         {
00329                 *imageRaw = _imageRaw;
00330         }
00331         if(depthRaw)
00332         {
00333                 *depthRaw = _depthRaw;
00334         }
00335         if(laserScanRaw)
00336         {
00337                 *laserScanRaw = _laserScanRaw;
00338         }
00339         if( (imageRaw && imageRaw->empty()) ||
00340                 (depthRaw && depthRaw->empty()) ||
00341                 (laserScanRaw && laserScanRaw->empty()))
00342         {
00343                 rtabmap::CompressionThread ctImage(_imageCompressed, true);
00344                 rtabmap::CompressionThread ctDepth(_depthCompressed, true);
00345                 rtabmap::CompressionThread ctLaserScan(_laserScanCompressed, false);
00346                 if(imageRaw && imageRaw->empty())
00347                 {
00348                         ctImage.start();
00349                 }
00350                 if(depthRaw && depthRaw->empty())
00351                 {
00352                         ctDepth.start();
00353                 }
00354                 if(laserScanRaw && laserScanRaw->empty())
00355                 {
00356                         ctLaserScan.start();
00357                 }
00358                 ctImage.join();
00359                 ctDepth.join();
00360                 ctLaserScan.join();
00361                 if(imageRaw && imageRaw->empty())
00362                 {
00363                         *imageRaw = ctImage.getUncompressedData();
00364                 }
00365                 if(depthRaw && depthRaw->empty())
00366                 {
00367                         *depthRaw = ctDepth.getUncompressedData();
00368                 }
00369                 if(laserScanRaw && laserScanRaw->empty())
00370                 {
00371                         *laserScanRaw = ctLaserScan.getUncompressedData();
00372                 }
00373         }
00374 }
00375 
00376 } //namespace rtabmap


rtabmap
Author(s): Mathieu Labbe
autogenerated on Fri Aug 28 2015 12:51:32