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, Link::Type type = Link::kUndef) const;
86 
87  void changeLinkIds(int idFrom, int idTo);
88 
89  void removeLinks(bool keepSelfReferringLinks = false);
90  void removeLink(int idTo);
91  void removeVirtualLinks();
92 
93  void addLandmark(const Link & landmark) {_landmarks.insert(std::make_pair(landmark.to(), landmark));}
94  const std::map<int, Link> & getLandmarks() const {return _landmarks;}
95  void removeLandmarks() {_landmarks.clear();}
96 
97  void setSaved(bool saved) {_saved = saved;}
98  void setModified(bool modified) {_modified = modified; _linksModified = modified;}
99 
100  const std::multimap<int, Link> & getLinks() const {return _links;}
101  bool isSaved() const {return _saved;}
102  bool isModified() const {return _modified || _linksModified;}
103  bool isLinksModified() const {return _linksModified;}
104 
105  //visual words stuff
106  void removeAllWords();
107  void changeWordsRef(int oldWordId, int activeWordId);
108  void setWords(const std::multimap<int, int> & words, const std::vector<cv::KeyPoint> & keypoints, const std::vector<cv::Point3f> & words3, const cv::Mat & descriptors);
109  bool isEnabled() const {return _enabled;}
110  void setEnabled(bool enabled) {_enabled = enabled;}
111  const std::multimap<int, int> & getWords() const {return _words;}
112  const std::vector<cv::KeyPoint> & getWordsKpts() const {return _wordsKpts;}
113  int getInvalidWordsCount() const {return _invalidWordsCount;}
114  const std::map<int, int> & getWordsChanged() const {return _wordsChanged;}
115  const cv::Mat & getWordsDescriptors() const {return _wordsDescriptors;}
116  void setWordsDescriptors(const cv::Mat & descriptors);
117 
118  //metric stuff
119  void setPose(const Transform & pose) {_pose = pose;}
120  void setGroundTruthPose(const Transform & pose) {_groundTruthPose = pose;}
121  void setVelocity(float vx, float vy, float vz, float vroll, float vpitch, float vyaw) {
122  _velocity = std::vector<float>(6,0);
123  _velocity[0]=vx;
124  _velocity[1]=vy;
125  _velocity[2]=vz;
126  _velocity[3]=vroll;
127  _velocity[4]=vpitch;
128  _velocity[5]=vyaw;
129  }
130 
131  const std::vector<cv::Point3f> & getWords3() const {return _words3;}
132  const Transform & getPose() const {return _pose;}
133  cv::Mat getPoseCovariance() const;
134  const Transform & getGroundTruthPose() const {return _groundTruthPose;}
135  const std::vector<float> & getVelocity() const {return _velocity;}
136 
137  SensorData & sensorData() {return _sensorData;}
138  const SensorData & sensorData() const {return _sensorData;}
139 
140  unsigned long getMemoryUsed(bool withSensorData=true) const; // Return memory usage in Bytes
141 
142 private:
143  int _id;
144  int _mapId;
145  double _stamp;
146  std::multimap<int, Link> _links; // id, transform
147  std::map<int, Link> _landmarks;
148  int _weight;
149  std::string _label;
150  bool _saved; // If it's saved to bd
151  bool _modified;
152  bool _linksModified; // Optimization when updating signatures in database
153 
154  // Contains all words (Some can be duplicates -> if a word appears 2
155  // times in the signature, it will be 2 times in this list)
156  // Words match with the CvSeq keypoints and descriptors
157  std::multimap<int, int> _words; // word <id, keypoint index>
158  std::vector<cv::KeyPoint> _wordsKpts;
159  std::vector<cv::Point3f> _words3; // in base_link frame (localTransform applied))
161  std::map<int, int> _wordsChanged; // <oldId, newId>
162  bool _enabled;
164 
167  std::vector<float> _velocity;
168 
170 };
171 
172 } // namespace rtabmap
const Transform & getGroundTruthPose() const
Definition: Signature.h:134
int mapId() const
Definition: Signature.h:71
const std::vector< float > & getVelocity() const
Definition: Signature.h:135
int getInvalidWordsCount() const
Definition: Signature.h:113
cv::Mat _wordsDescriptors
Definition: Signature.h:160
void setGroundTruthPose(const Transform &pose)
Definition: Signature.h:120
const SensorData & sensorData() const
Definition: Signature.h:138
std::string _label
Definition: Signature.h:149
std::map< int, Link > _landmarks
Definition: Signature.h:147
SensorData _sensorData
Definition: Signature.h:169
bool isSaved() const
Definition: Signature.h:101
void setEnabled(bool enabled)
Definition: Signature.h:110
std::vector< float > _velocity
Definition: Signature.h:167
bool isLinksModified() const
Definition: Signature.h:103
const std::vector< cv::KeyPoint > & getWordsKpts() const
Definition: Signature.h:112
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:102
std::vector< cv::Point3f > _words3
Definition: Signature.h:159
Transform _groundTruthPose
Definition: Signature.h:166
std::vector< cv::KeyPoint > _wordsKpts
Definition: Signature.h:158
bool isEnabled() const
Definition: Signature.h:109
const std::multimap< int, int > & getWords() const
Definition: Signature.h:111
const std::multimap< int, Link > & getLinks() const
Definition: Signature.h:100
void setWeight(int weight)
Definition: Signature.h:73
void addLandmark(const Link &landmark)
Definition: Signature.h:93
void removeLandmarks()
Definition: Signature.h:95
const std::map< int, int > & getWordsChanged() const
Definition: Signature.h:114
std::multimap< int, int > _words
Definition: Signature.h:157
void setVelocity(float vx, float vy, float vz, float vroll, float vpitch, float vyaw)
Definition: Signature.h:121
const cv::Mat & getWordsDescriptors() const
Definition: Signature.h:115
int id() const
Definition: Signature.h:70
std::multimap< int, Link > _links
Definition: Signature.h:146
const std::map< int, Link > & getLandmarks() const
Definition: Signature.h:94
int getWeight() const
Definition: Signature.h:74
void setPose(const Transform &pose)
Definition: Signature.h:119
void setSaved(bool saved)
Definition: Signature.h:97
void setLabel(const std::string &label)
Definition: Signature.h:76
const Transform & getPose() const
Definition: Signature.h:132
const std::vector< cv::Point3f > & getWords3() const
Definition: Signature.h:131
SensorData & sensorData()
Definition: Signature.h:137
void setModified(bool modified)
Definition: Signature.h:98
Transform _pose
Definition: Signature.h:165
std::map< int, int > _wordsChanged
Definition: Signature.h:161


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:35:00