ObjSignature.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 
00028 #ifndef OBJSIGNATURE_H_
00029 #define OBJSIGNATURE_H_
00030 
00031 #include <opencv2/opencv.hpp>
00032 #include <QtCore/QString>
00033 #include <QtCore/QMultiMap>
00034 #include <QtCore/QRect>
00035 #include <QtCore/QDataStream>
00036 #include <QtCore/QByteArray>
00037 
00038 namespace find_object {
00039 
00040 class ObjSignature {
00041 public:
00042         ObjSignature() :
00043                 id_(-1)
00044         {}
00045         ObjSignature(int id, const cv::Mat & image, const QString & filename) :
00046                 id_(id),
00047                 image_(image),
00048                 filename_(filename)
00049         {}
00050         virtual ~ObjSignature() {}
00051 
00052         void setData(const std::vector<cv::KeyPoint> & keypoints, const cv::Mat & descriptors)
00053         {
00054                 keypoints_ = keypoints;
00055                 descriptors_ = descriptors;
00056         }
00057         void setWords(const QMultiMap<int, int> & words) {words_ = words;}
00058         void setId(int id) {id_ = id;}
00059 
00060         QRect rect() const {return QRect(0,0,image_.cols, image_.rows);}
00061 
00062         int id() const {return id_;}
00063         const QString & filename() const {return filename_;}
00064         const cv::Mat & image() const {return image_;}
00065         const std::vector<cv::KeyPoint> & keypoints() const {return keypoints_;}
00066         const cv::Mat & descriptors() const {return descriptors_;}
00067         const QMultiMap<int, int> & words() const {return words_;}
00068 
00069         void save(QDataStream & streamPtr) const
00070         {
00071                 streamPtr << id_;
00072                 streamPtr << filename_;
00073                 streamPtr << (int)keypoints_.size();
00074                 for(unsigned int j=0; j<keypoints_.size(); ++j)
00075                 {
00076                                 streamPtr << keypoints_.at(j).angle <<
00077                                                                 keypoints_.at(j).class_id <<
00078                                                                 keypoints_.at(j).octave <<
00079                                                                 keypoints_.at(j).pt.x <<
00080                                                                 keypoints_.at(j).pt.y <<
00081                                                                 keypoints_.at(j).response <<
00082                                                                 keypoints_.at(j).size;
00083                 }
00084 
00085                 qint64 dataSize = descriptors_.elemSize()*descriptors_.cols*descriptors_.rows;
00086                 streamPtr << descriptors_.rows <<
00087                                                 descriptors_.cols <<
00088                                                 descriptors_.type() <<
00089                                                 dataSize;
00090                 streamPtr << QByteArray((char*)descriptors_.data, dataSize);
00091 
00092                 streamPtr << words_;
00093 
00094                 std::vector<unsigned char> bytes;
00095                 cv::imencode(".png", image_, bytes);
00096                 streamPtr << QByteArray((char*)bytes.data(), bytes.size());
00097         }
00098 
00099         void load(QDataStream & streamPtr)
00100         {
00101                 int nKpts;
00102                 streamPtr >> id_ >> filename_ >> nKpts;
00103                 keypoints_.resize(nKpts);
00104                 for(int i=0;i<nKpts;++i)
00105                 {
00106                                 streamPtr >>
00107                                 keypoints_[i].angle >>
00108                                 keypoints_[i].class_id >>
00109                                 keypoints_[i].octave >>
00110                                 keypoints_[i].pt.x >>
00111                                 keypoints_[i].pt.y >>
00112                                 keypoints_[i].response >>
00113                                 keypoints_[i].size;
00114                 }
00115 
00116                 int rows,cols,type;
00117                 qint64 dataSize;
00118                 streamPtr >> rows >> cols >> type >> dataSize;
00119                 QByteArray data;
00120                 streamPtr >> data;
00121                 descriptors_ = cv::Mat(rows, cols, type, data.data()).clone();
00122 
00123                 streamPtr >> words_;
00124 
00125                 QByteArray image;
00126                 streamPtr >> image;
00127                 std::vector<unsigned char> bytes(image.size());
00128                 memcpy(bytes.data(), image.data(), image.size());
00129                 image_ = cv::imdecode(bytes, cv::IMREAD_UNCHANGED);
00130         }
00131 
00132 private:
00133         int id_;
00134         cv::Mat image_;
00135         QString filename_;
00136         std::vector<cv::KeyPoint> keypoints_;
00137         cv::Mat descriptors_;
00138         QMultiMap<int, int> words_; // <word id, keypoint indexes>
00139 };
00140 
00141 } // namespace find_object
00142 
00143 #endif /* OBJSIGNATURE_H_ */


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