DetectionInfo.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2011-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 #ifndef DETECTIONINFO_H_
00028 #define DETECTIONINFO_H_
00029 
00030 #include <QtCore/QMultiMap>
00031 #include <QtGui/QTransform>
00032 #include <QtCore/QSize>
00033 #include <QtCore/QString>
00034 #include <opencv2/features2d/features2d.hpp>
00035 #include <vector>
00036 
00037 namespace find_object {
00038 
00039 class DetectionInfo
00040 {
00041 public:
00042         enum TimeStamp{
00043                 kTimeKeypointDetection,
00044                 kTimeDescriptorExtraction,
00045                 kTimeSkewAffine,
00046                 kTimeIndexing,
00047                 kTimeMatching,
00048                 kTimeHomography,
00049                 kTimeTotal
00050         };
00051         enum RejectedCode{
00052                 kRejectedUndef,
00053                 kRejectedLowMatches,
00054                 kRejectedLowInliers,
00055                 kRejectedSuperposed,
00056                 kRejectedAllInliers,
00057                 kRejectedNotValid,
00058                 kRejectedCornersOutside,
00059                 kRejectedByAngle
00060         };
00061 
00062 public:
00063         DetectionInfo() :
00064                 minMatchedDistance_(-1),
00065                 maxMatchedDistance_(-1)
00066         {}
00067 
00068 public:
00069         // Those maps have the same size
00070         QMultiMap<int, QTransform> objDetected_;
00071         QMultiMap<int, QSize> objDetectedSizes_; // Object ID <width, height> match the number of detected objects
00072         QMultiMap<int, QString > objDetectedFilenames_; // Object ID <filename> match the number of detected objects
00073         QMultiMap<int, int> objDetectedInliersCount_; // ObjectID <count> match the number of detected objects
00074         QMultiMap<int, int> objDetectedOutliersCount_; // ObjectID <count> match the number of detected objects
00075         QMultiMap<int, QMultiMap<int, int> > objDetectedInliers_; // ObjectID Map< ObjectDescriptorIndex, SceneDescriptorIndex >, match the number of detected objects
00076         QMultiMap<int, QMultiMap<int, int> > objDetectedOutliers_; // ObjectID Map< ObjectDescriptorIndex, SceneDescriptorIndex >, match the number of detected objects
00077 
00078         QMap<TimeStamp, float> timeStamps_;
00079         std::vector<cv::KeyPoint> sceneKeypoints_;
00080         cv::Mat sceneDescriptors_;
00081         QMultiMap<int, int> sceneWords_;
00082         QMap<int, QMultiMap<int, int> > matches_; // ObjectID Map< ObjectDescriptorIndex, SceneDescriptorIndex >, match the number of objects
00083 
00084         // Those maps have the same size
00085         QMultiMap<int, QMultiMap<int, int> > rejectedInliers_; // ObjectID Map< ObjectDescriptorIndex, SceneDescriptorIndex >
00086         QMultiMap<int, QMultiMap<int, int> > rejectedOutliers_; // ObjectID Map< ObjectDescriptorIndex, SceneDescriptorIndex >
00087         QMultiMap<int, RejectedCode> rejectedCodes_; // ObjectID rejected code
00088 
00089         float minMatchedDistance_;
00090         float maxMatchedDistance_;
00091 };
00092 
00093 inline QDataStream & operator<<(QDataStream &out, const DetectionInfo & info)
00094 {
00095         out << quint32(info.objDetected_.size());
00096 
00097         QMultiMap<int, int>::const_iterator iterInliers = info.objDetectedInliersCount_.constBegin();
00098         QMultiMap<int, int>::const_iterator iterOutliers = info.objDetectedOutliersCount_.constBegin();
00099         QMultiMap<int, QSize>::const_iterator iterSizes = info.objDetectedSizes_.constBegin();
00100         QMultiMap<int, QString>::const_iterator iterFilenames = info.objDetectedFilenames_.constBegin();
00101         for(QMultiMap<int, QTransform>::const_iterator iter=info.objDetected_.constBegin();
00102                 iter!=info.objDetected_.constEnd();
00103                 ++iter)
00104         {
00105                 // ID
00106                 out << iter.key();
00107 
00108                 // Size
00109                 out << iterSizes.value();
00110 
00111                 // Transform
00112                 out << iter.value();
00113 
00114                 // Filename
00115                 out << iterFilenames.value();
00116 
00117                 // inliers and outliers count
00118                 out << iterInliers.value();
00119                 out << iterOutliers.value();
00120 
00121                 ++iterInliers;
00122                 ++iterOutliers;
00123                 ++iterSizes;
00124                 ++iterFilenames;
00125         }
00126         return out;
00127 }
00128 
00129 inline QDataStream & operator>>(QDataStream &in, DetectionInfo & info)
00130 {
00131         QDataStream::Status oldStatus = in.status();
00132         in.resetStatus();
00133         info = DetectionInfo();
00134 
00135         quint32 n;
00136         in >> n;
00137 
00138         for (quint32 i = 0; i < n; ++i) {
00139                 if (in.status() != QDataStream::Ok)
00140                         break;
00141 
00142                 int id;
00143                 QSize size;
00144                 QTransform homography;
00145                 QString filename;
00146                 int inliers, outliers;
00147                 in >> id >> size >> homography >> filename >> inliers >> outliers;
00148                 info.objDetected_.insert(id, homography);
00149                 info.objDetectedSizes_.insert(id, size);
00150                 info.objDetectedFilenames_.insert(id, filename);
00151                 info.objDetectedInliersCount_.insert(id, inliers);
00152                 info.objDetectedOutliersCount_.insert(id, outliers);
00153         }
00154         if (in.status() != QDataStream::Ok)
00155                 info = DetectionInfo();
00156         if (oldStatus != QDataStream::Ok)
00157                 in.setStatus(oldStatus);
00158         return in;
00159 }
00160 
00161 } // namespace find_object
00162 
00163 #endif /* DETECTIONINFO_H_ */


find_object_2d
Author(s): Mathieu Labbe
autogenerated on Thu Aug 27 2015 13:00:33