Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #pragma once
00029
00030 #include "rtabmap/core/RtabmapExp.h"
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 RTABMAP_EXP Signature
00049 {
00050
00051 public:
00052 Signature();
00053 Signature(int id,
00054 int mapId = -1,
00055 int weight = 0,
00056 double stamp = 0.0,
00057 const std::string & label = std::string(),
00058 const Transform & pose = Transform(),
00059 const Transform & groundTruthPose = Transform(),
00060 const SensorData & sensorData = SensorData());
00061 Signature(const SensorData & data);
00062 virtual ~Signature();
00063
00067 float compareTo(const Signature & signature) const;
00068 bool isBadSignature() const;
00069
00070 int id() const {return _id;}
00071 int mapId() const {return _mapId;}
00072
00073 void setWeight(int weight) {_modified=_weight!=weight;_weight = weight;}
00074 int getWeight() const {return _weight;}
00075
00076 void setLabel(const std::string & label) {_modified=_label.compare(label)!=0;_label = label;}
00077 const std::string & getLabel() const {return _label;}
00078
00079 double getStamp() const {return _stamp;}
00080
00081 void addLinks(const std::list<Link> & links);
00082 void addLinks(const std::map<int, Link> & links);
00083 void addLink(const Link & link);
00084
00085 bool hasLink(int idTo) const;
00086
00087 void changeLinkIds(int idFrom, int idTo);
00088
00089 void removeLinks();
00090 void removeLink(int idTo);
00091 void removeVirtualLinks();
00092
00093 void setSaved(bool saved) {_saved = saved;}
00094 void setModified(bool modified) {_modified = modified; _linksModified = modified;}
00095
00096 const std::map<int, Link> & getLinks() const {return _links;}
00097 bool isSaved() const {return _saved;}
00098 bool isModified() const {return _modified || _linksModified;}
00099 bool isLinksModified() const {return _linksModified;}
00100
00101
00102 void removeAllWords();
00103 void removeWord(int wordId);
00104 void changeWordsRef(int oldWordId, int activeWordId);
00105 void setWords(const std::multimap<int, cv::KeyPoint> & words);
00106 bool isEnabled() const {return _enabled;}
00107 void setEnabled(bool enabled) {_enabled = enabled;}
00108 const std::multimap<int, cv::KeyPoint> & getWords() const {return _words;}
00109 int getInvalidWordsCount() const {return _invalidWordsCount;}
00110 const std::map<int, int> & getWordsChanged() const {return _wordsChanged;}
00111 const std::multimap<int, cv::Mat> & getWordsDescriptors() const {return _wordsDescriptors;}
00112 void setWordsDescriptors(const std::multimap<int, cv::Mat> & descriptors) {_wordsDescriptors = descriptors;}
00113
00114
00115 void setWords3(const std::multimap<int, cv::Point3f> & words3) {_words3 = words3;}
00116 void setPose(const Transform & pose) {_pose = pose;}
00117 void setGroundTruthPose(const Transform & pose) {_groundTruthPose = pose;}
00118 void setVelocity(float vx, float vy, float vz, float vroll, float vpitch, float vyaw) {
00119 _velocity = std::vector<float>(6,0);
00120 _velocity[0]=vx;
00121 _velocity[1]=vy;
00122 _velocity[2]=vz;
00123 _velocity[3]=vroll;
00124 _velocity[4]=vpitch;
00125 _velocity[5]=vyaw;
00126 }
00127
00128 const std::multimap<int, cv::Point3f> & getWords3() const {return _words3;}
00129 const Transform & getPose() const {return _pose;}
00130 cv::Mat getPoseCovariance() const;
00131 const Transform & getGroundTruthPose() const {return _groundTruthPose;}
00132 const std::vector<float> & getVelocity() const {return _velocity;}
00133
00134 SensorData & sensorData() {return _sensorData;}
00135 const SensorData & sensorData() const {return _sensorData;}
00136
00137 long getMemoryUsed(bool withSensorData=true) const;
00138
00139 private:
00140 int _id;
00141 int _mapId;
00142 double _stamp;
00143 std::map<int, Link> _links;
00144 int _weight;
00145 std::string _label;
00146 bool _saved;
00147 bool _modified;
00148 bool _linksModified;
00149
00150
00151
00152
00153 std::multimap<int, cv::KeyPoint> _words;
00154 std::multimap<int, cv::Point3f> _words3;
00155 std::multimap<int, cv::Mat> _wordsDescriptors;
00156 std::map<int, int> _wordsChanged;
00157 bool _enabled;
00158 int _invalidWordsCount;
00159
00160 Transform _pose;
00161 Transform _groundTruthPose;
00162 std::vector<float> _velocity;
00163
00164 SensorData _sensorData;
00165 };
00166
00167 }