Statistics.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, 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 #ifndef STATISTICS_H_
00029 #define STATISTICS_H_
00030 
00031 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
00032 
00033 #include <opencv2/core/core.hpp>
00034 #include <opencv2/features2d/features2d.hpp>
00035 #include <opencv2/imgproc/imgproc.hpp>
00036 #include <list>
00037 #include <vector>
00038 #include <rtabmap/core/Signature.h>
00039 #include <rtabmap/core/Link.h>
00040 
00041 namespace rtabmap {
00042 
00043 #define RTABMAP_STATS(PREFIX, NAME, UNIT) \
00044         public: \
00045                 static std::string k##PREFIX##NAME() {return #PREFIX "/" #NAME "/" #UNIT;} \
00046         private: \
00047                 class Dummy##PREFIX##NAME { \
00048                 public: \
00049                         Dummy##PREFIX##NAME() {if(!_defaultDataInitialized)_defaultData.insert(std::pair<std::string, float>(#PREFIX "/" #NAME "/" #UNIT, 0.0f));} \
00050                 }; \
00051                 Dummy##PREFIX##NAME dummy##PREFIX##NAME;
00052 
00053 class RTABMAP_EXP Statistics
00054 {
00055         RTABMAP_STATS(Loop, RejectedHypothesis,);
00056         RTABMAP_STATS(Loop, Accepted_hypothesis_id,);
00057         RTABMAP_STATS(Loop, Highest_hypothesis_id,);
00058         RTABMAP_STATS(Loop, Highest_hypothesis_value,);
00059         RTABMAP_STATS(Loop, Vp_hypothesis,);
00060         RTABMAP_STATS(Loop, Reactivate_id,);
00061         RTABMAP_STATS(Loop, Hypothesis_ratio,);
00062         RTABMAP_STATS(Loop, Hypothesis_reactivated,);
00063         RTABMAP_STATS(Loop, Visual_inliers,);
00064         RTABMAP_STATS(Loop, Last_id,);
00065         RTABMAP_STATS(Loop, Optimization_max_error, m);
00066         RTABMAP_STATS(Loop, Optimization_error, );
00067         RTABMAP_STATS(Loop, Optimization_iterations, );
00068 
00069         RTABMAP_STATS(Proximity, Time_detections,);
00070         RTABMAP_STATS(Proximity, Space_last_detection_id,);
00071         RTABMAP_STATS(Proximity, Space_paths,);
00072         RTABMAP_STATS(Proximity, Space_detections_added_visually,);
00073         RTABMAP_STATS(Proximity, Space_detections_added_icp_only,);
00074 
00075         RTABMAP_STATS(NeighborLinkRefining, Accepted,);
00076         RTABMAP_STATS(NeighborLinkRefining, Inliers,);
00077         RTABMAP_STATS(NeighborLinkRefining, Inliers_ratio,);
00078         RTABMAP_STATS(NeighborLinkRefining, Variance,);
00079         RTABMAP_STATS(NeighborLinkRefining, Pts,);
00080 
00081         RTABMAP_STATS(Memory, Working_memory_size,);
00082         RTABMAP_STATS(Memory, Short_time_memory_size,);
00083         RTABMAP_STATS(Memory, Database_memory_used, MB);
00084         RTABMAP_STATS(Memory, Signatures_removed,);
00085         RTABMAP_STATS(Memory, Immunized_globally,);
00086         RTABMAP_STATS(Memory, Immunized_locally,);
00087         RTABMAP_STATS(Memory, Immunized_locally_max,);
00088         RTABMAP_STATS(Memory, Signatures_retrieved,);
00089         RTABMAP_STATS(Memory, Images_buffered,);
00090         RTABMAP_STATS(Memory, Rehearsal_sim,);
00091         RTABMAP_STATS(Memory, Rehearsal_id,);
00092         RTABMAP_STATS(Memory, Rehearsal_merged,);
00093         RTABMAP_STATS(Memory, Local_graph_size,);
00094         RTABMAP_STATS(Memory, Small_movement,);
00095         RTABMAP_STATS(Memory, Distance_travelled, m);
00096 
00097         RTABMAP_STATS(Timing, Memory_update, ms);
00098         RTABMAP_STATS(Timing, Neighbor_link_refining, ms);
00099         RTABMAP_STATS(Timing, Proximity_by_time, ms);
00100         RTABMAP_STATS(Timing, Proximity_by_space, ms);
00101         RTABMAP_STATS(Timing, Cleaning_neighbors, ms);
00102         RTABMAP_STATS(Timing, Reactivation, ms);
00103         RTABMAP_STATS(Timing, Add_loop_closure_link, ms);
00104         RTABMAP_STATS(Timing, Map_optimization, ms);
00105         RTABMAP_STATS(Timing, Likelihood_computation, ms);
00106         RTABMAP_STATS(Timing, Posterior_computation, ms);
00107         RTABMAP_STATS(Timing, Hypotheses_creation, ms);
00108         RTABMAP_STATS(Timing, Hypotheses_validation, ms);
00109         RTABMAP_STATS(Timing, Statistics_creation, ms);
00110         RTABMAP_STATS(Timing, Memory_cleanup, ms);
00111         RTABMAP_STATS(Timing, Total, ms);
00112         RTABMAP_STATS(Timing, Forgetting, ms);
00113         RTABMAP_STATS(Timing, Joining_trash, ms);
00114         RTABMAP_STATS(Timing, Emptying_trash, ms);
00115 
00116         RTABMAP_STATS(TimingMem, Pre_update, ms);
00117         RTABMAP_STATS(TimingMem, Signature_creation, ms);
00118         RTABMAP_STATS(TimingMem, Rehearsal, ms);
00119         RTABMAP_STATS(TimingMem, Keypoints_detection, ms);
00120         RTABMAP_STATS(TimingMem, Subpixel, ms);
00121         RTABMAP_STATS(TimingMem, Stereo_correspondences, ms);
00122         RTABMAP_STATS(TimingMem, Descriptors_extraction, ms);
00123         RTABMAP_STATS(TimingMem, Keypoints_3D, ms);
00124         RTABMAP_STATS(TimingMem, Joining_dictionary_update, ms);
00125         RTABMAP_STATS(TimingMem, Add_new_words, ms);
00126         RTABMAP_STATS(TimingMem, Compressing_data, ms);
00127 
00128         RTABMAP_STATS(Keypoint, Dictionary_size, words);
00129         RTABMAP_STATS(Keypoint, Indexed_words, words);
00130         RTABMAP_STATS(Keypoint, Index_memory_usage, KB);
00131         RTABMAP_STATS(Keypoint, Response_threshold,);
00132 
00133 public:
00134         static const std::map<std::string, float> & defaultData();
00135 
00136 public:
00137         Statistics();
00138         virtual ~Statistics();
00139 
00140         // name format = "Grp/Name/unit"
00141         void addStatistic(const std::string & name, float value);
00142 
00143         // setters
00144         void setExtended(bool extended) {_extended = extended;}
00145         void setRefImageId(int refImageId) {_refImageId = refImageId;}
00146         void setLoopClosureId(int loopClosureId) {_loopClosureId = loopClosureId;}
00147         void setProximityDetectionId(int id) {_proximiyDetectionId = id;}
00148         void setStamp(double stamp) {_stamp = stamp;}
00149 
00150         void setSignatures(const std::map<int, Signature> & signatures) {_signatures = signatures;}
00151 
00152         void setPoses(const std::map<int, Transform> & poses) {_poses = poses;}
00153         void setConstraints(const std::multimap<int, Link> & constraints) {_constraints = constraints;}
00154         void setMapCorrection(const Transform & mapCorrection) {_mapCorrection = mapCorrection;}
00155         void setLoopClosureTransform(const Transform & loopClosureTransform) {_loopClosureTransform = loopClosureTransform;}
00156         void setWeights(const std::map<int, int> & weights) {_weights = weights;}
00157         void setPosterior(const std::map<int, float> & posterior) {_posterior = posterior;}
00158         void setLikelihood(const std::map<int, float> & likelihood) {_likelihood = likelihood;}
00159         void setRawLikelihood(const std::map<int, float> & rawLikelihood) {_rawLikelihood = rawLikelihood;}
00160         void setLocalPath(const std::vector<int> & localPath) {_localPath=localPath;}
00161         void setCurrentGoalId(int goal) {_currentGoalId=goal;}
00162         void setReducedIds(const std::map<int, int> & reducedIds) {_reducedIds = reducedIds;}
00163 
00164         // getters
00165         bool extended() const {return _extended;}
00166         int refImageId() const {return _refImageId;}
00167         int loopClosureId() const {return _loopClosureId;}
00168         int proximityDetectionId() const {return _proximiyDetectionId;}
00169         double stamp() const {return _stamp;}
00170 
00171         const std::map<int, Signature> & getSignatures() const {return _signatures;}
00172 
00173         const std::map<int, Transform> & poses() const {return _poses;}
00174         const std::multimap<int, Link> & constraints() const {return _constraints;}
00175         const Transform & mapCorrection() const {return _mapCorrection;}
00176         const Transform & loopClosureTransform() const {return _loopClosureTransform;}
00177         const std::map<int, int> & weights() const {return _weights;}
00178         const std::map<int, float> & posterior() const {return _posterior;}
00179         const std::map<int, float> & likelihood() const {return _likelihood;}
00180         const std::map<int, float> & rawLikelihood() const {return _rawLikelihood;}
00181         const std::vector<int> & localPath() const {return _localPath;}
00182         int currentGoalId() const {return _currentGoalId;}
00183         const std::map<int, int> & reducedIds() const {return _reducedIds;}
00184 
00185         const std::map<std::string, float> & data() const {return _data;}
00186 
00187 private:
00188         bool _extended; // 0 -> only loop closure and last signature ID fields are filled
00189 
00190         int _refImageId;
00191         int _loopClosureId;
00192         int _proximiyDetectionId;
00193         double _stamp;
00194 
00195         std::map<int, Signature> _signatures;
00196 
00197         std::map<int, Transform> _poses;
00198         std::multimap<int, Link> _constraints;
00199         Transform _mapCorrection;
00200         Transform _loopClosureTransform;
00201 
00202         std::map<int, int> _weights;
00203         std::map<int, float> _posterior;
00204         std::map<int, float> _likelihood;
00205         std::map<int, float> _rawLikelihood;
00206 
00207         std::vector<int> _localPath;
00208         int _currentGoalId;
00209 
00210         std::map<int, int> _reducedIds;
00211 
00212         // Format for statistics (Plottable statistics must go in that map) :
00213         // {"Group/Name/Unit", value}
00214         // Example : {"Timing/Total time/ms", 500.0f}
00215         std::map<std::string, float> _data;
00216         static std::map<std::string, float> _defaultData;
00217         static bool _defaultDataInitialized;
00218         // end extended data
00219 };
00220 
00221 }// end namespace rtabmap
00222 
00223 #endif /* STATISTICS_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:27