opencv  2.2.0
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
imgproc.hpp
Go to the documentation of this file.
1 
5 /*M///////////////////////////////////////////////////////////////////////////////////////
6 //
7 // IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.
8 //
9 // By downloading, copying, installing or using the software you agree to this license.
10 // If you do not agree to this license, do not download, install,
11 // copy or use the software.
12 //
13 //
14 // License Agreement
15 // For Open Source Computer Vision Library
16 //
17 // Copyright (C) 2000-2008, Intel Corporation, all rights reserved.
18 // Copyright (C) 2009, Willow Garage Inc., all rights reserved.
19 // Third party copyrights are property of their respective owners.
20 //
21 // Redistribution and use in source and binary forms, with or without modification,
22 // are permitted provided that the following conditions are met:
23 //
24 // * Redistribution's of source code must retain the above copyright notice,
25 // this list of conditions and the following disclaimer.
26 //
27 // * Redistribution's in binary form must reproduce the above copyright notice,
28 // this list of conditions and the following disclaimer in the documentation
29 // and/or other materials provided with the distribution.
30 //
31 // * The name of the copyright holders may not be used to endorse or promote products
32 // derived from this software without specific prior written permission.
33 //
34 // This software is provided by the copyright holders and contributors "as is" and
35 // any express or implied warranties, including, but not limited to, the implied
36 // warranties of merchantability and fitness for a particular purpose are disclaimed.
37 // In no event shall the Intel Corporation or contributors be liable for any direct,
38 // indirect, incidental, special, exemplary, or consequential damages
39 // (including, but not limited to, procurement of substitute goods or services;
40 // loss of use, data, or profits; or business interruption) however caused
41 // and on any theory of liability, whether in contract, strict liability,
42 // or tort (including negligence or otherwise) arising in any way out of
43 // the use of this software, even if advised of the possibility of such damage.
44 //
45 //M*/
46 
47 #ifndef __OPENCV_IMGPROC_HPP__
48 #define __OPENCV_IMGPROC_HPP__
49 
50 #include "opencv2/core/core.hpp"
52 
53 #ifdef __cplusplus
54 
58 namespace cv
59 {
60 
67 
69 CV_EXPORTS_W int borderInterpolate( int p, int len, int borderType );
70 
81 {
82 public:
84  BaseRowFilter();
86  virtual ~BaseRowFilter();
88  virtual void operator()(const uchar* src, uchar* dst,
89  int width, int cn) = 0;
90  int ksize, anchor;
91 };
92 
93 
108 {
109 public:
113  virtual ~BaseColumnFilter();
115  virtual void operator()(const uchar** src, uchar* dst, int dststep,
116  int dstcount, int width) = 0;
118  virtual void reset();
119  int ksize, anchor;
120 };
121 
134 {
135 public:
137  BaseFilter();
139  virtual ~BaseFilter();
141  virtual void operator()(const uchar** src, uchar* dst, int dststep,
142  int dstcount, int width, int cn) = 0;
144  virtual void reset();
147 };
148 
223 {
224 public:
226  FilterEngine();
228  FilterEngine(const Ptr<BaseFilter>& _filter2D,
229  const Ptr<BaseRowFilter>& _rowFilter,
230  const Ptr<BaseColumnFilter>& _columnFilter,
231  int srcType, int dstType, int bufType,
232  int _rowBorderType=BORDER_REPLICATE,
233  int _columnBorderType=-1,
234  const Scalar& _borderValue=Scalar());
236  virtual ~FilterEngine();
238  void init(const Ptr<BaseFilter>& _filter2D,
239  const Ptr<BaseRowFilter>& _rowFilter,
240  const Ptr<BaseColumnFilter>& _columnFilter,
241  int srcType, int dstType, int bufType,
242  int _rowBorderType=BORDER_REPLICATE, int _columnBorderType=-1,
243  const Scalar& _borderValue=Scalar());
245  virtual int start(Size wholeSize, Rect roi, int maxBufRows=-1);
247  virtual int start(const Mat& src, const Rect& srcRoi=Rect(0,0,-1,-1),
248  bool isolated=false, int maxBufRows=-1);
250  virtual int proceed(const uchar* src, int srcStep, int srcCount,
251  uchar* dst, int dstStep);
253  virtual void apply( const Mat& src, Mat& dst,
254  const Rect& srcRoi=Rect(0,0,-1,-1),
255  Point dstOfs=Point(0,0),
256  bool isolated=false);
258  bool isSeparable() const { return (const BaseFilter*)filter2D == 0; }
260  int remainingInputRows() const;
261  int remainingOutputRows() const;
262 
263  int srcType, dstType, bufType;
266  int maxWidth;
269  int dx1, dx2;
270  int rowBorderType, columnBorderType;
271  vector<int> borderTab;
273  vector<uchar> ringBuf;
274  vector<uchar> srcRow;
275  vector<uchar> constBorderValue;
276  vector<uchar> constBorderRow;
277  int bufStep, startY, startY0, endY, rowCount, dstY;
278  vector<uchar*> rows;
279 
283 };
284 
288 
290 CV_EXPORTS int getKernelType(const Mat& kernel, Point anchor);
291 
293 CV_EXPORTS Ptr<BaseRowFilter> getLinearRowFilter(int srcType, int bufType,
294  const Mat& kernel, int anchor,
295  int symmetryType);
296 
298 CV_EXPORTS Ptr<BaseColumnFilter> getLinearColumnFilter(int bufType, int dstType,
299  const Mat& kernel, int anchor,
300  int symmetryType, double delta=0,
301  int bits=0);
302 
304 CV_EXPORTS Ptr<BaseFilter> getLinearFilter(int srcType, int dstType,
305  const Mat& kernel,
306  Point anchor=Point(-1,-1),
307  double delta=0, int bits=0);
308 
310 CV_EXPORTS Ptr<FilterEngine> createSeparableLinearFilter(int srcType, int dstType,
311  const Mat& rowKernel, const Mat& columnKernel,
312  Point _anchor=Point(-1,-1), double delta=0,
313  int _rowBorderType=BORDER_DEFAULT,
314  int _columnBorderType=-1,
315  const Scalar& _borderValue=Scalar());
316 
318 CV_EXPORTS Ptr<FilterEngine> createLinearFilter(int srcType, int dstType,
319  const Mat& kernel, Point _anchor=Point(-1,-1),
320  double delta=0, int _rowBorderType=BORDER_DEFAULT,
321  int _columnBorderType=-1, const Scalar& _borderValue=Scalar());
322 
324 CV_EXPORTS_W Mat getGaussianKernel( int ksize, double sigma, int ktype=CV_64F );
325 
327 CV_EXPORTS Ptr<FilterEngine> createGaussianFilter( int type, Size ksize,
328  double sigma1, double sigma2=0,
331 CV_EXPORTS_W void getDerivKernels( CV_OUT Mat& kx, CV_OUT Mat& ky,
332  int dx, int dy, int ksize,
333  bool normalize=false, int ktype=CV_32F );
335 CV_EXPORTS Ptr<FilterEngine> createDerivFilter( int srcType, int dstType,
336  int dx, int dy, int ksize,
339 CV_EXPORTS Ptr<BaseRowFilter> getRowSumFilter(int srcType, int sumType,
340  int ksize, int anchor=-1);
342 CV_EXPORTS Ptr<BaseColumnFilter> getColumnSumFilter( int sumType, int dstType,
343  int ksize, int anchor=-1,
344  double scale=1);
346 CV_EXPORTS Ptr<FilterEngine> createBoxFilter( int srcType, int dstType, Size ksize,
347  Point anchor=Point(-1,-1),
348  bool normalize=true,
353 
355 CV_EXPORTS Ptr<BaseRowFilter> getMorphologyRowFilter(int op, int type, int ksize, int anchor=-1);
357 CV_EXPORTS Ptr<BaseColumnFilter> getMorphologyColumnFilter(int op, int type, int ksize, int anchor=-1);
359 CV_EXPORTS Ptr<BaseFilter> getMorphologyFilter(int op, int type, const Mat& kernel,
360  Point anchor=Point(-1,-1));
361 
363 static inline Scalar morphologyDefaultBorderValue() { return Scalar::all(DBL_MAX); }
364 
366 CV_EXPORTS Ptr<FilterEngine> createMorphologyFilter(int op, int type, const Mat& kernel,
367  Point anchor=Point(-1,-1), int _rowBorderType=BORDER_CONSTANT,
368  int _columnBorderType=-1,
369  const Scalar& _borderValue=morphologyDefaultBorderValue());
370 
374 CV_EXPORTS_W Mat getStructuringElement(int shape, Size ksize, Point anchor=Point(-1,-1));
375 
377 
379 CV_EXPORTS_W void copyMakeBorder( const Mat& src, CV_OUT Mat& dst,
380  int top, int bottom, int left, int right,
381  int borderType, const Scalar& value=Scalar() );
382 
384 CV_EXPORTS_W void medianBlur( const Mat& src, CV_OUT Mat& dst, int ksize );
386 CV_EXPORTS_AS(gaussianBlur) void GaussianBlur( const Mat& src, CV_OUT Mat& dst, Size ksize,
387  double sigma1, double sigma2=0,
388  int borderType=BORDER_DEFAULT );
390 CV_EXPORTS_W void bilateralFilter( const Mat& src, CV_OUT Mat& dst, int d,
391  double sigmaColor, double sigmaSpace,
392  int borderType=BORDER_DEFAULT );
394 CV_EXPORTS_W void boxFilter( const Mat& src, CV_OUT Mat& dst, int ddepth,
395  Size ksize, Point anchor=Point(-1,-1),
396  bool normalize=true,
397  int borderType=BORDER_DEFAULT );
399 CV_EXPORTS_W void blur( const Mat& src, CV_OUT Mat& dst,
400  Size ksize, Point anchor=Point(-1,-1),
401  int borderType=BORDER_DEFAULT );
402 
404 CV_EXPORTS_W void filter2D( const Mat& src, CV_OUT Mat& dst, int ddepth,
405  const Mat& kernel, Point anchor=Point(-1,-1),
406  double delta=0, int borderType=BORDER_DEFAULT );
407 
409 CV_EXPORTS_W void sepFilter2D( const Mat& src, CV_OUT Mat& dst, int ddepth,
410  const Mat& kernelX, const Mat& kernelY,
411  Point anchor=Point(-1,-1),
412  double delta=0, int borderType=BORDER_DEFAULT );
413 
415 CV_EXPORTS_AS(sobel) void Sobel( const Mat& src, CV_OUT Mat& dst, int ddepth,
416  int dx, int dy, int ksize=3,
417  double scale=1, double delta=0,
418  int borderType=BORDER_DEFAULT );
419 
421 CV_EXPORTS_AS(scharr) void Scharr( const Mat& src, CV_OUT Mat& dst, int ddepth,
422  int dx, int dy, double scale=1, double delta=0,
423  int borderType=BORDER_DEFAULT );
424 
426 CV_EXPORTS_AS(laplacian) void Laplacian( const Mat& src, CV_OUT Mat& dst, int ddepth,
427  int ksize=1, double scale=1, double delta=0,
428  int borderType=BORDER_DEFAULT );
429 
431 CV_EXPORTS_AS(canny) void Canny( const Mat& image, CV_OUT Mat& edges,
432  double threshold1, double threshold2,
433  int apertureSize=3, bool L2gradient=false );
434 
436 CV_EXPORTS_W void cornerMinEigenVal( const Mat& src, CV_OUT Mat& dst,
437  int blockSize, int ksize=3,
438  int borderType=BORDER_DEFAULT );
439 
441 CV_EXPORTS_W void cornerHarris( const Mat& src, CV_OUT Mat& dst, int blockSize,
442  int ksize, double k,
443  int borderType=BORDER_DEFAULT );
444 
446 CV_EXPORTS_W void cornerEigenValsAndVecs( const Mat& src, CV_OUT Mat& dst,
447  int blockSize, int ksize,
448  int borderType=BORDER_DEFAULT );
449 
451 CV_EXPORTS_W void preCornerDetect( const Mat& src, CV_OUT Mat& dst, int ksize,
452  int borderType=BORDER_DEFAULT );
453 
455 CV_EXPORTS void cornerSubPix( const Mat& image, vector<Point2f>& corners,
456  Size winSize, Size zeroZone,
457  TermCriteria criteria );
458 
460 CV_EXPORTS_W void goodFeaturesToTrack( const Mat& image, CV_OUT vector<Point2f>& corners,
461  int maxCorners, double qualityLevel, double minDistance,
462  const Mat& mask=Mat(), int blockSize=3,
463  bool useHarrisDetector=false, double k=0.04 );
464 
466 CV_EXPORTS_AS(houghLines) void HoughLines( const Mat& image, CV_OUT vector<Vec2f>& lines,
467  double rho, double theta, int threshold,
468  double srn=0, double stn=0 );
469 
471 CV_EXPORTS_AS(houghLinesP) void HoughLinesP( Mat& image, CV_OUT vector<Vec4i>& lines,
472  double rho, double theta, int threshold,
473  double minLineLength=0, double maxLineGap=0 );
474 
476 CV_EXPORTS_AS(houghCircles) void HoughCircles( const Mat& image, CV_OUT vector<Vec3f>& circles,
477  int method, double dp, double minDist,
478  double param1=100, double param2=100,
479  int minRadius=0, int maxRadius=0 );
480 
482 CV_EXPORTS_W void erode( const Mat& src, CV_OUT Mat& dst, const Mat& kernel,
483  Point anchor=Point(-1,-1), int iterations=1,
484  int borderType=BORDER_CONSTANT,
485  const Scalar& borderValue=morphologyDefaultBorderValue() );
486 
488 CV_EXPORTS_W void dilate( const Mat& src, CV_OUT Mat& dst, const Mat& kernel,
489  Point anchor=Point(-1,-1), int iterations=1,
490  int borderType=BORDER_CONSTANT,
491  const Scalar& borderValue=morphologyDefaultBorderValue() );
492 
494 CV_EXPORTS_W void morphologyEx( const Mat& src, CV_OUT Mat& dst,
495  int op, const Mat& kernel,
496  Point anchor=Point(-1,-1), int iterations=1,
497  int borderType=BORDER_CONSTANT,
498  const Scalar& borderValue=morphologyDefaultBorderValue() );
499 
501 enum
502 {
510 };
511 
513 CV_EXPORTS_W void resize( const Mat& src, CV_OUT Mat& dst,
514  Size dsize, double fx=0, double fy=0,
515  int interpolation=INTER_LINEAR );
516 
518 CV_EXPORTS_W void warpAffine( const Mat& src, CV_OUT Mat& dst,
519  const Mat& M, Size dsize,
520  int flags=INTER_LINEAR,
521  int borderMode=BORDER_CONSTANT,
522  const Scalar& borderValue=Scalar());
523 
525 CV_EXPORTS_W void warpPerspective( const Mat& src, CV_OUT Mat& dst,
526  const Mat& M, Size dsize,
527  int flags=INTER_LINEAR,
528  int borderMode=BORDER_CONSTANT,
529  const Scalar& borderValue=Scalar());
530 
534 
536 CV_EXPORTS_W void remap( const Mat& src, CV_OUT Mat& dst, const Mat& map1, const Mat& map2,
537  int interpolation, int borderMode=BORDER_CONSTANT,
538  const Scalar& borderValue=Scalar());
539 
541 CV_EXPORTS_W void convertMaps( const Mat& map1, const Mat& map2,
542  CV_OUT Mat& dstmap1, CV_OUT Mat& dstmap2,
543  int dstmap1type, bool nninterpolation=false );
544 
546 CV_EXPORTS_W Mat getRotationMatrix2D( Point2f center, double angle, double scale );
548 CV_EXPORTS Mat getPerspectiveTransform( const Point2f src[], const Point2f dst[] );
550 CV_EXPORTS Mat getAffineTransform( const Point2f src[], const Point2f dst[] );
552 CV_EXPORTS_W void invertAffineTransform( const Mat& M, CV_OUT Mat& iM );
553 
555 CV_EXPORTS_W void getRectSubPix( const Mat& image, Size patchSize,
556  Point2f center, CV_OUT Mat& patch, int patchType=-1 );
557 
559 CV_EXPORTS_W void integral( const Mat& src, CV_OUT Mat& sum, int sdepth=-1 );
561 CV_EXPORTS_AS(integral2) void integral( const Mat& src, CV_OUT Mat& sum, CV_OUT Mat& sqsum, int sdepth=-1 );
563 CV_EXPORTS_AS(integral3) void integral( const Mat& src, CV_OUT Mat& sum, CV_OUT Mat& sqsum, CV_OUT Mat& tilted, int sdepth=-1 );
564 
566 CV_EXPORTS_W void accumulate( const Mat& src, CV_IN_OUT Mat& dst, const Mat& mask=Mat() );
568 CV_EXPORTS_W void accumulateSquare( const Mat& src, CV_IN_OUT Mat& dst, const Mat& mask=Mat() );
570 CV_EXPORTS_W void accumulateProduct( const Mat& src1, const Mat& src2,
571  CV_IN_OUT Mat& dst, const Mat& mask=Mat() );
573 CV_EXPORTS_W void accumulateWeighted( const Mat& src, CV_IN_OUT Mat& dst,
574  double alpha, const Mat& mask=Mat() );
575 
579 
581 CV_EXPORTS_W double threshold( const Mat& src, CV_OUT Mat& dst, double thresh, double maxval, int type );
582 
585 
587 CV_EXPORTS_W void adaptiveThreshold( const Mat& src, CV_OUT Mat& dst, double maxValue,
588  int adaptiveMethod, int thresholdType,
589  int blockSize, double C );
590 
592 CV_EXPORTS_W void pyrDown( const Mat& src, CV_OUT Mat& dst, const Size& dstsize=Size());
594 CV_EXPORTS_W void pyrUp( const Mat& src, CV_OUT Mat& dst, const Size& dstsize=Size());
596 CV_EXPORTS void buildPyramid( const Mat& src, CV_OUT vector<Mat>& dst, int maxlevel );
597 
599 CV_EXPORTS_W void undistort( const Mat& src, CV_OUT Mat& dst, const Mat& cameraMatrix,
600  const Mat& distCoeffs, const Mat& newCameraMatrix=Mat() );
602 CV_EXPORTS_W void initUndistortRectifyMap( const Mat& cameraMatrix, const Mat& distCoeffs,
603  const Mat& R, const Mat& newCameraMatrix,
604  Size size, int m1type, CV_OUT Mat& map1, CV_OUT Mat& map2 );
605 
606 enum
607 {
610 };
611 
613 CV_EXPORTS_W float initWideAngleProjMap( const Mat& cameraMatrix, const Mat& distCoeffs,
614  Size imageSize, int destImageWidth,
615  int m1type, CV_OUT Mat& map1, CV_OUT Mat& map2,
616  int projType=PROJ_SPHERICAL_EQRECT, double alpha=0);
617 
619 CV_EXPORTS_W Mat getDefaultNewCameraMatrix( const Mat& cameraMatrix, Size imgsize=Size(),
620  bool centerPrincipalPoint=false );
622 CV_EXPORTS void undistortPoints( const Mat& src, CV_OUT vector<Point2f>& dst,
623  const Mat& cameraMatrix, const Mat& distCoeffs,
624  const Mat& R=Mat(), const Mat& P=Mat());
626 CV_EXPORTS_W void undistortPoints( const Mat& src, CV_OUT Mat& dst,
627  const Mat& cameraMatrix, const Mat& distCoeffs,
628  const Mat& R=Mat(), const Mat& P=Mat());
629 
630 template<> CV_EXPORTS void Ptr<CvHistogram>::delete_obj();
631 
633 CV_EXPORTS void calcHist( const Mat* images, int nimages,
634  const int* channels, const Mat& mask,
635  Mat& hist, int dims, const int* histSize,
636  const float** ranges, bool uniform=true, bool accumulate=false );
637 
639 CV_EXPORTS void calcHist( const Mat* images, int nimages,
640  const int* channels, const Mat& mask,
641  SparseMat& hist, int dims,
642  const int* histSize, const float** ranges,
643  bool uniform=true, bool accumulate=false );
644 
646 CV_EXPORTS void calcBackProject( const Mat* images, int nimages,
647  const int* channels, const Mat& hist,
648  Mat& backProject, const float** ranges,
649  double scale=1, bool uniform=true );
650 
652 CV_EXPORTS void calcBackProject( const Mat* images, int nimages,
653  const int* channels, const SparseMat& hist,
654  Mat& backProject, const float** ranges,
655  double scale=1, bool uniform=true );
656 
658 CV_EXPORTS_W double compareHist( const Mat& H1, const Mat& H2, int method );
659 
661 CV_EXPORTS double compareHist( const SparseMat& H1, const SparseMat& H2, int method );
662 
664 CV_EXPORTS_W void equalizeHist( const Mat& src, CV_OUT Mat& dst );
665 
667 CV_EXPORTS_W void watershed( const Mat& image, Mat& markers );
668 
670 CV_EXPORTS_W void pyrMeanShiftFiltering( const Mat& src, CV_OUT Mat& dst,
671  double sp, double sr, int maxLevel=1,
672  TermCriteria termcrit=TermCriteria(TermCriteria::MAX_ITER+TermCriteria::EPS,5,1) );
673 
675 enum { GC_BGD = 0,
676  GC_FGD = 1,
677  GC_PR_BGD = 2,
679  };
680 
682 enum { GC_INIT_WITH_RECT = 0,
685  };
686 
688 CV_EXPORTS_W void grabCut( const Mat& img, Mat& mask, Rect rect,
689  Mat& bgdModel, Mat& fgdModel,
690  int iterCount, int mode = GC_EVAL );
691 
693 enum
694 {
695  INPAINT_NS=0, // Navier-Stokes algorithm
696  INPAINT_TELEA=1 // A. Telea algorithm
697 };
698 
700 CV_EXPORTS_W void inpaint( const Mat& src, const Mat& inpaintMask,
701  CV_OUT Mat& dst, double inpaintRange, int flags );
702 
704 CV_EXPORTS_AS(distanceTransformWithLabels)
705  void distanceTransform( const Mat& src, CV_OUT Mat& dst, Mat& labels,
706  int distanceType, int maskSize );
707 
709 CV_EXPORTS_W void distanceTransform( const Mat& src, CV_OUT Mat& dst,
710  int distanceType, int maskSize );
711 
712 enum { FLOODFILL_FIXED_RANGE = 1 << 16,
713  FLOODFILL_MASK_ONLY = 1 << 17 };
714 
716 CV_EXPORTS_W int floodFill( Mat& image,
719  int flags=4 );
720 
722 CV_EXPORTS_AS(floodFillMask) int floodFill( Mat& image, Mat& mask,
723  Point seedPoint, Scalar newVal, CV_OUT Rect* rect=0,
724  Scalar loDiff=Scalar(), Scalar upDiff=Scalar(),
725  int flags=4 );
726 
728 CV_EXPORTS_W void cvtColor( const Mat& src, CV_OUT Mat& dst, int code, int dstCn=0 );
729 
732 {
733 public:
735  Moments();
737  Moments(double m00, double m10, double m01, double m20, double m11,
738  double m02, double m30, double m21, double m12, double m03 );
740  Moments( const CvMoments& moments );
742  operator CvMoments() const;
743 
745  CV_PROP_RW double m00, m10, m01, m20, m11, m02, m30, m21, m12, m03;
747  CV_PROP_RW double mu20, mu11, mu02, mu30, mu21, mu12, mu03;
749  CV_PROP_RW double nu20, nu11, nu02, nu30, nu21, nu12, nu03;
750 };
751 
753 CV_EXPORTS_W Moments moments( const Mat& array, bool binaryImage=false );
754 
756 CV_EXPORTS void HuMoments( const Moments& moments, double hu[7] );
757 
760 
762 CV_EXPORTS_W void matchTemplate( const Mat& image, const Mat& templ, CV_OUT Mat& result, int method );
763 
765 enum
766 {
771 };
772 
774 enum
775 {
780 };
781 
783 CV_EXPORTS void findContours( Mat& image, CV_OUT vector<vector<Point> >& contours,
784  vector<Vec4i>& hierarchy, int mode,
785  int method, Point offset=Point());
786 
788 CV_EXPORTS void findContours( Mat& image, CV_OUT vector<vector<Point> >& contours,
789  int mode, int method, Point offset=Point());
790 
792 CV_EXPORTS void drawContours( Mat& image, const vector<vector<Point> >& contours,
793  int contourIdx, const Scalar& color,
794  int thickness=1, int lineType=8,
795  const vector<Vec4i>& hierarchy=vector<Vec4i>(),
796  int maxLevel=INT_MAX, Point offset=Point() );
797 
799 CV_EXPORTS void approxPolyDP( const Mat& curve,
800  CV_OUT vector<Point>& approxCurve,
801  double epsilon, bool closed );
803 CV_EXPORTS void approxPolyDP( const Mat& curve,
804  CV_OUT vector<Point2f>& approxCurve,
805  double epsilon, bool closed );
807 CV_EXPORTS_W double arcLength( const Mat& curve, bool closed );
809 CV_EXPORTS_W Rect boundingRect( const Mat& points );
811 CV_EXPORTS_W double contourArea( const Mat& contour, bool oriented=false );
813 CV_EXPORTS_W RotatedRect minAreaRect( const Mat& points );
815 CV_EXPORTS_W void minEnclosingCircle( const Mat& points,
816  Point2f& center, float& radius );
818 CV_EXPORTS_W double matchShapes( const Mat& contour1,
819  const Mat& contour2,
820  int method, double parameter );
822 CV_EXPORTS void convexHull( const Mat& points, CV_OUT vector<int>& hull, bool clockwise=false );
824 CV_EXPORTS void convexHull( const Mat& points, CV_OUT vector<Point>& hull, bool clockwise=false );
826 CV_EXPORTS void convexHull( const Mat& points, CV_OUT vector<Point2f>& hull, bool clockwise=false );
827 
829 CV_EXPORTS_W bool isContourConvex( const Mat& contour );
830 
832 CV_EXPORTS_W RotatedRect fitEllipse( const Mat& points );
833 
835 CV_EXPORTS void fitLine( const Mat& points, CV_OUT Vec4f& line, int distType,
836  double param, double reps, double aeps );
838 CV_EXPORTS void fitLine( const Mat& points, CV_OUT Vec6f& line, int distType,
839  double param, double reps, double aeps );
841 CV_EXPORTS_W double pointPolygonTest( const Mat& contour,
842  Point2f pt, bool measureDist );
843 
845 CV_EXPORTS_W Mat estimateRigidTransform( const Mat& A, const Mat& B,
846  bool fullAffine );
847 
848 }
849 
850 
851 // 2009-01-12, Xavier Delacour <xavier.delacour@gmail.com>
852 
853 struct lsh_hash {
854  int h1, h2;
855 };
856 
858 {
859  virtual ~CvLSHOperations() {}
860 
861  virtual int vector_add(const void* data) = 0;
862  virtual void vector_remove(int i) = 0;
863  virtual const void* vector_lookup(int i) = 0;
864  virtual void vector_reserve(int n) = 0;
865  virtual unsigned int vector_count() = 0;
866 
867  virtual void hash_insert(lsh_hash h, int l, int i) = 0;
868  virtual void hash_remove(lsh_hash h, int l, int i) = 0;
869  virtual int hash_lookup(lsh_hash h, int l, int* ret_i, int ret_i_max) = 0;
870 };
871 
872 #endif /* __cplusplus */
873 
874 #endif
875 
876 /* End of file. */