Signature.h
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 #pragma once
00029 
00030 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
00031 
00032 #include <pcl/point_types.h>
00033 #include <opencv2/core/core.hpp>
00034 #include <opencv2/features2d/features2d.hpp>
00035 #include <opencv2/imgproc/imgproc.hpp>
00036 #include <map>
00037 #include <list>
00038 #include <vector>
00039 #include <set>
00040 
00041 #include <rtabmap/core/Transform.h>
00042 #include <rtabmap/core/SensorData.h>
00043 #include <rtabmap/core/Link.h>
00044 
00045 namespace rtabmap
00046 {
00047 
00048 class Memory;
00049 
00050 class RTABMAP_EXP Signature
00051 {
00052 
00053 public:
00054         Signature();
00055         Signature(int id,
00056                         int mapId,
00057                         int weight,
00058                         double stamp,
00059                         const std::string & label,
00060                         const std::multimap<int, cv::KeyPoint> & words,
00061                         const std::multimap<int, pcl::PointXYZ> & words3,
00062                         const Transform & pose = Transform(),
00063                         const std::vector<unsigned char> & userData = std::vector<unsigned char>(),
00064                         const cv::Mat & laserScan = cv::Mat(),
00065                         const cv::Mat & image = cv::Mat(),
00066                         const cv::Mat & depth = cv::Mat(),
00067                         float fx = 0.0f,
00068                         float fy = 0.0f,
00069                         float cx = 0.0f,
00070                         float cy = 0.0f,
00071                         const Transform & localTransform =Transform::getIdentity(),
00072                         int laserScanMaxPts = 0);
00073         virtual ~Signature();
00074 
00078         float compareTo(const Signature & signature) const;
00079         bool isBadSignature() const;
00080 
00081         int id() const {return _id;}
00082         int mapId() const {return _mapId;}
00083 
00084         void setWeight(int weight) {_modified=_weight!=weight;_weight = weight;}
00085         int getWeight() const {return _weight;}
00086 
00087         void setLabel(const std::string & label) {_modified=_label.compare(label)!=0;_label = label;}
00088         const std::string & getLabel() const {return _label;}
00089 
00090         void setUserData(const std::vector<unsigned char> & data);
00091         const std::vector<unsigned char> & getUserData() const {return _userData;}
00092 
00093         double getStamp() const {return _stamp;}
00094 
00095         void addLinks(const std::list<Link> & links);
00096         void addLinks(const std::map<int, Link> & links);
00097         void addLink(const Link & link);
00098 
00099         bool hasLink(int idTo) const;
00100 
00101         void changeLinkIds(int idFrom, int idTo);
00102 
00103         void removeLinks();
00104         void removeLink(int idTo);
00105         void removeVirtualLinks();
00106 
00107         void setSaved(bool saved) {_saved = saved;}
00108         void setModified(bool modified) {_modified = modified; _linksModified = modified;}
00109 
00110         const std::map<int, Link> & getLinks() const {return _links;}
00111         bool isSaved() const {return _saved;}
00112         bool isModified() const {return _modified || _linksModified;}
00113         bool isLinksModified() const {return _linksModified;}
00114 
00115         //visual words stuff
00116         void removeAllWords();
00117         void removeWord(int wordId);
00118         void changeWordsRef(int oldWordId, int activeWordId);
00119         void setWords(const std::multimap<int, cv::KeyPoint> & words) {_enabled = false;_words = words;}
00120         bool isEnabled() const {return _enabled;}
00121         void setEnabled(bool enabled) {_enabled = enabled;}
00122         const std::multimap<int, cv::KeyPoint> & getWords() const {return _words;}
00123         const std::map<int, int> & getWordsChanged() const {return _wordsChanged;}
00124         void setImageCompressed(const cv::Mat & bytes) {_imageCompressed = bytes;}
00125         const cv::Mat & getImageCompressed() const {return _imageCompressed;}
00126         void setImageRaw(const cv::Mat & image) {_imageRaw = image;}
00127         const cv::Mat & getImageRaw() const {return _imageRaw;}
00128 
00129         //metric stuff
00130         void setWords3(const std::multimap<int, pcl::PointXYZ> & words3) {_words3 = words3;}
00131         void setDepthCompressed(const cv::Mat & bytes, float fx, float fy, float cx, float cy);
00132         void setLaserScanCompressed(const cv::Mat & bytes, int maxPts) {_laserScanCompressed = bytes; _laserScanMaxPts=maxPts;}
00133         void setLocalTransform(const Transform & t) {_localTransform = t;}
00134         void setPose(const Transform & pose) {_pose = pose;}
00135         const std::multimap<int, pcl::PointXYZ> & getWords3() const {return _words3;}
00136         const cv::Mat & getDepthCompressed() const {return _depthCompressed;}
00137         const cv::Mat & getLaserScanCompressed() const {return _laserScanCompressed;}
00138         RTABMAP_DEPRECATED(float getDepthFx() const, "Use getFx() instead.");
00139         RTABMAP_DEPRECATED(float getDepthFy() const, "Use getFy() instead.");
00140         RTABMAP_DEPRECATED(float getDepthCx() const, "Use getCx() instead.");
00141         RTABMAP_DEPRECATED(float getDepthCy() const, "Use getCy() instead.");
00142         float getFx() const {return _fx;}
00143         float getFy() const {return _fy;}
00144         float getCx() const {return _cx;}
00145         float getCy() const {return _cy;}
00146         const Transform & getPose() const {return _pose;}
00147         void getPoseVariance(float & rotVariance, float & transVariance) const;
00148         const Transform & getLocalTransform() const {return _localTransform;}
00149         void setDepthRaw(const cv::Mat & depth) {_depthRaw = depth;}
00150         const cv::Mat & getDepthRaw() const {return _depthRaw;}
00151         void setLaserScanRaw(const cv::Mat & depth2D, int maxPts) {_laserScanRaw = depth2D; _laserScanMaxPts=maxPts;}
00152         const cv::Mat & getLaserScanRaw() const {return _laserScanRaw;}
00153         int getLaserScanMaxPts() const {return _laserScanMaxPts;}
00154 
00155         SensorData toSensorData();
00156         void uncompressData();
00157         void uncompressData(cv::Mat * imageRaw, cv::Mat * depthRaw, cv::Mat * laserScanRaw);
00158         void uncompressDataConst(cv::Mat * imageRaw, cv::Mat * depthRaw, cv::Mat * laserScanRaw) const;
00159 
00160 private:
00161         int _id;
00162         int _mapId;
00163         double _stamp;
00164         std::map<int, Link> _links; // id, transform
00165         int _weight;
00166         std::string _label;
00167         std::vector<unsigned char> _userData;
00168         bool _saved; // If it's saved to bd
00169         bool _modified;
00170         bool _linksModified; // Optimization when updating signatures in database
00171 
00172         // Contains all words (Some can be duplicates -> if a word appears 2
00173         // times in the signature, it will be 2 times in this list)
00174         // Words match with the CvSeq keypoints and descriptors
00175         std::multimap<int, cv::KeyPoint> _words; // word <id, keypoint>
00176         std::map<int, int> _wordsChanged; // <oldId, newId>
00177         bool _enabled;
00178         cv::Mat _imageCompressed; // compressed image
00179 
00180         cv::Mat _depthCompressed; // compressed image
00181         cv::Mat _laserScanCompressed; // compressed data
00182         float _fx;
00183         float _fy;
00184         float _cx;
00185         float _cy;
00186         Transform _pose;
00187         Transform _localTransform; // camera_link -> base_link
00188         std::multimap<int, pcl::PointXYZ> _words3; // word <id, keypoint>
00189         int _laserScanMaxPts;
00190 
00191         cv::Mat _imageRaw; // CV_8UC1 or CV_8UC3
00192         cv::Mat _depthRaw; // depth CV_16UC1 or CV_32FC1, right image CV_8UC1
00193         cv::Mat _laserScanRaw; // CV_32FC2
00194 };
00195 
00196 } // namespace rtabmap


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