Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024 #ifndef FERNIMAGEDETECTOR_H
00025 #define FERNIMAGEDETECTOR_H
00026
00033 #include <map>
00034 #include <vector>
00035 #include <iostream>
00036 #include <fstream>
00037
00038 #include "cv.h"
00039 #include "highgui.h"
00040 #include "cvaux.h"
00041
00042 #include "Camera.h"
00043 #include "EC.h"
00044
00045 using namespace cv;
00046
00047 namespace alvar{
00048
00052 class FernClassifierWrapper : public FernClassifier
00053 {
00054 public:
00055 FernClassifierWrapper();
00056 FernClassifierWrapper(const FileNode &fileNode);
00057 FernClassifierWrapper(const vector<vector<Point2f> > &points,
00058 const vector<Mat> &referenceImages,
00059 const vector<vector<int> > &labels = vector<vector<int> >(),
00060 int _nclasses = 0,
00061 int _patchSize = PATCH_SIZE,
00062 int _signatureSize = DEFAULT_SIGNATURE_SIZE,
00063 int _nstructs = DEFAULT_STRUCTS,
00064 int _structSize = DEFAULT_STRUCT_SIZE,
00065 int _nviews = DEFAULT_VIEWS,
00066 int _compressionMethod = COMPRESSION_NONE,
00067 const PatchGenerator &patchGenerator = PatchGenerator());
00068 virtual ~FernClassifierWrapper();
00069
00070 virtual void readBinary(std::fstream &stream);
00071 virtual void writeBinary(std::fstream &stream) const;
00072 };
00073
00077 class ALVAR_EXPORT FernImageDetector
00078 {
00079 public:
00080 FernImageDetector(const bool visualize = false);
00081 ~FernImageDetector();
00082
00083 void imagePoints(vector<CvPoint2D64f> &points);
00084 void modelPoints(vector<CvPoint3D64f> &points, bool normalize = true);
00085
00086 cv::Size size();
00087 cv::Mat homography();
00088 double inlierRatio();
00089
00090 void train(const std::string &filename);
00091 void train(Mat &image);
00092 void findFeatures(Mat &image, bool planeAssumption = true);
00093
00094 bool read(const std::string &filename, const bool binary = true);
00095 bool write(const std::string &filename, const bool binary = true);
00096
00097 private:
00098 PatchGenerator mPatchGenerator;
00099 LDetector mLDetector;
00100 std::vector<FernClassifierWrapper> mClassifier;
00101
00102 vector<KeyPoint> mKeyPoints;
00103 vector<cv::Point2f> mImagePoints;
00104 vector<cv::Point2f> mModelPoints;
00105
00106 bool mVisualize;
00107 std::vector<Mat> mObjects;
00108 cv::Size mSize;
00109 cv::Mat mCorrespondences;
00110 cv::Mat mHomography;
00111 double mInlierRatio;
00112 };
00113
00114 }
00115
00116 #endif