Statistics.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 #ifndef STATISTICS_H_
29 #define STATISTICS_H_
30 
31 #include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
32 
33 #include <opencv2/core/core.hpp>
34 #include <opencv2/features2d/features2d.hpp>
35 #include <opencv2/imgproc/imgproc.hpp>
36 #include <list>
37 #include <vector>
38 #include <rtabmap/core/Signature.h>
39 #include <rtabmap/core/Link.h>
40 
41 namespace rtabmap {
42 
43 #define RTABMAP_STATS(PREFIX, NAME, UNIT) \
44  public: \
45  static std::string k##PREFIX##NAME() {return #PREFIX "/" #NAME "/" #UNIT;} \
46  private: \
47  class Dummy##PREFIX##NAME { \
48  public: \
49  Dummy##PREFIX##NAME() {if(!_defaultDataInitialized)_defaultData.insert(std::pair<std::string, float>(#PREFIX "/" #NAME "/" #UNIT, 0.0f));} \
50  }; \
51  Dummy##PREFIX##NAME dummy##PREFIX##NAME
52 
53 class RTABMAP_CORE_EXPORT Statistics
54 {
55  RTABMAP_STATS(Loop, Id,); // Combined loop or proximity detection
56  RTABMAP_STATS(Loop, RejectedHypothesis,);
57  RTABMAP_STATS(Loop, Accepted_hypothesis_id,);
58  RTABMAP_STATS(Loop, Suppressed_hypothesis_id,);
59  RTABMAP_STATS(Loop, Highest_hypothesis_id,);
60  RTABMAP_STATS(Loop, Highest_hypothesis_value,);
61  RTABMAP_STATS(Loop, Vp_hypothesis,);
62  RTABMAP_STATS(Loop, Reactivate_id,);
63  RTABMAP_STATS(Loop, Hypothesis_ratio,);
64  RTABMAP_STATS(Loop, Hypothesis_reactivated,);
65  RTABMAP_STATS(Loop, Map_id,);
66  RTABMAP_STATS(Loop, Visual_words,);
67  RTABMAP_STATS(Loop, Visual_inliers,);
68  RTABMAP_STATS(Loop, Visual_inliers_ratio,);
69  RTABMAP_STATS(Loop, Visual_matches,);
70  RTABMAP_STATS(Loop, Distance_since_last_loc, m);
71  RTABMAP_STATS(Loop, Last_id,);
72  RTABMAP_STATS(Loop, Optimization_max_error, m);
73  RTABMAP_STATS(Loop, Optimization_max_error_ratio, );
74  RTABMAP_STATS(Loop, Optimization_max_ang_error, deg);
75  RTABMAP_STATS(Loop, Optimization_max_ang_error_ratio, );
76  RTABMAP_STATS(Loop, Optimization_error, );
77  RTABMAP_STATS(Loop, Optimization_iterations, );
78  RTABMAP_STATS(Loop, Linear_variance,);
79  RTABMAP_STATS(Loop, Angular_variance,);
80  RTABMAP_STATS(Loop, Landmark_detected,);
81  RTABMAP_STATS(Loop, Landmark_detected_node_ref,);
82  RTABMAP_STATS(Loop, Visual_inliers_mean_dist,m);
83  RTABMAP_STATS(Loop, Visual_inliers_distribution,);
84  //Odom correction
85  RTABMAP_STATS(Loop, Odom_correction_norm, m);
86  RTABMAP_STATS(Loop, Odom_correction_angle, deg);
87  RTABMAP_STATS(Loop, Odom_correction_x, m);
88  RTABMAP_STATS(Loop, Odom_correction_y, m);
89  RTABMAP_STATS(Loop, Odom_correction_z, m);
90  RTABMAP_STATS(Loop, Odom_correction_roll, deg);
91  RTABMAP_STATS(Loop, Odom_correction_pitch, deg);
92  RTABMAP_STATS(Loop, Odom_correction_yaw, deg);
93  // Map to Odom
94  RTABMAP_STATS(Loop, MapToOdom_norm, m);
95  RTABMAP_STATS(Loop, MapToOdom_angle, deg);
96  RTABMAP_STATS(Loop, MapToOdom_x, m);
97  RTABMAP_STATS(Loop, MapToOdom_y, m);
98  RTABMAP_STATS(Loop, MapToOdom_z, m);
99  RTABMAP_STATS(Loop, MapToOdom_roll, deg);
100  RTABMAP_STATS(Loop, MapToOdom_pitch, deg);
101  RTABMAP_STATS(Loop, MapToOdom_yaw, deg);
102  // Map to Base
103  RTABMAP_STATS(Loop, MapToBase_x, m);
104  RTABMAP_STATS(Loop, MapToBase_y, m);
105  RTABMAP_STATS(Loop, MapToBase_z, m);
106  RTABMAP_STATS(Loop, MapToBase_roll, deg);
107  RTABMAP_STATS(Loop, MapToBase_pitch, deg);
108  RTABMAP_STATS(Loop, MapToBase_yaw, deg);
109  RTABMAP_STATS(Loop, MapToBase_lin_std, m);
110  RTABMAP_STATS(Loop, MapToBase_lin_var, m2);
111 
112  RTABMAP_STATS(Proximity, Time_detections,);
113  RTABMAP_STATS(Proximity, Space_last_detection_id,);
114  RTABMAP_STATS(Proximity, Space_paths,);
115  RTABMAP_STATS(Proximity, Space_visual_paths_checked,);
116  RTABMAP_STATS(Proximity, Space_scan_paths_checked,);
117  RTABMAP_STATS(Proximity, Space_detections_added_visually,);
118  RTABMAP_STATS(Proximity, Space_detections_added_icp_multi,);
119  RTABMAP_STATS(Proximity, Space_detections_added_icp_global,);
120 
121  RTABMAP_STATS(NeighborLinkRefining, Accepted,);
122  RTABMAP_STATS(NeighborLinkRefining, Inliers,);
123  RTABMAP_STATS(NeighborLinkRefining, ICP_inliers_ratio,);
124  RTABMAP_STATS(NeighborLinkRefining, ICP_rotation, rad);
125  RTABMAP_STATS(NeighborLinkRefining, ICP_translation, m);
126  RTABMAP_STATS(NeighborLinkRefining, ICP_complexity,);
127  RTABMAP_STATS(NeighborLinkRefining, Variance,);
128  RTABMAP_STATS(NeighborLinkRefining, Pts,);
129 
130  RTABMAP_STATS(Memory, Working_memory_size,);
131  RTABMAP_STATS(Memory, Short_time_memory_size,);
132  RTABMAP_STATS(Memory, Database_memory_used, MB);
133  RTABMAP_STATS(Memory, Signatures_removed,);
134  RTABMAP_STATS(Memory, Immunized_globally,);
135  RTABMAP_STATS(Memory, Immunized_locally,);
136  RTABMAP_STATS(Memory, Immunized_locally_max,);
137  RTABMAP_STATS(Memory, Signatures_retrieved,);
138  RTABMAP_STATS(Memory, Images_buffered,);
139  RTABMAP_STATS(Memory, Rehearsal_sim,);
140  RTABMAP_STATS(Memory, Rehearsal_id,);
141  RTABMAP_STATS(Memory, Rehearsal_merged,);
142  RTABMAP_STATS(Memory, Local_graph_size,);
143  RTABMAP_STATS(Memory, Odom_cache_poses,);
144  RTABMAP_STATS(Memory, Odom_cache_links,);
145  RTABMAP_STATS(Memory, Small_movement,);
146  RTABMAP_STATS(Memory, Fast_movement,);
147  RTABMAP_STATS(Memory, New_landmark,);
148  RTABMAP_STATS(Memory, Odometry_variance_ang,);
149  RTABMAP_STATS(Memory, Odometry_variance_lin,);
150  RTABMAP_STATS(Memory, Distance_travelled, m);
151  RTABMAP_STATS(Memory, RAM_usage, MB);
152  RTABMAP_STATS(Memory, RAM_estimated, MB);
153  RTABMAP_STATS(Memory, Triangulated_points, );
154  RTABMAP_STATS(Memory, Closest_node_distance, m);
155  RTABMAP_STATS(Memory, Closest_node_angle, rad);
156 
157  RTABMAP_STATS(Timing, Memory_update, ms);
158  RTABMAP_STATS(Timing, Neighbor_link_refining, ms);
159  RTABMAP_STATS(Timing, Proximity_by_time, ms);
160  RTABMAP_STATS(Timing, Proximity_by_space_search, ms);
161  RTABMAP_STATS(Timing, Proximity_by_space_visual, ms);
162  RTABMAP_STATS(Timing, Proximity_by_space, ms);
163  RTABMAP_STATS(Timing, Cleaning_neighbors, ms);
164  RTABMAP_STATS(Timing, Reactivation, ms);
165  RTABMAP_STATS(Timing, Add_loop_closure_link, ms);
166  RTABMAP_STATS(Timing, Map_optimization, ms);
167  RTABMAP_STATS(Timing, Likelihood_computation, ms);
168  RTABMAP_STATS(Timing, Posterior_computation, ms);
169  RTABMAP_STATS(Timing, Hypotheses_creation, ms);
170  RTABMAP_STATS(Timing, Hypotheses_validation, ms);
171  RTABMAP_STATS(Timing, Statistics_creation, ms);
172  RTABMAP_STATS(Timing, Memory_cleanup, ms);
173  RTABMAP_STATS(Timing, Total, ms);
174  RTABMAP_STATS(Timing, Forgetting, ms);
175  RTABMAP_STATS(Timing, Joining_trash, ms);
176  RTABMAP_STATS(Timing, Emptying_trash, ms);
177  RTABMAP_STATS(Timing, Finalizing_statistics, ms);
178  RTABMAP_STATS(Timing, RAM_estimation, ms);
179 
180  RTABMAP_STATS(TimingMem, Pre_update, ms);
181  RTABMAP_STATS(TimingMem, Signature_creation, ms);
182  RTABMAP_STATS(TimingMem, Rehearsal, ms);
183  RTABMAP_STATS(TimingMem, Keypoints_detection, ms);
184  RTABMAP_STATS(TimingMem, Subpixel, ms);
185  RTABMAP_STATS(TimingMem, Stereo_correspondences, ms);
186  RTABMAP_STATS(TimingMem, Descriptors_extraction, ms);
187  RTABMAP_STATS(TimingMem, Rectification, ms);
188  RTABMAP_STATS(TimingMem, Keypoints_3D, ms);
189  RTABMAP_STATS(TimingMem, Keypoints_3D_motion, ms);
190  RTABMAP_STATS(TimingMem, Joining_dictionary_update, ms);
191  RTABMAP_STATS(TimingMem, Add_new_words, ms);
192  RTABMAP_STATS(TimingMem, Compressing_data, ms);
193  RTABMAP_STATS(TimingMem, Post_decimation, ms);
194  RTABMAP_STATS(TimingMem, Scan_filtering, ms);
195  RTABMAP_STATS(TimingMem, Occupancy_grid, ms);
196  RTABMAP_STATS(TimingMem, Markers_detection, ms);
197 
198  RTABMAP_STATS(Keypoint, Dictionary_size, words);
199  RTABMAP_STATS(Keypoint, Current_frame, words);
200  RTABMAP_STATS(Keypoint, Indexed_words, words);
201  RTABMAP_STATS(Keypoint, Index_memory_usage, KB);
202 
203  RTABMAP_STATS(Gt, Translational_rmse, m);
204  RTABMAP_STATS(Gt, Translational_mean, m);
205  RTABMAP_STATS(Gt, Translational_median, m);
206  RTABMAP_STATS(Gt, Translational_std, m);
207  RTABMAP_STATS(Gt, Translational_min, m);
208  RTABMAP_STATS(Gt, Translational_max, m);
209  RTABMAP_STATS(Gt, Rotational_rmse, deg);
210  RTABMAP_STATS(Gt, Rotational_mean, deg);
211  RTABMAP_STATS(Gt, Rotational_median, deg);
212  RTABMAP_STATS(Gt, Rotational_std, deg);
213  RTABMAP_STATS(Gt, Rotational_min, deg);
214  RTABMAP_STATS(Gt, Rotational_max, deg);
215  RTABMAP_STATS(Gt, Localization_linear_error, m);
216  RTABMAP_STATS(Gt, Localization_angular_error, deg);
217 
218 public:
219  static const std::map<std::string, float> & defaultData();
220  static std::string serializeData(const std::map<std::string, float> & data);
221  static std::map<std::string, float> deserializeData(const std::string & data);
222 
223 public:
224  Statistics();
225  virtual ~Statistics();
226 
227  // name format = "Grp/Name/unit"
228  void addStatistic(const std::string & name, float value);
229 
230  // setters
231  void setExtended(bool extended) {_extended = extended;}
232  void setRefImageId(int id) {_refImageId = id;}
233  void setRefImageMapId(int id) {_refImageMapId = id;}
234  void setLoopClosureId(int id) {_loopClosureId = id;}
235  void setLoopClosureMapId(int id) {_loopClosureMapId = id;}
236  void setProximityDetectionId(int id) {_proximiyDetectionId = id;}
237  void setProximityDetectionMapId(int id) {_proximiyDetectionMapId = id;}
238  void setStamp(double stamp) {_stamp = stamp;}
239 
240  // Use addSignatureData() instead.
241  RTABMAP_DEPRECATED void setLastSignatureData(const Signature & data);
242  void addSignatureData(const Signature & data) {_signaturesData.insert(std::make_pair(data.id(), data));}
243  void setSignaturesData(const std::map<int, Signature> & data) {_signaturesData = data;}
244 
245  void setPoses(const std::map<int, Transform> & poses) {_poses = poses;}
246  void setConstraints(const std::multimap<int, Link> & constraints) {_constraints = constraints;}
247  void setMapCorrection(const Transform & mapCorrection) {_mapCorrection = mapCorrection;}
248  void setLoopClosureTransform(const Transform & loopClosureTransform) {_loopClosureTransform = loopClosureTransform;}
249  void setLocalizationCovariance(const cv::Mat & covariance) {_localizationCovariance = covariance;}
250  void setLabels(const std::map<int, std::string> & labels) {_labels = labels;}
251  void setWeights(const std::map<int, int> & weights) {_weights = weights;}
252  void setPosterior(const std::map<int, float> & posterior) {_posterior = posterior;}
253  void setLikelihood(const std::map<int, float> & likelihood) {_likelihood = likelihood;}
254  void setRawLikelihood(const std::map<int, float> & rawLikelihood) {_rawLikelihood = rawLikelihood;}
255  void setLocalPath(const std::vector<int> & localPath) {_localPath=localPath;}
256  void setCurrentGoalId(int goal) {_currentGoalId=goal;}
257  void setReducedIds(const std::map<int, int> & reducedIds) {_reducedIds = reducedIds;}
258  void setWmState(const std::vector<int> & state) {_wmState = state;}
259  void setOdomCachePoses(const std::map<int, Transform> & poses) {_odomCachePoses = poses;}
260  void setOdomCacheConstraints(const std::multimap<int, Link> & constraints) {_odomCacheConstraints = constraints;}
261 
262  // getters
263  bool extended() const {return _extended;}
264  int refImageId() const {return _refImageId;}
265  int refImageMapId() const {return _refImageMapId;}
266  int loopClosureId() const {return _loopClosureId;}
267  int loopClosureMapId() const {return _loopClosureMapId;}
268  int proximityDetectionId() const {return _proximiyDetectionId;}
269  int proximityDetectionMapId() const {return _proximiyDetectionMapId;}
270  double stamp() const {return _stamp;}
271 
272  const Signature & getLastSignatureData() const {return _signaturesData.empty()?_dummyEmptyData:_signaturesData.rbegin()->second;}
273  const std::map<int, Signature> & getSignaturesData() const {return _signaturesData;}
274 
275  const std::map<int, Transform> & poses() const {return _poses;}
276  const std::multimap<int, Link> & constraints() const {return _constraints;}
277  const Transform & mapCorrection() const {return _mapCorrection;}
278  const Transform & loopClosureTransform() const {return _loopClosureTransform;}
279  const cv::Mat & localizationCovariance() const {return _localizationCovariance;}
280  const std::map<int, std::string> & labels() const {return _labels;}
281  const std::map<int, int> & weights() const {return _weights;}
282  const std::map<int, float> & posterior() const {return _posterior;}
283  const std::map<int, float> & likelihood() const {return _likelihood;}
284  const std::map<int, float> & rawLikelihood() const {return _rawLikelihood;}
285  const std::vector<int> & localPath() const {return _localPath;}
286  int currentGoalId() const {return _currentGoalId;}
287  const std::map<int, int> & reducedIds() const {return _reducedIds;}
288  const std::vector<int> & wmState() const {return _wmState;}
289  const std::map<int, Transform> & odomCachePoses() const {return _odomCachePoses;}
290  const std::multimap<int, Link> & odomCacheConstraints() const {return _odomCacheConstraints;}
291 
292  const std::map<std::string, float> & data() const {return _data;}
293 
294 private:
295  bool _extended; // 0 -> only loop closure and last signature ID fields are filled
296 
303  double _stamp;
304 
305  std::map<int, Signature> _signaturesData;
307 
308  std::map<int, Transform> _poses;
309  std::multimap<int, Link> _constraints;
313 
314  std::map<int, std::string> _labels;
315  std::map<int, int> _weights;
316  std::map<int, float> _posterior;
317  std::map<int, float> _likelihood;
318  std::map<int, float> _rawLikelihood;
319 
320  std::vector<int> _localPath;
322 
323  std::map<int, int> _reducedIds;
324 
325  std::vector<int> _wmState;
326 
327  std::map<int, Transform> _odomCachePoses;
328  std::multimap<int, Link> _odomCacheConstraints;
329 
330  // Format for statistics (Plottable statistics must go in that map) :
331  // {"Group/Name/Unit", value}
332  // Example : {"Timing/Total time/ms", 500.0f}
333  std::map<std::string, float> _data;
334  static std::map<std::string, float> _defaultData;
336  // end extended data
337 };
338 
339 }// end namespace rtabmap
340 
341 #endif /* STATISTICS_H_ */
rtabmap::Statistics::_loopClosureTransform
Transform _loopClosureTransform
Definition: Statistics.h:311
rtabmap::Statistics::loopClosureId
int loopClosureId() const
Definition: Statistics.h:266
rtabmap::Statistics::setMapCorrection
void setMapCorrection(const Transform &mapCorrection)
Definition: Statistics.h:247
rtabmap::Statistics::addSignatureData
void addSignatureData(const Signature &data)
Definition: Statistics.h:242
name
rtabmap::Statistics::getLastSignatureData
const Signature & getLastSignatureData() const
Definition: Statistics.h:272
rtabmap::Statistics
Definition: Statistics.h:53
rtabmap::Statistics::_odomCacheConstraints
std::multimap< int, Link > _odomCacheConstraints
Definition: Statistics.h:328
rtabmap::Statistics::_loopClosureMapId
int _loopClosureMapId
Definition: Statistics.h:300
rtabmap::Statistics::localizationCovariance
const cv::Mat & localizationCovariance() const
Definition: Statistics.h:279
rtabmap::Statistics::setReducedIds
void setReducedIds(const std::map< int, int > &reducedIds)
Definition: Statistics.h:257
rtabmap::Statistics::localPath
const std::vector< int > & localPath() const
Definition: Statistics.h:285
rtabmap::RTABMAP_DEPRECATED
RTABMAP_DEPRECATED(typedef SensorData Image, "rtabmap::Image class is renamed to rtabmap::SensorData, use the last one instead.")
rtabmap::Statistics::_odomCachePoses
std::map< int, Transform > _odomCachePoses
Definition: Statistics.h:327
rtabmap::Statistics::_data
std::map< std::string, float > _data
Definition: Statistics.h:333
state
RecoveryProgressState state
Definition: tools/Recovery/main.cpp:56
rtabmap::Statistics::setPosterior
void setPosterior(const std::map< int, float > &posterior)
Definition: Statistics.h:252
KB
#define KB
Definition: lz4.c:226
rtabmap::Statistics::proximityDetectionId
int proximityDetectionId() const
Definition: Statistics.h:268
rtabmap::Statistics::setLocalPath
void setLocalPath(const std::vector< int > &localPath)
Definition: Statistics.h:255
rtabmap::Statistics::setRefImageMapId
void setRefImageMapId(int id)
Definition: Statistics.h:233
rtabmap::Statistics::_proximiyDetectionMapId
int _proximiyDetectionMapId
Definition: Statistics.h:302
labels
std::vector< std::string > labels
rtabmap::Statistics::_refImageId
int _refImageId
Definition: Statistics.h:297
rtabmap::Statistics::odomCacheConstraints
const std::multimap< int, Link > & odomCacheConstraints() const
Definition: Statistics.h:290
m2
MatrixType m2(n_dims)
rtabmap::Statistics::setRawLikelihood
void setRawLikelihood(const std::map< int, float > &rawLikelihood)
Definition: Statistics.h:254
rtabmap::Statistics::data
const std::map< std::string, float > & data() const
Definition: Statistics.h:292
rtabmap::Statistics::_likelihood
std::map< int, float > _likelihood
Definition: Statistics.h:317
rtabmap::Statistics::posterior
const std::map< int, float > & posterior() const
Definition: Statistics.h:282
data
int data[]
rtabmap::Statistics::_posterior
std::map< int, float > _posterior
Definition: Statistics.h:316
rtabmap::Statistics::setLoopClosureId
void setLoopClosureId(int id)
Definition: Statistics.h:234
Signature.h
rtabmap::Statistics::labels
const std::map< int, std::string > & labels() const
Definition: Statistics.h:280
rtabmap::Statistics::_refImageMapId
int _refImageMapId
Definition: Statistics.h:298
rtabmap::Statistics::_constraints
std::multimap< int, Link > _constraints
Definition: Statistics.h:309
rtabmap::Statistics::_mapCorrection
Transform _mapCorrection
Definition: Statistics.h:310
rtabmap::Statistics::setLabels
void setLabels(const std::map< int, std::string > &labels)
Definition: Statistics.h:250
rtabmap::Statistics::currentGoalId
int currentGoalId() const
Definition: Statistics.h:286
m
Matrix3f m
rtabmap::Statistics::setProximityDetectionId
void setProximityDetectionId(int id)
Definition: Statistics.h:236
rtabmap::Statistics::_localizationCovariance
cv::Mat _localizationCovariance
Definition: Statistics.h:312
rtabmap::Statistics::setWeights
void setWeights(const std::map< int, int > &weights)
Definition: Statistics.h:251
rtabmap::Statistics::extended
bool extended() const
Definition: Statistics.h:263
rtabmap::Statistics::_poses
std::map< int, Transform > _poses
Definition: Statistics.h:308
rtabmap::Statistics::setLikelihood
void setLikelihood(const std::map< int, float > &likelihood)
Definition: Statistics.h:253
rtabmap::Statistics::likelihood
const std::map< int, float > & likelihood() const
Definition: Statistics.h:283
rtabmap::Statistics::setOdomCachePoses
void setOdomCachePoses(const std::map< int, Transform > &poses)
Definition: Statistics.h:259
rtabmap::Statistics::setPoses
void setPoses(const std::map< int, Transform > &poses)
Definition: Statistics.h:245
RTABMAP_STATS
#define RTABMAP_STATS(PREFIX, NAME, UNIT)
Definition: Statistics.h:43
rtabmap::Statistics::rawLikelihood
const std::map< int, float > & rawLikelihood() const
Definition: Statistics.h:284
rtabmap::Statistics::setLoopClosureTransform
void setLoopClosureTransform(const Transform &loopClosureTransform)
Definition: Statistics.h:248
rtabmap::Statistics::wmState
const std::vector< int > & wmState() const
Definition: Statistics.h:288
rtabmap::Statistics::getSignaturesData
const std::map< int, Signature > & getSignaturesData() const
Definition: Statistics.h:273
MB
#define MB
Definition: lz4.c:227
rtabmap::Statistics::_weights
std::map< int, int > _weights
Definition: Statistics.h:315
rtabmap::Statistics::_localPath
std::vector< int > _localPath
Definition: Statistics.h:320
rtabmap::Transform
Definition: Transform.h:41
rtabmap::Statistics::_loopClosureId
int _loopClosureId
Definition: Statistics.h:299
rtabmap::Statistics::_labels
std::map< int, std::string > _labels
Definition: Statistics.h:314
rtabmap::Statistics::setWmState
void setWmState(const std::vector< int > &state)
Definition: Statistics.h:258
rtabmap::Statistics::setExtended
void setExtended(bool extended)
Definition: Statistics.h:231
rtabmap::Statistics::setCurrentGoalId
void setCurrentGoalId(int goal)
Definition: Statistics.h:256
rtabmap::Statistics::mapCorrection
const Transform & mapCorrection() const
Definition: Statistics.h:277
rtabmap::Statistics::_dummyEmptyData
Signature _dummyEmptyData
Definition: Statistics.h:306
rtabmap::Statistics::_extended
bool _extended
Definition: Statistics.h:295
id
id
rtabmap::Statistics::proximityDetectionMapId
int proximityDetectionMapId() const
Definition: Statistics.h:269
rtabmap::Statistics::setSignaturesData
void setSignaturesData(const std::map< int, Signature > &data)
Definition: Statistics.h:243
rtabmap::Statistics::setProximityDetectionMapId
void setProximityDetectionMapId(int id)
Definition: Statistics.h:237
rtabmap::Statistics::reducedIds
const std::map< int, int > & reducedIds() const
Definition: Statistics.h:287
rtabmap::Statistics::setStamp
void setStamp(double stamp)
Definition: Statistics.h:238
rtabmap::Statistics::_rawLikelihood
std::map< int, float > _rawLikelihood
Definition: Statistics.h:318
rtabmap::Statistics::poses
const std::map< int, Transform > & poses() const
Definition: Statistics.h:275
rtabmap::Memory
Definition: Memory.h:64
rtabmap::Statistics::_currentGoalId
int _currentGoalId
Definition: Statistics.h:321
rtabmap::Statistics::setLoopClosureMapId
void setLoopClosureMapId(int id)
Definition: Statistics.h:235
rtabmap::Statistics::_defaultDataInitialized
static bool _defaultDataInitialized
Definition: Statistics.h:335
rtabmap::Statistics::_wmState
std::vector< int > _wmState
Definition: Statistics.h:325
rtabmap::Statistics::setOdomCacheConstraints
void setOdomCacheConstraints(const std::multimap< int, Link > &constraints)
Definition: Statistics.h:260
rtabmap::Statistics::constraints
const std::multimap< int, Link > & constraints() const
Definition: Statistics.h:276
rtabmap::Statistics::_defaultData
static std::map< std::string, float > _defaultData
Definition: Statistics.h:334
rtabmap::Statistics::loopClosureTransform
const Transform & loopClosureTransform() const
Definition: Statistics.h:278
rtabmap::Statistics::loopClosureMapId
int loopClosureMapId() const
Definition: Statistics.h:267
rtabmap::Statistics::odomCachePoses
const std::map< int, Transform > & odomCachePoses() const
Definition: Statistics.h:289
rtabmap
Definition: CameraARCore.cpp:35
rtabmap::Statistics::refImageMapId
int refImageMapId() const
Definition: Statistics.h:265
rtabmap::Statistics::_signaturesData
std::map< int, Signature > _signaturesData
Definition: Statistics.h:305
rtabmap::Statistics::_reducedIds
std::map< int, int > _reducedIds
Definition: Statistics.h:323
rtabmap::Statistics::setConstraints
void setConstraints(const std::multimap< int, Link > &constraints)
Definition: Statistics.h:246
rtabmap::Statistics::weights
const std::map< int, int > & weights() const
Definition: Statistics.h:281
value
value
rtabmap::Statistics::setRefImageId
void setRefImageId(int id)
Definition: Statistics.h:232
rtabmap::Statistics::_proximiyDetectionId
int _proximiyDetectionId
Definition: Statistics.h:301
rtabmap::Statistics::stamp
double stamp() const
Definition: Statistics.h:270
rtabmap::Statistics::refImageId
int refImageId() const
Definition: Statistics.h:264
rtabmap::Signature
Definition: Signature.h:48
rtabmap::Statistics::setLocalizationCovariance
void setLocalizationCovariance(const cv::Mat &covariance)
Definition: Statistics.h:249
rtabmap::Statistics::_stamp
double _stamp
Definition: Statistics.h:303


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:22