00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043 #ifndef __OPENCV_CONTRIB_HPP__
00044 #define __OPENCV_CONTRIB_HPP__
00045
00046 #include "opencv2/core/core.hpp"
00047 #include "opencv2/features2d/features2d.hpp"
00048 #include "opencv2/objdetect/objdetect.hpp"
00049
00050 #ifdef __cplusplus
00051
00052
00053
00054
00055
00056 class CV_EXPORTS CvAdaptiveSkinDetector
00057 {
00058 private:
00059 enum {
00060 GSD_HUE_LT = 3,
00061 GSD_HUE_UT = 33,
00062 GSD_INTENSITY_LT = 15,
00063 GSD_INTENSITY_UT = 250
00064 };
00065
00066 class CV_EXPORTS Histogram
00067 {
00068 private:
00069 enum {
00070 HistogramSize = (GSD_HUE_UT - GSD_HUE_LT + 1)
00071 };
00072
00073 protected:
00074 int findCoverageIndex(double surfaceToCover, int defaultValue = 0);
00075
00076 public:
00077 CvHistogram *fHistogram;
00078 Histogram();
00079 virtual ~Histogram();
00080
00081 void findCurveThresholds(int &x1, int &x2, double percent = 0.05);
00082 void mergeWith(Histogram *source, double weight);
00083 };
00084
00085 int nStartCounter, nFrameCount, nSkinHueLowerBound, nSkinHueUpperBound, nMorphingMethod, nSamplingDivider;
00086 double fHistogramMergeFactor, fHuePercentCovered;
00087 Histogram histogramHueMotion, skinHueHistogram;
00088 IplImage *imgHueFrame, *imgSaturationFrame, *imgLastGrayFrame, *imgMotionFrame, *imgFilteredFrame;
00089 IplImage *imgShrinked, *imgTemp, *imgGrayFrame, *imgHSVFrame;
00090
00091 protected:
00092 void initData(IplImage *src, int widthDivider, int heightDivider);
00093 void adaptiveFilter();
00094
00095 public:
00096
00097 enum {
00098 MORPHING_METHOD_NONE = 0,
00099 MORPHING_METHOD_ERODE = 1,
00100 MORPHING_METHOD_ERODE_ERODE = 2,
00101 MORPHING_METHOD_ERODE_DILATE = 3
00102 };
00103
00104 CvAdaptiveSkinDetector(int samplingDivider = 1, int morphingMethod = MORPHING_METHOD_NONE);
00105 virtual ~CvAdaptiveSkinDetector();
00106
00107 virtual void process(IplImage *inputBGRImage, IplImage *outputHueMask);
00108 };
00109
00110
00111
00112
00113
00114
00115 class CV_EXPORTS CvFuzzyPoint {
00116 public:
00117 double x, y, value;
00118
00119 CvFuzzyPoint(double _x, double _y);
00120 };
00121
00122 class CV_EXPORTS CvFuzzyCurve {
00123 private:
00124 std::vector<CvFuzzyPoint> points;
00125 double value, centre;
00126
00127 bool between(double x, double x1, double x2);
00128
00129 public:
00130 CvFuzzyCurve();
00131 ~CvFuzzyCurve();
00132
00133 void setCentre(double _centre);
00134 double getCentre();
00135 void clear();
00136 void addPoint(double x, double y);
00137 double calcValue(double param);
00138 double getValue();
00139 void setValue(double _value);
00140 };
00141
00142 class CV_EXPORTS CvFuzzyFunction {
00143 public:
00144 std::vector<CvFuzzyCurve> curves;
00145
00146 CvFuzzyFunction();
00147 ~CvFuzzyFunction();
00148 void addCurve(CvFuzzyCurve *curve, double value = 0);
00149 void resetValues();
00150 double calcValue();
00151 CvFuzzyCurve *newCurve();
00152 };
00153
00154 class CV_EXPORTS CvFuzzyRule {
00155 private:
00156 CvFuzzyCurve *fuzzyInput1, *fuzzyInput2;
00157 CvFuzzyCurve *fuzzyOutput;
00158 public:
00159 CvFuzzyRule();
00160 ~CvFuzzyRule();
00161 void setRule(CvFuzzyCurve *c1, CvFuzzyCurve *c2, CvFuzzyCurve *o1);
00162 double calcValue(double param1, double param2);
00163 CvFuzzyCurve *getOutputCurve();
00164 };
00165
00166 class CV_EXPORTS CvFuzzyController {
00167 private:
00168 std::vector<CvFuzzyRule*> rules;
00169 public:
00170 CvFuzzyController();
00171 ~CvFuzzyController();
00172 void addRule(CvFuzzyCurve *c1, CvFuzzyCurve *c2, CvFuzzyCurve *o1);
00173 double calcOutput(double param1, double param2);
00174 };
00175
00176 class CV_EXPORTS CvFuzzyMeanShiftTracker
00177 {
00178 private:
00179 class FuzzyResizer
00180 {
00181 private:
00182 CvFuzzyFunction iInput, iOutput;
00183 CvFuzzyController fuzzyController;
00184 public:
00185 FuzzyResizer();
00186 int calcOutput(double edgeDensity, double density);
00187 };
00188
00189 class SearchWindow
00190 {
00191 public:
00192 FuzzyResizer *fuzzyResizer;
00193 int x, y;
00194 int width, height, maxWidth, maxHeight, ellipseHeight, ellipseWidth;
00195 int ldx, ldy, ldw, ldh, numShifts, numIters;
00196 int xGc, yGc;
00197 long m00, m01, m10, m11, m02, m20;
00198 double ellipseAngle;
00199 double density;
00200 unsigned int depthLow, depthHigh;
00201 int verticalEdgeLeft, verticalEdgeRight, horizontalEdgeTop, horizontalEdgeBottom;
00202
00203 SearchWindow();
00204 ~SearchWindow();
00205 void setSize(int _x, int _y, int _width, int _height);
00206 void initDepthValues(IplImage *maskImage, IplImage *depthMap);
00207 bool shift();
00208 void extractInfo(IplImage *maskImage, IplImage *depthMap, bool initDepth);
00209 void getResizeAttribsEdgeDensityLinear(int &resizeDx, int &resizeDy, int &resizeDw, int &resizeDh);
00210 void getResizeAttribsInnerDensity(int &resizeDx, int &resizeDy, int &resizeDw, int &resizeDh);
00211 void getResizeAttribsEdgeDensityFuzzy(int &resizeDx, int &resizeDy, int &resizeDw, int &resizeDh);
00212 bool meanShift(IplImage *maskImage, IplImage *depthMap, int maxIteration, bool initDepth);
00213 };
00214
00215 public:
00216 enum TrackingState
00217 {
00218 tsNone = 0,
00219 tsSearching = 1,
00220 tsTracking = 2,
00221 tsSetWindow = 3,
00222 tsDisabled = 10
00223 };
00224
00225 enum ResizeMethod {
00226 rmEdgeDensityLinear = 0,
00227 rmEdgeDensityFuzzy = 1,
00228 rmInnerDensity = 2
00229 };
00230
00231 enum {
00232 MinKernelMass = 1000
00233 };
00234
00235 SearchWindow kernel;
00236 int searchMode;
00237
00238 private:
00239 enum
00240 {
00241 MaxMeanShiftIteration = 5,
00242 MaxSetSizeIteration = 5
00243 };
00244
00245 void findOptimumSearchWindow(SearchWindow &searchWindow, IplImage *maskImage, IplImage *depthMap, int maxIteration, int resizeMethod, bool initDepth);
00246
00247 public:
00248 CvFuzzyMeanShiftTracker();
00249 ~CvFuzzyMeanShiftTracker();
00250
00251 void track(IplImage *maskImage, IplImage *depthMap, int resizeMethod, bool resetSearch, int minKernelMass = MinKernelMass);
00252 };
00253
00254
00255 namespace cv
00256 {
00257
00258 class CV_EXPORTS Octree
00259 {
00260 public:
00261 struct Node
00262 {
00263 Node() {}
00264 int begin, end;
00265 float x_min, x_max, y_min, y_max, z_min, z_max;
00266 int maxLevels;
00267 bool isLeaf;
00268 int children[8];
00269 };
00270
00271 Octree();
00272 Octree( const vector<Point3f>& points, int maxLevels = 10, int minPoints = 20 );
00273 virtual ~Octree();
00274
00275 virtual void buildTree( const vector<Point3f>& points, int maxLevels = 10, int minPoints = 20 );
00276 virtual void getPointsWithinSphere( const Point3f& center, float radius,
00277 vector<Point3f>& points ) const;
00278 const vector<Node>& getNodes() const { return nodes; }
00279 private:
00280 int minPoints;
00281 vector<Point3f> points;
00282 vector<Node> nodes;
00283
00284 virtual void buildNext(size_t node_ind);
00285 };
00286
00287
00288 class CV_EXPORTS Mesh3D
00289 {
00290 public:
00291 struct EmptyMeshException {};
00292
00293 Mesh3D();
00294 Mesh3D(const vector<Point3f>& vtx);
00295 ~Mesh3D();
00296
00297 void buildOctree();
00298 void clearOctree();
00299 float estimateResolution(float tryRatio = 0.1f);
00300 void computeNormals(float normalRadius, int minNeighbors = 20);
00301 void computeNormals(const vector<int>& subset, float normalRadius, int minNeighbors = 20);
00302
00303 void writeAsVrml(const String& file, const vector<Scalar>& colors = vector<Scalar>()) const;
00304
00305 vector<Point3f> vtx;
00306 vector<Point3f> normals;
00307 float resolution;
00308 Octree octree;
00309
00310 const static Point3f allzero;
00311 };
00312
00313 class CV_EXPORTS SpinImageModel
00314 {
00315 public:
00316
00317
00318 float normalRadius;
00319 int minNeighbors;
00320
00321 float binSize;
00322 int imageWidth;
00323
00324 float lambda;
00325 float gamma;
00326
00327 float T_GeometriccConsistency;
00328 float T_GroupingCorespondances;
00329
00330
00331 SpinImageModel();
00332 explicit SpinImageModel(const Mesh3D& mesh);
00333 ~SpinImageModel();
00334
00335 void setLogger(std::ostream* log);
00336 void selectRandomSubset(float ratio);
00337 void setSubset(const vector<int>& subset);
00338 void compute();
00339
00340 void match(const SpinImageModel& scene, vector< vector<Vec2i> >& result);
00341
00342 Mat packRandomScaledSpins(bool separateScale = false, size_t xCount = 10, size_t yCount = 10) const;
00343
00344 size_t getSpinCount() const { return spinImages.rows; }
00345 Mat getSpinImage(size_t index) const { return spinImages.row((int)index); }
00346 const Point3f& getSpinVertex(size_t index) const { return mesh.vtx[subset[index]]; }
00347 const Point3f& getSpinNormal(size_t index) const { return mesh.normals[subset[index]]; }
00348
00349 const Mesh3D& getMesh() const { return mesh; }
00350 Mesh3D& getMesh() { return mesh; }
00351
00352
00353 static bool spinCorrelation(const Mat& spin1, const Mat& spin2, float lambda, float& result);
00354
00355 static Point2f calcSpinMapCoo(const Point3f& point, const Point3f& vertex, const Point3f& normal);
00356
00357 static float geometricConsistency(const Point3f& pointScene1, const Point3f& normalScene1,
00358 const Point3f& pointModel1, const Point3f& normalModel1,
00359 const Point3f& pointScene2, const Point3f& normalScene2,
00360 const Point3f& pointModel2, const Point3f& normalModel2);
00361
00362 static float groupingCreteria(const Point3f& pointScene1, const Point3f& normalScene1,
00363 const Point3f& pointModel1, const Point3f& normalModel1,
00364 const Point3f& pointScene2, const Point3f& normalScene2,
00365 const Point3f& pointModel2, const Point3f& normalModel2,
00366 float gamma);
00367 protected:
00368 void defaultParams();
00369
00370 void matchSpinToModel(const Mat& spin, vector<int>& indeces,
00371 vector<float>& corrCoeffs, bool useExtremeOutliers = true) const;
00372
00373 void repackSpinImages(const vector<uchar>& mask, Mat& spinImages, bool reAlloc = true) const;
00374
00375 vector<int> subset;
00376 Mesh3D mesh;
00377 Mat spinImages;
00378 std::ostream* out;
00379 };
00380
00381 class CV_EXPORTS TickMeter
00382 {
00383 public:
00384 TickMeter();
00385 void start();
00386 void stop();
00387
00388 int64 getTimeTicks() const;
00389 double getTimeMicro() const;
00390 double getTimeMilli() const;
00391 double getTimeSec() const;
00392 int64 getCounter() const;
00393
00394 void reset();
00395 private:
00396 int64 counter;
00397 int64 sumTime;
00398 int64 startTime;
00399 };
00400
00401 CV_EXPORTS std::ostream& operator<<(std::ostream& out, const TickMeter& tm);
00402
00403 class CV_EXPORTS SelfSimDescriptor
00404 {
00405 public:
00406 SelfSimDescriptor();
00407 SelfSimDescriptor(int _ssize, int _lsize,
00408 int _startDistanceBucket=DEFAULT_START_DISTANCE_BUCKET,
00409 int _numberOfDistanceBuckets=DEFAULT_NUM_DISTANCE_BUCKETS,
00410 int _nangles=DEFAULT_NUM_ANGLES);
00411 SelfSimDescriptor(const SelfSimDescriptor& ss);
00412 virtual ~SelfSimDescriptor();
00413 SelfSimDescriptor& operator = (const SelfSimDescriptor& ss);
00414
00415 size_t getDescriptorSize() const;
00416 Size getGridSize( Size imgsize, Size winStride ) const;
00417
00418 virtual void compute(const Mat& img, vector<float>& descriptors, Size winStride=Size(),
00419 const vector<Point>& locations=vector<Point>()) const;
00420 virtual void computeLogPolarMapping(Mat& mappingMask) const;
00421 virtual void SSD(const Mat& img, Point pt, Mat& ssd) const;
00422
00423 int smallSize;
00424 int largeSize;
00425 int startDistanceBucket;
00426 int numberOfDistanceBuckets;
00427 int numberOfAngles;
00428
00429 enum { DEFAULT_SMALL_SIZE = 5, DEFAULT_LARGE_SIZE = 41,
00430 DEFAULT_NUM_ANGLES = 20, DEFAULT_START_DISTANCE_BUCKET = 3,
00431 DEFAULT_NUM_DISTANCE_BUCKETS = 7 };
00432 };
00433
00434 class CV_EXPORTS LevMarqSparse
00435 {
00436 public:
00437 LevMarqSparse();
00438 LevMarqSparse(int npoints,
00439 int ncameras,
00440 int nPointParams,
00441 int nCameraParams,
00442 int nErrParams,
00443
00444 Mat& visibility,
00445
00446 Mat& P0,
00447 Mat& X,
00448 TermCriteria criteria,
00449
00450
00451 void (CV_CDECL * fjac)(int i, int j, Mat& point_params,
00452 Mat& cam_params, Mat& A, Mat& B, void* data),
00453
00454 void (CV_CDECL * func)(int i, int j, Mat& point_params,
00455 Mat& cam_params, Mat& estim, void* data),
00456 void* data
00457 );
00458 virtual ~LevMarqSparse();
00459
00460 virtual void run( int npoints,
00461 int ncameras,
00462 int nPointParams,
00463 int nCameraParams,
00464 int nErrParams,
00465
00466 Mat& visibility,
00467
00468 Mat& P0,
00469 Mat& X,
00470 TermCriteria criteria,
00471
00472
00473 void (CV_CDECL * fjac)(int i, int j, Mat& point_params,
00474 Mat& cam_params, Mat& A, Mat& B, void* data),
00475
00476 void (CV_CDECL * func)(int i, int j, Mat& point_params,
00477 Mat& cam_params, Mat& estim, void* data),
00478 void* data
00479 );
00480
00481 virtual void clear();
00482
00483
00484 static void bundleAdjust(vector<Point3d>& points,
00485 const vector<vector<Point2d> >& imagePoints,
00486 const vector<vector<int> >& visibility,
00487 vector<Mat>& cameraMatrix,
00488 vector<Mat>& R,
00489 vector<Mat>& T,
00490 vector<Mat>& distCoeffs,
00491 const TermCriteria& criteria=
00492 TermCriteria(TermCriteria::COUNT+TermCriteria::EPS, 30, DBL_EPSILON));
00493
00494 protected:
00495 virtual void optimize();
00496
00497
00498 void ask_for_proj();
00499
00500 void ask_for_projac();
00501
00502 CvMat* err;
00503 double prevErrNorm, errNorm;
00504 double lambda;
00505 CvTermCriteria criteria;
00506 int iters;
00507
00508 CvMat** U;
00509 CvMat** V;
00510 CvMat** inv_V_star;
00511
00512 CvMat* A;
00513 CvMat* B;
00514 CvMat* W;
00515
00516 CvMat* X;
00517 CvMat* hX;
00518
00519 CvMat* prevP;
00520 CvMat* P;
00521
00522
00523 CvMat* deltaP;
00524
00525 CvMat** ea;
00526
00527 CvMat** eb;
00528
00529
00530 CvMat** Yj;
00531
00532 CvMat* S;
00533
00534 CvMat* JtJ_diag;
00535
00536 CvMat* Vis_index;
00537
00538 int num_cams;
00539 int num_points;
00540 int num_err_param;
00541 int num_cam_param;
00542 int num_point_param;
00543
00544
00545 void (*fjac)(int i, int j, Mat& point_params, Mat& cam_params, Mat& A, Mat& B, void* data);
00546 void (*func)(int i, int j, Mat& point_params, Mat& cam_params, Mat& estim, void* data );
00547
00548 void* data;
00549 };
00550
00551
00552 CV_EXPORTS bool find4QuadCornerSubpix(const Mat& img, std::vector<Point2f>& corners, Size region_size);
00553
00554 CV_EXPORTS int chamerMatching( Mat& img, Mat& templ,
00555 vector<vector<Point> >& results, vector<float>& cost,
00556 double templScale=1, int maxMatches = 20,
00557 double minMatchDistance = 1.0, int padX = 3,
00558 int padY = 3, int scales = 5, double minScale = 0.6, double maxScale = 1.6,
00559 double orientationWeight = 0.5, double truncate = 20);
00560 }
00561
00562
00563 #endif
00564
00565 #endif
00566