Statistics.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2014, 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, ReactivateId,);
00061         RTABMAP_STATS(Loop, Hypothesis_ratio,);
00062         RTABMAP_STATS(Loop, Hypothesis_reactivated,);
00063         RTABMAP_STATS(Loop, VisualInliers,);
00064         RTABMAP_STATS(Loop, Last_id,);
00065 
00066         RTABMAP_STATS(LocalLoop, Time_closures,);
00067         RTABMAP_STATS(LocalLoop, Space_last_closure_id,);
00068         RTABMAP_STATS(LocalLoop, Space_paths,);
00069         RTABMAP_STATS(LocalLoop, Space_closures_added_visually,);
00070         RTABMAP_STATS(LocalLoop, Space_closures_added_icp_only,);
00071 
00072         RTABMAP_STATS(OdomCorrection, Accepted,);
00073         RTABMAP_STATS(OdomCorrection, Inliers,);
00074         RTABMAP_STATS(OdomCorrection, Inliers_ratio,);
00075         RTABMAP_STATS(OdomCorrection, Variance,);
00076 
00077         RTABMAP_STATS(Memory, Working_memory_size,);
00078         RTABMAP_STATS(Memory, Short_time_memory_size,);
00079         RTABMAP_STATS(Memory, Signatures_removed,);
00080         RTABMAP_STATS(Memory, Immunized_globally,);
00081         RTABMAP_STATS(Memory, Immunized_locally,);
00082         RTABMAP_STATS(Memory, Immunized_locally_max,);
00083         RTABMAP_STATS(Memory, Signatures_retrieved,);
00084         RTABMAP_STATS(Memory, Images_buffered,);
00085         RTABMAP_STATS(Memory, Rehearsal_sim,);
00086         RTABMAP_STATS(Memory, Rehearsal_merged,);
00087         RTABMAP_STATS(Memory, Local_graph_size,);
00088 
00089         RTABMAP_STATS(Timing, Memory_update, ms);
00090         RTABMAP_STATS(Timing, Scan_matching, ms);
00091         RTABMAP_STATS(Timing, Local_detection_TIME, ms);
00092         RTABMAP_STATS(Timing, Local_detection_SPACE, ms);
00093         RTABMAP_STATS(Timing, Cleaning_neighbors, ms);
00094         RTABMAP_STATS(Timing, Reactivation, ms);
00095         RTABMAP_STATS(Timing, Add_loop_closure_link, ms);
00096         RTABMAP_STATS(Timing, Map_optimization, ms);
00097         RTABMAP_STATS(Timing, Likelihood_computation, ms);
00098         RTABMAP_STATS(Timing, Posterior_computation, ms);
00099         RTABMAP_STATS(Timing, Hypotheses_creation, ms);
00100         RTABMAP_STATS(Timing, Hypotheses_validation, ms);
00101         RTABMAP_STATS(Timing, Statistics_creation, ms);
00102         RTABMAP_STATS(Timing, Memory_cleanup, ms);
00103         RTABMAP_STATS(Timing, Total, ms);
00104         RTABMAP_STATS(Timing, Forgetting, ms);
00105         RTABMAP_STATS(Timing, Joining_trash, ms);
00106         RTABMAP_STATS(Timing, Emptying_trash, ms);
00107 
00108         RTABMAP_STATS(TimingMem, Pre_update, ms);
00109         RTABMAP_STATS(TimingMem, Signature_creation, ms);
00110         RTABMAP_STATS(TimingMem, Rehearsal, ms);
00111         RTABMAP_STATS(TimingMem, Keypoints_detection, ms);
00112         RTABMAP_STATS(TimingMem, Subpixel, ms);
00113         RTABMAP_STATS(TimingMem, Stereo_correspondences, ms);
00114         RTABMAP_STATS(TimingMem, Descriptors_extraction, ms);
00115         RTABMAP_STATS(TimingMem, Keypoints_3D, ms);
00116         RTABMAP_STATS(TimingMem, Joining_dictionary_update, ms);
00117         RTABMAP_STATS(TimingMem, Add_new_words, ms);
00118         RTABMAP_STATS(TimingMem, Compressing_data, ms);
00119 
00120         RTABMAP_STATS(Keypoint, Dictionary_size, words);
00121         RTABMAP_STATS(Keypoint, Response_threshold,);
00122 
00123 public:
00124         static const std::map<std::string, float> & defaultData();
00125 
00126 public:
00127         Statistics();
00128         virtual ~Statistics();
00129 
00130         // name format = "Grp/Name/unit"
00131         void addStatistic(const std::string & name, float value);
00132 
00133         // setters
00134         void setExtended(bool extended) {_extended = extended;}
00135         void setRefImageId(int refImageId) {_refImageId = refImageId;}
00136         void setLoopClosureId(int loopClosureId) {_loopClosureId = loopClosureId;}
00137         void setLocalLoopClosureId(int localLoopClosureId) {_localLoopClosureId = localLoopClosureId;}
00138 
00139         void setMapIds(const std::map<int, int> & mapIds) {_mapIds = mapIds;}
00140         void setLabels(const std::map<int, std::string> & labels) {_labels = labels;}
00141         void setStamps(const std::map<int, double> & stamps) {_stamps = stamps;}
00142         void setUserDatas(const std::map<int, std::vector<unsigned char> > & userDatas) {_userDatas = userDatas;}
00143         void setSignature(const Signature & s) {_signature = s;}
00144 
00145         void setPoses(const std::map<int, Transform> & poses) {_poses = poses;}
00146         void setConstraints(const std::multimap<int, Link> & constraints) {_constraints = constraints;}
00147         void setMapCorrection(const Transform & mapCorrection) {_mapCorrection = mapCorrection;}
00148         void setLoopClosureTransform(const Transform & loopClosureTransform) {_loopClosureTransform = loopClosureTransform;}
00149         void setWeights(const std::map<int, int> & weights) {_weights = weights;}
00150         void setPosterior(const std::map<int, float> & posterior) {_posterior = posterior;}
00151         void setLikelihood(const std::map<int, float> & likelihood) {_likelihood = likelihood;}
00152         void setRawLikelihood(const std::map<int, float> & rawLikelihood) {_rawLikelihood = rawLikelihood;}
00153         void setLocalPath(const std::vector<int> & localPath) {_localPath=localPath;}
00154         void setCurrentGoalId(int goal) {_currentGoalId=goal;}
00155 
00156         // getters
00157         bool extended() const {return _extended;}
00158         int refImageId() const {return _refImageId;}
00159         int loopClosureId() const {return _loopClosureId;}
00160         int localLoopClosureId() const {return _localLoopClosureId;}
00161 
00162         const std::map<int, int> & getMapIds() const {return _mapIds;}
00163         const std::map<int, std::string> & getLabels() const {return _labels;}
00164         const std::map<int, double> & getStamps() const {return _stamps;}
00165         const std::map<int, std::vector<unsigned char> > & getUserDatas() const {return _userDatas;}
00166         const Signature & getSignature() const {return _signature;}
00167 
00168         const std::map<int, Transform> & poses() const {return _poses;}
00169         const std::multimap<int, Link> & constraints() const {return _constraints;}
00170         const Transform & mapCorrection() const {return _mapCorrection;}
00171         const Transform & loopClosureTransform() const {return _loopClosureTransform;}
00172         const std::map<int, int> & weights() const {return _weights;}
00173         const std::map<int, float> & posterior() const {return _posterior;}
00174         const std::map<int, float> & likelihood() const {return _likelihood;}
00175         const std::map<int, float> & rawLikelihood() const {return _rawLikelihood;}
00176         const std::vector<int> & localPath() const {return _localPath;}
00177         int currentGoalId() const {return _currentGoalId;}
00178 
00179         const std::map<std::string, float> & data() const {return _data;}
00180 
00181 private:
00182         bool _extended; // 0 -> only loop closure and last signature ID fields are filled
00183 
00184         int _refImageId;
00185         int _loopClosureId;
00186         int _localLoopClosureId;
00187 
00188         // extended data start here...
00189         std::map<int, int> _mapIds;
00190         std::map<int, std::string> _labels;
00191         std::map<int, double> _stamps;
00192         std::map<int, std::vector<unsigned char> > _userDatas;
00193 
00194         // Signature data
00195         Signature _signature;
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         // Format for statistics (Plottable statistics must go in that map) :
00211         // {"Group/Name/Unit", value}
00212         // Example : {"Timing/Total time/ms", 500.0f}
00213         std::map<std::string, float> _data;
00214         static std::map<std::string, float> _defaultData;
00215         static bool _defaultDataInitialized;
00216         // end extended data
00217 };
00218 
00219 }// end namespace rtabmap
00220 
00221 #endif /* STATISTICS_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Fri Aug 28 2015 12:51:42