Signature.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #pragma once
29 
30 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
31 
32 #include <pcl/point_types.h>
33 #include <opencv2/core/core.hpp>
34 #include <opencv2/features2d/features2d.hpp>
35 #include <opencv2/imgproc/imgproc.hpp>
36 #include <map>
37 #include <list>
38 #include <vector>
39 #include <set>
40 
41 #include <rtabmap/core/Transform.h>
43 #include <rtabmap/core/Link.h>
44 
45 namespace rtabmap
46 {
47 
49 {
50 
51 public:
52  Signature();
53  Signature(int id,
54  int mapId = -1,
55  int weight = 0,
56  double stamp = 0.0,
57  const std::string & label = std::string(),
58  const Transform & pose = Transform(),
59  const Transform & groundTruthPose = Transform(),
60  const SensorData & sensorData = SensorData());
61  Signature(const SensorData & data);
62  virtual ~Signature();
63 
67  float compareTo(const Signature & signature) const;
68  bool isBadSignature() const;
69 
70  int id() const {return _id;}
71  int mapId() const {return _mapId;}
72 
73  void setWeight(int weight) {_modified=_weight!=weight;_weight = weight;}
74  int getWeight() const {return _weight;}
75 
76  void setLabel(const std::string & label) {_modified=_label.compare(label)!=0;_label = label;}
77  const std::string & getLabel() const {return _label;}
78 
79  double getStamp() const {return _stamp;}
80 
81  void addLinks(const std::list<Link> & links);
82  void addLinks(const std::map<int, Link> & links);
83  void addLink(const Link & link);
84 
85  bool hasLink(int idTo) const;
86 
87  void changeLinkIds(int idFrom, int idTo);
88 
89  void removeLinks();
90  void removeLink(int idTo);
91  void removeVirtualLinks();
92 
93  void setSaved(bool saved) {_saved = saved;}
94  void setModified(bool modified) {_modified = modified; _linksModified = modified;}
95 
96  const std::map<int, Link> & getLinks() const {return _links;}
97  bool isSaved() const {return _saved;}
98  bool isModified() const {return _modified || _linksModified;}
99  bool isLinksModified() const {return _linksModified;}
100 
101  //visual words stuff
102  void removeAllWords();
103  void removeWord(int wordId);
104  void changeWordsRef(int oldWordId, int activeWordId);
105  void setWords(const std::multimap<int, cv::KeyPoint> & words);
106  bool isEnabled() const {return _enabled;}
107  void setEnabled(bool enabled) {_enabled = enabled;}
108  const std::multimap<int, cv::KeyPoint> & getWords() const {return _words;}
109  int getInvalidWordsCount() const {return _invalidWordsCount;}
110  const std::map<int, int> & getWordsChanged() const {return _wordsChanged;}
111  const std::multimap<int, cv::Mat> & getWordsDescriptors() const {return _wordsDescriptors;}
112  void setWordsDescriptors(const std::multimap<int, cv::Mat> & descriptors) {_wordsDescriptors = descriptors;}
113 
114  //metric stuff
115  void setWords3(const std::multimap<int, cv::Point3f> & words3) {_words3 = words3;}
116  void setPose(const Transform & pose) {_pose = pose;}
117  void setGroundTruthPose(const Transform & pose) {_groundTruthPose = pose;}
118  void setVelocity(float vx, float vy, float vz, float vroll, float vpitch, float vyaw) {
119  _velocity = std::vector<float>(6,0);
120  _velocity[0]=vx;
121  _velocity[1]=vy;
122  _velocity[2]=vz;
123  _velocity[3]=vroll;
124  _velocity[4]=vpitch;
125  _velocity[5]=vyaw;
126  }
127 
128  const std::multimap<int, cv::Point3f> & getWords3() const {return _words3;}
129  const Transform & getPose() const {return _pose;}
130  cv::Mat getPoseCovariance() const;
131  const Transform & getGroundTruthPose() const {return _groundTruthPose;}
132  const std::vector<float> & getVelocity() const {return _velocity;}
133 
134  SensorData & sensorData() {return _sensorData;}
135  const SensorData & sensorData() const {return _sensorData;}
136 
137  long getMemoryUsed(bool withSensorData=true) const; // Return memory usage in Bytes
138 
139 private:
140  int _id;
141  int _mapId;
142  double _stamp;
143  std::map<int, Link> _links; // id, transform
144  int _weight;
145  std::string _label;
146  bool _saved; // If it's saved to bd
147  bool _modified;
148  bool _linksModified; // Optimization when updating signatures in database
149 
150  // Contains all words (Some can be duplicates -> if a word appears 2
151  // times in the signature, it will be 2 times in this list)
152  // Words match with the CvSeq keypoints and descriptors
153  std::multimap<int, cv::KeyPoint> _words; // word <id, keypoint>
154  std::multimap<int, cv::Point3f> _words3; // word <id, point> // in base_link frame (localTransform applied))
155  std::multimap<int, cv::Mat> _wordsDescriptors;
156  std::map<int, int> _wordsChanged; // <oldId, newId>
157  bool _enabled;
159 
162  std::vector<float> _velocity;
163 
165 };
166 
167 } // namespace rtabmap
const std::multimap< int, cv::Point3f > & getWords3() const
Definition: Signature.h:128
const Transform & getGroundTruthPose() const
Definition: Signature.h:131
int mapId() const
Definition: Signature.h:71
const std::multimap< int, cv::KeyPoint > & getWords() const
Definition: Signature.h:108
void setWords3(const std::multimap< int, cv::Point3f > &words3)
Definition: Signature.h:115
const std::vector< float > & getVelocity() const
Definition: Signature.h:132
int getInvalidWordsCount() const
Definition: Signature.h:109
void setGroundTruthPose(const Transform &pose)
Definition: Signature.h:117
const SensorData & sensorData() const
Definition: Signature.h:135
std::string _label
Definition: Signature.h:145
const std::multimap< int, cv::Mat > & getWordsDescriptors() const
Definition: Signature.h:111
SensorData _sensorData
Definition: Signature.h:164
bool isSaved() const
Definition: Signature.h:97
std::multimap< int, cv::KeyPoint > _words
Definition: Signature.h:153
void setEnabled(bool enabled)
Definition: Signature.h:107
std::vector< float > _velocity
Definition: Signature.h:162
bool isLinksModified() const
Definition: Signature.h:99
const std::string & getLabel() const
Definition: Signature.h:77
double getStamp() const
Definition: Signature.h:79
#define RTABMAP_EXP
Definition: RtabmapExp.h:38
bool isModified() const
Definition: Signature.h:98
std::multimap< int, cv::Mat > _wordsDescriptors
Definition: Signature.h:155
Transform _groundTruthPose
Definition: Signature.h:161
bool isEnabled() const
Definition: Signature.h:106
void setWeight(int weight)
Definition: Signature.h:73
const std::map< int, int > & getWordsChanged() const
Definition: Signature.h:110
std::multimap< int, cv::Point3f > _words3
Definition: Signature.h:154
void setWordsDescriptors(const std::multimap< int, cv::Mat > &descriptors)
Definition: Signature.h:112
void setVelocity(float vx, float vy, float vz, float vroll, float vpitch, float vyaw)
Definition: Signature.h:118
int id() const
Definition: Signature.h:70
int getWeight() const
Definition: Signature.h:74
void setPose(const Transform &pose)
Definition: Signature.h:116
void setSaved(bool saved)
Definition: Signature.h:93
void setLabel(const std::string &label)
Definition: Signature.h:76
const std::map< int, Link > & getLinks() const
Definition: Signature.h:96
const Transform & getPose() const
Definition: Signature.h:129
SensorData & sensorData()
Definition: Signature.h:134
std::map< int, Link > _links
Definition: Signature.h:143
void setModified(bool modified)
Definition: Signature.h:94
Transform _pose
Definition: Signature.h:160
std::map< int, int > _wordsChanged
Definition: Signature.h:156


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:32