sift_gpu_wrapper.h
Go to the documentation of this file.
00001 /* This file is part of RGBDSLAM.
00002  * 
00003  * RGBDSLAM is free software: you can redistribute it and/or modify
00004  * it under the terms of the GNU General Public License as published by
00005  * the Free Software Foundation, either version 3 of the License, or
00006  * (at your option) any later version.
00007  * 
00008  * RGBDSLAM is distributed in the hope that it will be useful,
00009  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00010  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00011  * GNU General Public License for more details.
00012  * 
00013  * You should have received a copy of the GNU General Public License
00014  * along with RGBDSLAM.  If not, see <http://www.gnu.org/licenses/>.
00015  */
00016 
00017 
00018 #ifndef SIFT_GPU_FEATURE_DETECTOR_H
00019 #define SIFT_GPU_FEATURE_DETECTOR_H
00020 
00021 //#ifdef USE_SIFT_GPU
00022 #include <opencv2/features2d/features2d.hpp>
00023 #include <opencv/cv.h>
00024 #include <SiftGPU/SiftGPU.h>
00025 #include <QMutex>
00026 
00032 class SiftGPUWrapper {
00033 public:
00037         virtual ~SiftGPUWrapper();
00038 
00049         void detect(const cv::Mat& image, cv::vector<cv::KeyPoint>& keypoints, std::vector<float>& descriptors, const cv::Mat& mask = cv::Mat()) const;
00050 
00061         int match(const std::vector<float>& descriptors1, int num1, const std::vector<float>& descriptors2, int num2, std::vector<cv::DMatch>* matches);
00062 
00066         static SiftGPUWrapper* getInstance();
00067         static void destroyInstance();
00068 
00069 private:
00073         SiftGPUWrapper();
00074 
00075         void initializeMatcher();
00076 
00084         void cvMatToSiftGPU(const cv::Mat& image, unsigned char* siftImage) const;
00085 
00094         void writePGM(FILE *fp, unsigned char* data, int width, int height);
00095 
00096         mutable int imageWidth;          
00097         mutable int imageHeight;         
00098         mutable unsigned char* data;     
00099 
00100         static SiftGPUWrapper* instance;    
00101         SiftGPU* siftgpu;                           
00102         SiftMatchGPU *matcher;                      
00103         bool isMatcherInitialized;                  
00104         bool error;                                 
00105   mutable QMutex gpu_mutex;
00106 };
00107 
00108 #endif
00109 //#endif


rgbdslam_v2
Author(s): Felix Endres, Juergen Hess, Nikolas Engelhard
autogenerated on Thu Jun 6 2019 21:49:45