]> rtime.felk.cvut.cz Git - opencv.git/commitdiff
struct -> class in cxcore.hpp and cv.hpp; some fields made protected; Vec_ -> Vec
authorvp153 <vp153@73c94f0f-984f-4a5f-82bc-2d8db8d8ee08>
Sun, 5 Jul 2009 22:10:47 +0000 (22:10 +0000)
committervp153 <vp153@73c94f0f-984f-4a5f-82bc-2d8db8d8ee08>
Sun, 5 Jul 2009 22:10:47 +0000 (22:10 +0000)
git-svn-id: https://code.ros.org/svn/opencv/trunk@1902 73c94f0f-984f-4a5f-82bc-2d8db8d8ee08

16 files changed:
opencv/include/opencv/cv.hpp
opencv/include/opencv/cvaux.hpp
opencv/include/opencv/cxcore.hpp
opencv/include/opencv/cxmat.hpp
opencv/include/opencv/cxoperations.hpp
opencv/src/cv/cvaccum.cpp
opencv/src/cv/cvcamshift.cpp
opencv/src/cv/cvfilter.cpp
opencv/src/cv/cvhaar.cpp
opencv/src/cxcore/cxarithm.cpp
opencv/src/cxcore/cxcopy.cpp
opencv/src/cxcore/cxmatrix.cpp
opencv/src/cxcore/cxpersistence.cpp
opencv/src/cxcore/cxrand.cpp
opencv/src/cxcore/cxstat.cpp
opencv/src/highgui/loadsave.cpp

index 29a95853413a61525edc7d60daf59ea7d8eee2d0..532cbc0fd77d114e80d2987fb302f627b8ce8554 100644 (file)
@@ -55,8 +55,9 @@ enum { BORDER_REPLICATE=IPL_BORDER_REPLICATE, BORDER_CONSTANT=IPL_BORDER_CONSTAN
 \r
 CV_EXPORTS int borderInterpolate( int p, int len, int borderType );\r
 \r
-struct CV_EXPORTS BaseRowFilter\r
+class CV_EXPORTS BaseRowFilter\r
 {\r
+public:\r
     BaseRowFilter();\r
     virtual ~BaseRowFilter();\r
     virtual void operator()(const uchar* src, uchar* dst,\r
@@ -65,8 +66,9 @@ struct CV_EXPORTS BaseRowFilter
 };\r
 \r
 \r
-struct CV_EXPORTS BaseColumnFilter\r
+class CV_EXPORTS BaseColumnFilter\r
 {\r
+public:\r
     BaseColumnFilter();\r
     virtual ~BaseColumnFilter();\r
     virtual void operator()(const uchar** src, uchar* dst, int dststep,\r
@@ -76,8 +78,9 @@ struct CV_EXPORTS BaseColumnFilter
 };\r
 \r
 \r
-struct CV_EXPORTS BaseFilter\r
+class CV_EXPORTS BaseFilter\r
 {\r
+public:\r
     BaseFilter();\r
     virtual ~BaseFilter();\r
     virtual void operator()(const uchar** src, uchar* dst, int dststep,\r
@@ -88,8 +91,9 @@ struct CV_EXPORTS BaseFilter
 };\r
 \r
 \r
-struct CV_EXPORTS FilterEngine\r
+class CV_EXPORTS FilterEngine\r
 {\r
+public:\r
     FilterEngine();\r
     FilterEngine(const Ptr<BaseFilter>& _filter2D,\r
                  const Ptr<BaseRowFilter>& _rowFilter,\r
@@ -114,7 +118,7 @@ struct CV_EXPORTS FilterEngine
                         const Rect& srcRoi=Rect(0,0,-1,-1),\r
                         Point dstOfs=Point(0,0),\r
                         bool isolated=false);\r
-    bool isSeparable() const { return filter2D.obj == 0; }\r
+    bool isSeparable() const { return (const BaseFilter*)filter2D == 0; }\r
     int remainingInputRows() const;\r
     int remainingOutputRows() const;\r
     \r
@@ -257,7 +261,7 @@ CV_EXPORTS void Laplacian( const Mat& src, Mat& dst, int ddepth,
                            int borderType=BORDER_DEFAULT );\r
 \r
 CV_EXPORTS void Canny( const Mat& image, Mat& edges,\r
-                       double threshold1, double threshol2,\r
+                       double threshold1, double threshold2,\r
                        int apertureSize=3, bool L2gradient=false );\r
 \r
 CV_EXPORTS void cornerMinEigenVal( const Mat& src, Mat& dst,\r
@@ -449,8 +453,9 @@ CV_EXPORTS int floodFill( Mat& image, Mat& mask,
 \r
 CV_EXPORTS void cvtColor( const Mat& src, Mat& dst, int code, int dstCn=0 );\r
 \r
-struct CV_EXPORTS Moments\r
+class CV_EXPORTS Moments\r
 {\r
+public:\r
     Moments();\r
     Moments(double m00, double m10, double m01, double m20, double m11,\r
             double m02, double m30, double m21, double m12, double m03 );\r
@@ -574,11 +579,12 @@ CV_EXPORTS double calcGlobalOrientation( const Mat& orientation, const Mat& mask
 CV_EXPORTS RotatedRect CAMShift( const Mat& probImage, Rect& window,\r
                                  TermCriteria criteria );\r
 \r
-CV_EXPORTS int MeanShift( const Mat& probImage, Rect& window,\r
+CV_EXPORTS int meanShift( const Mat& probImage, Rect& window,\r
                           TermCriteria criteria );\r
 \r
-struct CV_EXPORTS KalmanFilter\r
+class CV_EXPORTS KalmanFilter\r
 {\r
+public:\r
     KalmanFilter();\r
     KalmanFilter(int dynamParams, int measureParams, int controlParams=0);\r
     void init(int dynamParams, int measureParams, int controlParams=0);\r
@@ -615,8 +621,9 @@ struct CV_EXPORTS KalmanFilter
 template<> inline void Ptr<CvHaarClassifierCascade>::delete_obj()\r
 { cvReleaseHaarClassifierCascade(&obj); }\r
 \r
-struct CV_EXPORTS HaarClassifierCascade\r
+class CV_EXPORTS HaarClassifierCascade\r
 {\r
+public:\r
     enum { DO_CANNY_PRUNING = CV_HAAR_DO_CANNY_PRUNING,\r
            SCALE_IMAGE = CV_HAAR_SCALE_IMAGE,\r
            FIND_BIGGEST_OBJECT = CV_HAAR_FIND_BIGGEST_OBJECT,\r
@@ -812,7 +819,7 @@ template<> inline void Ptr<CvStereoBMState>::delete_obj()
 { cvReleaseStereoBMState(&obj); }\r
 \r
 // Block matching stereo correspondence algorithm\r
-struct CV_EXPORTS StereoBM\r
+class CV_EXPORTS StereoBM\r
 {\r
     enum { NORMALIZED_RESPONSE = CV_STEREO_BM_NORMALIZED_RESPONSE,\r
         BASIC_PRESET=CV_STEREO_BM_BASIC,\r
@@ -831,15 +838,17 @@ CV_EXPORTS void reprojectImageTo3D( const Mat& disparity,
                                     Mat& _3dImage, const Mat& Q,\r
                                     bool handleMissingValues=false );\r
 \r
-struct CV_EXPORTS SURFKeypoint : public CvSURFPoint\r
+class CV_EXPORTS SURFKeypoint : public CvSURFPoint\r
 {\r
+public:\r
     SURFKeypoint() { pt=Point2f(); laplacian=size=0; dir=hessian=0; }\r
     SURFKeypoint(Point2f _pt, int _laplacian, int _size, float _dir=0.f, float _hessian=0.f)\r
     { pt = _pt; laplacian = _laplacian; size = _size; dir = _dir; hessian = _hessian; }\r
 };\r
 \r
-struct CV_EXPORTS SURF : public CvSURFParams\r
+class CV_EXPORTS SURF : public CvSURFParams\r
 {\r
+public:\r
     SURF();\r
     SURF(double _hessianThreshold, bool _extended=false);\r
 \r
@@ -853,8 +862,9 @@ struct CV_EXPORTS SURF : public CvSURFParams
 };\r
 \r
 \r
-struct CV_EXPORTS MSER : public CvMSERParams\r
+class CV_EXPORTS MSER : public CvMSERParams\r
 {\r
+public:\r
     MSER();\r
     MSER( int _delta, int _min_area, int _max_area,\r
           float _max_variation, float _min_diversity,\r
@@ -863,8 +873,9 @@ struct CV_EXPORTS MSER : public CvMSERParams
     Vector<Vector<Point> > operator()(Mat& image, const Mat& mask) const;\r
 };\r
 \r
-struct CV_EXPORTS StarKeypoint : public CvStarKeypoint\r
+class CV_EXPORTS StarKeypoint : public CvStarKeypoint\r
 {\r
+public:\r
     StarKeypoint() { pt = Point(); size = 0; response = 0.f; }\r
     StarKeypoint(Point _pt, int _size, float _response)\r
     {\r
@@ -872,8 +883,9 @@ struct CV_EXPORTS StarKeypoint : public CvStarKeypoint
     }\r
 };\r
 \r
-struct CV_EXPORTS StarDetector : CvStarDetectorParams\r
+class CV_EXPORTS StarDetector : CvStarDetectorParams\r
 {\r
+public:\r
     StarDetector();\r
     StarDetector(int _maxSize, int _responseThreshold,\r
                  int _lineThresholdProjected,\r
@@ -887,8 +899,9 @@ struct CV_EXPORTS StarDetector : CvStarDetectorParams
 \r
 //////////////////////////////////////////////////////////////////////////////////////////\r
 \r
-struct CV_EXPORTS CvLevMarq\r
+class CV_EXPORTS CvLevMarq\r
 {\r
+public:\r
     CvLevMarq();\r
     CvLevMarq( int nparams, int nerrs, CvTermCriteria criteria=\r
         cvTermCriteria(CV_TERMCRIT_EPS+CV_TERMCRIT_ITER,30,DBL_EPSILON),\r
@@ -929,7 +942,8 @@ struct lsh_hash {
   int h1, h2;\r
 };\r
 \r
-struct CvLSHOperations {\r
+struct CvLSHOperations\r
+{\r
   virtual ~CvLSHOperations() {}\r
 \r
   virtual int vector_add(const void* data) = 0;\r
index e584d537af4cd0ad99aa745e3eb77369629a0b6a..2f7443e42a713c0544bfe3045ade8ccb3a3ba5ef 100644 (file)
@@ -395,6 +395,7 @@ CV_EXPORTS void computeSpinImages( const OctTree& octtree,
 
 struct CV_EXPORTS HOGDescriptor
 {
+public:
     enum { L2Hys=0 };
 
     HOGDescriptor() : winSize(64,128), blockSize(16,16), blockStride(8,8),
index 70c28cc94f212c485fd96a46fd17bb2fe294a9eb..80962eb6dbe9b14cbed7e1fcae1ab5a4727bd327 100644 (file)
-/*M///////////////////////////////////////////////////////////////////////////////////////
-//
-//  IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.
-//
-//  By downloading, copying, installing or using the software you agree to this license.
-//  If you do not agree to this license, do not download, install,
-//  copy or use the software.
-//
-//
-//                           License Agreement
-//                For Open Source Computer Vision Library
-//
-// Copyright (C) 2000-2008, Intel Corporation, all rights reserved.
-// Copyright (C) 2009, Willow Garage Inc., all rights reserved.
-// Third party copyrights are property of their respective owners.
-//
-// Redistribution and use in source and binary forms, with or without modification,
-// are permitted provided that the following conditions are met:
-//
-//   * Redistribution's of source code must retain the above copyright notice,
-//     this list of conditions and the following disclaimer.
-//
-//   * Redistribution's in binary form must reproduce the above copyright notice,
-//     this list of conditions and the following disclaimer in the documentation
-//     and/or other materials provided with the distribution.
-//
-//   * The name of the copyright holders may not be used to endorse or promote products
-//     derived from this software without specific prior written permission.
-//
-// This software is provided by the copyright holders and contributors "as is" and
-// any express or implied warranties, including, but not limited to, the implied
-// warranties of merchantability and fitness for a particular purpose are disclaimed.
-// In no event shall the Intel Corporation or contributors be liable for any direct,
-// indirect, incidental, special, exemplary, or consequential damages
-// (including, but not limited to, procurement of substitute goods or services;
-// loss of use, data, or profits; or business interruption) however caused
-// and on any theory of liability, whether in contract, strict liability,
-// or tort (including negligence or otherwise) arising in any way out of
-// the use of this software, even if advised of the possibility of such damage.
-//
-//M*/
-
-#ifndef _CXCORE_HPP_
-#define _CXCORE_HPP_
-
-#include "cxmisc.h"
-
-#ifdef __cplusplus
-
-#ifndef SKIP_INCLUDES
-#include <algorithm>
-#include <complex>
-#include <map>
-#include <new>
-#include <string>
-#include <vector>
-#endif // SKIP_INCLUDES
-
-namespace cv {
-
-template<typename _Tp> struct CV_EXPORTS Size_;
-template<typename _Tp> struct CV_EXPORTS Point_;
-template<typename _Tp> struct CV_EXPORTS Rect_;
-
-typedef std::string String;
-typedef std::basic_string<wchar_t> WString;
-
-CV_EXPORTS String fromUtf16(const WString& str);
-CV_EXPORTS WString toUtf16(const String& str);
-
-struct CV_EXPORTS Exception
-{
-    Exception() { code = 0; line = 0; }
-    Exception(int _code, const String& _err, const String& _func, const String& _file, int _line)
-        : code(_code), err(_err), func(_func), file(_file), line(_line) {}
-    Exception(const Exception& exc)
-        : code(exc.code), err(exc.err), func(exc.func), file(exc.file), line(exc.line) {}
-    Exception& operator = (const Exception& exc)
-    {
-        if( this != &exc )
-        {
-            code = exc.code; err = exc.err; func = exc.func; file = exc.file; line = exc.line;
-        }
-        return *this;
-    }
-
-    int code;
-    String err;
-    String func;
-    String file;
-    int line;
-};
-
-CV_EXPORTS String format( const char* fmt, ... );
-CV_EXPORTS void error( const Exception& exc );
-
-#ifdef __GNUC__
-#define CV_Error( code, msg ) cv::error( cv::Exception(code, msg, __func__, __FILE__, __LINE__) )
-#define CV_Error_( code, args ) cv::error( cv::Exception(code, cv::format args, __func__, __FILE__, __LINE__) )
-#define CV_Assert( expr ) { if(!(expr)) cv::error( cv::Exception(CV_StsAssert, #expr, __func__, __FILE__, __LINE__) ); }
-#else
-#define CV_Error( code, msg ) cv::error( cv::Exception(code, msg, "", __FILE__, __LINE__) )
-#define CV_Error_( code, args ) cv::error( cv::Exception(code, cv::format args, "", __FILE__, __LINE__) )
-#define CV_Assert( expr ) { if(!(expr)) cv::error( cv::Exception(CV_StsAssert, #expr, "", __FILE__, __LINE__) ); }
-#endif
-    
-#ifdef _DEBUG
-#define CV_DbgAssert(expr) CV_Assert(expr)
-#else
-#define CV_DbgAssert(expr)
-#endif
-
-CV_EXPORTS void setNumThreads(int);
-CV_EXPORTS int getNumThreads();
-CV_EXPORTS int getThreadNum();
-
-CV_EXPORTS int64 getTickCount();
-CV_EXPORTS double getTickFrequency();
-
-CV_EXPORTS void* fastMalloc(size_t);
-CV_EXPORTS void fastFree(void* ptr);
-
-template<typename _Tp> static inline _Tp* fastMalloc_(size_t n)
-{
-    _Tp* ptr = (_Tp*)fastMalloc(n*sizeof(ptr[0]));
-    ::new(ptr) _Tp[n];
-    return ptr;
-}
-
-template<typename _Tp> static inline void fastFree_(_Tp* ptr, size_t n)
-{
-    for( size_t i = 0; i < n; i++ ) (ptr+i)->~_Tp();
-    fastFree(ptr);
-}
-
-template<typename _Tp> static inline _Tp* alignPtr(_Tp* ptr, int n=(int)sizeof(_Tp))
-{
-    return (_Tp*)(((size_t)ptr + n-1) & -n);
-}
-
-static inline size_t alignSize(size_t sz, int n)
-{
-    return (sz + n-1) & -n;
-}
-
-CV_EXPORTS void setUseOptimized(bool);
-CV_EXPORTS bool useOptimized();
-
-template<typename _Tp> class CV_EXPORTS Allocator
-{
-public: 
-    typedef _Tp value_type;
-    typedef value_type* pointer;
-    typedef const value_type* const_pointer;
-    typedef value_type& reference;
-    typedef const value_type& const_reference;
-    typedef size_t size_type;
-    typedef ptrdiff_t difference_type;
-    template<typename U> struct rebind { typedef Allocator<U> other; };
-
-public : 
-    explicit Allocator() {}
-    ~Allocator() {}
-    explicit Allocator(Allocator const&) {}
-    template<typename U>
-    explicit Allocator(Allocator<U> const&) {}
-
-    // address
-    pointer address(reference r) { return &r; }
-    const_pointer address(const_reference r) { return &r; }
-
-    pointer allocate(size_type count, const void* =0)
-    { return reinterpret_cast<pointer>(fastMalloc(count * sizeof (_Tp))); }
-
-    void deallocate(pointer p, size_type) {fastFree(p); }
-
-    size_type max_size() const
-    { return max(static_cast<_Tp>(-1)/sizeof(_Tp), 1); }
-
-    void construct(pointer p, const _Tp& v) { new(static_cast<void*>(p)) _Tp(v); }
-    void destroy(pointer p) { p->~_Tp(); }
-};
-
-/////////////////////// Vec_ (used as element of multi-channel images ///////////////////// 
-
-template<typename _Tp> struct CV_EXPORTS DataDepth { enum { value = -1, fmt=(int)'\0' }; };
-
-template<> struct DataDepth<bool> { enum { value = CV_8U, fmt=(int)'u' }; };
-template<> struct DataDepth<uchar> { enum { value = CV_8U, fmt=(int)'u' }; };
-template<> struct DataDepth<schar> { enum { value = CV_8S, fmt=(int)'c' }; };
-template<> struct DataDepth<ushort> { enum { value = CV_16U, fmt=(int)'w' }; };
-template<> struct DataDepth<short> { enum { value = CV_16S, fmt=(int)'s' }; };
-template<> struct DataDepth<int> { enum { value = CV_32S, fmt=(int)'i' }; };
-template<> struct DataDepth<float> { enum { value = CV_32F, fmt=(int)'f' }; };
-template<> struct DataDepth<double> { enum { value = CV_64F, fmt=(int)'d' }; };
-template<typename _Tp> struct DataDepth<_Tp*> { enum { value = CV_USRTYPE1, fmt=(int)'r' }; };
-
-template<typename _Tp, int cn> struct CV_EXPORTS Vec_
-{
-    typedef _Tp value_type;
-    enum { depth = DataDepth<_Tp>::value, channels = cn, type = CV_MAKETYPE(depth, channels) };
-    
-    Vec_();
-    Vec_(_Tp v0);
-    Vec_(_Tp v0, _Tp v1);
-    Vec_(_Tp v0, _Tp v1, _Tp v2);
-    Vec_(_Tp v0, _Tp v1, _Tp v2, _Tp v3);
-    Vec_(const Vec_<_Tp, cn>& v);
-    static Vec_ all(_Tp alpha);
-    _Tp dot(const Vec_& v) const;
-    double ddot(const Vec_& v) const;
-    Vec_ cross(const Vec_& v) const;
-    template<typename T2> operator Vec_<T2, cn>() const;
-    operator CvScalar() const;
-    _Tp operator [](int i) const;
-    _Tp& operator[](int i);
-
-    _Tp val[cn];
-};
-
-typedef Vec_<uchar, 2> Vec2b;
-typedef Vec_<uchar, 3> Vec3b;
-typedef Vec_<uchar, 4> Vec4b;
-
-typedef Vec_<short, 2> Vec2s;
-typedef Vec_<short, 3> Vec3s;
-typedef Vec_<short, 4> Vec4s;
-
-typedef Vec_<int, 2> Vec2i;
-typedef Vec_<int, 3> Vec3i;
-typedef Vec_<int, 4> Vec4i;
-
-typedef Vec_<float, 2> Vec2f;
-typedef Vec_<float, 3> Vec3f;
-typedef Vec_<float, 4> Vec4f;
-typedef Vec_<float, 6> Vec6f;
-
-typedef Vec_<double, 2> Vec2d;
-typedef Vec_<double, 3> Vec3d;
-typedef Vec_<double, 4> Vec4d;
-typedef Vec_<double, 6> Vec6d;
-
-//////////////////////////////// Complex //////////////////////////////
-
-template<typename _Tp> struct CV_EXPORTS Complex
-{
-    Complex();
-    Complex( _Tp _re, _Tp _im=0 );
-    template<typename T2> operator Complex<T2>() const;
-    Complex conj() const;
-
-    _Tp re, im;
-};
-
-typedef Complex<float> Complexf;
-typedef Complex<double> Complexd;
-
-//////////////////////////////// Point_ ////////////////////////////////
-
-template<typename _Tp> struct CV_EXPORTS Point_
-{
-    typedef _Tp value_type;
-    
-    Point_();
-    Point_(_Tp _x, _Tp _y);
-    Point_(const Point_& pt);
-    Point_(const CvPoint& pt);
-    Point_(const CvPoint2D32f& pt);
-    Point_(const Size_<_Tp>& sz);
-    Point_& operator = (const Point_& pt);
-    operator Point_<int>() const;
-    operator Point_<float>() const;
-    operator Point_<double>() const;
-    operator CvPoint() const;
-    operator CvPoint2D32f() const;
-
-    _Tp dot(const Point_& pt) const;
-    double ddot(const Point_& pt) const;
-    bool inside(const Rect_<_Tp>& r) const;
-    
-    _Tp x, y;
-};
-
-template<typename _Tp> struct CV_EXPORTS Point3_
-{
-    typedef _Tp value_type;
-    
-    Point3_();
-    Point3_(_Tp _x, _Tp _y, _Tp _z);
-    Point3_(const Point3_& pt);
-       Point3_(const Point_<_Tp>& pt);
-    Point3_(const CvPoint3D32f& pt);
-    Point3_(const Vec_<_Tp, 3>& t);
-    Point3_& operator = (const Point3_& pt);
-    operator Point3_<int>() const;
-    operator Point3_<float>() const;
-    operator Point3_<double>() const;
-    operator CvPoint3D32f() const;
-
-    _Tp dot(const Point3_& pt) const;
-    double ddot(const Point3_& pt) const;
-    
-    _Tp x, y, z;
-};
-
-//////////////////////////////// Size_ ////////////////////////////////
-
-template<typename _Tp> struct CV_EXPORTS Size_
-{
-    typedef _Tp value_type;
-    
-    Size_();
-    Size_(_Tp _width, _Tp _height);
-    Size_(const Size_& sz);
-    Size_(const CvSize& sz);
-    Size_(const CvSize2D32f& sz);
-    Size_(const Point_<_Tp>& pt);
-    Size_& operator = (const Size_& sz);
-    _Tp area() const;
-
-    operator Size_<int>() const;
-    operator Size_<float>() const;
-    operator Size_<double>() const;
-    operator CvSize() const;
-    operator CvSize2D32f() const;
-
-    _Tp width, height;
-};
-
-//////////////////////////////// Rect_ ////////////////////////////////
-
-template<typename _Tp> struct CV_EXPORTS Rect_
-{
-    typedef _Tp value_type;
-    
-    Rect_();
-    Rect_(_Tp _x, _Tp _y, _Tp _width, _Tp _height);
-    Rect_(const Rect_& r);
-    Rect_(const CvRect& r);
-    Rect_(const Point_<_Tp>& org, const Size_<_Tp>& sz);
-    Rect_(const Point_<_Tp>& pt1, const Point_<_Tp>& pt2);
-    Rect_& operator = ( const Rect_& r );
-    Point_<_Tp> tl() const;
-    Point_<_Tp> br() const;
-    
-    Size_<_Tp> size() const;
-    _Tp area() const;
-
-    operator Rect_<int>() const;
-    operator Rect_<float>() const;
-    operator Rect_<double>() const;
-    operator CvRect() const;
-
-    bool contains(const Point_<_Tp>& pt) const;
-
-    _Tp x, y, width, height;
-};
-
-typedef Point_<int> Point2i;
-typedef Point2i Point;
-typedef Size_<int> Size2i;
-typedef Size2i Size;
-typedef Rect_<int> Rect;
-typedef Point_<float> Point2f;
-typedef Point_<double> Point2d;
-typedef Size_<float> Size2f;
-typedef Point3_<int> Point3i;
-typedef Point3_<float> Point3f;
-typedef Point3_<double> Point3d;
-
-struct CV_EXPORTS RotatedRect
-{
-    RotatedRect();
-    RotatedRect(const Point2f& _center, const Size2f& _size, float _angle);
-    RotatedRect(const CvBox2D& box);
-    Rect boundingRect() const;
-    operator CvBox2D() const;
-    Point2f center;
-    Size2f size;
-    float angle;
-};
-
-//////////////////////////////// Scalar_ ///////////////////////////////
-
-template<typename _Tp> struct CV_EXPORTS Scalar_ : Vec_<_Tp, 4>
-{
-    Scalar_();
-    Scalar_(_Tp v0, _Tp v1, _Tp v2=0, _Tp v3=0);
-    Scalar_(const CvScalar& s);
-    Scalar_(_Tp v0);
-    static Scalar_<_Tp> all(_Tp v0);
-    operator CvScalar() const;
-
-    template<typename T2> operator Scalar_<T2>() const;
-
-    Scalar_<_Tp> mul(const Scalar_<_Tp>& t, double scale=1 ) const;
-    template<typename T2> void convertTo(T2* buf, int channels, int unroll_to=0) const;
-};
-
-typedef Scalar_<double> Scalar;
-
-//////////////////////////////// Range /////////////////////////////////
-
-struct CV_EXPORTS Range
-{
-    Range();
-    Range(int _start, int _end);
-    Range(const CvSlice& slice);
-    int size() const;
-    bool empty() const;
-    static Range all();
-    operator CvSlice() const;
-
-    int start, end;
-};
-
-/////////////////////////////// DataType ////////////////////////////////
-
-template<typename _Tp> struct DataType
-{
-    typedef _Tp value_type;
-    typedef value_type work_type;
-    typedef value_type channel_type;
-    enum { depth = DataDepth<channel_type>::value, channels = 1,
-           fmt=DataDepth<channel_type>::fmt,
-           type = CV_MAKETYPE(depth, channels) };
-};
-
-template<> struct DataType<bool>
-{
-    typedef bool value_type;
-    typedef int work_type;
-    typedef value_type channel_type;
-    enum { depth = DataDepth<channel_type>::value, channels = 1,
-           fmt=DataDepth<channel_type>::fmt,
-           type = CV_MAKETYPE(depth, channels) };
-};
-
-template<> struct DataType<uchar>
-{
-    typedef uchar value_type;
-    typedef int work_type;
-    typedef value_type channel_type;
-    enum { depth = DataDepth<channel_type>::value, channels = 1,
-           fmt=DataDepth<channel_type>::fmt,
-           type = CV_MAKETYPE(depth, channels) };
-};
-
-template<> struct DataType<schar>
-{
-    typedef schar value_type;
-    typedef int work_type;
-    typedef value_type channel_type;
-    enum { depth = DataDepth<channel_type>::value, channels = 1,
-           fmt=DataDepth<channel_type>::fmt,
-           type = CV_MAKETYPE(depth, channels) };
-};
-
-template<> struct DataType<ushort>
-{
-    typedef ushort value_type;
-    typedef int work_type;
-    typedef value_type channel_type;
-    enum { depth = DataDepth<channel_type>::value, channels = 1,
-           fmt=DataDepth<channel_type>::fmt,
-           type = CV_MAKETYPE(depth, channels) };
-};
-
-template<> struct DataType<short>
-{
-    typedef short value_type;
-    typedef int work_type;
-    typedef value_type channel_type;
-    enum { depth = DataDepth<channel_type>::value, channels = 1,
-           fmt=DataDepth<channel_type>::fmt,
-           type = CV_MAKETYPE(depth, channels) };
-};
-
-template<> struct DataType<int>
-{
-    typedef int value_type;
-    typedef value_type work_type;
-    typedef value_type channel_type;
-    enum { depth = DataDepth<channel_type>::value, channels = 1,
-           fmt=DataDepth<channel_type>::fmt,
-           type = CV_MAKETYPE(depth, channels) };
-};
-
-template<> struct DataType<float>
-{
-    typedef float value_type;
-    typedef value_type work_type;
-    typedef value_type channel_type;
-    enum { depth = DataDepth<channel_type>::value, channels = 1,
-           fmt=DataDepth<channel_type>::fmt,
-           type = CV_MAKETYPE(depth, channels) };
-};
-
-template<> struct DataType<double>
-{
-    typedef double value_type;
-    typedef value_type work_type;
-    typedef value_type channel_type;
-    enum { depth = DataDepth<channel_type>::value, channels = 1,
-           fmt=DataDepth<channel_type>::fmt,
-           type = CV_MAKETYPE(depth, channels) };
-};
-
-template<typename _Tp, int cn> struct DataType<Vec_<_Tp, cn> >
-{
-    typedef Vec_<_Tp, cn> value_type;
-    typedef Vec_<typename DataType<_Tp>::work_type, cn> work_type;
-    typedef _Tp channel_type;
-    enum { depth = DataDepth<channel_type>::value, channels = cn,
-           fmt = ((channels-1)<<8) + DataDepth<channel_type>::fmt,
-           type = CV_MAKETYPE(depth, channels) };
-};
-
-template<typename _Tp> struct DataType<std::complex<_Tp> >
-{
-    typedef std::complex<_Tp> value_type;
-    typedef value_type work_type;
-    typedef _Tp channel_type;
-    enum { depth = DataDepth<channel_type>::value, channels = 2,
-           fmt = ((channels-1)<<8) + DataDepth<channel_type>::fmt,
-           type = CV_MAKETYPE(depth, channels) };
-};
-
-template<typename _Tp> struct DataType<Complex<_Tp> >
-{
-    typedef Complex<_Tp> value_type;
-    typedef value_type work_type;
-    typedef _Tp channel_type;
-    enum { depth = DataDepth<channel_type>::value, channels = 2,
-           fmt = ((channels-1)<<8) + DataDepth<channel_type>::fmt,
-           type = CV_MAKETYPE(depth, channels) };
-};
-
-template<typename _Tp> struct DataType<Point_<_Tp> >
-{
-    typedef Point_<_Tp> value_type;
-    typedef Point_<typename DataType<_Tp>::work_type> work_type;
-    typedef _Tp channel_type;
-    enum { depth = DataDepth<channel_type>::value, channels = 2,
-           fmt = ((channels-1)<<8) + DataDepth<channel_type>::fmt,
-           type = CV_MAKETYPE(depth, channels) };
-};
-
-template<typename _Tp> struct DataType<Point3_<_Tp> >
-{
-    typedef Point3_<_Tp> value_type;
-    typedef Point3_<typename DataType<_Tp>::work_type> work_type;
-    typedef _Tp channel_type;
-    enum { depth = DataDepth<channel_type>::value, channels = 3,
-           fmt = ((channels-1)<<8) + DataDepth<channel_type>::fmt,
-           type = CV_MAKETYPE(depth, channels) };
-};
-
-template<typename _Tp> struct DataType<Size_<_Tp> >
-{
-    typedef Size_<_Tp> value_type;
-    typedef Size_<typename DataType<_Tp>::work_type> work_type;
-    typedef _Tp channel_type;
-    enum { depth = DataDepth<channel_type>::value, channels = 2,
-           fmt = ((channels-1)<<8) + DataDepth<channel_type>::fmt,
-           type = CV_MAKETYPE(depth, channels) };
-};
-
-template<typename _Tp> struct DataType<Rect_<_Tp> >
-{
-    typedef Rect_<_Tp> value_type;
-    typedef Rect_<typename DataType<_Tp>::work_type> work_type;
-    typedef _Tp channel_type;
-    enum { depth = DataDepth<channel_type>::value, channels = 4,
-           fmt = ((channels-1)<<8) + DataDepth<channel_type>::fmt,
-           type = CV_MAKETYPE(depth, channels) };
-};
-
-template<typename _Tp> struct DataType<Scalar_<_Tp> >
-{
-    typedef Scalar_<_Tp> value_type;
-    typedef Scalar_<typename DataType<_Tp>::work_type> work_type;
-    typedef _Tp channel_type;
-    enum { depth = DataDepth<channel_type>::value, channels = 4,
-           fmt = ((channels-1)<<8) + DataDepth<channel_type>::fmt,
-           type = CV_MAKETYPE(depth, channels) };
-};
-
-template<> struct DataType<Range>
-{
-    typedef Range value_type;
-    typedef value_type work_type;
-    typedef int channel_type;
-    enum { depth = DataDepth<channel_type>::value, channels = 2,
-           fmt = ((channels-1)<<8) + DataDepth<channel_type>::fmt,
-           type = CV_MAKETYPE(depth, channels) };
-};
-
-
-//////////////////////////////// Vector ////////////////////////////////
-
-// template vector class. It is similar to STL's vector,
-// with a few important differences:
-//   1) it can be created on top of user-allocated data w/o copying it
-//   2) Vector b = a means copying the header,
-//      not the underlying data (use clone() to make a deep copy)
-template <typename _Tp> class CV_EXPORTS Vector
-{
-public:
-    typedef _Tp value_type;
-    typedef _Tp* iterator;
-    typedef const _Tp* const_iterator;
-    typedef _Tp& reference;
-    typedef const _Tp& const_reference;
-
-    struct CV_EXPORTS Hdr
-    {
-        Hdr() : data(0), datastart(0), refcount(0), size(0), capacity(0) {};
-        _Tp* data;
-        _Tp* datastart;
-        int* refcount;
-        size_t size;
-        size_t capacity;
-    };
-
-    Vector();
-    Vector(size_t _size);
-    Vector(size_t _size, const _Tp& val);
-    Vector(_Tp* _data, size_t _size, bool _copyData=false);
-    Vector(const std::vector<_Tp>& vec, bool _copyData=false);
-    Vector(const Vector& d);
-    Vector(const Vector& d, const Range& r);
-
-    Vector<_Tp>& operator = (const Vector& d);
-    ~Vector();
-    Vector clone() const;
-    void copyTo(Vector<_Tp>& vec) const;
-    void copyTo(std::vector<_Tp>& vec) const;
-    operator CvMat() const;
-    
-    _Tp& operator [] (size_t i);
-    const _Tp& operator [] (size_t i) const;
-    _Tp& operator [] (int i);
-    const _Tp& operator [] (int i) const;
-    Vector operator() (const Range& r) const;
-    _Tp& back();
-    const _Tp& back() const;
-    _Tp& front();
-    const _Tp& front() const;
-
-    _Tp* begin();
-    _Tp* end();
-    const _Tp* begin() const;
-    const _Tp* end() const;
-
-    void addref();
-    void release();
-    void set(_Tp* _data, size_t _size, bool _copyData=false);
-
-    void reserve(size_t newCapacity);
-    void resize(size_t newSize);
-    Vector<_Tp>& push_back(const _Tp& elem);
-    Vector<_Tp>& pop_back();
-    size_t size() const;
-    size_t capacity() const;
-    bool empty() const;
-    void clear();
-    int type() const;
-
-protected:
-    Hdr hdr;
-};
-
-//////////////////// Generic ref-cointing pointer class for C/C++ objects ////////////////////////
-
-template<typename _Tp> struct CV_EXPORTS Ptr
-{
-    Ptr();
-    Ptr(_Tp* _obj);
-    ~Ptr();
-    Ptr(const Ptr& ptr);
-    Ptr& operator = (const Ptr& ptr);
-    void addref();
-    void release();
-    void delete_obj();
-
-    _Tp* operator -> ();
-    const _Tp* operator -> () const;
-
-    operator _Tp* ();
-    operator const _Tp*() const;
-
-    _Tp* obj;
-    int* refcount;
-};
-
-//////////////////////////////// Mat ////////////////////////////////
-
-struct Mat;
-template<typename M> struct CV_EXPORTS MatExpr_Base_;
-typedef MatExpr_Base_<Mat> MatExpr_Base;
-template<typename E, typename M> struct MatExpr_;
-template<typename A1, typename M, typename Op> struct MatExpr_Op1_;
-template<typename A1, typename A2, typename M, typename Op> struct MatExpr_Op2_;
-template<typename A1, typename A2, typename A3, typename M, typename Op> struct MatExpr_Op3_;
-template<typename A1, typename A2, typename A3, typename A4,
-        typename M, typename Op> struct MatExpr_Op4_;
-template<typename A1, typename A2, typename A3, typename A4,
-        typename A5, typename M, typename Op> struct MatExpr_Op5_;
-template<typename M> struct CV_EXPORTS MatOp_DivRS_;
-template<typename M> struct CV_EXPORTS MatOp_Inv_;
-template<typename M> struct CV_EXPORTS MatOp_MulDiv_;
-template<typename M> struct CV_EXPORTS MatOp_Repeat_;
-template<typename M> struct CV_EXPORTS MatOp_Set_;
-template<typename M> struct CV_EXPORTS MatOp_Scale_;
-template<typename M> struct CV_EXPORTS MatOp_T_;
-
-struct Mat;
-
-typedef MatExpr_<MatExpr_Op4_<Size, int, Scalar,
-    int, Mat, MatOp_Set_<Mat> >, Mat> MatExpr_Initializer;
-
-template<typename _Tp> struct MatIterator_;
-template<typename _Tp> struct MatConstIterator_;
-
-enum { MAGIC_MASK=0xFFFF0000, TYPE_MASK=0x00000FFF, DEPTH_MASK=7 };
-
-static inline size_t getElemSize(int type) { return CV_ELEM_SIZE(type); }
-
-// matrix decomposition types
-enum { DECOMP_LU=0, DECOMP_SVD=1, DECOMP_EIG=2, DECOMP_CHOLESKY=3, DECOMP_QR=4, DECOMP_NORMAL=16 };
-enum { NORM_INF=1, NORM_L1=2, NORM_L2=4, NORM_TYPE_MASK=7, NORM_RELATIVE=8};
-enum { CMP_EQ=0, CMP_GT=1, CMP_GE=2, CMP_LT=3, CMP_LE=4, CMP_NE=5 };
-enum { GEMM_1_T=1, GEMM_2_T=2, GEMM_3_T=4 };
-enum { DFT_INVERSE=1, DFT_SCALE=2, DFT_ROWS=4, DFT_COMPLEX_OUTPUT=16, DFT_REAL_OUTPUT=32,
-    DCT_INVERSE = DFT_INVERSE, DCT_ROWS=DFT_ROWS };
-
-struct CV_EXPORTS Mat
-{
-    Mat();
-    Mat(int _rows, int _cols, int _type);
-    Mat(int _rows, int _cols, int _type, const Scalar& _s);
-    Mat(Size _size, int _type);
-    Mat(const Mat& m);
-    Mat(int _rows, int _cols, int _type, void* _data, size_t _step=AUTO_STEP);
-    Mat(Size _size, int _type, void* _data, size_t _step=AUTO_STEP);
-    Mat(const Mat& m, const Range& rowRange, const Range& colRange);
-    Mat(const Mat& m, const Rect& roi);
-    Mat(const CvMat* m, bool copyData=false);
-    Mat(const IplImage* img, bool copyData=false);
-    Mat( const MatExpr_Base& expr );
-    ~Mat();
-    Mat& operator = (const Mat& m);
-    Mat& operator = (const MatExpr_Base& expr);
-
-    operator MatExpr_<Mat, Mat>() const;
-
-    Mat row(int y) const;
-    Mat col(int x) const;
-    Mat rowRange(int startrow, int endrow) const;
-    Mat rowRange(const Range& r) const;
-    Mat colRange(int startcol, int endcol) const;
-    Mat colRange(const Range& r) const;
-    Mat diag(int d=0) const;
-    static Mat diag(const Mat& d);
-
-    Mat clone() const;
-    void copyTo( Mat& m ) const;
-    void copyTo( Mat& m, const Mat& mask ) const;
-    void convertTo( Mat& m, int rtype, double alpha=1, double beta=0 ) const;
-
-    void assignTo( Mat& m, int type=-1 ) const;
-    Mat& operator = (const Scalar& s);
-    Mat& setTo(const Scalar& s, const Mat& mask=Mat());
-    Mat reshape(int _cn, int _rows=0) const;
-
-    MatExpr_<MatExpr_Op2_<Mat, double, Mat, MatOp_T_<Mat> >, Mat>
-    t() const;
-    MatExpr_<MatExpr_Op2_<Mat, int, Mat, MatOp_Inv_<Mat> >, Mat>
-        inv(int method=DECOMP_LU) const;
-    MatExpr_<MatExpr_Op4_<Mat, Mat, double, char, Mat, MatOp_MulDiv_<Mat> >, Mat>
-    mul(const Mat& m, double scale=1) const;
-    MatExpr_<MatExpr_Op4_<Mat, Mat, double, char, Mat, MatOp_MulDiv_<Mat> >, Mat>
-    mul(const MatExpr_<MatExpr_Op2_<Mat, double, Mat, MatOp_Scale_<Mat> >, Mat>& m, double scale=1) const;
-    MatExpr_<MatExpr_Op4_<Mat, Mat, double, char, Mat, MatOp_MulDiv_<Mat> >, Mat>    
-    mul(const MatExpr_<MatExpr_Op2_<Mat, double, Mat, MatOp_DivRS_<Mat> >, Mat>& m, double scale=1) const;
-
-    Mat cross(const Mat& m) const;
-    double dot(const Mat& m) const;
-
-    static MatExpr_Initializer zeros(int rows, int cols, int type);
-    static MatExpr_Initializer zeros(Size size, int type);
-    static MatExpr_Initializer ones(int rows, int cols, int type);
-    static MatExpr_Initializer ones(Size size, int type);
-    static MatExpr_Initializer eye(int rows, int cols, int type);
-    static MatExpr_Initializer eye(Size size, int type);
-
-    void create(int _rows, int _cols, int _type);
-    void create(Size _size, int _type);
-    void addref();
-    void release();
-
-    void locateROI( Size& wholeSize, Point& ofs ) const;
-    Mat& adjustROI( int dtop, int dbottom, int dleft, int dright );
-    Mat operator()( Range rowRange, Range colRange ) const;
-    Mat operator()( const Rect& roi ) const;
-
-    operator CvMat() const;
-    operator IplImage() const;
-    bool isContinuous() const;
-    size_t elemSize() const;
-    size_t elemSize1() const;
-    int type() const;
-    int depth() const;
-    int channels() const;
-    size_t step1() const;
-    Size size() const;
-
-    uchar* ptr(int y=0);
-    const uchar* ptr(int y=0) const;
-
-    template<typename _Tp> _Tp* ptr(int y=0);
-    template<typename _Tp> const _Tp* ptr(int y=0) const;
-
-    enum { MAGIC_VAL=0x42FF0000, AUTO_STEP=0, CONTINUOUS_FLAG=CV_MAT_CONT_FLAG };
-
-    int flags;
-    int rows, cols;
-    size_t step;
-    uchar* data;
-    int* refcount;
-
-    uchar* datastart;
-    uchar* dataend;
-};
-
-
-// Multiply-with-Carry RNG
-struct CV_EXPORTS RNG
-{
-    enum { A=4164903690U, UNIFORM=0, NORMAL=1 };
-
-    RNG();
-    RNG(uint64 _state);
-    unsigned next();
-
-    operator uchar();
-    operator schar();
-    operator ushort();
-    operator short();
-    operator unsigned();
-    operator int();
-    operator float();
-    operator double();
-    int uniform(int a, int b);
-    float uniform(float a, float b);
-    double uniform(double a, double b);
-    void fill( Mat& mat, int distType, const Scalar& a, const Scalar& b );
-
-    uint64 state;
-};
-
-struct CV_EXPORTS TermCriteria
-{
-    enum { COUNT=1, MAX_ITER=COUNT, EPS=2 };
-
-    TermCriteria();
-    TermCriteria(int _type, int _maxCount, double _epsilon);
-    TermCriteria(const CvTermCriteria& criteria);
-    operator CvTermCriteria() const;
-    
-    int type;
-    int maxCount;
-    double epsilon;
-};
-
-CV_EXPORTS Mat cvarrToMat(const CvArr* arr, bool copyData=false, bool allowND=true);
-CV_EXPORTS Mat extractImageCOI(const CvArr* arr);
-
-CV_EXPORTS void add(const Mat& a, const Mat& b, Mat& c, const Mat& mask);
-CV_EXPORTS void subtract(const Mat& a, const Mat& b, Mat& c, const Mat& mask);
-CV_EXPORTS void add(const Mat& a, const Mat& b, Mat& c);
-CV_EXPORTS void subtract(const Mat& a, const Mat& b, Mat& c);
-CV_EXPORTS void add(const Mat& a, const Scalar& s, Mat& c, const Mat& mask=Mat());
-CV_EXPORTS void subtract(const Mat& a, const Scalar& s, Mat& c, const Mat& mask=Mat());
-
-CV_EXPORTS void multiply(const Mat& a, const Mat& b, Mat& c, double scale=1);
-CV_EXPORTS void divide(const Mat& a, const Mat& b, Mat& c, double scale=1);
-CV_EXPORTS void divide(double scale, const Mat& b, Mat& c);
-
-CV_EXPORTS void subtract(const Scalar& s, const Mat& a, Mat& c, const Mat& mask=Mat());
-CV_EXPORTS void scaleAdd(const Mat& a, double alpha, const Mat& b, Mat& c);
-CV_EXPORTS void addWeighted(const Mat& a, double alpha, const Mat& b,
-                            double beta, double gamma, Mat& c);
-CV_EXPORTS void convertScaleAbs(const Mat& a, Mat& c, double alpha=1, double beta=0);
-CV_EXPORTS void LUT(const Mat& a, const Mat& lut, Mat& b);
-
-CV_EXPORTS Scalar sum(const Mat& m);
-CV_EXPORTS int countNonZero( const Mat& m );
-
-CV_EXPORTS Scalar mean(const Mat& m);
-CV_EXPORTS Scalar mean(const Mat& m, const Mat& mask);
-CV_EXPORTS void meanStdDev(const Mat& m, Scalar& mean, Scalar& stddev, const Mat& mask=Mat());
-CV_EXPORTS double norm(const Mat& a, int normType=NORM_L2);
-CV_EXPORTS double norm(const Mat& a, const Mat& b, int normType=NORM_L2);
-CV_EXPORTS double norm(const Mat& a, int normType, const Mat& mask);
-CV_EXPORTS double norm(const Mat& a, const Mat& b,
-                       int normType, const Mat& mask);
-CV_EXPORTS void normalize( const Mat& a, Mat& b, double alpha=1, double beta=0,
-                          int norm_type=NORM_L2, int rtype=-1, const Mat& mask=Mat());
-
-CV_EXPORTS void minMaxLoc(const Mat& a, double* minVal,
-                          double* maxVal=0, Point* minLoc=0,
-                          Point* maxLoc=0, const Mat& mask=Mat());
-CV_EXPORTS void reduce(const Mat& m, Mat& dst, int dim, int rtype, int dtype=-1);
-CV_EXPORTS void merge(const Vector<Mat>& mv, Mat& dst);
-CV_EXPORTS void split(const Mat& m, Vector<Mat>& mv);
-CV_EXPORTS void mixChannels(const Vector<Mat>& src, Vector<Mat>& dst,
-                            const Vector<int>& fromTo);
-CV_EXPORTS void flip(const Mat& a, Mat& b, int flipCode);
-
-CV_EXPORTS void repeat(const Mat& a, int ny, int nx, Mat& b);
-static inline Mat repeat(const Mat& src, int ny, int nx)
-{
-    if( nx == 1 && ny == 1 ) return src;
-    Mat dst; repeat(src, ny, nx, dst); return dst;
-}
-
-CV_EXPORTS void bitwise_and(const Mat& a, const Mat& b, Mat& c, const Mat& mask=Mat());
-CV_EXPORTS void bitwise_or(const Mat& a, const Mat& b, Mat& c, const Mat& mask=Mat());
-CV_EXPORTS void bitwise_xor(const Mat& a, const Mat& b, Mat& c, const Mat& mask=Mat());
-CV_EXPORTS void bitwise_and(const Mat& a, const Scalar& s, Mat& c, const Mat& mask=Mat());
-CV_EXPORTS void bitwise_or(const Mat& a, const Scalar& s, Mat& c, const Mat& mask=Mat());
-CV_EXPORTS void bitwise_xor(const Mat& a, const Scalar& s, Mat& c, const Mat& mask=Mat());
-CV_EXPORTS void bitwise_not(const Mat& a, Mat& c);
-CV_EXPORTS void absdiff(const Mat& a, const Mat& b, Mat& c);
-CV_EXPORTS void absdiff(const Mat& a, const Scalar& s, Mat& c);
-CV_EXPORTS void inRange(const Mat& src, const Mat& lowerb,
-                        const Mat& upperb, Mat& dst);
-CV_EXPORTS void inRange(const Mat& src, const Scalar& lowerb,
-                        const Scalar& upperb, Mat& dst);
-CV_EXPORTS void compare(const Mat& a, const Mat& b, Mat& c, int cmpop);
-CV_EXPORTS void compare(const Mat& a, double s, Mat& c, int cmpop);
-CV_EXPORTS void min(const Mat& a, const Mat& b, Mat& c);
-CV_EXPORTS void min(const Mat& a, double alpha, Mat& c);
-CV_EXPORTS void max(const Mat& a, const Mat& b, Mat& c);
-CV_EXPORTS void max(const Mat& a, double alpha, Mat& c);
-
-CV_EXPORTS void sqrt(const Mat& a, Mat& b);
-CV_EXPORTS void pow(const Mat& a, double power, Mat& b);
-CV_EXPORTS void exp(const Mat& a, Mat& b);
-CV_EXPORTS void log(const Mat& a, Mat& b);
-CV_EXPORTS float cubeRoot(float val);
-CV_EXPORTS float fastAtan2(float y, float x);
-CV_EXPORTS void polarToCart(const Mat& magnitude, const Mat& angle,
-                            Mat& x, Mat& y, bool angleInDegrees=false);
-CV_EXPORTS void cartToPolar(const Mat& x, const Mat& y,
-                            Mat& magnitude, Mat& angle,
-                            bool angleInDegrees=false);
-CV_EXPORTS void phase(const Mat& x, const Mat& y, Mat& angle,
-                            bool angleInDegrees=false);
-CV_EXPORTS void magnitude(const Mat& x, const Mat& y, Mat& magnitude);
-CV_EXPORTS bool checkRange(const Mat& a, bool quiet=true, Point* pt=0,
-                           double minVal=-DBL_MAX, double maxVal=DBL_MAX);
-
-CV_EXPORTS void gemm(const Mat& a, const Mat& b, double alpha,
-                     const Mat& c, double gamma, Mat& d, int flags=0);
-CV_EXPORTS void mulTransposed( const Mat& a, Mat& c, bool aTa,
-                               const Mat& delta=Mat(),
-                               double scale=1, int rtype=-1 );
-CV_EXPORTS void transpose(const Mat& a, Mat& b);
-CV_EXPORTS void transform(const Mat& src, Mat& dst, const Mat& m );
-CV_EXPORTS void perspectiveTransform(const Mat& src, Mat& dst, const Mat& m );
-
-CV_EXPORTS void completeSymm(Mat& a, bool lowerToUpper=false);
-CV_EXPORTS void setIdentity(Mat& c, const Scalar& s=Scalar(1));
-CV_EXPORTS double determinant(const Mat& m);
-CV_EXPORTS Scalar trace(const Mat& m);
-CV_EXPORTS double invert(const Mat& a, Mat& c, int flags=DECOMP_LU);
-CV_EXPORTS bool solve(const Mat& a, const Mat& b, Mat& x, int flags=DECOMP_LU);
-CV_EXPORTS void sort(const Mat& a, Mat& b, int flags);
-CV_EXPORTS void sortIdx(const Mat& a, Mat& b, int flags);
-CV_EXPORTS void solveCubic(const Mat& coeffs, Mat& roots);
-CV_EXPORTS void solvePoly(const Mat& coeffs, Mat& roots, int maxIters=20, int fig=100);
-CV_EXPORTS bool eigen(const Mat& a, Mat& eigenvalues);
-CV_EXPORTS bool eigen(const Mat& a, Mat& eigenvalues, Mat& eigenvectors);
-
-CV_EXPORTS void calcCovariation( const Vector<Mat>& data, Mat& covar, Mat& mean,
-                                 int flags, int ctype=CV_64F);
-CV_EXPORTS void calcCovariation( const Mat& data, Mat& covar, Mat& mean,
-                                 int flags, int ctype=CV_64F);
-
-struct CV_EXPORTS PCA
-{
-    PCA();
-    PCA(const Mat& data, const Mat& mean, int flags, int maxComponents=0);
-    PCA& operator()(const Mat& data, const Mat& mean, int flags, int maxComponents=0);
-    Mat project(const Mat& vec) const;
-    void project(const Mat& vec, Mat& result) const;
-    Mat backProject(const Mat& vec) const;
-    void backProject(const Mat& vec, Mat& result) const;
-
-    Mat eigenvectors;
-    Mat eigenvalues;
-    Mat mean;
-};
-
-struct CV_EXPORTS SVD
-{
-    enum { MODIFY_A=1, NO_UV=2, FULL_UV=4 };
-    SVD();
-    SVD( const Mat& m, int flags=0 );
-    SVD& operator ()( const Mat& m, int flags=0 );
-
-    static void solveZ( const Mat& m, Mat& dst );
-    void backSubst( const Mat& rhs, Mat& dst ) const;
-
-    Mat u, w, vt;
-};
-
-CV_EXPORTS double mahalanobis(const Mat& v1, const Mat& v2, const Mat& icovar);
-static inline double mahalonobis(const Mat& v1, const Mat& v2, const Mat& icovar)
-{ return mahalanobis(v1, v2, icovar); }
-
-CV_EXPORTS void dft(const Mat& src, Mat& dst, int flags=0, int nonzeroRows=0);
-CV_EXPORTS void idft(const Mat& src, Mat& dst, int flags=0, int nonzeroRows=0);
-CV_EXPORTS void dct(const Mat& src, Mat& dst, int flags=0);
-CV_EXPORTS void idct(const Mat& src, Mat& dst, int flags=0);
-CV_EXPORTS void mulSpectrums(const Mat& a, const Mat& b, Mat& c,
-                             int flags, bool conjB=false);
-CV_EXPORTS int getOptimalDFTSize(int vecsize);
-
-enum { KMEANS_CENTERS_RANDOM=0, KMEANS_CENTERS_SPP=2, KMEANS_USE_INITIAL_LABELS=1 };
-CV_EXPORTS int kmeans( const Mat& samples, int K,
-                       Mat& labels, Mat& centers,
-                       TermCriteria crit, int attempts=1,
-                       int flags=KMEANS_CENTERS_SPP,
-                       double* compactness=0);
-
-CV_EXPORTS void seqToVector( const CvSeq* ptseq, Vector<Point>& pts );
-
-CV_EXPORTS RNG& theRNG();
-static inline int randi() { return (int)theRNG(); }
-static inline unsigned randu() { return (unsigned)theRNG(); }
-static inline float randf() { return (float)theRNG(); }
-static inline double randd() { return (double)theRNG(); }
-static inline void randu(Mat& dst, const Scalar& low, const Scalar& high)
-{ theRNG().fill(dst, RNG::UNIFORM, low, high); }
-static inline void randn(Mat& dst, const Scalar& mean, const Scalar& stddev)
-{ theRNG().fill(dst, RNG::NORMAL, mean, stddev); }
-CV_EXPORTS void randShuffle(Mat& dst, RNG& rng, double iterFactor=1.);
-static inline void randShuffle(Mat& dst, double iterFactor=1.)
-{ randShuffle(dst, theRNG(), iterFactor); }
-
-CV_EXPORTS void line(Mat& img, Point pt1, Point pt2, const Scalar& color,
-                     int thickness=1, int lineType=8, int shift=0);
-
-CV_EXPORTS void rectangle(Mat& img, Point pt1, Point pt2,
-                          const Scalar& color, int thickness=1,
-                          int lineType=8, int shift=0);
-
-CV_EXPORTS void circle(Mat& img, Point center, int radius,
-                       const Scalar& color, int thickness=1,
-                       int lineType=8, int shift=0);
-
-CV_EXPORTS void ellipse(Mat& img, Point center, Size axes,
-                        double angle, double startAngle, double endAngle,
-                        const Scalar& color, int thickness=1,
-                        int lineType=8, int shift=0);
-
-CV_EXPORTS void ellipse(Mat& img, const RotatedRect& box, const Scalar& color,
-                        int thickness=1, int lineType=8, int shift=0 );
-
-CV_EXPORTS void fillConvexPoly(Mat& img, const Vector<Point>& pts,
-                               const Scalar& color, int lineType=8,
-                               int shift=0);
-
-CV_EXPORTS void fillPoly(Mat& img, const Vector<Vector<Point> >& pts,
-                         const Scalar& color, int lineType=8, int shift=0,
-                         Point offset=Point() );
-
-CV_EXPORTS void polylines(Mat& img, const Vector<Vector<Point> >& pts, bool isClosed,
-                          const Scalar& color, int thickness=1, int lineType=8, int shift=0 );
-
-CV_EXPORTS bool clipLine(Size imgSize, Point& pt1, Point& pt2);
-
-struct CV_EXPORTS LineIterator
-{
-    LineIterator(const Mat& img, Point pt1, Point pt2,
-                 int connectivity=8, bool leftToRight=false);
-    uchar* operator *();
-    LineIterator& operator ++();
-    LineIterator operator ++(int);
-
-    uchar* ptr;
-    int err, count;
-    int minusDelta, plusDelta;
-    int minusStep, plusStep;
-};
-
-CV_EXPORTS void ellipse2Poly( Point center, Size axes, int angle,
-                              int arcStart, int arcEnd, int delta, Vector<Point>& pts );
-
-enum
-{
-    FONT_HERSHEY_SIMPLEX = 0,
-    FONT_HERSHEY_PLAIN = 1,
-    FONT_HERSHEY_DUPLEX = 2,
-    FONT_HERSHEY_COMPLEX = 3,
-    FONT_HERSHEY_TRIPLEX = 4,
-    FONT_HERSHEY_COMPLEX_SMALL = 5,
-    FONT_HERSHEY_SCRIPT_SIMPLEX = 6,
-    FONT_HERSHEY_SCRIPT_COMPLEX = 7,
-    FONT_ITALIC = 16
-};
-
-CV_EXPORTS void putText( Mat& img, const String& text, Point org,
-                         int fontFace, double fontScale, Scalar color,
-                         int thickness=1, int linetype=8,
-                         bool bottomLeftOrigin=false );
-
-CV_EXPORTS Size getTextSize(const String& text, int fontFace,
-                            double fontScale, int thickness,
-                            int* baseLine);
-
-///////////////////////////////// Mat_<_Tp> ////////////////////////////////////
-
-template<typename _Tp> struct CV_EXPORTS Mat_ : public Mat
-{
-    typedef _Tp value_type;
-    typedef typename DataType<_Tp>::channel_type channel_type;
-    typedef MatIterator_<_Tp> iterator;
-    typedef MatConstIterator_<_Tp> const_iterator;
-    
-    Mat_();
-    Mat_(int _rows, int _cols);
-    Mat_(int _rows, int _cols, const _Tp& value);
-    explicit Mat_(Size _size);
-    Mat_(Size _size, const _Tp& value);
-    Mat_(const Mat& m);
-    Mat_(const Mat_& m);
-    Mat_(int _rows, int _cols, _Tp* _data, size_t _step=AUTO_STEP);
-    Mat_(const Mat_& m, const Range& rowRange, const Range& colRange);
-    Mat_(const Mat_& m, const Rect& roi);
-    Mat_(const MatExpr_Base& expr);
-    template<int n> explicit Mat_(const Vec_<_Tp, n>& vec);
-    Mat_(const Vector<_Tp>& vec);
-
-    Mat_& operator = (const Mat& m);
-    Mat_& operator = (const Mat_& m);
-    Mat_& operator = (const _Tp& s);
-
-    iterator begin();
-    iterator end();
-    const_iterator begin() const;
-    const_iterator end() const;
-
-    void create(int _rows, int _cols);
-    void create(Size _size);
-    Mat_ cross(const Mat_& m) const;
-    Mat_& operator = (const MatExpr_Base& expr);
-    template<typename T2> operator Mat_<T2>() const;
-    Mat_ row(int y) const;
-    Mat_ col(int x) const;
-    Mat_ diag(int d=0) const;
-    Mat_ clone() const;
-
-    MatExpr_<MatExpr_Op2_<Mat_, double, Mat_, MatOp_T_<Mat> >, Mat_> t() const;
-    MatExpr_<MatExpr_Op2_<Mat_, int, Mat_, MatOp_Inv_<Mat> >, Mat_> inv(int method=DECOMP_LU) const;
-
-    MatExpr_<MatExpr_Op4_<Mat_, Mat_, double, char, Mat_, MatOp_MulDiv_<Mat> >, Mat_>
-    mul(const Mat_& m, double scale=1) const;
-    MatExpr_<MatExpr_Op4_<Mat_, Mat_, double, char, Mat_, MatOp_MulDiv_<Mat> >, Mat_>
-    mul(const MatExpr_<MatExpr_Op2_<Mat_, double, Mat_,
-        MatOp_Scale_<Mat> >, Mat_>& m, double scale=1) const;
-    MatExpr_<MatExpr_Op4_<Mat_, Mat_, double, char, Mat_, MatOp_MulDiv_<Mat> >, Mat_>    
-    mul(const MatExpr_<MatExpr_Op2_<Mat_, double, Mat_,
-        MatOp_DivRS_<Mat> >, Mat_>& m, double scale=1) const;
-
-    size_t elemSize() const;
-    size_t elemSize1() const;
-    int type() const;
-    int depth() const;
-    int channels() const;
-    size_t stepT() const;
-    size_t step1() const;
-
-    static MatExpr_Initializer zeros(int rows, int cols);
-    static MatExpr_Initializer zeros(Size size);
-    static MatExpr_Initializer ones(int rows, int cols);
-    static MatExpr_Initializer ones(Size size);
-    static MatExpr_Initializer eye(int rows, int cols);
-    static MatExpr_Initializer eye(Size size);
-
-    Mat_ reshape(int _rows) const;
-    Mat_& adjustROI( int dtop, int dbottom, int dleft, int dright );
-    Mat_ operator()( const Range& rowRange, const Range& colRange ) const;
-    Mat_ operator()( const Rect& roi ) const;
-
-    _Tp* operator [](int y);
-    const _Tp* operator [](int y) const;
-
-    _Tp& operator ()(int row, int col);
-    const _Tp& operator ()(int row, int col) const;
-
-    operator MatExpr_<Mat_, Mat_>() const;
-    operator Vector<_Tp>() const;
-};
-
-//////////// Iterators & Comma initializers //////////////////
-
-template<typename _Tp>
-struct CV_EXPORTS MatConstIterator_
-{
-    typedef _Tp value_type;
-    typedef int difference_type;
-
-    MatConstIterator_();
-    MatConstIterator_(const Mat_<_Tp>* _m);
-    MatConstIterator_(const Mat_<_Tp>* _m, int _row, int _col=0);
-    MatConstIterator_(const Mat_<_Tp>* _m, Point _pt);
-    MatConstIterator_(const MatConstIterator_& it);
-
-    MatConstIterator_& operator = (const MatConstIterator_& it );
-    _Tp operator *() const;
-    _Tp operator [](int i) const;
-    
-    MatConstIterator_& operator += (int ofs);
-    MatConstIterator_& operator -= (int ofs);
-    MatConstIterator_& operator --();
-    MatConstIterator_ operator --(int);
-    MatConstIterator_& operator ++();
-    MatConstIterator_ operator ++(int);
-    Point pos() const;
-
-    const Mat_<_Tp>* m;
-    _Tp* ptr;
-    _Tp* sliceEnd;
-};
-
-
-template<typename _Tp>
-struct CV_EXPORTS MatIterator_ : MatConstIterator_<_Tp>
-{
-    typedef _Tp* pointer;
-    typedef _Tp& reference;
-    typedef std::random_access_iterator_tag iterator_category;
-
-    MatIterator_();
-    MatIterator_(Mat_<_Tp>* _m);
-    MatIterator_(Mat_<_Tp>* _m, int _row, int _col=0);
-    MatIterator_(const Mat_<_Tp>* _m, Point _pt);
-    MatIterator_(const MatIterator_& it);
-    MatIterator_& operator = (const MatIterator_<_Tp>& it );
-
-    _Tp& operator *() const;
-    _Tp& operator [](int i) const;
-
-    MatIterator_& operator += (int ofs);
-    MatIterator_& operator -= (int ofs);
-    MatIterator_& operator --();
-    MatIterator_ operator --(int);
-    MatIterator_& operator ++();
-    MatIterator_ operator ++(int);
-};
-
-template<typename _Tp> struct CV_EXPORTS MatOp_Iter_;
-
-template<typename _Tp> struct CV_EXPORTS MatCommaInitializer_ :
-    MatExpr_<MatExpr_Op1_<MatIterator_<_Tp>, Mat_<_Tp>, MatOp_Iter_<_Tp> >, Mat_<_Tp> >
-{
-    MatCommaInitializer_(Mat_<_Tp>* _m);
-    template<typename T2> MatCommaInitializer_<_Tp>& operator , (T2 v);
-    operator Mat_<_Tp>() const;
-    Mat_<_Tp> operator *() const;
-    void assignTo(Mat& m, int type=-1) const;
-};
-
-template<typename _Tp> struct VectorCommaInitializer_
-{
-    VectorCommaInitializer_(Vector<_Tp>* _vec);
-    template<typename T2> VectorCommaInitializer_<_Tp>& operator , (T2 val);
-    operator Vector<_Tp>() const;
-    Vector<_Tp> operator *() const;
-
-    Vector<_Tp>* vec;
-    int idx;
-};
-
-template<typename _Tp, size_t fixed_size=4096/sizeof(_Tp)+8> struct CV_EXPORTS AutoBuffer
-{
-    typedef _Tp value_type;
-
-    AutoBuffer();
-    AutoBuffer(size_t _size);
-    ~AutoBuffer();
-
-    void allocate(size_t _size);
-    void deallocate();
-    operator _Tp* ();
-    operator const _Tp* () const;
-
-    _Tp* ptr;
-    size_t size;
-    _Tp buf[fixed_size];
-};
-
-/////////////////////////// multi-dimensional dense matrix //////////////////////////
-
-struct MatND;
-struct SparseMat;
-
-struct CV_EXPORTS MatND
-{
-    MatND();
-    MatND(const Vector<int>& _sizes, int _type);
-    MatND(const Vector<int>& _sizes, int _type, const Scalar& _s);
-    MatND(const MatND& m);
-    MatND(const MatND& m, const Vector<Range>& ranges);
-    MatND(const CvMatND* m, bool copyData=false);
-    //MatND( const MatExpr_BaseND& expr );
-    ~MatND();
-    MatND& operator = (const MatND& m);
-    //MatND& operator = (const MatExpr_BaseND& expr);
-
-    //operator MatExpr_<MatND, MatND>() const;
-
-    MatND clone() const;
-    MatND operator()(const Vector<Range>& ranges) const;
-
-    void copyTo( MatND& m ) const;
-    void copyTo( MatND& m, const MatND& mask ) const;
-    void convertTo( MatND& m, int rtype, double alpha=1, double beta=0 ) const;
-
-    void assignTo( MatND& m, int type=-1 ) const;
-    MatND& operator = (const Scalar& s);
-    MatND& setTo(const Scalar& s, const MatND& mask=MatND());
-    MatND reshape(int newcn, const Vector<int>& newsz=Vector<int>()) const;
-
-    void create(const Vector<int>& _sizes, int _type);
-    void addref();
-    void release();
-
-    operator Mat() const;
-    operator CvMatND() const;
-    bool isContinuous() const;
-    size_t elemSize() const;
-    size_t elemSize1() const;
-    int type() const;
-    int depth() const;
-    int channels() const;
-    size_t step(int i) const;
-    size_t step1(int i) const;
-    Vector<int> size() const;
-    int size(int i) const;
-
-    uchar* ptr(int i0);
-    const uchar* ptr(int i0) const;
-    uchar* ptr(int i0, int i1);
-    const uchar* ptr(int i0, int i1) const;
-    uchar* ptr(int i0, int i1, int i2);
-    const uchar* ptr(int i0, int i1, int i2) const;
-    uchar* ptr(const int* idx);
-    const uchar* ptr(const int* idx) const;
-
-    enum { MAGIC_VAL=0x42FE0000, AUTO_STEP=-1,
-        CONTINUOUS_FLAG=CV_MAT_CONT_FLAG, MAX_DIM=CV_MAX_DIM };
-
-    int flags;
-    int dims;
-    
-    int* refcount;
-    uchar* data;
-    uchar* datastart;
-    uchar* dataend;
-    
-    struct
-    {
-        int size;
-        size_t step;
-    }
-    dim[MAX_DIM];
-};
-
-struct CV_EXPORTS NAryMatNDIterator
-{
-    NAryMatNDIterator();
-    NAryMatNDIterator(const Vector<MatND>& arrays);
-    void init(const Vector<MatND>& arrays);
-
-    NAryMatNDIterator& operator ++();
-    NAryMatNDIterator operator ++(int);
-    
-    Vector<MatND> arrays;
-    Vector<Mat> planes;
-    int iterdepth, idx, nplanes;
-};
-
-CV_EXPORTS void add(const MatND& a, const MatND& b, MatND& c, const MatND& mask);
-CV_EXPORTS void subtract(const MatND& a, const MatND& b, MatND& c, const MatND& mask);
-CV_EXPORTS void add(const MatND& a, const MatND& b, MatND& c);
-CV_EXPORTS void subtract(const MatND& a, const MatND& b, MatND& c);
-CV_EXPORTS void add(const MatND& a, const Scalar& s, MatND& c, const MatND& mask=MatND());
-
-CV_EXPORTS void multiply(const MatND& a, const MatND& b, MatND& c, double scale=1);
-CV_EXPORTS void divide(const MatND& a, const MatND& b, MatND& c, double scale=1);
-CV_EXPORTS void divide(double scale, const MatND& b, MatND& c);
-
-CV_EXPORTS void subtract(const Scalar& s, const MatND& a, MatND& c, const MatND& mask=MatND());
-CV_EXPORTS void scaleAdd(const MatND& a, double alpha, const MatND& b, MatND& c);
-CV_EXPORTS void addWeighted(const MatND& a, double alpha, const MatND& b,
-                            double beta, double gamma, MatND& c);
-
-CV_EXPORTS Scalar sum(const MatND& m);
-CV_EXPORTS int countNonZero( const MatND& m );
-
-CV_EXPORTS Scalar mean(const MatND& m);
-CV_EXPORTS Scalar mean(const MatND& m, const MatND& mask);
-CV_EXPORTS void meanStdDev(const MatND& m, Scalar& mean, Scalar& stddev, const MatND& mask=MatND());
-CV_EXPORTS double norm(const MatND& a, int normType=NORM_L2, const MatND& mask=MatND());
-CV_EXPORTS double norm(const MatND& a, const MatND& b,
-                       int normType=NORM_L2, const MatND& mask=MatND());
-CV_EXPORTS void normalize( const MatND& a, MatND& b, double alpha=1, double beta=0,
-                           int norm_type=NORM_L2, int rtype=-1, const MatND& mask=MatND());
-
-CV_EXPORTS void minMaxLoc(const MatND& a, double* minVal,
-                       double* maxVal, int* minIdx=0, int* maxIdx=0,
-                       const MatND& mask=MatND());
-CV_EXPORTS void merge(const Vector<MatND>& mv, MatND& dst);
-CV_EXPORTS void split(const MatND& m, Vector<MatND>& mv);
-CV_EXPORTS void mixChannels(const Vector<MatND>& src, Vector<MatND>& dst,
-                            const Vector<int>& fromTo);
-
-CV_EXPORTS void bitwise_and(const MatND& a, const MatND& b, MatND& c, const MatND& mask=MatND());
-CV_EXPORTS void bitwise_or(const MatND& a, const MatND& b, MatND& c, const MatND& mask=MatND());
-CV_EXPORTS void bitwise_xor(const MatND& a, const MatND& b, MatND& c, const MatND& mask=MatND());
-CV_EXPORTS void bitwise_and(const MatND& a, const Scalar& s, MatND& c, const MatND& mask=MatND());
-CV_EXPORTS void bitwise_or(const MatND& a, const Scalar& s, MatND& c, const MatND& mask=MatND());
-CV_EXPORTS void bitwise_xor(const MatND& a, const Scalar& s, MatND& c, const MatND& mask=MatND());
-CV_EXPORTS void bitwise_not(const MatND& a, MatND& c);
-CV_EXPORTS void absdiff(const MatND& a, const MatND& b, MatND& c);
-CV_EXPORTS void absdiff(const MatND& a, const Scalar& s, MatND& c);
-CV_EXPORTS void inRange(const MatND& src, const MatND& lowerb,
-                        const MatND& upperb, MatND& dst);
-CV_EXPORTS void inRange(const MatND& src, const Scalar& lowerb,
-                        const Scalar& upperb, MatND& dst);
-CV_EXPORTS void compare(const MatND& a, const MatND& b, MatND& c, int cmpop);
-CV_EXPORTS void compare(const MatND& a, double s, MatND& c, int cmpop);
-CV_EXPORTS void min(const MatND& a, const MatND& b, MatND& c);
-CV_EXPORTS void min(const MatND& a, double alpha, MatND& c);
-CV_EXPORTS void max(const MatND& a, const MatND& b, MatND& c);
-CV_EXPORTS void max(const MatND& a, double alpha, MatND& c);
-
-CV_EXPORTS void sqrt(const MatND& a, MatND& b);
-CV_EXPORTS void pow(const MatND& a, double power, MatND& b);
-CV_EXPORTS void exp(const MatND& a, MatND& b);
-CV_EXPORTS void log(const MatND& a, MatND& b);
-CV_EXPORTS bool checkRange(const MatND& a, bool quiet=true, int* idx=0,
-                           double minVal=-DBL_MAX, double maxVal=DBL_MAX);
-
-typedef void (*ConvertData)(const void* from, void* to, int cn);
-typedef void (*ConvertScaleData)(const void* from, void* to, int cn, double alpha, double beta);
-
-CV_EXPORTS ConvertData getConvertElem(int fromType, int toType);
-CV_EXPORTS ConvertScaleData getConvertScaleElem(int fromType, int toType);
-
-template<typename _Tp> struct CV_EXPORTS MatND_ : public MatND
-{
-    typedef _Tp value_type;
-    typedef typename DataType<_Tp>::channel_type channel_type;
-
-    MatND_();
-    MatND_(const Vector<int>& _sizes);
-    MatND_(const Vector<int>& _sizes, const _Tp& _s);
-    MatND_(const MatND& m);
-    MatND_(const MatND_& m);
-    MatND_(const MatND_& m, const Vector<Range>& ranges);
-    MatND_(const CvMatND* m, bool copyData=false);
-    MatND_& operator = (const MatND& m);
-    MatND_& operator = (const MatND_& m);
-    MatND_& operator = (const _Tp& s);
-
-    void create(const Vector<int>& _sizes);
-    template<typename T2> operator MatND_<T2>() const;
-    MatND_ clone() const;
-    MatND_ operator()(const Vector<Range>& ranges) const;
-
-    size_t elemSize() const;
-    size_t elemSize1() const;
-    int type() const;
-    int depth() const;
-    int channels() const;
-    size_t stepT(int i) const;
-    size_t step1(int i) const;
-
-    _Tp& operator ()(const int* idx);
-    const _Tp& operator ()(const int* idx) const;
-
-    _Tp& operator ()(int idx0, int idx1, int idx2);
-    const _Tp& operator ()(int idx0, int idx1, int idx2) const;
-};
-
-/////////////////////////// multi-dimensional sparse matrix //////////////////////////
-
-struct SparseMatIterator;
-struct SparseMatConstIterator;
-
-struct CV_EXPORTS SparseMat
-{
-    typedef SparseMatIterator iterator;
-    typedef SparseMatConstIterator const_iterator;
-
-    struct CV_EXPORTS Hdr
-    {
-        Hdr(const Vector<int>& _sizes, int _type);
-        void clear();
-        int refcount;
-        int dims;
-        int valueOffset;
-        size_t nodeSize;
-        size_t nodeCount;
-        size_t freeList;
-        Vector<uchar> pool;
-        Vector<size_t> hashtab;
-        int size[CV_MAX_DIM];
-    };
-
-    struct CV_EXPORTS Node
-    {
-        size_t hashval;
-        size_t next;
-        int idx[CV_MAX_DIM];
-    };
-
-    SparseMat();
-    SparseMat(const Vector<int>& _sizes, int _type);
-    SparseMat(const SparseMat& m);
-    SparseMat(const Mat& m, bool try1d=false);
-    SparseMat(const MatND& m);
-    SparseMat(const CvSparseMat* m);
-    ~SparseMat();
-    SparseMat& operator = (const SparseMat& m);
-    SparseMat& operator = (const Mat& m);
-    SparseMat& operator = (const MatND& m);
-
-    SparseMat clone() const;
-    void copyTo( SparseMat& m ) const;
-    void copyTo( Mat& m ) const;
-    void copyTo( MatND& m ) const;
-    void convertTo( SparseMat& m, int rtype, double alpha=1 ) const;
-    void convertTo( Mat& m, int rtype, double alpha=1, double beta=0 ) const;
-    void convertTo( MatND& m, int rtype, double alpha=1, double beta=0 ) const;
-
-    void assignTo( SparseMat& m, int type=-1 ) const;
-
-    void create(const Vector<int>& _sizes, int _type);
-    void clear();
-    void addref();
-    void release();
-
-    operator CvSparseMat*() const;
-    size_t elemSize() const;
-    size_t elemSize1() const;
-    int type() const;
-    int depth() const;
-    int channels() const;
-    Vector<int> size() const;
-    int size(int i) const;
-    int dims() const;
-    size_t nzcount() const;
-    
-    size_t hash(int i0) const;
-    size_t hash(int i0, int i1) const;
-    size_t hash(int i0, int i1, int i2) const;
-    size_t hash(const int* idx) const;
-    
-    uchar* ptr(int i0, int i1, bool createMissing, size_t* hashval=0);
-    const uchar* get(int i0, int i1, size_t* hashval=0) const;
-    uchar* ptr(int i0, int i1, int i2, bool createMissing, size_t* hashval=0);
-    const uchar* get(int i0, int i1, int i2, size_t* hashval=0) const;
-    uchar* ptr(const int* idx, bool createMissing, size_t* hashval=0);
-    const uchar* get(const int* idx, size_t* hashval=0) const;
-
-    void erase(int i0, int i1, size_t* hashval=0);
-    void erase(int i0, int i1, int i2, size_t* hashval=0);
-    void erase(const int* idx, size_t* hashval=0);
-
-    SparseMatIterator begin();
-    SparseMatConstIterator begin() const;
-    SparseMatIterator end();
-    SparseMatConstIterator end() const;
-
-    uchar* value(Node* n);
-    const uchar* value(const Node* n) const;
-    Node* node(size_t nidx);
-    const Node* node(size_t nidx) const;
-
-    uchar* newNode(const int* idx, size_t hashval);
-    void removeNode(size_t hidx, size_t nidx, size_t previdx);
-    void resizeHashTab(size_t newsize);
-
-    enum { MAGIC_VAL=0x42FD0000, MAX_DIM=CV_MAX_DIM, HASH_SCALE=0x5bd1e995, HASH_BIT=0x80000000 };
-
-    int flags;
-    Hdr* hdr;
-};
-
-
-CV_EXPORTS void minMaxLoc(const SparseMat& a, double* minVal,
-                          double* maxVal, int* minIdx=0, int* maxIdx=0);
-CV_EXPORTS double norm( const SparseMat& src, int normType );
-CV_EXPORTS void normalize( const SparseMat& src, SparseMat& dst, double alpha, int normType );
-
-struct CV_EXPORTS SparseMatConstIterator
-{
-    SparseMatConstIterator();
-    SparseMatConstIterator(const SparseMat* _m);
-    SparseMatConstIterator(const SparseMatConstIterator& it);
-
-    SparseMatConstIterator& operator = (const SparseMatConstIterator& it);
-    const uchar* value() const;
-    const SparseMat::Node* node() const;
-    
-    SparseMatConstIterator& operator --();
-    SparseMatConstIterator operator --(int);
-    SparseMatConstIterator& operator ++();
-    SparseMatConstIterator operator ++(int);
-
-    const SparseMat* m;
-    size_t hashidx;
-    uchar* ptr;
-};
-
-struct CV_EXPORTS SparseMatIterator : SparseMatConstIterator
-{
-    SparseMatIterator();
-    SparseMatIterator(SparseMat* _m);
-    SparseMatIterator(SparseMat* _m, const int* idx);
-    SparseMatIterator(const SparseMatIterator& it);
-
-    SparseMatIterator& operator = (const SparseMatIterator& it);
-    uchar* value() const;
-    SparseMat::Node* node() const;
-    
-    SparseMatIterator& operator ++();
-    SparseMatIterator operator ++(int);
-};
-
-
-template<typename _Tp> struct SparseMatIterator_;
-template<typename _Tp> struct SparseMatConstIterator_;
-
-template<typename _Tp> struct CV_EXPORTS SparseMat_ : public SparseMat
-{
-    typedef SparseMatIterator_<_Tp> iterator;
-    typedef SparseMatConstIterator_<_Tp> const_iterator;
-
-    SparseMat_();
-    SparseMat_(const Vector<int>& _sizes);
-    SparseMat_(const SparseMat& m);
-    SparseMat_(const SparseMat_& m);
-    SparseMat_(const Mat& m);
-    SparseMat_(const MatND& m);
-    SparseMat_(const CvSparseMat* m);
-    SparseMat_& operator = (const SparseMat& m);
-    SparseMat_& operator = (const SparseMat_& m);
-    SparseMat_& operator = (const Mat& m);
-    SparseMat_& operator = (const MatND& m);
-
-    SparseMat_ clone() const;
-    void create(const Vector<int>& _sizes);
-    operator CvSparseMat*() const;
-
-    int type() const;
-    int depth() const;
-    int channels() const;
-    
-    _Tp& operator()(int i0, int i1, size_t* hashval=0);
-    _Tp operator()(int i0, int i1, size_t* hashval=0) const;
-    _Tp& operator()(int i0, int i1, int i2, size_t* hashval=0);
-    _Tp operator()(int i0, int i1, int i2, size_t* hashval=0) const;
-    _Tp& operator()(const int* idx, size_t* hashval=0);
-    _Tp operator()(const int* idx, size_t* hashval=0) const;
-
-    SparseMatIterator_<_Tp> begin();
-    SparseMatConstIterator_<_Tp> begin() const;
-    SparseMatIterator_<_Tp> end();
-    SparseMatConstIterator_<_Tp> end() const;
-};
-
-template<typename _Tp> struct CV_EXPORTS SparseMatConstIterator_ : SparseMatConstIterator
-{
-    typedef std::forward_iterator_tag iterator_category;
-    
-    SparseMatConstIterator_();
-    SparseMatConstIterator_(const SparseMat_<_Tp>* _m);
-    SparseMatConstIterator_(const SparseMatConstIterator_& it);
-
-    SparseMatConstIterator_& operator = (const SparseMatConstIterator_& it);
-    const _Tp& operator *() const;
-    
-    SparseMatConstIterator_& operator ++();
-    SparseMatConstIterator_ operator ++(int);
-
-    const SparseMat_<_Tp>* m;
-    size_t hashidx;
-    uchar* ptr;
-};
-
-template<typename _Tp> struct CV_EXPORTS SparseMatIterator_ : SparseMatConstIterator_<_Tp>
-{
-    typedef std::forward_iterator_tag iterator_category;
-    
-    SparseMatIterator_();
-    SparseMatIterator_(SparseMat_<_Tp>* _m);
-    SparseMatIterator_(const SparseMatIterator_& it);
-
-    SparseMatIterator_& operator = (const SparseMatIterator_& it);
-    _Tp& operator *() const;
-    
-    SparseMatIterator_& operator ++();
-    SparseMatIterator_ operator ++(int);
-};
-
-//////////////////// Fast Nearest-Neighbor Search Structure ////////////////////
-
-struct CV_EXPORTS KDTree
-{
-    struct Node
-    {
-        Node() : idx(-1), left(-1), right(-1), boundary(0.f) {}
-        Node(int _idx, int _left, int _right, float _boundary)
-            : idx(_idx), left(_left), right(_right), boundary(_boundary) {}
-        int idx;            // split dimension; >=0 for nodes (dim),
-                            // < 0 for leaves (index of the point)
-        int left, right;    // node indices of left and right branches
-        float boundary;     // left if vec[dim]<=boundary, otherwise right
-    };
-
-    KDTree();
-    KDTree(const Mat& _points, bool copyPoints=true);
-    void build(const Mat& _points, bool copyPoints=true);
-
-    void findNearest(const Mat& vec, int K, int Emax, Vector<int>* neighborsIdx,
-        Mat* neighbors=0, Vector<float>* dist=0) const;
-    void findNearest(const Vector<float>& vec, int K, int Emax, Vector<int>* neighborsIdx,
-        Vector<float>* neighbors=0, Vector<float>* dist=0) const;
-    void findOrthoRange(const Mat& minBounds, const Mat& maxBounds,
-        Vector<int>* neighborsIdx, Mat* neighbors=0) const;
-    void findOrthoRange(const Vector<float>& minBounds, const Vector<float>& maxBounds,
-        Vector<int>* neighborsIdx, Vector<float>* neighbors=0) const;
-    void getPoints(const Vector<int>& ids, Mat& pts) const;
-    void getPoints(const Vector<int>& ids, Vector<float>& pts) const;
-    Vector<float> at(int ptidx, bool copyData=false) const;
-
-    Vector<Node> nodes;
-    Mat points;
-    int maxDepth;
-};
-
-//////////////////////////////////////// XML & YAML I/O ////////////////////////////////////
-
-struct CV_EXPORTS FileNode;
-
-struct CV_EXPORTS FileStorage
-{
-    enum { READ=0, WRITE=1, APPEND=2 };
-    enum { UNDEFINED=0, VALUE_EXPECTED=1, NAME_EXPECTED=2, INSIDE_MAP=4 };
-    FileStorage();
-    FileStorage(const String& filename, int flags);
-    FileStorage(CvFileStorage* fs);
-    virtual ~FileStorage();
-
-    virtual bool open(const String& filename, int flags);
-    virtual bool isOpened() const;
-    virtual void release();
-
-    FileNode getFirstTopLevelNode() const;
-    FileNode root(int streamidx=0) const;
-    FileNode operator[](const String& nodename) const;
-    FileNode operator[](const char* nodename) const;
-
-    CvFileStorage* operator *() { return fs.obj; }
-    const CvFileStorage* operator *() const { return fs.obj; }
-    void writeRaw( const String& fmt, const Vector<uchar>& vec );
-    void writeObj( const String& name, const void* obj );
-
-    static String getDefaultObjectName(const String& filename);
-
-    Ptr<CvFileStorage> fs;
-    String elname;
-    Vector<char> structs;
-    int state;
-};
-
-struct CV_EXPORTS FileNodeIterator;
-
-struct CV_EXPORTS FileNode
-{
-    enum { NONE=0, INT=1, REAL=2, FLOAT=REAL, STR=3, STRING=STR, REF=4, SEQ=5, MAP=6, TYPE_MASK=7,
-        FLOW=8, USER=16, EMPTY=32, NAMED=64 };
-    FileNode();
-    FileNode(const CvFileStorage* fs, const CvFileNode* node);
-    FileNode(const FileNode& node);
-    FileNode operator[](const String& nodename) const;
-    FileNode operator[](const char* nodename) const;
-    FileNode operator[](int i) const;
-    int type() const;
-    int rawDataSize(const String& fmt) const;
-    bool isNone() const;
-    bool isSeq() const;
-    bool isMap() const;
-    bool isInt() const;
-    bool isReal() const;
-    bool isString() const;
-    bool isNamed() const;
-    String name() const;
-    size_t count() const;
-    operator int() const;
-    operator float() const;
-    operator double() const;
-    operator String() const;
-
-    FileNodeIterator begin() const;
-    FileNodeIterator end() const;
-
-    void readRaw( const String& fmt, Vector<uchar>& vec ) const;
-    void* readObj() const;
-
-    // do not use wrapper pointer classes for better efficiency
-    const CvFileStorage* fs;
-    const CvFileNode* node;
-};
-
-struct CV_EXPORTS FileNodeIterator
-{
-    FileNodeIterator();
-    FileNodeIterator(const CvFileStorage* fs, const CvFileNode* node, size_t ofs=0);
-    FileNodeIterator(const FileNodeIterator& it);
-    FileNode operator *() const;
-    FileNode operator ->() const;
-
-    FileNodeIterator& operator ++();
-    FileNodeIterator operator ++(int);
-    FileNodeIterator& operator --();
-    FileNodeIterator operator --(int);
-    FileNodeIterator& operator += (int);
-    FileNodeIterator& operator -= (int);
-
-    FileNodeIterator& readRaw( const String& fmt, Vector<uchar>& vec,
-                               size_t maxCount=(size_t)INT_MAX );
-
-    const CvFileStorage* fs;
-    const CvFileNode* container;
-    CvSeqReader reader;
-    size_t remaining;
-};
-
-////////////// convenient wrappers for operating old-style dynamic structures //////////////
-
-// !!! NOTE that the wrappers are "thin", i.e. they do not call
-// any element constructors/destructors
-
-template<typename _Tp> struct SeqIterator;
-
-template<> inline void Ptr<CvMemStorage>::delete_obj()
-{ cvReleaseMemStorage(&obj); }
-
-typedef Ptr<CvMemStorage> MemStorage;
-
-template<typename _Tp> struct CV_EXPORTS Seq
-{
-    Seq();
-    Seq(const CvSeq* seq);
-    Seq(const MemStorage& storage, int headerSize = sizeof(CvSeq));
-    _Tp& operator [](int idx);
-    const _Tp& operator[](int idx) const;
-    SeqIterator<_Tp> begin() const;
-    SeqIterator<_Tp> end() const;
-    size_t size() const;
-    int type() const;
-    int depth() const;
-    int channels() const;
-    size_t elemSize() const;
-    size_t index(const _Tp& elem) const;
-    void push_back(const _Tp& elem);
-    void push_front(const _Tp& elem);
-    _Tp& front();
-    const _Tp& front() const;
-    _Tp& back();
-    const _Tp& back() const;
-    bool empty() const;
-
-    void clear();
-    void pop_front();
-    void pop_back();
-
-    void copyTo(Vector<_Tp>& vec, const Range& range=Range::all()) const;
-    operator Vector<_Tp>() const;
-    
-    CvSeq* seq;
-};
-
-template<typename _Tp> struct CV_EXPORTS SeqIterator : public CvSeqReader
-{
-    SeqIterator();
-    SeqIterator(const Seq<_Tp>& seq, bool seekEnd=false);
-    void seek(size_t pos);
-    size_t tell() const;
-    _Tp& operator *();
-    const _Tp& operator *() const;
-    SeqIterator& operator ++();
-    SeqIterator operator ++(int) const;
-    SeqIterator& operator --();
-    SeqIterator operator --(int) const;
-
-    SeqIterator& operator +=(int);
-    SeqIterator& operator -=(int);
-
-    // this is index of the current element module seq->total*2
-    // (to distinguish between 0 and seq->total)
-    int index;
-};
-
-}
-
-#endif // __cplusplus
-
-#include "cxoperations.hpp"
-#include "cxmat.hpp"
-
-#endif /*_CXCORE_HPP_*/
+/*M///////////////////////////////////////////////////////////////////////////////////////\r
+//\r
+//  IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.\r
+//\r
+//  By downloading, copying, installing or using the software you agree to this license.\r
+//  If you do not agree to this license, do not download, install,\r
+//  copy or use the software.\r
+//\r
+//\r
+//                           License Agreement\r
+//                For Open Source Computer Vision Library\r
+//\r
+// Copyright (C) 2000-2008, Intel Corporation, all rights reserved.\r
+// Copyright (C) 2009, Willow Garage Inc., all rights reserved.\r
+// Third party copyrights are property of their respective owners.\r
+//\r
+// Redistribution and use in source and binary forms, with or without modification,\r
+// are permitted provided that the following conditions are met:\r
+//\r
+//   * Redistribution's of source code must retain the above copyright notice,\r
+//     this list of conditions and the following disclaimer.\r
+//\r
+//   * Redistribution's in binary form must reproduce the above copyright notice,\r
+//     this list of conditions and the following disclaimer in the documentation\r
+//     and/or other materials provided with the distribution.\r
+//\r
+//   * The name of the copyright holders may not be used to endorse or promote products\r
+//     derived from this software without specific prior written permission.\r
+//\r
+// This software is provided by the copyright holders and contributors "as is" and\r
+// any express or implied warranties, including, but not limited to, the implied\r
+// warranties of merchantability and fitness for a particular purpose are disclaimed.\r
+// In no event shall the Intel Corporation or contributors be liable for any direct,\r
+// indirect, incidental, special, exemplary, or consequential damages\r
+// (including, but not limited to, procurement of substitute goods or services;\r
+// loss of use, data, or profits; or business interruption) however caused\r
+// and on any theory of liability, whether in contract, strict liability,\r
+// or tort (including negligence or otherwise) arising in any way out of\r
+// the use of this software, even if advised of the possibility of such damage.\r
+//\r
+//M*/\r
+\r
+#ifndef _CXCORE_HPP_\r
+#define _CXCORE_HPP_\r
+\r
+#include "cxmisc.h"\r
+\r
+#ifdef __cplusplus\r
+\r
+#ifndef SKIP_INCLUDES\r
+#include <algorithm>\r
+#include <complex>\r
+#include <map>\r
+#include <new>\r
+#include <string>\r
+#include <vector>\r
+#endif // SKIP_INCLUDES\r
+\r
+namespace cv {\r
+\r
+template<typename _Tp> class CV_EXPORTS Size_;\r
+template<typename _Tp> class CV_EXPORTS Point_;\r
+template<typename _Tp> class CV_EXPORTS Rect_;\r
+\r
+typedef std::string String;\r
+typedef std::basic_string<wchar_t> WString;\r
+\r
+CV_EXPORTS String fromUtf16(const WString& str);\r
+CV_EXPORTS WString toUtf16(const String& str);\r
+\r
+class CV_EXPORTS Exception\r
+{\r
+public:\r
+    Exception() { code = 0; line = 0; }\r
+    Exception(int _code, const String& _err, const String& _func, const String& _file, int _line)\r
+        : code(_code), err(_err), func(_func), file(_file), line(_line) {}\r
+    Exception(const Exception& exc)\r
+        : code(exc.code), err(exc.err), func(exc.func), file(exc.file), line(exc.line) {}\r
+    Exception& operator = (const Exception& exc)\r
+    {\r
+        if( this != &exc )\r
+        {\r
+            code = exc.code; err = exc.err; func = exc.func; file = exc.file; line = exc.line;\r
+        }\r
+        return *this;\r
+    }\r
+\r
+    int code;\r
+    String err;\r
+    String func;\r
+    String file;\r
+    int line;\r
+};\r
+\r
+CV_EXPORTS String format( const char* fmt, ... );\r
+CV_EXPORTS void error( const Exception& exc );\r
+\r
+#ifdef __GNUC__\r
+#define CV_Error( code, msg ) cv::error( cv::Exception(code, msg, __func__, __FILE__, __LINE__) )\r
+#define CV_Error_( code, args ) cv::error( cv::Exception(code, cv::format args, __func__, __FILE__, __LINE__) )\r
+#define CV_Assert( expr ) { if(!(expr)) cv::error( cv::Exception(CV_StsAssert, #expr, __func__, __FILE__, __LINE__) ); }\r
+#else\r
+#define CV_Error( code, msg ) cv::error( cv::Exception(code, msg, "", __FILE__, __LINE__) )\r
+#define CV_Error_( code, args ) cv::error( cv::Exception(code, cv::format args, "", __FILE__, __LINE__) )\r
+#define CV_Assert( expr ) { if(!(expr)) cv::error( cv::Exception(CV_StsAssert, #expr, "", __FILE__, __LINE__) ); }\r
+#endif\r
+    \r
+#ifdef _DEBUG\r
+#define CV_DbgAssert(expr) CV_Assert(expr)\r
+#else\r
+#define CV_DbgAssert(expr)\r
+#endif\r
+\r
+CV_EXPORTS void setNumThreads(int);\r
+CV_EXPORTS int getNumThreads();\r
+CV_EXPORTS int getThreadNum();\r
+\r
+CV_EXPORTS int64 getTickCount();\r
+CV_EXPORTS double getTickFrequency();\r
+\r
+CV_EXPORTS void* fastMalloc(size_t);\r
+CV_EXPORTS void fastFree(void* ptr);\r
+\r
+template<typename _Tp> static inline _Tp* allocate(size_t n)\r
+{\r
+    _Tp* ptr = (_Tp*)fastMalloc(n*sizeof(ptr[0]));\r
+    ::new(ptr) _Tp[n];\r
+    return ptr;\r
+}\r
+\r
+template<typename _Tp> static inline void deallocate(_Tp* ptr, size_t n)\r
+{\r
+    for( size_t i = 0; i < n; i++ ) (ptr+i)->~_Tp();\r
+    fastFree(ptr);\r
+}\r
+\r
+template<typename _Tp> static inline _Tp* alignPtr(_Tp* ptr, int n=(int)sizeof(_Tp))\r
+{\r
+    return (_Tp*)(((size_t)ptr + n-1) & -n);\r
+}\r
+\r
+static inline size_t alignSize(size_t sz, int n)\r
+{\r
+    return (sz + n-1) & -n;\r
+}\r
+\r
+CV_EXPORTS void setUseOptimized(bool);\r
+CV_EXPORTS bool useOptimized();\r
+\r
+template<typename _Tp> class CV_EXPORTS Allocator\r
+{\r
+public: \r
+    typedef _Tp value_type;\r
+    typedef value_type* pointer;\r
+    typedef const value_type* const_pointer;\r
+    typedef value_type& reference;\r
+    typedef const value_type& const_reference;\r
+    typedef size_t size_type;\r
+    typedef ptrdiff_t difference_type;\r
+    template<typename U> class rebind { typedef Allocator<U> other; };\r
+\r
+    explicit Allocator() {}\r
+    ~Allocator() {}\r
+    explicit Allocator(Allocator const&) {}\r
+    template<typename U>\r
+    explicit Allocator(Allocator<U> const&) {}\r
+\r
+    // address\r
+    pointer address(reference r) { return &r; }\r
+    const_pointer address(const_reference r) { return &r; }\r
+\r
+    pointer allocate(size_type count, const void* =0)\r
+    { return reinterpret_cast<pointer>(fastMalloc(count * sizeof (_Tp))); }\r
+\r
+    void deallocate(pointer p, size_type) {fastFree(p); }\r
+\r
+    size_type max_size() const\r
+    { return max(static_cast<_Tp>(-1)/sizeof(_Tp), 1); }\r
+\r
+    void construct(pointer p, const _Tp& v) { new(static_cast<void*>(p)) _Tp(v); }\r
+    void destroy(pointer p) { p->~_Tp(); }\r
+};\r
+\r
+/////////////////////// Vec (used as element of multi-channel images ///////////////////// \r
+\r
+template<typename _Tp> class CV_EXPORTS DataDepth { public: enum { value = -1, fmt=(int)'\0' }; };\r
+\r
+template<> class DataDepth<bool> { public: enum { value = CV_8U, fmt=(int)'u' }; };\r
+template<> class DataDepth<uchar> { public: enum { value = CV_8U, fmt=(int)'u' }; };\r
+template<> class DataDepth<schar> { public: enum { value = CV_8S, fmt=(int)'c' }; };\r
+template<> class DataDepth<ushort> { public: enum { value = CV_16U, fmt=(int)'w' }; };\r
+template<> class DataDepth<short> { public: enum { value = CV_16S, fmt=(int)'s' }; };\r
+template<> class DataDepth<int> { public: enum { value = CV_32S, fmt=(int)'i' }; };\r
+template<> class DataDepth<float> { public: enum { value = CV_32F, fmt=(int)'f' }; };\r
+template<> class DataDepth<double> { public: enum { value = CV_64F, fmt=(int)'d' }; };\r
+template<typename _Tp> class DataDepth<_Tp*> { public: enum { value = CV_USRTYPE1, fmt=(int)'r' }; };\r
+\r
+template<typename _Tp, int cn> class CV_EXPORTS Vec\r
+{\r
+public:\r
+    typedef _Tp value_type;\r
+    enum { depth = DataDepth<_Tp>::value, channels = cn, type = CV_MAKETYPE(depth, channels) };\r
+    \r
+    Vec();\r
+    Vec(_Tp v0);\r
+    Vec(_Tp v0, _Tp v1);\r
+    Vec(_Tp v0, _Tp v1, _Tp v2);\r
+    Vec(_Tp v0, _Tp v1, _Tp v2, _Tp v3);\r
+    Vec(_Tp v0, _Tp v1, _Tp v2, _Tp v3, _Tp v4);\r
+    Vec(_Tp v0, _Tp v1, _Tp v2, _Tp v3, _Tp v4, _Tp v5);\r
+    Vec(_Tp v0, _Tp v1, _Tp v2, _Tp v3, _Tp v4, _Tp v5, _Tp v6);\r
+    Vec(_Tp v0, _Tp v1, _Tp v2, _Tp v3, _Tp v4, _Tp v5, _Tp v6, _Tp v7);\r
+    Vec(_Tp v0, _Tp v1, _Tp v2, _Tp v3, _Tp v4, _Tp v5, _Tp v6, _Tp v7, _Tp v8);\r
+    Vec(_Tp v0, _Tp v1, _Tp v2, _Tp v3, _Tp v4, _Tp v5, _Tp v6, _Tp v7, _Tp v8, _Tp v9);\r
+    Vec(const Vec<_Tp, cn>& v);\r
+    static Vec all(_Tp alpha);\r
+    _Tp dot(const Vec& v) const;\r
+    double ddot(const Vec& v) const;\r
+    Vec cross(const Vec& v) const;\r
+    template<typename T2> operator Vec<T2, cn>() const;\r
+    operator CvScalar() const;\r
+    _Tp operator [](int i) const;\r
+    _Tp& operator[](int i);\r
+\r
+    _Tp val[cn];\r
+};\r
+\r
+typedef Vec<uchar, 2> Vec2b;\r
+typedef Vec<uchar, 3> Vec3b;\r
+typedef Vec<uchar, 4> Vec4b;\r
+\r
+typedef Vec<short, 2> Vec2s;\r
+typedef Vec<short, 3> Vec3s;\r
+typedef Vec<short, 4> Vec4s;\r
+\r
+typedef Vec<int, 2> Vec2i;\r
+typedef Vec<int, 3> Vec3i;\r
+typedef Vec<int, 4> Vec4i;\r
+\r
+typedef Vec<float, 2> Vec2f;\r
+typedef Vec<float, 3> Vec3f;\r
+typedef Vec<float, 4> Vec4f;\r
+typedef Vec<float, 6> Vec6f;\r
+\r
+typedef Vec<double, 2> Vec2d;\r
+typedef Vec<double, 3> Vec3d;\r
+typedef Vec<double, 4> Vec4d;\r
+typedef Vec<double, 6> Vec6d;\r
+\r
+//////////////////////////////// Complex //////////////////////////////\r
+\r
+template<typename _Tp> class CV_EXPORTS Complex\r
+{\r
+public:\r
+    Complex();\r
+    Complex( _Tp _re, _Tp _im=0 );\r
+    Complex( const std::complex<_Tp>& c );\r
+    template<typename T2> operator Complex<T2>() const;\r
+    Complex conj() const;\r
+    operator std::complex<_Tp>() const;\r
+\r
+    _Tp re, im;\r
+};\r
+\r
+typedef Complex<float> Complexf;\r
+typedef Complex<double> Complexd;\r
+\r
+//////////////////////////////// Point_ ////////////////////////////////\r
+\r
+template<typename _Tp> class CV_EXPORTS Point_\r
+{\r
+public:\r
+    typedef _Tp value_type;\r
+    \r
+    Point_();\r
+    Point_(_Tp _x, _Tp _y);\r
+    Point_(const Point_& pt);\r
+    Point_(const CvPoint& pt);\r
+    Point_(const CvPoint2D32f& pt);\r
+    Point_(const Size_<_Tp>& sz);\r
+    Point_& operator = (const Point_& pt);\r
+    operator Point_<int>() const;\r
+    operator Point_<float>() const;\r
+    operator Point_<double>() const;\r
+    operator CvPoint() const;\r
+    operator CvPoint2D32f() const;\r
+\r
+    _Tp dot(const Point_& pt) const;\r
+    double ddot(const Point_& pt) const;\r
+    bool inside(const Rect_<_Tp>& r) const;\r
+    \r
+    _Tp x, y;\r
+};\r
+\r
+template<typename _Tp> class CV_EXPORTS Point3_\r
+{\r
+public:\r
+    typedef _Tp value_type;\r
+    \r
+    Point3_();\r
+    Point3_(_Tp _x, _Tp _y, _Tp _z);\r
+    Point3_(const Point3_& pt);\r
+       Point3_(const Point_<_Tp>& pt);\r
+    Point3_(const CvPoint3D32f& pt);\r
+    Point3_(const Vec<_Tp, 3>& t);\r
+    Point3_& operator = (const Point3_& pt);\r
+    operator Point3_<int>() const;\r
+    operator Point3_<float>() const;\r
+    operator Point3_<double>() const;\r
+    operator CvPoint3D32f() const;\r
+\r
+    _Tp dot(const Point3_& pt) const;\r
+    double ddot(const Point3_& pt) const;\r
+    \r
+    _Tp x, y, z;\r
+};\r
+\r
+//////////////////////////////// Size_ ////////////////////////////////\r
+\r
+template<typename _Tp> class CV_EXPORTS Size_\r
+{\r
+public:\r
+    typedef _Tp value_type;\r
+    \r
+    Size_();\r
+    Size_(_Tp _width, _Tp _height);\r
+    Size_(const Size_& sz);\r
+    Size_(const CvSize& sz);\r
+    Size_(const CvSize2D32f& sz);\r
+    Size_(const Point_<_Tp>& pt);\r
+    Size_& operator = (const Size_& sz);\r
+    _Tp area() const;\r
+\r
+    operator Size_<int>() const;\r
+    operator Size_<float>() const;\r
+    operator Size_<double>() const;\r
+    operator CvSize() const;\r
+    operator CvSize2D32f() const;\r
+\r
+    _Tp width, height;\r
+};\r
+\r
+//////////////////////////////// Rect_ ////////////////////////////////\r
+\r
+template<typename _Tp> class CV_EXPORTS Rect_\r
+{\r
+public:\r
+    typedef _Tp value_type;\r
+    \r
+    Rect_();\r
+    Rect_(_Tp _x, _Tp _y, _Tp _width, _Tp _height);\r
+    Rect_(const Rect_& r);\r
+    Rect_(const CvRect& r);\r
+    Rect_(const Point_<_Tp>& org, const Size_<_Tp>& sz);\r
+    Rect_(const Point_<_Tp>& pt1, const Point_<_Tp>& pt2);\r
+    Rect_& operator = ( const Rect_& r );\r
+    Point_<_Tp> tl() const;\r
+    Point_<_Tp> br() const;\r
+    \r
+    Size_<_Tp> size() const;\r
+    _Tp area() const;\r
+\r
+    operator Rect_<int>() const;\r
+    operator Rect_<float>() const;\r
+    operator Rect_<double>() const;\r
+    operator CvRect() const;\r
+\r
+    bool contains(const Point_<_Tp>& pt) const;\r
+\r
+    _Tp x, y, width, height;\r
+};\r
+\r
+typedef Point_<int> Point2i;\r
+typedef Point2i Point;\r
+typedef Size_<int> Size2i;\r
+typedef Size2i Size;\r
+typedef Rect_<int> Rect;\r
+typedef Point_<float> Point2f;\r
+typedef Point_<double> Point2d;\r
+typedef Size_<float> Size2f;\r
+typedef Point3_<int> Point3i;\r
+typedef Point3_<float> Point3f;\r
+typedef Point3_<double> Point3d;\r
+\r
+class CV_EXPORTS RotatedRect\r
+{\r
+public:\r
+    RotatedRect();\r
+    RotatedRect(const Point2f& _center, const Size2f& _size, float _angle);\r
+    RotatedRect(const CvBox2D& box);\r
+    Rect boundingRect() const;\r
+    operator CvBox2D() const;\r
+    Point2f center;\r
+    Size2f size;\r
+    float angle;\r
+};\r
+\r
+//////////////////////////////// Scalar_ ///////////////////////////////\r
+\r
+template<typename _Tp> class CV_EXPORTS Scalar_ : public Vec<_Tp, 4>\r
+{\r
+public:\r
+    Scalar_();\r
+    Scalar_(_Tp v0, _Tp v1, _Tp v2=0, _Tp v3=0);\r
+    Scalar_(const CvScalar& s);\r
+    Scalar_(_Tp v0);\r
+    static Scalar_<_Tp> all(_Tp v0);\r
+    operator CvScalar() const;\r
+\r
+    template<typename T2> operator Scalar_<T2>() const;\r
+\r
+    Scalar_<_Tp> mul(const Scalar_<_Tp>& t, double scale=1 ) const;\r
+    template<typename T2> void convertTo(T2* buf, int channels, int unroll_to=0) const;\r
+};\r
+\r
+typedef Scalar_<double> Scalar;\r
+\r
+//////////////////////////////// Range /////////////////////////////////\r
+\r
+class CV_EXPORTS Range\r
+{\r
+public:\r
+    Range();\r
+    Range(int _start, int _end);\r
+    Range(const CvSlice& slice);\r
+    int size() const;\r
+    bool empty() const;\r
+    static Range all();\r
+    operator CvSlice() const;\r
+\r
+    int start, end;\r
+};\r
+\r
+/////////////////////////////// DataType ////////////////////////////////\r
+\r
+template<typename _Tp> class DataType\r
+{\r
+public:\r
+    typedef _Tp value_type;\r
+    typedef value_type work_type;\r
+    typedef value_type channel_type;\r
+    enum { depth = DataDepth<channel_type>::value, channels = 1,\r
+           fmt=DataDepth<channel_type>::fmt,\r
+           type = CV_MAKETYPE(depth, channels) };\r
+};\r
+\r
+template<> class DataType<bool>\r
+{\r
+public:\r
+    typedef bool value_type;\r
+    typedef int work_type;\r
+    typedef value_type channel_type;\r
+    enum { depth = DataDepth<channel_type>::value, channels = 1,\r
+           fmt=DataDepth<channel_type>::fmt,\r
+           type = CV_MAKETYPE(depth, channels) };\r
+};\r
+\r
+template<> class DataType<uchar>\r
+{\r
+public:\r
+    typedef uchar value_type;\r
+    typedef int work_type;\r
+    typedef value_type channel_type;\r
+    enum { depth = DataDepth<channel_type>::value, channels = 1,\r
+           fmt=DataDepth<channel_type>::fmt,\r
+           type = CV_MAKETYPE(depth, channels) };\r
+};\r
+\r
+template<> class DataType<schar>\r
+{\r
+public:\r
+    typedef schar value_type;\r
+    typedef int work_type;\r
+    typedef value_type channel_type;\r
+    enum { depth = DataDepth<channel_type>::value, channels = 1,\r
+           fmt=DataDepth<channel_type>::fmt,\r
+           type = CV_MAKETYPE(depth, channels) };\r
+};\r
+\r
+template<> class DataType<ushort>\r
+{\r
+public:\r
+    typedef ushort value_type;\r
+    typedef int work_type;\r
+    typedef value_type channel_type;\r
+    enum { depth = DataDepth<channel_type>::value, channels = 1,\r
+           fmt=DataDepth<channel_type>::fmt,\r
+           type = CV_MAKETYPE(depth, channels) };\r
+};\r
+\r
+template<> class DataType<short>\r
+{\r
+public:\r
+    typedef short value_type;\r
+    typedef int work_type;\r
+    typedef value_type channel_type;\r
+    enum { depth = DataDepth<channel_type>::value, channels = 1,\r
+           fmt=DataDepth<channel_type>::fmt,\r
+           type = CV_MAKETYPE(depth, channels) };\r
+};\r
+\r
+template<> class DataType<int>\r
+{\r
+public:\r
+    typedef int value_type;\r
+    typedef value_type work_type;\r
+    typedef value_type channel_type;\r
+    enum { depth = DataDepth<channel_type>::value, channels = 1,\r
+           fmt=DataDepth<channel_type>::fmt,\r
+           type = CV_MAKETYPE(depth, channels) };\r
+};\r
+\r
+template<> class DataType<float>\r
+{\r
+public:\r
+    typedef float value_type;\r
+    typedef value_type work_type;\r
+    typedef value_type channel_type;\r
+    enum { depth = DataDepth<channel_type>::value, channels = 1,\r
+           fmt=DataDepth<channel_type>::fmt,\r
+           type = CV_MAKETYPE(depth, channels) };\r
+};\r
+\r
+template<> class DataType<double>\r
+{\r
+public:\r
+    typedef double value_type;\r
+    typedef value_type work_type;\r
+    typedef value_type channel_type;\r
+    enum { depth = DataDepth<channel_type>::value, channels = 1,\r
+           fmt=DataDepth<channel_type>::fmt,\r
+           type = CV_MAKETYPE(depth, channels) };\r
+};\r
+\r
+template<typename _Tp, int cn> class DataType<Vec<_Tp, cn> >\r
+{\r
+public:\r
+    typedef Vec<_Tp, cn> value_type;\r
+    typedef Vec<typename DataType<_Tp>::work_type, cn> work_type;\r
+    typedef _Tp channel_type;\r
+    enum { depth = DataDepth<channel_type>::value, channels = cn,\r
+           fmt = ((channels-1)<<8) + DataDepth<channel_type>::fmt,\r
+           type = CV_MAKETYPE(depth, channels) };\r
+};\r
+\r
+template<typename _Tp> class DataType<std::complex<_Tp> >\r
+{\r
+public:\r
+    typedef std::complex<_Tp> value_type;\r
+    typedef value_type work_type;\r
+    typedef _Tp channel_type;\r
+    enum { depth = DataDepth<channel_type>::value, channels = 2,\r
+           fmt = ((channels-1)<<8) + DataDepth<channel_type>::fmt,\r
+           type = CV_MAKETYPE(depth, channels) };\r
+};\r
+\r
+template<typename _Tp> class DataType<Complex<_Tp> >\r
+{\r
+public:\r
+    typedef Complex<_Tp> value_type;\r
+    typedef value_type work_type;\r
+    typedef _Tp channel_type;\r
+    enum { depth = DataDepth<channel_type>::value, channels = 2,\r
+           fmt = ((channels-1)<<8) + DataDepth<channel_type>::fmt,\r
+           type = CV_MAKETYPE(depth, channels) };\r
+};\r
+\r
+template<typename _Tp> class DataType<Point_<_Tp> >\r
+{\r
+public:\r
+    typedef Point_<_Tp> value_type;\r
+    typedef Point_<typename DataType<_Tp>::work_type> work_type;\r
+    typedef _Tp channel_type;\r
+    enum { depth = DataDepth<channel_type>::value, channels = 2,\r
+           fmt = ((channels-1)<<8) + DataDepth<channel_type>::fmt,\r
+           type = CV_MAKETYPE(depth, channels) };\r
+};\r
+\r
+template<typename _Tp> class DataType<Point3_<_Tp> >\r
+{\r
+public:\r
+    typedef Point3_<_Tp> value_type;\r
+    typedef Point3_<typename DataType<_Tp>::work_type> work_type;\r
+    typedef _Tp channel_type;\r
+    enum { depth = DataDepth<channel_type>::value, channels = 3,\r
+           fmt = ((channels-1)<<8) + DataDepth<channel_type>::fmt,\r
+           type = CV_MAKETYPE(depth, channels) };\r
+};\r
+\r
+template<typename _Tp> class DataType<Size_<_Tp> >\r
+{\r
+public:\r
+    typedef Size_<_Tp> value_type;\r
+    typedef Size_<typename DataType<_Tp>::work_type> work_type;\r
+    typedef _Tp channel_type;\r
+    enum { depth = DataDepth<channel_type>::value, channels = 2,\r
+           fmt = ((channels-1)<<8) + DataDepth<channel_type>::fmt,\r
+           type = CV_MAKETYPE(depth, channels) };\r
+};\r
+\r
+template<typename _Tp> class DataType<Rect_<_Tp> >\r
+{\r
+public:\r
+    typedef Rect_<_Tp> value_type;\r
+    typedef Rect_<typename DataType<_Tp>::work_type> work_type;\r
+    typedef _Tp channel_type;\r
+    enum { depth = DataDepth<channel_type>::value, channels = 4,\r
+           fmt = ((channels-1)<<8) + DataDepth<channel_type>::fmt,\r
+           type = CV_MAKETYPE(depth, channels) };\r
+};\r
+\r
+template<typename _Tp> class DataType<Scalar_<_Tp> >\r
+{\r
+public:\r
+    typedef Scalar_<_Tp> value_type;\r
+    typedef Scalar_<typename DataType<_Tp>::work_type> work_type;\r
+    typedef _Tp channel_type;\r
+    enum { depth = DataDepth<channel_type>::value, channels = 4,\r
+           fmt = ((channels-1)<<8) + DataDepth<channel_type>::fmt,\r
+           type = CV_MAKETYPE(depth, channels) };\r
+};\r
+\r
+template<> class DataType<Range>\r
+{\r
+public:\r
+    typedef Range value_type;\r
+    typedef value_type work_type;\r
+    typedef int channel_type;\r
+    enum { depth = DataDepth<channel_type>::value, channels = 2,\r
+           fmt = ((channels-1)<<8) + DataDepth<channel_type>::fmt,\r
+           type = CV_MAKETYPE(depth, channels) };\r
+};\r
+\r
+\r
+//////////////////////////////// Vector ////////////////////////////////\r
+\r
+// template vector class. It is similar to STL's vector,\r
+// with a few important differences:\r
+//   1) it can be created on top of user-allocated data w/o copying it\r
+//   2) Vector b = a means copying the header,\r
+//      not the underlying data (use clone() to make a deep copy)\r
+template <typename _Tp> class CV_EXPORTS Vector\r
+{\r
+public:\r
+    typedef _Tp value_type;\r
+    typedef _Tp* iterator;\r
+    typedef const _Tp* const_iterator;\r
+    typedef _Tp& reference;\r
+    typedef const _Tp& const_reference;\r
+\r
+    struct CV_EXPORTS Hdr\r
+    {\r
+        Hdr() : data(0), datastart(0), refcount(0), size(0), capacity(0) {};\r
+        _Tp* data;\r
+        _Tp* datastart;\r
+        int* refcount;\r
+        size_t size;\r
+        size_t capacity;\r
+    };\r
+\r
+    Vector();\r
+    Vector(size_t _size);\r
+    Vector(size_t _size, const _Tp& val);\r
+    Vector(_Tp* _data, size_t _size, bool _copyData=false);\r
+    template<int n> Vector(const Vec<_Tp, n>& vec);\r
+    Vector(const std::vector<_Tp>& vec, bool _copyData=false);\r
+    Vector(const Vector& d);\r
+    Vector(const Vector& d, const Range& r);\r
+\r
+    Vector<_Tp>& operator = (const Vector& d);\r
+    ~Vector();\r
+    Vector clone() const;\r
+    void copyTo(Vector<_Tp>& vec) const;\r
+    void copyTo(std::vector<_Tp>& vec) const;\r
+    operator CvMat() const;\r
+    \r
+    _Tp& operator [] (size_t i);\r
+    const _Tp& operator [] (size_t i) const;\r
+    _Tp& operator [] (int i);\r
+    const _Tp& operator [] (int i) const;\r
+    Vector operator() (const Range& r) const;\r
+    _Tp& back();\r
+    const _Tp& back() const;\r
+    _Tp& front();\r
+    const _Tp& front() const;\r
+\r
+    _Tp* begin();\r
+    _Tp* end();\r
+    const _Tp* begin() const;\r
+    const _Tp* end() const;\r
+\r
+    void addref();\r
+    void release();\r
+    void set(_Tp* _data, size_t _size, bool _copyData=false);\r
+\r
+    void reserve(size_t newCapacity);\r
+    void resize(size_t newSize);\r
+    Vector<_Tp>& push_back(const _Tp& elem);\r
+    Vector<_Tp>& pop_back();\r
+    size_t size() const;\r
+    size_t capacity() const;\r
+    bool empty() const;\r
+    void clear();\r
+    int type() const;\r
+\r
+protected:\r
+    Hdr hdr;\r
+};\r
+\r
+//////////////////// Generic ref-cointing pointer class for C/C++ objects ////////////////////////\r
+\r
+template<typename _Tp> class CV_EXPORTS Ptr\r
+{\r
+public:\r
+    Ptr();\r
+    Ptr(_Tp* _obj);\r
+    ~Ptr();\r
+    Ptr(const Ptr& ptr);\r
+    Ptr& operator = (const Ptr& ptr);\r
+    void addref();\r
+    void release();\r
+    void delete_obj();\r
+    bool empty() const;\r
+\r
+    _Tp* operator -> ();\r
+    const _Tp* operator -> () const;\r
+\r
+    operator _Tp* ();\r
+    operator const _Tp*() const;\r
+protected:\r
+    _Tp* obj;\r
+    int* refcount;\r
+};\r
+\r
+//////////////////////////////// Mat ////////////////////////////////\r
+\r
+class Mat;\r
+template<typename M> class CV_EXPORTS MatExpr_Base_;\r
+typedef MatExpr_Base_<Mat> MatExpr_Base;\r
+template<typename E, typename M> class MatExpr_;\r
+template<typename A1, typename M, typename Op> class MatExpr_Op1_;\r
+template<typename A1, typename A2, typename M, typename Op> class MatExpr_Op2_;\r
+template<typename A1, typename A2, typename A3, typename M, typename Op> class MatExpr_Op3_;\r
+template<typename A1, typename A2, typename A3, typename A4,\r
+        typename M, typename Op> class MatExpr_Op4_;\r
+template<typename A1, typename A2, typename A3, typename A4,\r
+        typename A5, typename M, typename Op> class MatExpr_Op5_;\r
+template<typename M> class CV_EXPORTS MatOp_DivRS_;\r
+template<typename M> class CV_EXPORTS MatOp_Inv_;\r
+template<typename M> class CV_EXPORTS MatOp_MulDiv_;\r
+template<typename M> class CV_EXPORTS MatOp_Repeat_;\r
+template<typename M> class CV_EXPORTS MatOp_Set_;\r
+template<typename M> class CV_EXPORTS MatOp_Scale_;\r
+template<typename M> class CV_EXPORTS MatOp_T_;\r
+\r
+typedef MatExpr_<MatExpr_Op4_<Size, int, Scalar,\r
+    int, Mat, MatOp_Set_<Mat> >, Mat> MatExpr_Initializer;\r
+\r
+template<typename _Tp> class MatIterator_;\r
+template<typename _Tp> class MatConstIterator_;\r
+\r
+enum { MAGIC_MASK=0xFFFF0000, TYPE_MASK=0x00000FFF, DEPTH_MASK=7 };\r
+\r
+static inline size_t getElemSize(int type) { return CV_ELEM_SIZE(type); }\r
+\r
+// matrix decomposition types\r
+enum { DECOMP_LU=0, DECOMP_SVD=1, DECOMP_EIG=2, DECOMP_CHOLESKY=3, DECOMP_QR=4, DECOMP_NORMAL=16 };\r
+enum { NORM_INF=1, NORM_L1=2, NORM_L2=4, NORM_TYPE_MASK=7, NORM_RELATIVE=8};\r
+enum { CMP_EQ=0, CMP_GT=1, CMP_GE=2, CMP_LT=3, CMP_LE=4, CMP_NE=5 };\r
+enum { GEMM_1_T=1, GEMM_2_T=2, GEMM_3_T=4 };\r
+enum { DFT_INVERSE=1, DFT_SCALE=2, DFT_ROWS=4, DFT_COMPLEX_OUTPUT=16, DFT_REAL_OUTPUT=32,\r
+    DCT_INVERSE = DFT_INVERSE, DCT_ROWS=DFT_ROWS };\r
+\r
+class CV_EXPORTS Mat\r
+{\r
+public:\r
+    Mat();\r
+    Mat(int _rows, int _cols, int _type);\r
+    Mat(int _rows, int _cols, int _type, const Scalar& _s);\r
+    Mat(Size _size, int _type);\r
+    Mat(const Mat& m);\r
+    Mat(int _rows, int _cols, int _type, void* _data, size_t _step=AUTO_STEP);\r
+    Mat(Size _size, int _type, void* _data, size_t _step=AUTO_STEP);\r
+    Mat(const Mat& m, const Range& rowRange, const Range& colRange);\r
+    Mat(const Mat& m, const Rect& roi);\r
+    Mat(const CvMat* m, bool copyData=false);\r
+    Mat(const IplImage* img, bool copyData=false);\r
+    Mat( const MatExpr_Base& expr );\r
+    ~Mat();\r
+    Mat& operator = (const Mat& m);\r
+    Mat& operator = (const MatExpr_Base& expr);\r
+\r
+    operator MatExpr_<Mat, Mat>() const;\r
+\r
+    Mat row(int y) const;\r
+    Mat col(int x) const;\r
+    Mat rowRange(int startrow, int endrow) const;\r
+    Mat rowRange(const Range& r) const;\r
+    Mat colRange(int startcol, int endcol) const;\r
+    Mat colRange(const Range& r) const;\r
+    Mat diag(int d=0) const;\r
+    static Mat diag(const Mat& d);\r
+\r
+    Mat clone() const;\r
+    void copyTo( Mat& m ) const;\r
+    void copyTo( Mat& m, const Mat& mask ) const;\r
+    void convertTo( Mat& m, int rtype, double alpha=1, double beta=0 ) const;\r
+\r
+    void assignTo( Mat& m, int type=-1 ) const;\r
+    Mat& operator = (const Scalar& s);\r
+    Mat& setTo(const Scalar& s, const Mat& mask=Mat());\r
+    Mat reshape(int _cn, int _rows=0) const;\r
+\r
+    MatExpr_<MatExpr_Op2_<Mat, double, Mat, MatOp_T_<Mat> >, Mat>\r
+    t() const;\r
+    MatExpr_<MatExpr_Op2_<Mat, int, Mat, MatOp_Inv_<Mat> >, Mat>\r
+        inv(int method=DECOMP_LU) const;\r
+    MatExpr_<MatExpr_Op4_<Mat, Mat, double, char, Mat, MatOp_MulDiv_<Mat> >, Mat>\r
+    mul(const Mat& m, double scale=1) const;\r
+    MatExpr_<MatExpr_Op4_<Mat, Mat, double, char, Mat, MatOp_MulDiv_<Mat> >, Mat>\r
+    mul(const MatExpr_<MatExpr_Op2_<Mat, double, Mat, MatOp_Scale_<Mat> >, Mat>& m, double scale=1) const;\r
+    MatExpr_<MatExpr_Op4_<Mat, Mat, double, char, Mat, MatOp_MulDiv_<Mat> >, Mat>    \r
+    mul(const MatExpr_<MatExpr_Op2_<Mat, double, Mat, MatOp_DivRS_<Mat> >, Mat>& m, double scale=1) const;\r
+\r
+    Mat cross(const Mat& m) const;\r
+    double dot(const Mat& m) const;\r
+\r
+    static MatExpr_Initializer zeros(int rows, int cols, int type);\r
+    static MatExpr_Initializer zeros(Size size, int type);\r
+    static MatExpr_Initializer ones(int rows, int cols, int type);\r
+    static MatExpr_Initializer ones(Size size, int type);\r
+    static MatExpr_Initializer eye(int rows, int cols, int type);\r
+    static MatExpr_Initializer eye(Size size, int type);\r
+\r
+    void create(int _rows, int _cols, int _type);\r
+    void create(Size _size, int _type);\r
+    void addref();\r
+    void release();\r
+\r
+    void locateROI( Size& wholeSize, Point& ofs ) const;\r
+    Mat& adjustROI( int dtop, int dbottom, int dleft, int dright );\r
+    Mat operator()( Range rowRange, Range colRange ) const;\r
+    Mat operator()( const Rect& roi ) const;\r
+\r
+    operator CvMat() const;\r
+    operator IplImage() const;\r
+    bool isContinuous() const;\r
+    size_t elemSize() const;\r
+    size_t elemSize1() const;\r
+    int type() const;\r
+    int depth() const;\r
+    int channels() const;\r
+    size_t step1() const;\r
+    Size size() const;\r
+\r
+    uchar* ptr(int y=0);\r
+    const uchar* ptr(int y=0) const;\r
+\r
+    template<typename _Tp> _Tp* ptr(int y=0);\r
+    template<typename _Tp> const _Tp* ptr(int y=0) const;\r
+\r
+    enum { MAGIC_VAL=0x42FF0000, AUTO_STEP=0, CONTINUOUS_FLAG=CV_MAT_CONT_FLAG };\r
+\r
+    int flags;\r
+    int rows, cols;\r
+    size_t step;\r
+    uchar* data;\r
+\r
+    int* refcount;\r
+    uchar* datastart;\r
+    uchar* dataend;\r
+};\r
+\r
+\r
+// Multiply-with-Carry RNG\r
+class CV_EXPORTS RNG\r
+{\r
+public:\r
+    enum { A=4164903690U, UNIFORM=0, NORMAL=1 };\r
+\r
+    RNG();\r
+    RNG(uint64 _state);\r
+    unsigned next();\r
+\r
+    operator uchar();\r
+    operator schar();\r
+    operator ushort();\r
+    operator short();\r
+    operator unsigned();\r
+    operator int();\r
+    operator float();\r
+    operator double();\r
+    int uniform(int a, int b);\r
+    float uniform(float a, float b);\r
+    double uniform(double a, double b);\r
+    void fill( Mat& mat, int distType, const Scalar& a, const Scalar& b );\r
+\r
+    uint64 state;\r
+};\r
+\r
+class CV_EXPORTS TermCriteria\r
+{\r
+public:\r
+    enum { COUNT=1, MAX_ITER=COUNT, EPS=2 };\r
+\r
+    TermCriteria();\r
+    TermCriteria(int _type, int _maxCount, double _epsilon);\r
+    TermCriteria(const CvTermCriteria& criteria);\r
+    operator CvTermCriteria() const;\r
+    \r
+    int type;\r
+    int maxCount;\r
+    double epsilon;\r
+};\r
+\r
+CV_EXPORTS Mat cvarrToMat(const CvArr* arr, bool copyData=false, bool allowND=true);\r
+CV_EXPORTS Mat extractImageCOI(const CvArr* arr);\r
+\r
+CV_EXPORTS void add(const Mat& a, const Mat& b, Mat& c, const Mat& mask);\r
+CV_EXPORTS void subtract(const Mat& a, const Mat& b, Mat& c, const Mat& mask);\r
+CV_EXPORTS void add(const Mat& a, const Mat& b, Mat& c);\r
+CV_EXPORTS void subtract(const Mat& a, const Mat& b, Mat& c);\r
+CV_EXPORTS void add(const Mat& a, const Scalar& s, Mat& c, const Mat& mask=Mat());\r
+CV_EXPORTS void subtract(const Mat& a, const Scalar& s, Mat& c, const Mat& mask=Mat());\r
+\r
+CV_EXPORTS void multiply(const Mat& a, const Mat& b, Mat& c, double scale=1);\r
+CV_EXPORTS void divide(const Mat& a, const Mat& b, Mat& c, double scale=1);\r
+CV_EXPORTS void divide(double scale, const Mat& b, Mat& c);\r
+\r
+CV_EXPORTS void subtract(const Scalar& s, const Mat& a, Mat& c, const Mat& mask=Mat());\r
+CV_EXPORTS void scaleAdd(const Mat& a, double alpha, const Mat& b, Mat& c);\r
+CV_EXPORTS void addWeighted(const Mat& a, double alpha, const Mat& b,\r
+                            double beta, double gamma, Mat& c);\r
+CV_EXPORTS void convertScaleAbs(const Mat& a, Mat& c, double alpha=1, double beta=0);\r
+CV_EXPORTS void LUT(const Mat& a, const Mat& lut, Mat& b);\r
+\r
+CV_EXPORTS Scalar sum(const Mat& m);\r
+CV_EXPORTS int countNonZero( const Mat& m );\r
+\r
+CV_EXPORTS Scalar mean(const Mat& m);\r
+CV_EXPORTS Scalar mean(const Mat& m, const Mat& mask);\r
+CV_EXPORTS void meanStdDev(const Mat& m, Scalar& mean, Scalar& stddev, const Mat& mask=Mat());\r
+CV_EXPORTS double norm(const Mat& a, int normType=NORM_L2);\r
+CV_EXPORTS double norm(const Mat& a, const Mat& b, int normType=NORM_L2);\r
+CV_EXPORTS double norm(const Mat& a, int normType, const Mat& mask);\r
+CV_EXPORTS double norm(const Mat& a, const Mat& b,\r
+                       int normType, const Mat& mask);\r
+CV_EXPORTS void normalize( const Mat& a, Mat& b, double alpha=1, double beta=0,\r
+                          int norm_type=NORM_L2, int rtype=-1, const Mat& mask=Mat());\r
+\r
+CV_EXPORTS void minMaxLoc(const Mat& a, double* minVal,\r
+                          double* maxVal=0, Point* minLoc=0,\r
+                          Point* maxLoc=0, const Mat& mask=Mat());\r
+CV_EXPORTS void reduce(const Mat& m, Mat& dst, int dim, int rtype, int dtype=-1);\r
+CV_EXPORTS void merge(const Vector<Mat>& mv, Mat& dst);\r
+CV_EXPORTS void split(const Mat& m, Vector<Mat>& mv);\r
+CV_EXPORTS void mixChannels(const Vector<Mat>& src, Vector<Mat>& dst,\r
+                            const Vector<int>& fromTo);\r
+CV_EXPORTS void flip(const Mat& a, Mat& b, int flipCode);\r
+\r
+CV_EXPORTS void repeat(const Mat& a, int ny, int nx, Mat& b);\r
+static inline Mat repeat(const Mat& src, int ny, int nx)\r
+{\r
+    if( nx == 1 && ny == 1 ) return src;\r
+    Mat dst; repeat(src, ny, nx, dst); return dst;\r
+}\r
+\r
+CV_EXPORTS void bitwise_and(const Mat& a, const Mat& b, Mat& c, const Mat& mask=Mat());\r
+CV_EXPORTS void bitwise_or(const Mat& a, const Mat& b, Mat& c, const Mat& mask=Mat());\r
+CV_EXPORTS void bitwise_xor(const Mat& a, const Mat& b, Mat& c, const Mat& mask=Mat());\r
+CV_EXPORTS void bitwise_and(const Mat& a, const Scalar& s, Mat& c, const Mat& mask=Mat());\r
+CV_EXPORTS void bitwise_or(const Mat& a, const Scalar& s, Mat& c, const Mat& mask=Mat());\r
+CV_EXPORTS void bitwise_xor(const Mat& a, const Scalar& s, Mat& c, const Mat& mask=Mat());\r
+CV_EXPORTS void bitwise_not(const Mat& a, Mat& c);\r
+CV_EXPORTS void absdiff(const Mat& a, const Mat& b, Mat& c);\r
+CV_EXPORTS void absdiff(const Mat& a, const Scalar& s, Mat& c);\r
+CV_EXPORTS void inRange(const Mat& src, const Mat& lowerb,\r
+                        const Mat& upperb, Mat& dst);\r
+CV_EXPORTS void inRange(const Mat& src, const Scalar& lowerb,\r
+                        const Scalar& upperb, Mat& dst);\r
+CV_EXPORTS void compare(const Mat& a, const Mat& b, Mat& c, int cmpop);\r
+CV_EXPORTS void compare(const Mat& a, double s, Mat& c, int cmpop);\r
+CV_EXPORTS void min(const Mat& a, const Mat& b, Mat& c);\r
+CV_EXPORTS void min(const Mat& a, double alpha, Mat& c);\r
+CV_EXPORTS void max(const Mat& a, const Mat& b, Mat& c);\r
+CV_EXPORTS void max(const Mat& a, double alpha, Mat& c);\r
+\r
+CV_EXPORTS void sqrt(const Mat& a, Mat& b);\r
+CV_EXPORTS void pow(const Mat& a, double power, Mat& b);\r
+CV_EXPORTS void exp(const Mat& a, Mat& b);\r
+CV_EXPORTS void log(const Mat& a, Mat& b);\r
+CV_EXPORTS float cubeRoot(float val);\r
+CV_EXPORTS float fastAtan2(float y, float x);\r
+CV_EXPORTS void polarToCart(const Mat& magnitude, const Mat& angle,\r
+                            Mat& x, Mat& y, bool angleInDegrees=false);\r
+CV_EXPORTS void cartToPolar(const Mat& x, const Mat& y,\r
+                            Mat& magnitude, Mat& angle,\r
+                            bool angleInDegrees=false);\r
+CV_EXPORTS void phase(const Mat& x, const Mat& y, Mat& angle,\r
+                            bool angleInDegrees=false);\r
+CV_EXPORTS void magnitude(const Mat& x, const Mat& y, Mat& magnitude);\r
+CV_EXPORTS bool checkRange(const Mat& a, bool quiet=true, Point* pt=0,\r
+                           double minVal=-DBL_MAX, double maxVal=DBL_MAX);\r
+\r
+CV_EXPORTS void gemm(const Mat& a, const Mat& b, double alpha,\r
+                     const Mat& c, double gamma, Mat& d, int flags=0);\r
+CV_EXPORTS void mulTransposed( const Mat& a, Mat& c, bool aTa,\r
+                               const Mat& delta=Mat(),\r
+                               double scale=1, int rtype=-1 );\r
+CV_EXPORTS void transpose(const Mat& a, Mat& b);\r
+CV_EXPORTS void transform(const Mat& src, Mat& dst, const Mat& m );\r
+CV_EXPORTS void perspectiveTransform(const Mat& src, Mat& dst, const Mat& m );\r
+\r
+CV_EXPORTS void completeSymm(Mat& a, bool lowerToUpper=false);\r
+CV_EXPORTS void setIdentity(Mat& c, const Scalar& s=Scalar(1));\r
+CV_EXPORTS double determinant(const Mat& m);\r
+CV_EXPORTS Scalar trace(const Mat& m);\r
+CV_EXPORTS double invert(const Mat& a, Mat& c, int flags=DECOMP_LU);\r
+CV_EXPORTS bool solve(const Mat& a, const Mat& b, Mat& x, int flags=DECOMP_LU);\r
+CV_EXPORTS void sort(const Mat& a, Mat& b, int flags);\r
+CV_EXPORTS void sortIdx(const Mat& a, Mat& b, int flags);\r
+CV_EXPORTS void solveCubic(const Mat& coeffs, Mat& roots);\r
+CV_EXPORTS void solvePoly(const Mat& coeffs, Mat& roots, int maxIters=20, int fig=100);\r
+CV_EXPORTS bool eigen(const Mat& a, Mat& eigenvalues);\r
+CV_EXPORTS bool eigen(const Mat& a, Mat& eigenvalues, Mat& eigenvectors);\r
+\r
+CV_EXPORTS void calcCovariation( const Vector<Mat>& data, Mat& covar, Mat& mean,\r
+                                 int flags, int ctype=CV_64F);\r
+CV_EXPORTS void calcCovariation( const Mat& data, Mat& covar, Mat& mean,\r
+                                 int flags, int ctype=CV_64F);\r
+\r
+class CV_EXPORTS PCA\r
+{\r
+public:\r
+    PCA();\r
+    PCA(const Mat& data, const Mat& mean, int flags, int maxComponents=0);\r
+    PCA& operator()(const Mat& data, const Mat& mean, int flags, int maxComponents=0);\r
+    Mat project(const Mat& vec) const;\r
+    void project(const Mat& vec, Mat& result) const;\r
+    Mat backProject(const Mat& vec) const;\r
+    void backProject(const Mat& vec, Mat& result) const;\r
+\r
+    Mat eigenvectors;\r
+    Mat eigenvalues;\r
+    Mat mean;\r
+};\r
+\r
+class CV_EXPORTS SVD\r
+{\r
+public:\r
+    enum { MODIFY_A=1, NO_UV=2, FULL_UV=4 };\r
+    SVD();\r
+    SVD( const Mat& m, int flags=0 );\r
+    SVD& operator ()( const Mat& m, int flags=0 );\r
+\r
+    static void solveZ( const Mat& m, Mat& dst );\r
+    void backSubst( const Mat& rhs, Mat& dst ) const;\r
+\r
+    Mat u, w, vt;\r
+};\r
+\r
+CV_EXPORTS double mahalanobis(const Mat& v1, const Mat& v2, const Mat& icovar);\r
+static inline double mahalonobis(const Mat& v1, const Mat& v2, const Mat& icovar)\r
+{ return mahalanobis(v1, v2, icovar); }\r
+\r
+CV_EXPORTS void dft(const Mat& src, Mat& dst, int flags=0, int nonzeroRows=0);\r
+CV_EXPORTS void idft(const Mat& src, Mat& dst, int flags=0, int nonzeroRows=0);\r
+CV_EXPORTS void dct(const Mat& src, Mat& dst, int flags=0);\r
+CV_EXPORTS void idct(const Mat& src, Mat& dst, int flags=0);\r
+CV_EXPORTS void mulSpectrums(const Mat& a, const Mat& b, Mat& c,\r
+                             int flags, bool conjB=false);\r
+CV_EXPORTS int getOptimalDFTSize(int vecsize);\r
+\r
+enum { KMEANS_CENTERS_RANDOM=0, KMEANS_CENTERS_SPP=2, KMEANS_USE_INITIAL_LABELS=1 };\r
+CV_EXPORTS int kmeans( const Mat& samples, int K,\r
+                       Mat& labels, Mat& centers,\r
+                       TermCriteria crit, int attempts=1,\r
+                       int flags=KMEANS_CENTERS_SPP,\r
+                       double* compactness=0);\r
+\r
+CV_EXPORTS void seqToVector( const CvSeq* ptseq, Vector<Point>& pts );\r
+\r
+CV_EXPORTS RNG& theRNG();\r
+static inline int randi() { return (int)theRNG(); }\r
+static inline unsigned randu() { return (unsigned)theRNG(); }\r
+static inline float randf() { return (float)theRNG(); }\r
+static inline double randd() { return (double)theRNG(); }\r
+static inline void randu(Mat& dst, const Scalar& low, const Scalar& high)\r
+{ theRNG().fill(dst, RNG::UNIFORM, low, high); }\r
+static inline void randn(Mat& dst, const Scalar& mean, const Scalar& stddev)\r
+{ theRNG().fill(dst, RNG::NORMAL, mean, stddev); }\r
+CV_EXPORTS void randShuffle(Mat& dst, RNG& rng, double iterFactor=1.);\r
+static inline void randShuffle(Mat& dst, double iterFactor=1.)\r
+{ randShuffle(dst, theRNG(), iterFactor); }\r
+\r
+CV_EXPORTS void line(Mat& img, Point pt1, Point pt2, const Scalar& color,\r
+                     int thickness=1, int lineType=8, int shift=0);\r
+\r
+CV_EXPORTS void rectangle(Mat& img, Point pt1, Point pt2,\r
+                          const Scalar& color, int thickness=1,\r
+                          int lineType=8, int shift=0);\r
+\r
+CV_EXPORTS void circle(Mat& img, Point center, int radius,\r
+                       const Scalar& color, int thickness=1,\r
+                       int lineType=8, int shift=0);\r
+\r
+CV_EXPORTS void ellipse(Mat& img, Point center, Size axes,\r
+                        double angle, double startAngle, double endAngle,\r
+                        const Scalar& color, int thickness=1,\r
+                        int lineType=8, int shift=0);\r
+\r
+CV_EXPORTS void ellipse(Mat& img, const RotatedRect& box, const Scalar& color,\r
+                        int thickness=1, int lineType=8, int shift=0 );\r
+\r
+CV_EXPORTS void fillConvexPoly(Mat& img, const Vector<Point>& pts,\r
+                               const Scalar& color, int lineType=8,\r
+                               int shift=0);\r
+\r
+CV_EXPORTS void fillPoly(Mat& img, const Vector<Vector<Point> >& pts,\r
+                         const Scalar& color, int lineType=8, int shift=0,\r
+                         Point offset=Point() );\r
+\r
+CV_EXPORTS void polylines(Mat& img, const Vector<Vector<Point> >& pts, bool isClosed,\r
+                          const Scalar& color, int thickness=1, int lineType=8, int shift=0 );\r
+\r
+CV_EXPORTS bool clipLine(Size imgSize, Point& pt1, Point& pt2);\r
+\r
+class CV_EXPORTS LineIterator\r
+{\r
+public:\r
+    LineIterator(const Mat& img, Point pt1, Point pt2,\r
+                 int connectivity=8, bool leftToRight=false);\r
+    uchar* operator *();\r
+    LineIterator& operator ++();\r
+    LineIterator operator ++(int);\r
+\r
+    uchar* ptr;\r
+    int err, count;\r
+    int minusDelta, plusDelta;\r
+    int minusStep, plusStep;\r
+};\r
+\r
+CV_EXPORTS void ellipse2Poly( Point center, Size axes, int angle,\r
+                              int arcStart, int arcEnd, int delta, Vector<Point>& pts );\r
+\r
+enum\r
+{\r
+    FONT_HERSHEY_SIMPLEX = 0,\r
+    FONT_HERSHEY_PLAIN = 1,\r
+    FONT_HERSHEY_DUPLEX = 2,\r
+    FONT_HERSHEY_COMPLEX = 3,\r
+    FONT_HERSHEY_TRIPLEX = 4,\r
+    FONT_HERSHEY_COMPLEX_SMALL = 5,\r
+    FONT_HERSHEY_SCRIPT_SIMPLEX = 6,\r
+    FONT_HERSHEY_SCRIPT_COMPLEX = 7,\r
+    FONT_ITALIC = 16\r
+};\r
+\r
+CV_EXPORTS void putText( Mat& img, const String& text, Point org,\r
+                         int fontFace, double fontScale, Scalar color,\r
+                         int thickness=1, int linetype=8,\r
+                         bool bottomLeftOrigin=false );\r
+\r
+CV_EXPORTS Size getTextSize(const String& text, int fontFace,\r
+                            double fontScale, int thickness,\r
+                            int* baseLine);\r
+\r
+///////////////////////////////// Mat_<_Tp> ////////////////////////////////////\r
+\r
+template<typename _Tp> class CV_EXPORTS Mat_ : public Mat\r
+{\r
+public:\r
+    typedef _Tp value_type;\r
+    typedef typename DataType<_Tp>::channel_type channel_type;\r
+    typedef MatIterator_<_Tp> iterator;\r
+    typedef MatConstIterator_<_Tp> const_iterator;\r
+    \r
+    Mat_();\r
+    Mat_(int _rows, int _cols);\r
+    Mat_(int _rows, int _cols, const _Tp& value);\r
+    explicit Mat_(Size _size);\r
+    Mat_(Size _size, const _Tp& value);\r
+    Mat_(const Mat& m);\r
+    Mat_(const Mat_& m);\r
+    Mat_(int _rows, int _cols, _Tp* _data, size_t _step=AUTO_STEP);\r
+    Mat_(const Mat_& m, const Range& rowRange, const Range& colRange);\r
+    Mat_(const Mat_& m, const Rect& roi);\r
+    Mat_(const MatExpr_Base& expr);\r
+    template<int n> explicit Mat_(const Vec<_Tp, n>& vec);\r
+    Mat_(const Vector<_Tp>& vec);\r
+\r
+    Mat_& operator = (const Mat& m);\r
+    Mat_& operator = (const Mat_& m);\r
+    Mat_& operator = (const _Tp& s);\r
+\r
+    iterator begin();\r
+    iterator end();\r
+    const_iterator begin() const;\r
+    const_iterator end() const;\r
+\r
+    void create(int _rows, int _cols);\r
+    void create(Size _size);\r
+    Mat_ cross(const Mat_& m) const;\r
+    Mat_& operator = (const MatExpr_Base& expr);\r
+    template<typename T2> operator Mat_<T2>() const;\r
+    Mat_ row(int y) const;\r
+    Mat_ col(int x) const;\r
+    Mat_ diag(int d=0) const;\r
+    Mat_ clone() const;\r
+\r
+    MatExpr_<MatExpr_Op2_<Mat_, double, Mat_, MatOp_T_<Mat> >, Mat_> t() const;\r
+    MatExpr_<MatExpr_Op2_<Mat_, int, Mat_, MatOp_Inv_<Mat> >, Mat_> inv(int method=DECOMP_LU) const;\r
+\r
+    MatExpr_<MatExpr_Op4_<Mat_, Mat_, double, char, Mat_, MatOp_MulDiv_<Mat> >, Mat_>\r
+    mul(const Mat_& m, double scale=1) const;\r
+    MatExpr_<MatExpr_Op4_<Mat_, Mat_, double, char, Mat_, MatOp_MulDiv_<Mat> >, Mat_>\r
+    mul(const MatExpr_<MatExpr_Op2_<Mat_, double, Mat_,\r
+        MatOp_Scale_<Mat> >, Mat_>& m, double scale=1) const;\r
+    MatExpr_<MatExpr_Op4_<Mat_, Mat_, double, char, Mat_, MatOp_MulDiv_<Mat> >, Mat_>    \r
+    mul(const MatExpr_<MatExpr_Op2_<Mat_, double, Mat_,\r
+        MatOp_DivRS_<Mat> >, Mat_>& m, double scale=1) const;\r
+\r
+    size_t elemSize() const;\r
+    size_t elemSize1() const;\r
+    int type() const;\r
+    int depth() const;\r
+    int channels() const;\r
+    size_t stepT() const;\r
+    size_t step1() const;\r
+\r
+    static MatExpr_Initializer zeros(int rows, int cols);\r
+    static MatExpr_Initializer zeros(Size size);\r
+    static MatExpr_Initializer ones(int rows, int cols);\r
+    static MatExpr_Initializer ones(Size size);\r
+    static MatExpr_Initializer eye(int rows, int cols);\r
+    static MatExpr_Initializer eye(Size size);\r
+\r
+    Mat_ reshape(int _rows) const;\r
+    Mat_& adjustROI( int dtop, int dbottom, int dleft, int dright );\r
+    Mat_ operator()( const Range& rowRange, const Range& colRange ) const;\r
+    Mat_ operator()( const Rect& roi ) const;\r
+\r
+    _Tp* operator [](int y);\r
+    const _Tp* operator [](int y) const;\r
+\r
+    _Tp& operator ()(int row, int col);\r
+    const _Tp& operator ()(int row, int col) const;\r
+\r
+    operator MatExpr_<Mat_, Mat_>() const;\r
+    operator Vector<_Tp>() const;\r
+};\r
+\r
+//////////// Iterators & Comma initializers //////////////////\r
+\r
+template<typename _Tp>\r
+class CV_EXPORTS MatConstIterator_\r
+{\r
+public:\r
+    typedef _Tp value_type;\r
+    typedef int difference_type;\r
+\r
+    MatConstIterator_();\r
+    MatConstIterator_(const Mat_<_Tp>* _m);\r
+    MatConstIterator_(const Mat_<_Tp>* _m, int _row, int _col=0);\r
+    MatConstIterator_(const Mat_<_Tp>* _m, Point _pt);\r
+    MatConstIterator_(const MatConstIterator_& it);\r
+\r
+    MatConstIterator_& operator = (const MatConstIterator_& it );\r
+    _Tp operator *() const;\r
+    _Tp operator [](int i) const;\r
+    \r
+    MatConstIterator_& operator += (int ofs);\r
+    MatConstIterator_& operator -= (int ofs);\r
+    MatConstIterator_& operator --();\r
+    MatConstIterator_ operator --(int);\r
+    MatConstIterator_& operator ++();\r
+    MatConstIterator_ operator ++(int);\r
+    Point pos() const;\r
+\r
+protected:\r
+    const Mat_<_Tp>* m;\r
+    _Tp* ptr;\r
+    _Tp* sliceEnd;\r
+};\r
+\r
+\r
+template<typename _Tp>\r
+class CV_EXPORTS MatIterator_ : public MatConstIterator_<_Tp>\r
+{\r
+public:\r
+    typedef _Tp* pointer;\r
+    typedef _Tp& reference;\r
+    typedef std::random_access_iterator_tag iterator_category;\r
+\r
+    MatIterator_();\r
+    MatIterator_(Mat_<_Tp>* _m);\r
+    MatIterator_(Mat_<_Tp>* _m, int _row, int _col=0);\r
+    MatIterator_(const Mat_<_Tp>* _m, Point _pt);\r
+    MatIterator_(const MatIterator_& it);\r
+    MatIterator_& operator = (const MatIterator_<_Tp>& it );\r
+\r
+    _Tp& operator *() const;\r
+    _Tp& operator [](int i) const;\r
+\r
+    MatIterator_& operator += (int ofs);\r
+    MatIterator_& operator -= (int ofs);\r
+    MatIterator_& operator --();\r
+    MatIterator_ operator --(int);\r
+    MatIterator_& operator ++();\r
+    MatIterator_ operator ++(int);\r
+};\r
+\r
+template<typename _Tp> class CV_EXPORTS MatOp_Iter_;\r
+\r
+template<typename _Tp> class CV_EXPORTS MatCommaInitializer_ :\r
+    public MatExpr_<MatExpr_Op1_<MatIterator_<_Tp>, Mat_<_Tp>, MatOp_Iter_<_Tp> >, Mat_<_Tp> >\r
+{\r
+public:\r
+    MatCommaInitializer_(Mat_<_Tp>* _m);\r
+    template<typename T2> MatCommaInitializer_<_Tp>& operator , (T2 v);\r
+    operator Mat_<_Tp>() const;\r
+    Mat_<_Tp> operator *() const;\r
+    void assignTo(Mat& m, int type=-1) const;\r
+};\r
+\r
+template<typename _Tp> class VectorCommaInitializer_\r
+{\r
+public:\r
+    VectorCommaInitializer_(Vector<_Tp>* _vec);\r
+    template<typename T2> VectorCommaInitializer_<_Tp>& operator , (T2 val);\r
+    operator Vector<_Tp>() const;\r
+    Vector<_Tp> operator *() const;\r
+\r
+protected:\r
+    Vector<_Tp>* vec;\r
+    int idx;\r
+};\r
+\r
+template<typename _Tp, size_t fixed_size=4096/sizeof(_Tp)+8> class CV_EXPORTS AutoBuffer\r
+{\r
+public:\r
+    typedef _Tp value_type;\r
+\r
+    AutoBuffer();\r
+    AutoBuffer(size_t _size);\r
+    ~AutoBuffer();\r
+\r
+    void allocate(size_t _size);\r
+    void deallocate();\r
+    operator _Tp* ();\r
+    operator const _Tp* () const;\r
+\r
+protected:\r
+    _Tp* ptr;\r
+    size_t size;\r
+    _Tp buf[fixed_size];\r
+};\r
+\r
+/////////////////////////// multi-dimensional dense matrix //////////////////////////\r
+\r
+class MatND;\r
+class SparseMat;\r
+\r
+class CV_EXPORTS MatND\r
+{\r
+public:\r
+    MatND();\r
+    MatND(const Vector<int>& _sizes, int _type);\r
+    MatND(const Vector<int>& _sizes, int _type, const Scalar& _s);\r
+    MatND(const MatND& m);\r
+    MatND(const MatND& m, const Vector<Range>& ranges);\r
+    MatND(const CvMatND* m, bool copyData=false);\r
+    //MatND( const MatExpr_BaseND& expr );\r
+    ~MatND();\r
+    MatND& operator = (const MatND& m);\r
+    //MatND& operator = (const MatExpr_BaseND& expr);\r
+\r
+    //operator MatExpr_<MatND, MatND>() const;\r
+\r
+    MatND clone() const;\r
+    MatND operator()(const Vector<Range>& ranges) const;\r
+\r
+    void copyTo( MatND& m ) const;\r
+    void copyTo( MatND& m, const MatND& mask ) const;\r
+    void convertTo( MatND& m, int rtype, double alpha=1, double beta=0 ) const;\r
+\r
+    void assignTo( MatND& m, int type=-1 ) const;\r
+    MatND& operator = (const Scalar& s);\r
+    MatND& setTo(const Scalar& s, const MatND& mask=MatND());\r
+    MatND reshape(int newcn, const Vector<int>& newsz=Vector<int>()) const;\r
+\r
+    void create(const Vector<int>& _sizes, int _type);\r
+    void addref();\r
+    void release();\r
+\r
+    operator Mat() const;\r
+    operator CvMatND() const;\r
+    bool isContinuous() const;\r
+    size_t elemSize() const;\r
+    size_t elemSize1() const;\r
+    int type() const;\r
+    int depth() const;\r
+    int channels() const;\r
+    size_t step(int i) const;\r
+    size_t step1(int i) const;\r
+    Vector<int> size() const;\r
+    int size(int i) const;\r
+\r
+    uchar* ptr(int i0);\r
+    const uchar* ptr(int i0) const;\r
+    uchar* ptr(int i0, int i1);\r
+    const uchar* ptr(int i0, int i1) const;\r
+    uchar* ptr(int i0, int i1, int i2);\r
+    const uchar* ptr(int i0, int i1, int i2) const;\r
+    uchar* ptr(const int* idx);\r
+    const uchar* ptr(const int* idx) const;\r
+\r
+    enum { MAGIC_VAL=0x42FE0000, AUTO_STEP=-1,\r
+        CONTINUOUS_FLAG=CV_MAT_CONT_FLAG, MAX_DIM=CV_MAX_DIM };\r
+\r
+    int flags;\r
+    int dims;\r
+    \r
+    uchar* data;\r
+    int* refcount;\r
+    uchar* datastart;\r
+    uchar* dataend;\r
+\r
+    struct\r
+    {\r
+        int size;\r
+        size_t step;\r
+    }\r
+    dim[MAX_DIM];\r
+};\r
+\r
+class CV_EXPORTS NAryMatNDIterator\r
+{\r
+public:\r
+    NAryMatNDIterator();\r
+    NAryMatNDIterator(const Vector<MatND>& arrays);\r
+    void init(const Vector<MatND>& arrays);\r
+\r
+    NAryMatNDIterator& operator ++();\r
+    NAryMatNDIterator operator ++(int);\r
+    \r
+    Vector<MatND> arrays;\r
+    Vector<Mat> planes;\r
+\r
+    int nplanes;\r
+protected:\r
+    int iterdepth, idx;\r
+};\r
+\r
+CV_EXPORTS void add(const MatND& a, const MatND& b, MatND& c, const MatND& mask);\r
+CV_EXPORTS void subtract(const MatND& a, const MatND& b, MatND& c, const MatND& mask);\r
+CV_EXPORTS void add(const MatND& a, const MatND& b, MatND& c);\r
+CV_EXPORTS void subtract(const MatND& a, const MatND& b, MatND& c);\r
+CV_EXPORTS void add(const MatND& a, const Scalar& s, MatND& c, const MatND& mask=MatND());\r
+\r
+CV_EXPORTS void multiply(const MatND& a, const MatND& b, MatND& c, double scale=1);\r
+CV_EXPORTS void divide(const MatND& a, const MatND& b, MatND& c, double scale=1);\r
+CV_EXPORTS void divide(double scale, const MatND& b, MatND& c);\r
+\r
+CV_EXPORTS void subtract(const Scalar& s, const MatND& a, MatND& c, const MatND& mask=MatND());\r
+CV_EXPORTS void scaleAdd(const MatND& a, double alpha, const MatND& b, MatND& c);\r
+CV_EXPORTS void addWeighted(const MatND& a, double alpha, const MatND& b,\r
+                            double beta, double gamma, MatND& c);\r
+\r
+CV_EXPORTS Scalar sum(const MatND& m);\r
+CV_EXPORTS int countNonZero( const MatND& m );\r
+\r
+CV_EXPORTS Scalar mean(const MatND& m);\r
+CV_EXPORTS Scalar mean(const MatND& m, const MatND& mask);\r
+CV_EXPORTS void meanStdDev(const MatND& m, Scalar& mean, Scalar& stddev, const MatND& mask=MatND());\r
+CV_EXPORTS double norm(const MatND& a, int normType=NORM_L2, const MatND& mask=MatND());\r
+CV_EXPORTS double norm(const MatND& a, const MatND& b,\r
+                       int normType=NORM_L2, const MatND& mask=MatND());\r
+CV_EXPORTS void normalize( const MatND& a, MatND& b, double alpha=1, double beta=0,\r
+                           int norm_type=NORM_L2, int rtype=-1, const MatND& mask=MatND());\r
+\r
+CV_EXPORTS void minMaxLoc(const MatND& a, double* minVal,\r
+                       double* maxVal, int* minIdx=0, int* maxIdx=0,\r
+                       const MatND& mask=MatND());\r
+CV_EXPORTS void merge(const Vector<MatND>& mv, MatND& dst);\r
+CV_EXPORTS void split(const MatND& m, Vector<MatND>& mv);\r
+CV_EXPORTS void mixChannels(const Vector<MatND>& src, Vector<MatND>& dst,\r
+                            const Vector<int>& fromTo);\r
+\r
+CV_EXPORTS void bitwise_and(const MatND& a, const MatND& b, MatND& c, const MatND& mask=MatND());\r
+CV_EXPORTS void bitwise_or(const MatND& a, const MatND& b, MatND& c, const MatND& mask=MatND());\r
+CV_EXPORTS void bitwise_xor(const MatND& a, const MatND& b, MatND& c, const MatND& mask=MatND());\r
+CV_EXPORTS void bitwise_and(const MatND& a, const Scalar& s, MatND& c, const MatND& mask=MatND());\r
+CV_EXPORTS void bitwise_or(const MatND& a, const Scalar& s, MatND& c, const MatND& mask=MatND());\r
+CV_EXPORTS void bitwise_xor(const MatND& a, const Scalar& s, MatND& c, const MatND& mask=MatND());\r
+CV_EXPORTS void bitwise_not(const MatND& a, MatND& c);\r
+CV_EXPORTS void absdiff(const MatND& a, const MatND& b, MatND& c);\r
+CV_EXPORTS void absdiff(const MatND& a, const Scalar& s, MatND& c);\r
+CV_EXPORTS void inRange(const MatND& src, const MatND& lowerb,\r
+                        const MatND& upperb, MatND& dst);\r
+CV_EXPORTS void inRange(const MatND& src, const Scalar& lowerb,\r
+                        const Scalar& upperb, MatND& dst);\r
+CV_EXPORTS void compare(const MatND& a, const MatND& b, MatND& c, int cmpop);\r
+CV_EXPORTS void compare(const MatND& a, double s, MatND& c, int cmpop);\r
+CV_EXPORTS void min(const MatND& a, const MatND& b, MatND& c);\r
+CV_EXPORTS void min(const MatND& a, double alpha, MatND& c);\r
+CV_EXPORTS void max(const MatND& a, const MatND& b, MatND& c);\r
+CV_EXPORTS void max(const MatND& a, double alpha, MatND& c);\r
+\r
+CV_EXPORTS void sqrt(const MatND& a, MatND& b);\r
+CV_EXPORTS void pow(const MatND& a, double power, MatND& b);\r
+CV_EXPORTS void exp(const MatND& a, MatND& b);\r
+CV_EXPORTS void log(const MatND& a, MatND& b);\r
+CV_EXPORTS bool checkRange(const MatND& a, bool quiet=true, int* idx=0,\r
+                           double minVal=-DBL_MAX, double maxVal=DBL_MAX);\r
+\r
+typedef void (*ConvertData)(const void* from, void* to, int cn);\r
+typedef void (*ConvertScaleData)(const void* from, void* to, int cn, double alpha, double beta);\r
+\r
+CV_EXPORTS ConvertData getConvertElem(int fromType, int toType);\r
+CV_EXPORTS ConvertScaleData getConvertScaleElem(int fromType, int toType);\r
+\r
+template<typename _Tp> class CV_EXPORTS MatND_ : public MatND\r
+{\r
+public:\r
+    typedef _Tp value_type;\r
+    typedef typename DataType<_Tp>::channel_type channel_type;\r
+\r
+    MatND_();\r
+    MatND_(const Vector<int>& _sizes);\r
+    MatND_(const Vector<int>& _sizes, const _Tp& _s);\r
+    MatND_(const MatND& m);\r
+    MatND_(const MatND_& m);\r
+    MatND_(const MatND_& m, const Vector<Range>& ranges);\r
+    MatND_(const CvMatND* m, bool copyData=false);\r
+    MatND_& operator = (const MatND& m);\r
+    MatND_& operator = (const MatND_& m);\r
+    MatND_& operator = (const _Tp& s);\r
+\r
+    void create(const Vector<int>& _sizes);\r
+    template<typename T2> operator MatND_<T2>() const;\r
+    MatND_ clone() const;\r
+    MatND_ operator()(const Vector<Range>& ranges) const;\r
+\r
+    size_t elemSize() const;\r
+    size_t elemSize1() const;\r
+    int type() const;\r
+    int depth() const;\r
+    int channels() const;\r
+    size_t stepT(int i) const;\r
+    size_t step1(int i) const;\r
+\r
+    _Tp& operator ()(const int* idx);\r
+    const _Tp& operator ()(const int* idx) const;\r
+\r
+    _Tp& operator ()(int idx0, int idx1, int idx2);\r
+    const _Tp& operator ()(int idx0, int idx1, int idx2) const;\r
+};\r
+\r
+/////////////////////////// multi-dimensional sparse matrix //////////////////////////\r
+\r
+class SparseMatIterator;\r
+class SparseMatConstIterator;\r
+\r
+class CV_EXPORTS SparseMat\r
+{\r
+public:\r
+    typedef SparseMatIterator iterator;\r
+    typedef SparseMatConstIterator const_iterator;\r
+\r
+    struct CV_EXPORTS Hdr\r
+    {\r
+        Hdr(const Vector<int>& _sizes, int _type);\r
+        void clear();\r
+        int refcount;\r
+        int dims;\r
+        int valueOffset;\r
+        size_t nodeSize;\r
+        size_t nodeCount;\r
+        size_t freeList;\r
+        Vector<uchar> pool;\r
+        Vector<size_t> hashtab;\r
+        int size[CV_MAX_DIM];\r
+    };\r
+\r
+    struct CV_EXPORTS Node\r
+    {\r
+        size_t hashval;\r
+        size_t next;\r
+        int idx[CV_MAX_DIM];\r
+    };\r
+\r
+    SparseMat();\r
+    SparseMat(const Vector<int>& _sizes, int _type);\r
+    SparseMat(const SparseMat& m);\r
+    SparseMat(const Mat& m, bool try1d=false);\r
+    SparseMat(const MatND& m);\r
+    SparseMat(const CvSparseMat* m);\r
+    ~SparseMat();\r
+    SparseMat& operator = (const SparseMat& m);\r
+    SparseMat& operator = (const Mat& m);\r
+    SparseMat& operator = (const MatND& m);\r
+\r
+    SparseMat clone() const;\r
+    void copyTo( SparseMat& m ) const;\r
+    void copyTo( Mat& m ) const;\r
+    void copyTo( MatND& m ) const;\r
+    void convertTo( SparseMat& m, int rtype, double alpha=1 ) const;\r
+    void convertTo( Mat& m, int rtype, double alpha=1, double beta=0 ) const;\r
+    void convertTo( MatND& m, int rtype, double alpha=1, double beta=0 ) const;\r
+\r
+    void assignTo( SparseMat& m, int type=-1 ) const;\r
+\r
+    void create(const Vector<int>& _sizes, int _type);\r
+    void clear();\r
+    void addref();\r
+    void release();\r
+\r
+    operator CvSparseMat*() const;\r
+    size_t elemSize() const;\r
+    size_t elemSize1() const;\r
+    int type() const;\r
+    int depth() const;\r
+    int channels() const;\r
+    Vector<int> size() const;\r
+    int size(int i) const;\r
+    int dims() const;\r
+    size_t nzcount() const;\r
+    \r
+    size_t hash(int i0) const;\r
+    size_t hash(int i0, int i1) const;\r
+    size_t hash(int i0, int i1, int i2) const;\r
+    size_t hash(const int* idx) const;\r
+    \r
+    uchar* ptr(int i0, int i1, bool createMissing, size_t* hashval=0);\r
+    const uchar* get(int i0, int i1, size_t* hashval=0) const;\r
+    uchar* ptr(int i0, int i1, int i2, bool createMissing, size_t* hashval=0);\r
+    const uchar* get(int i0, int i1, int i2, size_t* hashval=0) const;\r
+    uchar* ptr(const int* idx, bool createMissing, size_t* hashval=0);\r
+    const uchar* get(const int* idx, size_t* hashval=0) const;\r
+\r
+    void erase(int i0, int i1, size_t* hashval=0);\r
+    void erase(int i0, int i1, int i2, size_t* hashval=0);\r
+    void erase(const int* idx, size_t* hashval=0);\r
+\r
+    SparseMatIterator begin();\r
+    SparseMatConstIterator begin() const;\r
+    SparseMatIterator end();\r
+    SparseMatConstIterator end() const;\r
+\r
+    uchar* value(Node* n);\r
+    const uchar* value(const Node* n) const;\r
+    Node* node(size_t nidx);\r
+    const Node* node(size_t nidx) const;\r
+\r
+    uchar* newNode(const int* idx, size_t hashval);\r
+    void removeNode(size_t hidx, size_t nidx, size_t previdx);\r
+    void resizeHashTab(size_t newsize);\r
+\r
+    enum { MAGIC_VAL=0x42FD0000, MAX_DIM=CV_MAX_DIM, HASH_SCALE=0x5bd1e995, HASH_BIT=0x80000000 };\r
+\r
+    int flags;\r
+    Hdr* hdr;\r
+};\r
+\r
+\r
+CV_EXPORTS void minMaxLoc(const SparseMat& a, double* minVal,\r
+                          double* maxVal, int* minIdx=0, int* maxIdx=0);\r
+CV_EXPORTS double norm( const SparseMat& src, int normType );\r
+CV_EXPORTS void normalize( const SparseMat& src, SparseMat& dst, double alpha, int normType );\r
+\r
+class CV_EXPORTS SparseMatConstIterator\r
+{\r
+public:\r
+    SparseMatConstIterator();\r
+    SparseMatConstIterator(const SparseMat* _m);\r
+    SparseMatConstIterator(const SparseMatConstIterator& it);\r
+\r
+    SparseMatConstIterator& operator = (const SparseMatConstIterator& it);\r
+    const uchar* value() const;\r
+    const SparseMat::Node* node() const;\r
+    \r
+    SparseMatConstIterator& operator --();\r
+    SparseMatConstIterator operator --(int);\r
+    SparseMatConstIterator& operator ++();\r
+    SparseMatConstIterator operator ++(int);\r
+\r
+    const SparseMat* m;\r
+    size_t hashidx;\r
+    uchar* ptr;\r
+};\r
+\r
+class CV_EXPORTS SparseMatIterator : public SparseMatConstIterator\r
+{\r
+public:\r
+    SparseMatIterator();\r
+    SparseMatIterator(SparseMat* _m);\r
+    SparseMatIterator(SparseMat* _m, const int* idx);\r
+    SparseMatIterator(const SparseMatIterator& it);\r
+\r
+    SparseMatIterator& operator = (const SparseMatIterator& it);\r
+    uchar* value() const;\r
+    SparseMat::Node* node() const;\r
+    \r
+    SparseMatIterator& operator ++();\r
+    SparseMatIterator operator ++(int);\r
+};\r
+\r
+\r
+template<typename _Tp> class SparseMatIterator_;\r
+template<typename _Tp> class SparseMatConstIterator_;\r
+\r
+template<typename _Tp> class CV_EXPORTS SparseMat_ : public SparseMat\r
+{\r
+public:\r
+    typedef SparseMatIterator_<_Tp> iterator;\r
+    typedef SparseMatConstIterator_<_Tp> const_iterator;\r
+\r
+    SparseMat_();\r
+    SparseMat_(const Vector<int>& _sizes);\r
+    SparseMat_(const SparseMat& m);\r
+    SparseMat_(const SparseMat_& m);\r
+    SparseMat_(const Mat& m);\r
+    SparseMat_(const MatND& m);\r
+    SparseMat_(const CvSparseMat* m);\r
+    SparseMat_& operator = (const SparseMat& m);\r
+    SparseMat_& operator = (const SparseMat_& m);\r
+    SparseMat_& operator = (const Mat& m);\r
+    SparseMat_& operator = (const MatND& m);\r
+\r
+    SparseMat_ clone() const;\r
+    void create(const Vector<int>& _sizes);\r
+    operator CvSparseMat*() const;\r
+\r
+    int type() const;\r
+    int depth() const;\r
+    int channels() const;\r
+    \r
+    _Tp& operator()(int i0, int i1, size_t* hashval=0);\r
+    _Tp operator()(int i0, int i1, size_t* hashval=0) const;\r
+    _Tp& operator()(int i0, int i1, int i2, size_t* hashval=0);\r
+    _Tp operator()(int i0, int i1, int i2, size_t* hashval=0) const;\r
+    _Tp& operator()(const int* idx, size_t* hashval=0);\r
+    _Tp operator()(const int* idx, size_t* hashval=0) const;\r
+\r
+    SparseMatIterator_<_Tp> begin();\r
+    SparseMatConstIterator_<_Tp> begin() const;\r
+    SparseMatIterator_<_Tp> end();\r
+    SparseMatConstIterator_<_Tp> end() const;\r
+};\r
+\r
+template<typename _Tp> class CV_EXPORTS SparseMatConstIterator_ : public SparseMatConstIterator\r
+{\r
+public:\r
+    typedef std::forward_iterator_tag iterator_category;\r
+    \r
+    SparseMatConstIterator_();\r
+    SparseMatConstIterator_(const SparseMat_<_Tp>* _m);\r
+    SparseMatConstIterator_(const SparseMatConstIterator_& it);\r
+\r
+    SparseMatConstIterator_& operator = (const SparseMatConstIterator_& it);\r
+    const _Tp& operator *() const;\r
+    \r
+    SparseMatConstIterator_& operator ++();\r
+    SparseMatConstIterator_ operator ++(int);\r
+\r
+protected:\r
+    const SparseMat_<_Tp>* m;\r
+    size_t hashidx;\r
+    uchar* ptr;\r
+};\r
+\r
+template<typename _Tp> class CV_EXPORTS SparseMatIterator_ : public SparseMatConstIterator_<_Tp>\r
+{\r
+public:\r
+    typedef std::forward_iterator_tag iterator_category;\r
+    \r
+    SparseMatIterator_();\r
+    SparseMatIterator_(SparseMat_<_Tp>* _m);\r
+    SparseMatIterator_(const SparseMatIterator_& it);\r
+\r
+    SparseMatIterator_& operator = (const SparseMatIterator_& it);\r
+    _Tp& operator *() const;\r
+    \r
+    SparseMatIterator_& operator ++();\r
+    SparseMatIterator_ operator ++(int);\r
+};\r
+\r
+//////////////////// Fast Nearest-Neighbor Search Structure ////////////////////\r
+\r
+class CV_EXPORTS KDTree\r
+{\r
+public:\r
+    struct Node\r
+    {\r
+        Node() : idx(-1), left(-1), right(-1), boundary(0.f) {}\r
+        Node(int _idx, int _left, int _right, float _boundary)\r
+            : idx(_idx), left(_left), right(_right), boundary(_boundary) {}\r
+        int idx;            // split dimension; >=0 for nodes (dim),\r
+                            // < 0 for leaves (index of the point)\r
+        int left, right;    // node indices of left and right branches\r
+        float boundary;     // left if vec[dim]<=boundary, otherwise right\r
+    };\r
+\r
+    KDTree();\r
+    KDTree(const Mat& _points, bool copyPoints=true);\r
+    void build(const Mat& _points, bool copyPoints=true);\r
+\r
+    void findNearest(const Mat& vec, int K, int Emax, Vector<int>* neighborsIdx,\r
+        Mat* neighbors=0, Vector<float>* dist=0) const;\r
+    void findNearest(const Vector<float>& vec, int K, int Emax, Vector<int>* neighborsIdx,\r
+        Vector<float>* neighbors=0, Vector<float>* dist=0) const;\r
+    void findOrthoRange(const Mat& minBounds, const Mat& maxBounds,\r
+        Vector<int>* neighborsIdx, Mat* neighbors=0) const;\r
+    void findOrthoRange(const Vector<float>& minBounds, const Vector<float>& maxBounds,\r
+        Vector<int>* neighborsIdx, Vector<float>* neighbors=0) const;\r
+    void getPoints(const Vector<int>& ids, Mat& pts) const;\r
+    void getPoints(const Vector<int>& ids, Vector<float>& pts) const;\r
+    Vector<float> at(int ptidx, bool copyData=false) const;\r
+\r
+    Vector<Node> nodes;\r
+    Mat points;\r
+    int maxDepth;\r
+};\r
+\r
+//////////////////////////////////////// XML & YAML I/O ////////////////////////////////////\r
+\r
+class CV_EXPORTS FileNode;\r
+\r
+class CV_EXPORTS FileStorage\r
+{\r
+public:\r
+    enum { READ=0, WRITE=1, APPEND=2 };\r
+    enum { UNDEFINED=0, VALUE_EXPECTED=1, NAME_EXPECTED=2, INSIDE_MAP=4 };\r
+    FileStorage();\r
+    FileStorage(const String& filename, int flags);\r
+    FileStorage(CvFileStorage* fs);\r
+    virtual ~FileStorage();\r
+\r
+    virtual bool open(const String& filename, int flags);\r
+    virtual bool isOpened() const;\r
+    virtual void release();\r
+\r
+    FileNode getFirstTopLevelNode() const;\r
+    FileNode root(int streamidx=0) const;\r
+    FileNode operator[](const String& nodename) const;\r
+    FileNode operator[](const char* nodename) const;\r
+\r
+    CvFileStorage* operator *() { return fs; }\r
+    const CvFileStorage* operator *() const { return fs; }\r
+    void writeRaw( const String& fmt, const Vector<uchar>& vec );\r
+    void writeObj( const String& name, const void* obj );\r
+\r
+    static String getDefaultObjectName(const String& filename);\r
+\r
+    Ptr<CvFileStorage> fs;\r
+    String elname;\r
+    Vector<char> structs;\r
+    int state;\r
+};\r
+\r
+class CV_EXPORTS FileNodeIterator;\r
+\r
+class CV_EXPORTS FileNode\r
+{\r
+public:\r
+    enum { NONE=0, INT=1, REAL=2, FLOAT=REAL, STR=3, STRING=STR, REF=4, SEQ=5, MAP=6, TYPE_MASK=7,\r
+        FLOW=8, USER=16, EMPTY=32, NAMED=64 };\r
+    FileNode();\r
+    FileNode(const CvFileStorage* fs, const CvFileNode* node);\r
+    FileNode(const FileNode& node);\r
+    FileNode operator[](const String& nodename) const;\r
+    FileNode operator[](const char* nodename) const;\r
+    FileNode operator[](int i) const;\r
+    int type() const;\r
+    int rawDataSize(const String& fmt) const;\r
+    bool isNone() const;\r
+    bool isSeq() const;\r
+    bool isMap() const;\r
+    bool isInt() const;\r
+    bool isReal() const;\r
+    bool isString() const;\r
+    bool isNamed() const;\r
+    String name() const;\r
+    size_t count() const;\r
+    operator int() const;\r
+    operator float() const;\r
+    operator double() const;\r
+    operator String() const;\r
+\r
+    FileNodeIterator begin() const;\r
+    FileNodeIterator end() const;\r
+\r
+    void readRaw( const String& fmt, Vector<uchar>& vec ) const;\r
+    void* readObj() const;\r
+\r
+    // do not use wrapper pointer classes for better efficiency\r
+    const CvFileStorage* fs;\r
+    const CvFileNode* node;\r
+};\r
+\r
+class CV_EXPORTS FileNodeIterator\r
+{\r
+public:\r
+    FileNodeIterator();\r
+    FileNodeIterator(const CvFileStorage* fs, const CvFileNode* node, size_t ofs=0);\r
+    FileNodeIterator(const FileNodeIterator& it);\r
+    FileNode operator *() const;\r
+    FileNode operator ->() const;\r
+\r
+    FileNodeIterator& operator ++();\r
+    FileNodeIterator operator ++(int);\r
+    FileNodeIterator& operator --();\r
+    FileNodeIterator operator --(int);\r
+    FileNodeIterator& operator += (int);\r
+    FileNodeIterator& operator -= (int);\r
+\r
+    FileNodeIterator& readRaw( const String& fmt, Vector<uchar>& vec,\r
+                               size_t maxCount=(size_t)INT_MAX );\r
+\r
+    const CvFileStorage* fs;\r
+    const CvFileNode* container;\r
+    CvSeqReader reader;\r
+    size_t remaining;\r
+};\r
+\r
+////////////// convenient wrappers for operating old-style dynamic structures //////////////\r
+\r
+// !!! NOTE that the wrappers are "thin", i.e. they do not call\r
+// any element constructors/destructors\r
+\r
+template<typename _Tp> class SeqIterator;\r
+\r
+template<> inline void Ptr<CvMemStorage>::delete_obj()\r
+{ cvReleaseMemStorage(&obj); }\r
+\r
+typedef Ptr<CvMemStorage> MemStorage;\r
+\r
+template<typename _Tp> class CV_EXPORTS Seq\r
+{\r
+public:\r
+    Seq();\r
+    Seq(const CvSeq* seq);\r
+    Seq(const MemStorage& storage, int headerSize = sizeof(CvSeq));\r
+    _Tp& operator [](int idx);\r
+    const _Tp& operator[](int idx) const;\r
+    SeqIterator<_Tp> begin() const;\r
+    SeqIterator<_Tp> end() const;\r
+    size_t size() const;\r
+    int type() const;\r
+    int depth() const;\r
+    int channels() const;\r
+    size_t elemSize() const;\r
+    size_t index(const _Tp& elem) const;\r
+    void push_back(const _Tp& elem);\r
+    void push_front(const _Tp& elem);\r
+    _Tp& front();\r
+    const _Tp& front() const;\r
+    _Tp& back();\r
+    const _Tp& back() const;\r
+    bool empty() const;\r
+\r
+    void clear();\r
+    void pop_front();\r
+    void pop_back();\r
+\r
+    void copyTo(Vector<_Tp>& vec, const Range& range=Range::all()) const;\r
+    operator Vector<_Tp>() const;\r
+    \r
+    CvSeq* seq;\r
+};\r
+\r
+template<typename _Tp> class CV_EXPORTS SeqIterator : public CvSeqReader\r
+{\r
+public:\r
+    SeqIterator();\r
+    SeqIterator(const Seq<_Tp>& seq, bool seekEnd=false);\r
+    void seek(size_t pos);\r
+    size_t tell() const;\r
+    _Tp& operator *();\r
+    const _Tp& operator *() const;\r
+    SeqIterator& operator ++();\r
+    SeqIterator operator ++(int) const;\r
+    SeqIterator& operator --();\r
+    SeqIterator operator --(int) const;\r
+\r
+    SeqIterator& operator +=(int);\r
+    SeqIterator& operator -=(int);\r
+\r
+    // this is index of the current element module seq->total*2\r
+    // (to distinguish between 0 and seq->total)\r
+    int index;\r
+};\r
+\r
+}\r
+\r
+#endif // __cplusplus\r
+\r
+#include "cxoperations.hpp"\r
+#include "cxmat.hpp"\r
+\r
+#endif /*_CXCORE_HPP_*/\r
index f8ce59237a14af99f02b9477a67a8da4f56b0610..8503eef75866839baf758428a72be4233096971c 100644 (file)
@@ -460,7 +460,7 @@ template<typename _Tp> inline Mat_<_Tp>::Mat_(const Mat_& m, const Range& rowRan
 template<typename _Tp> inline Mat_<_Tp>::Mat_(const Mat_& m, const Rect& roi)\r
     : Mat(m, roi) {}\r
 \r
-template<typename _Tp> template<int n> inline Mat_<_Tp>::Mat_(const Vec_<_Tp, n>& vec)\r
+template<typename _Tp> template<int n> inline Mat_<_Tp>::Mat_(const Vec<_Tp, n>& vec)\r
     : Mat(n, 1, DataType<_Tp>::type)\r
 {\r
     _Tp* d = (_Tp*)data;\r
@@ -626,15 +626,17 @@ process( const Mat_<T1>& m1, const Mat_<T2>& m2, Mat_<T3>& m3, Op op )
     }\r
 }\r
 \r
-template<typename M> struct CV_EXPORTS MatExpr_Base_\r
+template<typename M> class CV_EXPORTS MatExpr_Base_\r
 {\r
+public:\r
     MatExpr_Base_() {}\r
     virtual ~MatExpr_Base_() {}\r
     virtual void assignTo(M& m, int type=-1) const = 0;\r
 };\r
 \r
-template<typename E, typename M> struct CV_EXPORTS MatExpr_ : MatExpr_Base_<M>\r
+template<typename E, typename M> class CV_EXPORTS MatExpr_ : public MatExpr_Base_<M>\r
 {\r
+public:\r
     MatExpr_(const E& _e) : e(_e) {}\r
     ~MatExpr_() {}\r
     operator M() const { return (M)e; }\r
@@ -696,8 +698,9 @@ template<typename _Tp> inline Mat_<_Tp>::operator MatExpr_<Mat_<_Tp>, Mat_<_Tp>
 inline Mat::operator MatExpr_<Mat, Mat>() const\r
 { return MatExpr_<Mat, Mat>(*this); }\r
 \r
-template<typename M> struct CV_EXPORTS MatOp_Sub_\r
+template<typename M> class CV_EXPORTS MatOp_Sub_\r
 {\r
+public:\r
     MatOp_Sub_() {}\r
 \r
     static void apply(const M& a, const M& b, M& c, int type=-1)\r
@@ -715,8 +718,9 @@ template<typename M> struct CV_EXPORTS MatOp_Sub_
     }\r
 };\r
 \r
-template<typename M> struct CV_EXPORTS MatOp_Scale_\r
+template<typename M> class CV_EXPORTS MatOp_Scale_\r
 {\r
+public:\r
     MatOp_Scale_() {}\r
 \r
     static void apply(const M& a, double alpha, M& c, int type=-1)\r
@@ -725,8 +729,9 @@ template<typename M> struct CV_EXPORTS MatOp_Scale_
     }\r
 };\r
 \r
-template<typename M> struct CV_EXPORTS MatOp_ScaleAddS_\r
+template<typename M> class CV_EXPORTS MatOp_ScaleAddS_\r
 {\r
+public:\r
     MatOp_ScaleAddS_() {}\r
 \r
     static void apply(const M& a, double alpha, double beta, M& c, int type=-1)\r
@@ -735,8 +740,9 @@ template<typename M> struct CV_EXPORTS MatOp_ScaleAddS_
     }\r
 };\r
 \r
-template<typename M> struct CV_EXPORTS MatOp_AddS_\r
+template<typename M> class CV_EXPORTS MatOp_AddS_\r
 {\r
+public:\r
     MatOp_AddS_() {}\r
 \r
     static void apply(const M& a, const Scalar& s, M& c, int type=-1)\r
@@ -754,8 +760,9 @@ template<typename M> struct CV_EXPORTS MatOp_AddS_
     }\r
 };\r
 \r
-template<typename M> struct CV_EXPORTS MatOp_AddEx_\r
+template<typename M> class CV_EXPORTS MatOp_AddEx_\r
 {\r
+public:\r
     MatOp_AddEx_() {}\r
 \r
     static void apply(const M& a, double alpha, const M& b,\r
@@ -774,8 +781,9 @@ template<typename M> struct CV_EXPORTS MatOp_AddEx_
     }\r
 };\r
 \r
-template<typename M> struct CV_EXPORTS MatOp_Bin_\r
+template<typename M> class CV_EXPORTS MatOp_Bin_\r
 {\r
+public:\r
     MatOp_Bin_() {}\r
 \r
     static void apply(const M& a, const M& b, int _op, M& c, int type=-1)\r
@@ -807,8 +815,9 @@ template<typename M> struct CV_EXPORTS MatOp_Bin_
     }\r
 };\r
 \r
-template<typename M> struct CV_EXPORTS MatOp_BinS_\r
+template<typename M> class CV_EXPORTS MatOp_BinS_\r
 {\r
+public:\r
     MatOp_BinS_() {}\r
 \r
     static void apply(const M& a, const Scalar& s, int _op, M& c, int type=-1)\r
@@ -842,8 +851,9 @@ template<typename M> struct CV_EXPORTS MatOp_BinS_
     }\r
 };\r
 \r
-template<typename M> struct CV_EXPORTS MatOp_T_\r
+template<typename M> class CV_EXPORTS MatOp_T_\r
 {\r
+public:\r
     MatOp_T_() {}\r
 \r
     static void apply(const M& a, double scale, M& c, int type=-1)\r
@@ -864,8 +874,9 @@ template<typename M> struct CV_EXPORTS MatOp_T_
 };\r
 \r
 \r
-template<typename M> struct CV_EXPORTS MatOp_MatMul_\r
+template<typename M> class CV_EXPORTS MatOp_MatMul_\r
 {\r
+public:\r
     MatOp_MatMul_() {}\r
 \r
     static void apply(const M& a, const M& b, double scale, int flags, M& c, int type=-1)\r
@@ -884,8 +895,9 @@ template<typename M> struct CV_EXPORTS MatOp_MatMul_
 };\r
 \r
 \r
-template<typename M> struct CV_EXPORTS MatOp_MatMulAdd_\r
+template<typename M> class CV_EXPORTS MatOp_MatMulAdd_\r
 {\r
+public:\r
     MatOp_MatMulAdd_() {}\r
 \r
     static void apply(const M& a, const M& b, double alpha,\r
@@ -905,8 +917,9 @@ template<typename M> struct CV_EXPORTS MatOp_MatMulAdd_
 };\r
 \r
 \r
-template<typename M> struct CV_EXPORTS MatOp_Cmp_\r
+template<typename M> class CV_EXPORTS MatOp_Cmp_\r
 {\r
+public:\r
     MatOp_Cmp_() {}\r
 \r
     static void apply(const M& a, const M& b, int op, M& c, int type=-1)\r
@@ -924,8 +937,9 @@ template<typename M> struct CV_EXPORTS MatOp_Cmp_
     }\r
 };\r
 \r
-template<typename M> struct CV_EXPORTS MatOp_CmpS_\r
+template<typename M> class CV_EXPORTS MatOp_CmpS_\r
 {\r
+public:\r
     MatOp_CmpS_() {}\r
 \r
     static void apply(const M& a, double alpha, int op, M& c, int type=-1)\r
@@ -943,8 +957,9 @@ template<typename M> struct CV_EXPORTS MatOp_CmpS_
     }\r
 };\r
 \r
-template<typename M> struct CV_EXPORTS MatOp_MulDiv_\r
+template<typename M> class CV_EXPORTS MatOp_MulDiv_\r
 {\r
+public:\r
     MatOp_MulDiv_() {}\r
 \r
     static void apply(const M& a, const M& b, double alpha, char op, M& c, int type=-1)\r
@@ -965,8 +980,9 @@ template<typename M> struct CV_EXPORTS MatOp_MulDiv_
     }\r
 };\r
 \r
-template<typename M> struct CV_EXPORTS MatOp_DivRS_\r
+template<typename M> class CV_EXPORTS MatOp_DivRS_\r
 {\r
+public:\r
     MatOp_DivRS_() {}\r
 \r
     static void apply(const M& a, double alpha, M& c, int type=-1)\r
@@ -986,8 +1002,9 @@ template<typename M> struct CV_EXPORTS MatOp_DivRS_
 };\r
 \r
 \r
-template<typename M> struct CV_EXPORTS MatOp_Inv_\r
+template<typename M> class CV_EXPORTS MatOp_Inv_\r
 {\r
+public:\r
     MatOp_Inv_() {}\r
 \r
     static void apply(const M& a, int method, M& c, int type=-1)\r
@@ -1006,8 +1023,9 @@ template<typename M> struct CV_EXPORTS MatOp_Inv_
 };\r
 \r
 \r
-template<typename M> struct CV_EXPORTS MatOp_Solve_\r
+template<typename M> class CV_EXPORTS MatOp_Solve_\r
 {\r
+public:\r
     MatOp_Solve_() {}\r
 \r
     static void apply(const M& a, const M& b, int method, M& c, int type=-1)\r
@@ -1025,8 +1043,9 @@ template<typename M> struct CV_EXPORTS MatOp_Solve_
     }\r
 };\r
 \r
-template<typename M> struct CV_EXPORTS MatOp_Set_\r
+template<typename M> class CV_EXPORTS MatOp_Set_\r
 {\r
+public:\r
     MatOp_Set_() {}\r
 \r
     static void apply(Size size, int type0, const Scalar& s, int mtype, M& c, int type=-1)\r
@@ -1044,8 +1063,9 @@ template<typename M> struct CV_EXPORTS MatOp_Set_
 };\r
 \r
 template<typename A1, typename M, typename Op>\r
-struct CV_EXPORTS MatExpr_Op1_\r
+class CV_EXPORTS MatExpr_Op1_\r
 {\r
+public:\r
     MatExpr_Op1_(const A1& _a1) : a1(_a1) {}\r
     void assignTo(Mat& m, int type=-1) const { Op::apply(a1, (M&)m, type); }\r
     operator M() const { M result; assignTo(result); return result; }\r
@@ -1054,8 +1074,9 @@ struct CV_EXPORTS MatExpr_Op1_
 };\r
 \r
 template<typename A1, typename A2, typename M, typename Op>\r
-struct CV_EXPORTS MatExpr_Op2_\r
+class CV_EXPORTS MatExpr_Op2_\r
 {\r
+public:\r
     MatExpr_Op2_(const A1& _a1, const A2& _a2) : a1(_a1), a2(_a2) {}\r
     void assignTo(Mat& m, int type=-1) const { Op::apply(a1, a2, (M&)m, type); }\r
     operator M() const { M result; assignTo(result); return result; }\r
@@ -1064,8 +1085,9 @@ struct CV_EXPORTS MatExpr_Op2_
 };\r
 \r
 template<typename A1, typename A2, typename A3, typename M, typename Op>\r
-struct CV_EXPORTS MatExpr_Op3_\r
+class CV_EXPORTS MatExpr_Op3_\r
 {\r
+public:\r
     MatExpr_Op3_(const A1& _a1, const A2& _a2, const A3& _a3) : a1(_a1), a2(_a2), a3(_a3) {}\r
     void assignTo(Mat& m, int type=-1) const { Op::apply(a1, a2, a3, (M&)m, type); }\r
     operator M() const { M result; assignTo(result); return result; }\r
@@ -1074,8 +1096,9 @@ struct CV_EXPORTS MatExpr_Op3_
 };\r
 \r
 template<typename A1, typename A2, typename A3, typename A4, typename M, typename Op>\r
-struct CV_EXPORTS MatExpr_Op4_\r
+class CV_EXPORTS MatExpr_Op4_\r
 {\r
+public:\r
     MatExpr_Op4_(const A1& _a1, const A2& _a2, const A3& _a3, const A4& _a4)\r
         : a1(_a1), a2(_a2), a3(_a3), a4(_a4) {}\r
     void assignTo(Mat& m, int type=-1) const { Op::apply(a1, a2, a3, a4, (M&)m, type); }\r
@@ -1085,8 +1108,9 @@ struct CV_EXPORTS MatExpr_Op4_
 };\r
 \r
 template<typename A1, typename A2, typename A3, typename A4, typename A5, typename M, typename Op>\r
-struct CV_EXPORTS MatExpr_Op5_\r
+class CV_EXPORTS MatExpr_Op5_\r
 {\r
+public:\r
     MatExpr_Op5_(const A1& _a1, const A2& _a2, const A3& _a3, const A4& _a4, const A5& _a5)\r
         : a1(_a1), a2(_a2), a3(_a3), a4(_a4), a5(_a5) {}\r
     void assignTo(Mat& m, int type=-1) const { Op::apply(a1, a2, a3, a4, a5, (M&)m, type); }\r
@@ -1096,8 +1120,9 @@ struct CV_EXPORTS MatExpr_Op5_
 };\r
 \r
 template<typename A1, typename A2, typename A3, typename A4, typename A5, typename A6, typename M, typename Op>\r
-struct CV_EXPORTS MatExpr_Op6_\r
+class CV_EXPORTS MatExpr_Op6_\r
 {\r
+public:\r
     MatExpr_Op6_(const A1& _a1, const A2& _a2, const A3& _a3,\r
                     const A4& _a4, const A5& _a5, const A6& _a6)\r
         : a1(_a1), a2(_a2), a3(_a3), a4(_a4), a5(_a5), a6(_a6) {}\r
@@ -3425,7 +3450,7 @@ template<typename _Tp> inline MatIterator_<_Tp> Mat_<_Tp>::end()
     return it;\r
 }\r
 \r
-template<typename _Tp> struct CV_EXPORTS MatOp_Iter_\r
+template<typename _Tp> class CV_EXPORTS MatOp_Iter_\r
 {\r
     MatOp_Iter_() {}\r
 \r
index 1c5e8de6427750f9905c82ada1f605a421549228..bdb2eb6f2c48a8ece6eb2c0818631c7c62413315 100644 (file)
@@ -133,73 +133,133 @@ template<> inline unsigned saturate_cast<unsigned>(float v){ return cvRound(v);
 template<> inline unsigned saturate_cast<unsigned>(double v) { return cvRound(v); }
 
 
-/////////////////////////// short vector (Vec_) /////////////////////////////
+/////////////////////////// short vector (Vec) /////////////////////////////
 
-template<typename _Tp, int cn> inline Vec_<_Tp, cn>::Vec_() {}
-template<typename _Tp, int cn> inline Vec_<_Tp, cn>::Vec_(_Tp v0)
+template<typename _Tp, int cn> inline Vec<_Tp, cn>::Vec() {}
+template<typename _Tp, int cn> inline Vec<_Tp, cn>::Vec(_Tp v0)
 {
     val[0] = v0;
     for(int i = 1; i < cn; i++) val[i] = _Tp();
 }
 
-template<typename _Tp, int cn> inline Vec_<_Tp, cn>::Vec_(_Tp v0, _Tp v1)
+template<typename _Tp, int cn> inline Vec<_Tp, cn>::Vec(_Tp v0, _Tp v1)
 {
+    assert(cn >= 2);
     val[0] = v0; val[1] = v1;
     for(int i = 2; i < cn; i++) val[i] = _Tp(0);
 }
 
-template<typename _Tp, int cn> inline Vec_<_Tp, cn>::Vec_(_Tp v0, _Tp v1, _Tp v2)
+template<typename _Tp, int cn> inline Vec<_Tp, cn>::Vec(_Tp v0, _Tp v1, _Tp v2)
 {
+    assert(cn >= 3);
     val[0] = v0; val[1] = v1; val[2] = v2;
     for(int i = 3; i < cn; i++) val[i] = _Tp(0);
 }
 
-template<typename _Tp, int cn> inline Vec_<_Tp, cn>::Vec_(_Tp v0, _Tp v1, _Tp v2, _Tp v3)
+template<typename _Tp, int cn> inline Vec<_Tp, cn>::Vec(_Tp v0, _Tp v1, _Tp v2, _Tp v3)
 {
+    assert(cn >= 4);
     val[0] = v0; val[1] = v1; val[2] = v2; val[3] = v3;
     for(int i = 4; i < cn; i++) val[i] = _Tp(0);
 }
 
-template<typename _Tp, int cn> inline Vec_<_Tp, cn>::Vec_(const Vec_<_Tp, cn>& v)
+template<typename _Tp, int cn> inline Vec<_Tp, cn>::Vec(_Tp v0, _Tp v1, _Tp v2, _Tp v3, _Tp v4)
+{
+    assert(cn >= 5);
+    val[0] = v0; val[1] = v1; val[2] = v2; val[3] = v3; val[4] = v4;
+    for(int i = 5; i < cn; i++) val[i] = _Tp(0);
+}
+
+template<typename _Tp, int cn> inline Vec<_Tp, cn>::Vec(_Tp v0, _Tp v1, _Tp v2, _Tp v3,
+                                                        _Tp v4, _Tp v5)
+{
+    assert(cn >= 6);
+    val[0] = v0; val[1] = v1; val[2] = v2; val[3] = v3;
+    val[4] = v4; val[5] = v5;
+    for(int i = 6; i < cn; i++) val[i] = _Tp(0);
+}
+
+template<typename _Tp, int cn> inline Vec<_Tp, cn>::Vec(_Tp v0, _Tp v1, _Tp v2, _Tp v3,
+                                                        _Tp v4, _Tp v5, _Tp v6)
+{
+    assert(cn >= 7);
+    val[0] = v0; val[1] = v1; val[2] = v2; val[3] = v3;
+    val[4] = v4; val[5] = v5; val[6] = v6;
+    for(int i = 7; i < cn; i++) val[i] = _Tp(0);
+}
+
+template<typename _Tp, int cn> inline Vec<_Tp, cn>::Vec(_Tp v0, _Tp v1, _Tp v2, _Tp v3,
+                                                        _Tp v4, _Tp v5, _Tp v6, _Tp v7)
+{
+    assert(cn >= 8);
+    val[0] = v0; val[1] = v1; val[2] = v2; val[3] = v3;
+    val[4] = v4; val[5] = v5; val[6] = v6; val[7] = v7;
+    for(int i = 8; i < cn; i++) val[i] = _Tp(0);
+}
+
+template<typename _Tp, int cn> inline Vec<_Tp, cn>::Vec(_Tp v0, _Tp v1, _Tp v2, _Tp v3,
+                                                        _Tp v4, _Tp v5, _Tp v6, _Tp v7,
+                                                        _Tp v8)
+{
+    assert(cn >= 9);
+    val[0] = v0; val[1] = v1; val[2] = v2; val[3] = v3;
+    val[4] = v4; val[5] = v5; val[6] = v6; val[7] = v7;
+    val[8] = v8;
+    for(int i = 9; i < cn; i++) val[i] = _Tp(0);
+}
+
+template<typename _Tp, int cn> inline Vec<_Tp, cn>::Vec(_Tp v0, _Tp v1, _Tp v2, _Tp v3,
+                                                        _Tp v4, _Tp v5, _Tp v6, _Tp v7,
+                                                        _Tp v8, _Tp v9)
+{
+    assert(cn >= 10);
+    val[0] = v0; val[1] = v1; val[2] = v2; val[3] = v3;
+    val[4] = v4; val[5] = v5; val[6] = v6; val[7] = v7;
+    val[8] = v8; val[9] = v9;
+    for(int i = 10; i < cn; i++) val[i] = _Tp(0);
+}
+
+
+template<typename _Tp, int cn> inline Vec<_Tp, cn>::Vec(const Vec<_Tp, cn>& v)
 {
     for( int i = 0; i < cn; i++ ) val[i] = v.val[i];
 }
 
-template<typename _Tp, int cn> inline Vec_<_Tp, cn> Vec_<_Tp, cn>::all(_Tp alpha)
+template<typename _Tp, int cn> inline Vec<_Tp, cn> Vec<_Tp, cn>::all(_Tp alpha)
 {
-    Vec_ v;
+    Vec v;
     for( int i = 0; i < cn; i++ ) v.val[i] = alpha;
     return v;
 }
 
-template<typename _Tp, int cn> inline _Tp Vec_<_Tp, cn>::dot(const Vec_<_Tp, cn>& v) const
+template<typename _Tp, int cn> inline _Tp Vec<_Tp, cn>::dot(const Vec<_Tp, cn>& v) const
 {
     _Tp s = 0;
     for( int i = 0; i < cn; i++ ) s += val[i]*v.val[i];
     return s;
 }
 
-template<typename _Tp, int cn> inline double Vec_<_Tp, cn>::ddot(const Vec_<_Tp, cn>& v) const
+template<typename _Tp, int cn> inline double Vec<_Tp, cn>::ddot(const Vec<_Tp, cn>& v) const
 {
     double s = 0;
     for( int i = 0; i < cn; i++ ) s += (double)val[i]*v.val[i];
     return s;
 }
 
-template<typename _Tp, int cn> inline Vec_<_Tp, cn> Vec_<_Tp, cn>::cross(const Vec_<_Tp, cn>& v) const
+template<typename _Tp, int cn> inline Vec<_Tp, cn> Vec<_Tp, cn>::cross(const Vec<_Tp, cn>& v) const
 {
-    return Vec_<_Tp, cn>(); // for arbitrary-size vector there is no cross-product defined
+    return Vec<_Tp, cn>(); // for arbitrary-size vector there is no cross-product defined
 }
 
 template<typename _Tp, int cn> template<typename T2>
-inline Vec_<_Tp, cn>::operator Vec_<T2, cn>() const
+inline Vec<_Tp, cn>::operator Vec<T2, cn>() const
 {
-    Vec_<T2, cn> v;
+    Vec<T2, cn> v;
     for( int i = 0; i < cn; i++ ) v.val[i] = saturate_cast<T2>(val[i]);
     return v;
 }
 
-template<typename _Tp, int cn> inline Vec_<_Tp, cn>::operator CvScalar() const
+template<typename _Tp, int cn> inline Vec<_Tp, cn>::operator CvScalar() const
 {
     CvScalar s = {{0,0,0,0}};
     int i;
@@ -208,81 +268,81 @@ template<typename _Tp, int cn> inline Vec_<_Tp, cn>::operator CvScalar() const
     return s;
 }
 
-template<typename _Tp, int cn> inline _Tp Vec_<_Tp, cn>::operator [](int i) const { return val[i]; }
-template<typename _Tp, int cn> inline _Tp& Vec_<_Tp, cn>::operator[](int i) { return val[i]; }
+template<typename _Tp, int cn> inline _Tp Vec<_Tp, cn>::operator [](int i) const { return val[i]; }
+template<typename _Tp, int cn> inline _Tp& Vec<_Tp, cn>::operator[](int i) { return val[i]; }
 
-template<typename _Tp, int cn> static inline Vec_<_Tp, cn>
-operator + (const Vec_<_Tp, cn>& a, const Vec_<_Tp, cn>& b)
+template<typename _Tp, int cn> static inline Vec<_Tp, cn>
+operator + (const Vec<_Tp, cn>& a, const Vec<_Tp, cn>& b)
 {
-    Vec_<_Tp, cn> c = a;
+    Vec<_Tp, cn> c = a;
     return c += b;
 }
 
-template<typename _Tp, int cn> static inline Vec_<_Tp, cn>
-operator - (const Vec_<_Tp, cn>& a, const Vec_<_Tp, cn>& b)
+template<typename _Tp, int cn> static inline Vec<_Tp, cn>
+operator - (const Vec<_Tp, cn>& a, const Vec<_Tp, cn>& b)
 {
-    Vec_<_Tp, cn> c = a;
+    Vec<_Tp, cn> c = a;
     return c -= b;
 }
 
 template<typename _Tp> static inline
-Vec_<_Tp, 2>& operator *= (Vec_<_Tp, 2>& a, _Tp alpha)
+Vec<_Tp, 2>& operator *= (Vec<_Tp, 2>& a, _Tp alpha)
 {
     a[0] *= alpha; a[1] *= alpha;
     return a;
 }
 
 template<typename _Tp> static inline
-Vec_<_Tp, 3>& operator *= (Vec_<_Tp, 3>& a, _Tp alpha)
+Vec<_Tp, 3>& operator *= (Vec<_Tp, 3>& a, _Tp alpha)
 {
     a[0] *= alpha; a[1] *= alpha; a[2] *= alpha;
     return a;
 }
 
 template<typename _Tp> static inline
-Vec_<_Tp, 4>& operator *= (Vec_<_Tp, 4>& a, _Tp alpha)
+Vec<_Tp, 4>& operator *= (Vec<_Tp, 4>& a, _Tp alpha)
 {
     a[0] *= alpha; a[1] *= alpha; a[2] *= alpha; a[3] *= alpha;
     return a;
 }
 
-template<typename _Tp, int cn> static inline Vec_<_Tp, cn>
-operator * (const Vec_<_Tp, cn>& a, _Tp alpha)
+template<typename _Tp, int cn> static inline Vec<_Tp, cn>
+operator * (const Vec<_Tp, cn>& a, _Tp alpha)
 {
-    Vec_<_Tp, cn> c = a;
+    Vec<_Tp, cn> c = a;
     return c *= alpha;
 }
 
-template<typename _Tp, int cn> static inline Vec_<_Tp, cn>
-operator * (_Tp alpha, const Vec_<_Tp, cn>& a)
+template<typename _Tp, int cn> static inline Vec<_Tp, cn>
+operator * (_Tp alpha, const Vec<_Tp, cn>& a)
 {
     return a * alpha;
 }
 
-template<typename _Tp, int cn> static inline Vec_<_Tp, cn>
-operator - (const Vec_<_Tp, cn>& a)
+template<typename _Tp, int cn> static inline Vec<_Tp, cn>
+operator - (const Vec<_Tp, cn>& a)
 {
-    Vec_<_Tp,cn> t;
+    Vec<_Tp,cn> t;
     for( int i = 0; i < cn; i++ ) t.val[i] = saturate_cast<_Tp>(-a.val[i]);
     return t;
 }
 
-template<> inline Vec_<float, 3> Vec_<float, 3>::cross(const Vec_<float, 3>& v) const
+template<> inline Vec<float, 3> Vec<float, 3>::cross(const Vec<float, 3>& v) const
 {
-    return Vec_<float,3>(val[1]*v.val[2] - val[2]*v.val[1],
+    return Vec<float,3>(val[1]*v.val[2] - val[2]*v.val[1],
                      val[2]*v.val[0] - val[0]*v.val[2],
                      val[0]*v.val[1] - val[1]*v.val[0]);
 }
 
-template<> inline Vec_<double, 3> Vec_<double, 3>::cross(const Vec_<double, 3>& v) const
+template<> inline Vec<double, 3> Vec<double, 3>::cross(const Vec<double, 3>& v) const
 {
-    return Vec_<double,3>(val[1]*v.val[2] - val[2]*v.val[1],
+    return Vec<double,3>(val[1]*v.val[2] - val[2]*v.val[1],
                      val[2]*v.val[0] - val[0]*v.val[2],
                      val[0]*v.val[1] - val[1]*v.val[0]);
 }
 
 template<typename T1, typename T2> static inline
-Vec_<T1, 2>& operator += (Vec_<T1, 2>& a, const Vec_<T2, 2>& b)
+Vec<T1, 2>& operator += (Vec<T1, 2>& a, const Vec<T2, 2>& b)
 {
     a[0] = saturate_cast<T1>(a[0] + b[0]);
     a[1] = saturate_cast<T1>(a[1] + b[1]);
@@ -290,7 +350,7 @@ Vec_<T1, 2>& operator += (Vec_<T1, 2>& a, const Vec_<T2, 2>& b)
 }
 
 template<typename T1, typename T2> static inline
-Vec_<T1, 3>& operator += (Vec_<T1, 3>& a, const Vec_<T2, 3>& b)
+Vec<T1, 3>& operator += (Vec<T1, 3>& a, const Vec<T2, 3>& b)
 {
     a[0] = saturate_cast<T1>(a[0] + b[0]);
     a[1] = saturate_cast<T1>(a[1] + b[1]);
@@ -299,7 +359,7 @@ Vec_<T1, 3>& operator += (Vec_<T1, 3>& a, const Vec_<T2, 3>& b)
 }
 
 template<typename T1, typename T2> static inline
-Vec_<T1, 4>& operator += (Vec_<T1, 4>& a, const Vec_<T2, 4>& b)
+Vec<T1, 4>& operator += (Vec<T1, 4>& a, const Vec<T2, 4>& b)
 {
     a[0] = saturate_cast<T1>(a[0] + b[0]);
     a[1] = saturate_cast<T1>(a[1] + b[1]);
@@ -481,7 +541,7 @@ template<typename _Tp> inline Point3_<_Tp>::Point3_(const Point3_& pt) : x(pt.x)
 template<typename _Tp> inline Point3_<_Tp>::Point3_(const Point_<_Tp>& pt) : x(pt.x), y(pt.y), z(_Tp()) {}
 template<typename _Tp> inline Point3_<_Tp>::Point3_(const CvPoint3D32f& pt) :
     x(saturate_cast<_Tp>(pt.x)), y(saturate_cast<_Tp>(pt.y)), z(saturate_cast<_Tp>(pt.z)) {}
-template<typename _Tp> inline Point3_<_Tp>::Point3_(const Vec_<_Tp, 3>& t) : x(t[0]), y(t[1]), z(t[2]) {}
+template<typename _Tp> inline Point3_<_Tp>::Point3_(const Vec<_Tp, 3>& t) : x(t[0]), y(t[1]), z(t[2]) {}
 
 template<typename _Tp> inline Point3_<_Tp>::operator Point3_<int>() const
 { return Point3_<int>(saturate_cast<int>(x), saturate_cast<int>(y), saturate_cast<int>(z)); }
@@ -900,6 +960,8 @@ template <typename _Tp> inline Vector<_Tp>::Vector(size_t _size, const _Tp& val)
 }
 template <typename _Tp> inline Vector<_Tp>::Vector(_Tp* _data, size_t _size, bool _copyData)
 { set(_data, _size, _copyData); }
+template <typename _Tp> template<int n> inline Vector<_Tp>::Vector(const Vec<_Tp, n>& vec)
+{ set((_Tp*)&vec.val[0], n, true); }
 template <typename _Tp> inline Vector<_Tp>::Vector(const std::vector<_Tp>& vec, bool _copyData)
 { set(&vec[0], vec.size(), _copyData); }
 template <typename _Tp> inline Vector<_Tp>::Vector(const Vector& d)
@@ -979,7 +1041,7 @@ template <typename _Tp> inline void Vector<_Tp>::addref()
 template <typename _Tp> inline void Vector<_Tp>::release()
 {
     if( hdr.refcount && --*hdr.refcount == 0 )
-        fastFree_<_Tp>(hdr.datastart, hdr.capacity);
+        deallocate<_Tp>(hdr.datastart, hdr.capacity);
     hdr = Hdr();
 }
 
@@ -1171,7 +1233,7 @@ template<typename _Tp, size_t fixed_size> inline void AutoBuffer<_Tp, fixed_size
     deallocate();
     if(_size > fixed_size)
     {
-        ptr = (_Tp*)fastMalloc(_size*sizeof(_Tp));
+        ptr = cv::allocate<_Tp>(_size);
         size = _size;
     }
 }
@@ -1180,7 +1242,7 @@ template<typename _Tp, size_t fixed_size> inline void AutoBuffer<_Tp, fixed_size
 {
     if( ptr != buf )
     {
-        fastFree(ptr);
+        cv::deallocate<_Tp>(ptr, size);
         ptr = buf;
         size = fixed_size;
     }
@@ -1252,6 +1314,8 @@ template<typename _Tp> inline const _Tp* Ptr<_Tp>::operator -> () const { return
 template<typename _Tp> inline Ptr<_Tp>::operator _Tp* () { return obj; }
 template<typename _Tp> inline Ptr<_Tp>::operator const _Tp*() const { return obj; }
 
+template<typename _Tp> inline bool Ptr<_Tp>::empty() const { return obj == 0; }
+
 //////////////////////////////////////// XML & YAML I/O ////////////////////////////////////
 
 template<> inline void Ptr<CvFileStorage>::delete_obj()
@@ -1317,7 +1381,7 @@ template<typename _Tp> inline void write(FileStorage& fs, const Rect_<_Tp>& r )
     write(fs, r.height);
 }
 
-template<typename _Tp, int cn> inline void write(FileStorage& fs, const Vec_<_Tp, cn>& v )
+template<typename _Tp, int cn> inline void write(FileStorage& fs, const Vec<_Tp, cn>& v )
 {
     for(int i = 0; i < cn; i++)
         write(fs, v.val[i]);
@@ -1337,8 +1401,9 @@ inline void write(FileStorage& fs, const Range& r )
     write(fs, r.end);
 }
 
-struct CV_EXPORTS WriteStructContext
+class CV_EXPORTS WriteStructContext
 {
+public:
     WriteStructContext(FileStorage& _fs, const String& name,
         int flags, const String& typeName=String()) : fs(&_fs)
     {
@@ -1387,7 +1452,7 @@ template<typename _Tp> inline void write(FileStorage& fs, const String& name, co
     write(fs, r.height);
 }
 
-template<typename _Tp, int cn> inline void write(FileStorage& fs, const String& name, const Vec_<_Tp, cn>& v )
+template<typename _Tp, int cn> inline void write(FileStorage& fs, const String& name, const Vec<_Tp, cn>& v )
 {
     WriteStructContext ws(fs, name, CV_NODE_SEQ+CV_NODE_FLOW);
     for(int i = 0; i < cn; i++)
@@ -1410,8 +1475,9 @@ inline void write(FileStorage& fs, const String& name, const Range& r )
     write(fs, r.end);
 }
 
-template<typename _Tp, int numflag> struct CV_EXPORTS VecWriterProxy
+template<typename _Tp, int numflag> class CV_EXPORTS VecWriterProxy
 {
+public:
     VecWriterProxy( FileStorage* _fs ) : fs(_fs) {}
     void operator()(const Vector<_Tp>& vec) const
     {
@@ -1422,8 +1488,9 @@ template<typename _Tp, int numflag> struct CV_EXPORTS VecWriterProxy
     FileStorage* fs;
 };
 
-template<typename _Tp> struct CV_EXPORTS VecWriterProxy<_Tp,1>
+template<typename _Tp> class CV_EXPORTS VecWriterProxy<_Tp,1>
 {
+public:
     VecWriterProxy( FileStorage* _fs ) : fs(_fs) {}
     void operator()(const Vector<_Tp>& vec) const
     {
@@ -1470,11 +1537,11 @@ static inline FileStorage& operator << (FileStorage& fs, const char* str)
 
 inline FileNode FileStorage::operator[](const String& nodename) const
 {
-    return FileNode(fs.obj, cvGetFileNodeByName(fs.obj, 0, nodename.c_str()));
+    return FileNode(fs, cvGetFileNodeByName(fs, 0, nodename.c_str()));
 }
 inline FileNode FileStorage::operator[](const char* nodename) const
 {
-    return FileNode(fs.obj, cvGetFileNodeByName(fs.obj, 0, nodename));
+    return FileNode(fs, cvGetFileNodeByName(fs, 0, nodename));
 }
 
 inline FileNode::FileNode() : fs(0), node(0) {}
@@ -1566,8 +1633,9 @@ inline void FileNode::readRaw( const String& fmt, Vector<uchar>& vec ) const
     begin().readRaw( fmt, vec );
 }
 
-template<typename _Tp, int numflag> struct CV_EXPORTS VecReaderProxy
+template<typename _Tp, int numflag> class CV_EXPORTS VecReaderProxy
 {
+public:
     VecReaderProxy( FileNodeIterator* _it ) : it(_it) {}
     void operator()(Vector<_Tp>& vec, size_t count) const
     {
@@ -1579,8 +1647,9 @@ template<typename _Tp, int numflag> struct CV_EXPORTS VecReaderProxy
     FileNodeIterator* it;
 };
 
-template<typename _Tp> struct CV_EXPORTS VecReaderProxy<_Tp,1>
+template<typename _Tp> class CV_EXPORTS VecReaderProxy<_Tp,1>
 {
+public:
     VecReaderProxy( FileNodeIterator* _it ) : it(_it) {}
     void operator()(Vector<_Tp>& vec, size_t count) const
     {
@@ -1884,25 +1953,29 @@ template<typename _Tp, class _LT> void sort( Vector<_Tp>& vec, _LT LT=_LT() )
     }
 }
 
-template<typename _Tp> struct CV_EXPORTS LessThan
+template<typename _Tp> class CV_EXPORTS LessThan
 {
+public:
     bool operator()(const _Tp& a, const _Tp& b) const { return a < b; }
 };
 
-template<typename _Tp> struct CV_EXPORTS GreaterEq
+template<typename _Tp> class CV_EXPORTS GreaterEq
 {
+public:
     bool operator()(const _Tp& a, const _Tp& b) const { return a >= b; }
 };
 
-template<typename _Tp> struct CV_EXPORTS LessThanIdx
+template<typename _Tp> class CV_EXPORTS LessThanIdx
 {
+public:
     LessThanIdx( const _Tp* _arr ) : arr(_arr) {}
     bool operator()(int a, int b) const { return arr[a] < arr[b]; }
     const _Tp* arr;
 };
 
-template<typename _Tp> struct CV_EXPORTS GreaterEqIdx
+template<typename _Tp> class CV_EXPORTS GreaterEqIdx
 {
+public:
     GreaterEqIdx( const _Tp* _arr ) : arr(_arr) {}
     bool operator()(int a, int b) const { return arr[a] >= arr[b]; }
     const _Tp* arr;
index cc3a3e7db2c1323912825ce90194b3dae114e0e9..a71b3880f68103f581180f14a3cce0be63b678f2 100644 (file)
@@ -47,26 +47,26 @@ namespace cv
 
 inline float sqr(uchar a) { return CV_8TO32F_SQR(a); }
 inline float sqr(float a) { return a*a; }
-inline Vec_<float, 3> sqr(const Vec_<uchar, 3>& a)
+inline Vec<float, 3> sqr(const Vec<uchar, 3>& a)
 {
-    return Vec_<float, 3>(CV_8TO32F_SQR(a[0]), CV_8TO32F_SQR(a[1]), CV_8TO32F_SQR(a[2]));
+    return Vec<float, 3>(CV_8TO32F_SQR(a[0]), CV_8TO32F_SQR(a[1]), CV_8TO32F_SQR(a[2]));
 }
-inline Vec_<float, 3> sqr(const Vec_<float, 3>& a)
+inline Vec<float, 3> sqr(const Vec<float, 3>& a)
 {
-    return Vec_<float, 3>(a[0]*a[0], a[1]*a[1], a[2]*a[2]);
+    return Vec<float, 3>(a[0]*a[0], a[1]*a[1], a[2]*a[2]);
 }
 inline float multiply(uchar a, uchar b) { return CV_8TO32F(a)*CV_8TO32F(b); }
 inline float multiply(float a, float b) { return a*b; }
-inline Vec_<float, 3> multiply(const Vec_<uchar, 3>& a, const Vec_<uchar, 3>& b)
+inline Vec<float, 3> multiply(const Vec<uchar, 3>& a, const Vec<uchar, 3>& b)
 {
-    return Vec_<float, 3>(
+    return Vec<float, 3>(
         CV_8TO32F(a[0])*CV_8TO32F(b[0]),
         CV_8TO32F(a[1])*CV_8TO32F(b[1]),
         CV_8TO32F(a[2])*CV_8TO32F(b[2]));
 }
-inline Vec_<float, 3> multiply(const Vec_<float, 3>& a, const Vec_<float, 3>& b)
+inline Vec<float, 3> multiply(const Vec<float, 3>& a, const Vec<float, 3>& b)
 {
-    return Vec_<float, 3>(a[0]*b[0], a[1]*b[1], a[2]*b[2]);
+    return Vec<float, 3>(a[0]*b[0], a[1]*b[1], a[2]*b[2]);
 }
 inline float addw(uchar a, float alpha, float b, float beta)
 {
@@ -76,15 +76,15 @@ inline float addw(float a, float alpha, float b, float beta)
 {
     return b*beta + a*alpha;
 }
-inline Vec_<float, 3> addw(const Vec_<uchar, 3>& a, float alpha, const Vec_<float, 3>& b, float beta)
+inline Vec<float, 3> addw(const Vec<uchar, 3>& a, float alpha, const Vec<float, 3>& b, float beta)
 {
-    return Vec_<float, 3>(b[0]*beta + CV_8TO32F(a[0])*alpha,
+    return Vec<float, 3>(b[0]*beta + CV_8TO32F(a[0])*alpha,
                           b[1]*beta + CV_8TO32F(a[1])*alpha,
                           b[2]*beta + CV_8TO32F(a[2])*alpha);
 }
-inline Vec_<float, 3> addw(const Vec_<float, 3>& a, float alpha, const Vec_<float, 3>& b, float beta)
+inline Vec<float, 3> addw(const Vec<float, 3>& a, float alpha, const Vec<float, 3>& b, float beta)
 {
-    return Vec_<float, 3>(b[0]*beta + a[0]*alpha,
+    return Vec<float, 3>(b[0]*beta + a[0]*alpha,
                           b[1]*beta + a[1]*alpha,
                           b[2]*beta + a[2]*alpha);
 }
@@ -361,11 +361,11 @@ void accumulate( const Mat& src, Mat& dst, const Mat& mask )
         if( src.type() == CV_8UC1 && dst.type() == CV_32FC1 )
             func = accMask_<uchar, float>;
         else if( src.type() == CV_8UC3 && dst.type() == CV_32FC3 )
-            func = accMask_<Vec_<uchar, 3>, Vec_<float, 3> >;
+            func = accMask_<Vec<uchar, 3>, Vec<float, 3> >;
         else if( src.type() == CV_32FC1 && dst.type() == CV_32FC1 )
             func = accMask_<float, float>;
         else if( src.type() == CV_32FC3 && dst.type() == CV_32FC3 )
-            func = accMask_<Vec_<float, 3>, Vec_<float, 3> >;
+            func = accMask_<Vec<float, 3>, Vec<float, 3> >;
         else
             CV_Error( CV_StsUnsupportedFormat, "" );
 
@@ -398,11 +398,11 @@ void accumulateSquare( const Mat& src, Mat& dst, const Mat& mask )
         if( src.type() == CV_8UC1 && dst.type() == CV_32FC1 )
             func = accSqrMask_<uchar, float>;
         else if( src.type() == CV_8UC3 && dst.type() == CV_32FC3 )
-            func = accSqrMask_<Vec_<uchar, 3>, Vec_<float, 3> >;
+            func = accSqrMask_<Vec<uchar, 3>, Vec<float, 3> >;
         else if( src.type() == CV_32FC1 && dst.type() == CV_32FC1 )
             func = accSqrMask_<float, float>;
         else if( src.type() == CV_32FC3 && dst.type() == CV_32FC3 )
-            func = accSqrMask_<Vec_<float, 3>, Vec_<float, 3> >;
+            func = accSqrMask_<Vec<float, 3>, Vec<float, 3> >;
         else
             CV_Error( CV_StsUnsupportedFormat, "" );
 
@@ -436,11 +436,11 @@ void accumulateProduct( const Mat& src1, const Mat& src2, Mat& dst, const Mat& m
         if( src1.type() == CV_8UC1 && dst.type() == CV_32FC1 )
             func = accProdMask_<uchar, float>;
         else if( src1.type() == CV_8UC3 && dst.type() == CV_32FC3 )
-            func = accProdMask_<Vec_<uchar, 3>, Vec_<float, 3> >;
+            func = accProdMask_<Vec<uchar, 3>, Vec<float, 3> >;
         else if( src1.type() == CV_32FC1 && dst.type() == CV_32FC1 )
             func = accProdMask_<float, float>;
         else if( src1.type() == CV_32FC3 && dst.type() == CV_32FC3 )
-            func = accProdMask_<Vec_<float, 3>, Vec_<float, 3> >;
+            func = accProdMask_<Vec<float, 3>, Vec<float, 3> >;
         else
             CV_Error( CV_StsUnsupportedFormat, "" );
 
@@ -473,11 +473,11 @@ void accumulateWeighted( const Mat& src, Mat& dst, double alpha, const Mat& mask
         if( src.type() == CV_8UC1 && dst.type() == CV_32FC1 )
             func = accWMask_<uchar, float>;
         else if( src.type() == CV_8UC3 && dst.type() == CV_32FC3 )
-            func = accWMask_<Vec_<uchar, 3>, Vec_<float, 3> >;
+            func = accWMask_<Vec<uchar, 3>, Vec<float, 3> >;
         else if( src.type() == CV_32FC1 && dst.type() == CV_32FC1 )
             func = accWMask_<float, float>;
         else if( src.type() == CV_32FC3 && dst.type() == CV_32FC3 )
-            func = accWMask_<Vec_<float, 3>, Vec_<float, 3> >;
+            func = accWMask_<Vec<float, 3>, Vec<float, 3> >;
         else
             CV_Error( CV_StsUnsupportedFormat, "" );
 
index 3544f9d086a5d42e3fffdf58fbfcec996ece2c6f..4c2da982d050abb80e8ac71d6c3abb483d896279 100644 (file)
@@ -311,7 +311,7 @@ RotatedRect CAMShift( const Mat& probImage, Rect& window,
     return RotatedRect(Point2f(box.center), Size2f(box.size), box.angle);\r
 }\r
 \r
-int MeanShift( const Mat& probImage, Rect& window, TermCriteria criteria )\r
+int meanShift( const Mat& probImage, Rect& window, TermCriteria criteria )\r
 {\r
     CvConnectedComp comp;\r
     CvMat _probImage = probImage;\r
index 41bc0ef6d9df3964f6c6ee2198da9bd7a9e1c2a4..35530ae325ca5a8a3816cecae9c93d1dfb7e7de4 100644 (file)
@@ -161,7 +161,7 @@ void FilterEngine::init( const Ptr<BaseFilter>& _filter2D,
     
     if( isSeparable() )
     {
-        CV_Assert( rowFilter.obj && columnFilter.obj );
+        CV_Assert( !rowFilter.empty() && !columnFilter.empty() );
         ksize = Size(rowFilter->ksize, columnFilter->ksize);
         anchor = Point(rowFilter->anchor, columnFilter->anchor);
     }
@@ -290,9 +290,9 @@ int FilterEngine::start(Size _wholeSize, Rect _roi, int _maxBufRows)
     rowCount = dstY = 0;
     startY = startY0 = std::max(roi.y - anchor.y, 0);
     endY = std::min(roi.y + roi.height + ksize.height - anchor.y - 1, wholeSize.height);
-    if( columnFilter.obj )
+    if( !columnFilter.empty() )
         columnFilter->reset();
-    if( filter2D.obj )
+    if( !filter2D.empty() )
         filter2D->reset();
 
     return startY;
index 9104aa71ae73b0e6190935e79888961d285c06bb..cbe73f9840ae2948c7a9fd45899bcf1dad014768 100644 (file)
@@ -2329,7 +2329,7 @@ HaarClassifierCascade::HaarClassifierCascade(const String& filename)
 bool HaarClassifierCascade::load(const String& filename)\r
 {\r
     cascade = Ptr<CvHaarClassifierCascade>((CvHaarClassifierCascade*)cvLoad(filename.c_str(), 0, 0, 0));\r
-    return cascade.obj != 0;\r
+    return (CvHaarClassifierCascade*)cascade != 0;\r
 }\r
 \r
 void HaarClassifierCascade::detectMultiScale( const Mat& image,\r
index b1db264de4c3810c60b40b630c60a3f520c0f7e2..426a3477fd17bc309e8da4c9f4963457135ac7fe 100644 (file)
@@ -1057,8 +1057,8 @@ template<typename T, typename WT> struct InRangeC1
 
 template<typename T, typename WT> struct InRangeC2
 {
-    typedef Vec_<T,2> xtype;
-    typedef Vec_<WT,2> btype;
+    typedef Vec<T,2> xtype;
+    typedef Vec<WT,2> btype;
     uchar operator()(const xtype& x, const btype& a, const btype& b) const
     {
         return (uchar)-(a[0] <= x[0] && x[0] < b[0] &&
@@ -1068,8 +1068,8 @@ template<typename T, typename WT> struct InRangeC2
 
 template<typename T, typename WT> struct InRangeC3
 {
-    typedef Vec_<T,3> xtype;
-    typedef Vec_<WT,3> btype;
+    typedef Vec<T,3> xtype;
+    typedef Vec<WT,3> btype;
     uchar operator()(const xtype& x, const btype& a, const btype& b) const
     {
         return (uchar)-(a[0] <= x[0] && x[0] < b[0] &&
@@ -1080,8 +1080,8 @@ template<typename T, typename WT> struct InRangeC3
 
 template<typename T, typename WT> struct InRangeC4
 {
-    typedef Vec_<T,4> xtype;
-    typedef Vec_<WT,4> btype;
+    typedef Vec<T,4> xtype;
+    typedef Vec<WT,4> btype;
     uchar operator()(const xtype& x, const btype& a, const btype& b) const
     {
         return (uchar)-(a[0] <= x[0] && x[0] < b[0] &&
index 1f5f6a38a4d0bc1cebeeeb67046da9c2977fd088..78505d7c7668f6827afceb94ac94952eeea2fdf4 100644 (file)
@@ -125,20 +125,20 @@ CopyMaskFunc g_copyMaskFuncTab[] =
     0,
     copyMask_<uchar>, // 1
     copyMask_<ushort>, // 2
-    copyMask_<Vec_<uchar,3> >, // 3
+    copyMask_<Vec<uchar,3> >, // 3
     copyMask_<int>, // 4
     0,
-    copyMask_<Vec_<ushort,3> >, // 6
+    copyMask_<Vec<ushort,3> >, // 6
     0,
     copyMask_<int64>, // 8
     0, 0, 0,
-    copyMask_<Vec_<int,3> >, // 12
+    copyMask_<Vec<int,3> >, // 12
     0, 0, 0,
-    copyMask_<Vec_<int64,2> >, // 16
+    copyMask_<Vec<int64,2> >, // 16
     0, 0, 0, 0, 0, 0, 0,
-    copyMask_<Vec_<int64,3> >, // 24
+    copyMask_<Vec<int64,3> >, // 24
     0, 0, 0, 0, 0, 0, 0,
-    copyMask_<Vec_<int64,4> > // 32
+    copyMask_<Vec<int64,4> > // 32
 };
 
 static SetMaskFunc setMaskFuncTab[] =
@@ -146,20 +146,20 @@ static SetMaskFunc setMaskFuncTab[] =
     0,
     setMask_<uchar>, // 1
     setMask_<ushort>, // 2
-    setMask_<Vec_<uchar,3> >, // 3
+    setMask_<Vec<uchar,3> >, // 3
     setMask_<int>, // 4
     0,
-    setMask_<Vec_<ushort,3> >, // 6
+    setMask_<Vec<ushort,3> >, // 6
     0,
     setMask_<int64>, // 8
     0, 0, 0,
-    setMask_<Vec_<int,3> >, // 12
+    setMask_<Vec<int,3> >, // 12
     0, 0, 0,
-    setMask_<Vec_<int64,2> >, // 16
+    setMask_<Vec<int64,2> >, // 16
     0, 0, 0, 0, 0, 0, 0,
-    setMask_<Vec_<int64,3> >, // 24
+    setMask_<Vec<int64,3> >, // 24
     0, 0, 0, 0, 0, 0, 0,
-    setMask_<Vec_<int64,4> > // 32
+    setMask_<Vec<int64,4> > // 32
 };
 
 
@@ -363,20 +363,20 @@ void flip( const Mat& src, Mat& dst, int flip_mode )
         0,
         flipHoriz_<uchar>, // 1
         flipHoriz_<ushort>, // 2
-        flipHoriz_<Vec_<uchar,3> >, // 3
+        flipHoriz_<Vec<uchar,3> >, // 3
         flipHoriz_<int>, // 4
         0,
-        flipHoriz_<Vec_<ushort,3> >, // 6
+        flipHoriz_<Vec<ushort,3> >, // 6
         0,
         flipHoriz_<int64>, // 8
         0, 0, 0,
-        flipHoriz_<Vec_<int,3> >, // 12
+        flipHoriz_<Vec<int,3> >, // 12
         0, 0, 0,
-        flipHoriz_<Vec_<int64,2> >, // 16
+        flipHoriz_<Vec<int64,2> >, // 16
         0, 0, 0, 0, 0, 0, 0,
-        flipHoriz_<Vec_<int64,3> >, // 24
+        flipHoriz_<Vec<int64,3> >, // 24
         0, 0, 0, 0, 0, 0, 0,
-        flipHoriz_<Vec_<int64,4> > // 32
+        flipHoriz_<Vec<int64,4> > // 32
     };
     
     dst.create( src.size(), src.type() );
index 629bbc9248958b7d3d550fa1756d55b9a49e027c..616ed18b17eec292413a6e96c4c60f58cc476ca3 100644 (file)
@@ -276,20 +276,20 @@ void transpose( const Mat& src, Mat& dst )
         0,
         transposeI_<uchar>, // 1
         transposeI_<ushort>, // 2
-        transposeI_<Vec_<uchar,3> >, // 3
+        transposeI_<Vec<uchar,3> >, // 3
         transposeI_<int>, // 4
         0,
-        transposeI_<Vec_<ushort,3> >, // 6
+        transposeI_<Vec<ushort,3> >, // 6
         0,
         transposeI_<int64>, // 8
         0, 0, 0,
-        transposeI_<Vec_<int,3> >, // 12
+        transposeI_<Vec<int,3> >, // 12
         0, 0, 0,
-        transposeI_<Vec_<int64,2> >, // 16
+        transposeI_<Vec<int64,2> >, // 16
         0, 0, 0, 0, 0, 0, 0,
-        transposeI_<Vec_<int64,3> >, // 24
+        transposeI_<Vec<int64,3> >, // 24
         0, 0, 0, 0, 0, 0, 0,
-        transposeI_<Vec_<int64,4> > // 32
+        transposeI_<Vec<int64,4> > // 32
     };
 
     TransposeFunc tab[] =
@@ -297,20 +297,20 @@ void transpose( const Mat& src, Mat& dst )
         0,
         transpose_<uchar>, // 1
         transpose_<ushort>, // 2
-        transpose_<Vec_<uchar,3> >, // 3
+        transpose_<Vec<uchar,3> >, // 3
         transpose_<int>, // 4
         0,
-        transpose_<Vec_<ushort,3> >, // 6
+        transpose_<Vec<ushort,3> >, // 6
         0,
         transpose_<int64>, // 8
         0, 0, 0,
-        transpose_<Vec_<int,3> >, // 12
+        transpose_<Vec<int,3> >, // 12
         0, 0, 0,
-        transpose_<Vec_<int64,2> >, // 16
+        transpose_<Vec<int64,2> >, // 16
         0, 0, 0, 0, 0, 0, 0,
-        transpose_<Vec_<int64,3> >, // 24
+        transpose_<Vec<int64,3> >, // 24
         0, 0, 0, 0, 0, 0, 0,
-        transpose_<Vec_<int64,4> > // 32
+        transpose_<Vec<int64,4> > // 32
     };
 
     size_t esz = src.elemSize();
@@ -2748,7 +2748,10 @@ void SparseMat::erase(const int* idx, size_t* hashval)
 void SparseMat::resizeHashTab(size_t newsize)
 {
     size_t i, hsize = hdr->hashtab.size();
-    Vector<size_t> newh(newsize, (size_t)0);
+    Vector<size_t> _newh(newsize);
+    size_t* newh = &_newh[0];
+    for( size_t i = 0; i < newsize; i++ )
+        newh[i] = 0;
     uchar* pool = &hdr->pool[0];
     for( i = 0; i < hsize; i++ )
     {
@@ -2763,7 +2766,7 @@ void SparseMat::resizeHashTab(size_t newsize)
             nidx = next;
         }
     }
-    hdr->hashtab = newh;
+    hdr->hashtab = _newh;
 }
 
 uchar* SparseMat::newNode(const int* idx, size_t hashval)
index 66b86415a1c1993eaa1c06466d4a3c8e39c7b4d0..a007dee2ed9f6796177d125f5e0b3395c8c75bf1 100644 (file)
@@ -4828,14 +4828,14 @@ FileStorage::FileStorage(const String& filename, int flags)
 FileStorage::FileStorage(CvFileStorage* _fs)\r
 {\r
     fs = Ptr<CvFileStorage>(_fs);\r
-    state = fs.obj ? NAME_EXPECTED + INSIDE_MAP : UNDEFINED;\r
+    state = _fs ? NAME_EXPECTED + INSIDE_MAP : UNDEFINED;\r
 }\r
 \r
 FileStorage::~FileStorage()\r
 {\r
     while( structs.size() > 0 )\r
     {\r
-        cvEndWriteStruct(fs.obj);\r
+        cvEndWriteStruct(fs);\r
         structs.pop_back();\r
     }\r
 }\r
@@ -4844,13 +4844,14 @@ bool FileStorage::open(const String& filename, int flags)
 {\r
     release();\r
     fs = Ptr<CvFileStorage>(cvOpenFileStorage( filename.c_str(), 0, flags ));\r
-    state = fs.obj ? NAME_EXPECTED + INSIDE_MAP : UNDEFINED;\r
-    return fs.obj != 0;\r
+    bool ok = isOpened();\r
+    state = ok ? NAME_EXPECTED + INSIDE_MAP : UNDEFINED;\r
+    return ok;\r
 }\r
 \r
 bool FileStorage::isOpened() const\r
 {\r
-    return fs.obj != 0;\r
+    return !fs.empty();\r
 }\r
 \r
 void FileStorage::release()\r
@@ -4862,7 +4863,7 @@ void FileStorage::release()
 \r
 FileNode FileStorage::root(int streamidx) const\r
 {\r
-    return fs.obj ? FileNode(fs.obj, cvGetRootFileNode(fs.obj, streamidx)) : FileNode();\r
+    return isOpened() ? FileNode(fs, cvGetRootFileNode(fs, streamidx)) : FileNode();\r
 }\r
 \r
 FileStorage& operator << (FileStorage& fs, const String& str)\r
@@ -4931,7 +4932,7 @@ void FileStorage::writeRaw( const String& fmt, const Vector<uchar>& vec )
     size_t elemSize, cn;\r
     getElemSize( fmt, elemSize, cn );\r
     CV_Assert( vec.size() % elemSize == 0 );\r
-    cvWriteRawData( fs.obj, &vec[0], (int)(vec.size()/elemSize), fmt.c_str());\r
+    cvWriteRawData( fs, &vec[0], (int)(vec.size()/elemSize), fmt.c_str());\r
 }\r
 \r
 \r
@@ -4939,7 +4940,7 @@ void FileStorage::writeObj( const String& name, const void* obj )
 {\r
     if( !isOpened() )\r
         return;\r
-    cvWrite( fs.obj, name.size() > 0 ? name.c_str() : 0, obj );\r
+    cvWrite( fs, name.size() > 0 ? name.c_str() : 0, obj );\r
 }\r
 \r
 \r
index 6fc29b189378f5969127cb05b47aecbd5d01b64a..32988bad74998879febc73b9122962f64018febe 100644 (file)
@@ -315,22 +315,22 @@ Randn_0_1_32f_C1R( float* arr, int len, uint64* state )
         
         // Set up the tables
         double q = vn/std::exp(-.5*dn*dn);
-        kn[0] = (dn/q)*m1;
+        kn[0] = (unsigned)((dn/q)*m1);
         kn[1] = 0;
         
-        wn[0] = q/m1;
-        wn[127] = dn/m1;
+        wn[0] = (float)(q/m1);
+        wn[127] = (float)(dn/m1);
         
-        fn[0] = 1.;
-        fn[127] = std::exp(-.5*dn*dn);
+        fn[0] = 1.f;
+        fn[127] = (float)std::exp(-.5*dn*dn);
         
         for(i=126;i>=1;i--)
         {
             dn = std::sqrt(-2.*std::log(vn/dn+std::exp(-.5*dn*dn)));
-            kn[i+1] = (dn/tn)*m1;
+            kn[i+1] = (unsigned)((dn/tn)*m1);
             tn = dn;
-            fn[i] = std::exp(-.5*dn*dn);
-            wn[i] = dn/m1;
+            fn[i] = (float)std::exp(-.5*dn*dn);
+            wn[i] = (float)(dn/m1);
         }
         initialized = true;
     }
@@ -354,8 +354,8 @@ Randn_0_1_32f_C1R( float* arr, int len, uint64* state )
                     temp = RNG_NEXT(temp);
                     y = (unsigned)temp*rng_flt;
                     temp = RNG_NEXT(temp);
-                    x = -std::log(x+FLT_MIN)*0.2904764;
-                    y = -std::log(y+FLT_MIN);
+                    x = (float)(-std::log(x+FLT_MIN)*0.2904764);
+                    y = (float)-std::log(y+FLT_MIN);
                 }      // .2904764 is 1/r
                 while( y + y < x*x );
                 x = hz > 0 ? r + x : -r - x;
@@ -646,20 +646,20 @@ void randShuffle( Mat& dst, RNG& rng, double iterFactor )
         0,
         randShuffle_<uchar>, // 1
         randShuffle_<ushort>, // 2
-        randShuffle_<Vec_<uchar,3> >, // 3
+        randShuffle_<Vec<uchar,3> >, // 3
         randShuffle_<int>, // 4
         0,
-        randShuffle_<Vec_<ushort,3> >, // 6
+        randShuffle_<Vec<ushort,3> >, // 6
         0,
         randShuffle_<int64>, // 8
         0, 0, 0,
-        randShuffle_<Vec_<int,3> >, // 12
+        randShuffle_<Vec<int,3> >, // 12
         0, 0, 0,
-        randShuffle_<Vec_<int64,2> >, // 16
+        randShuffle_<Vec<int64,2> >, // 16
         0, 0, 0, 0, 0, 0, 0,
-        randShuffle_<Vec_<int64,3> >, // 24
+        randShuffle_<Vec<int64,3> >, // 24
         0, 0, 0, 0, 0, 0, 0,
-        randShuffle_<Vec_<int64,4> > // 32
+        randShuffle_<Vec<int64,4> > // 32
     };
 
     CV_Assert( dst.elemSize() <= 32 );
index 2c6f02e9e36a4098b0d723e19f5d6bd1c25cad6c..78009427b3e5dc2f8f76571fee6fe370a03b22bb 100644 (file)
@@ -134,26 +134,26 @@ Scalar sum( const Mat& m )
         sum_<float, double>,
         sum_<double, double>, 0,
 
-        sumBlock_<Vec_<uchar, 2>, Vec_<unsigned, 2>, Vec_<double, 2>, 1<<24>, 0,
-        sumBlock_<Vec_<ushort, 2>, Vec_<unsigned, 2>, Vec_<double, 2>, 1<<16>,
-        sumBlock_<Vec_<short, 2>, Vec_<int, 2>, Vec_<double, 2>, 1<<16>,
-        sum_<Vec_<int, 2>, Vec_<double, 2> >,
-        sum_<Vec_<float, 2>, Vec_<double, 2> >,
-        sum_<Vec_<double, 2>, Vec_<double, 2> >, 0,
-
-        sumBlock_<Vec_<uchar, 3>, Vec_<unsigned, 3>, Vec_<double, 3>, 1<<24>, 0,
-        sumBlock_<Vec_<ushort, 3>, Vec_<unsigned, 3>, Vec_<double, 3>, 1<<16>,
-        sumBlock_<Vec_<short, 3>, Vec_<int, 3>, Vec_<double, 3>, 1<<16>,
-        sum_<Vec_<int, 3>, Vec_<double, 3> >,
-        sum_<Vec_<float, 3>, Vec_<double, 3> >,
-        sum_<Vec_<double, 3>, Vec_<double, 3> >, 0,
-
-        sumBlock_<Vec_<uchar, 4>, Vec_<unsigned, 4>, Vec_<double, 4>, 1<<24>, 0,
-        sumBlock_<Vec_<ushort, 4>, Vec_<unsigned, 4>, Vec_<double, 4>, 1<<16>,
-        sumBlock_<Vec_<short, 4>, Vec_<int, 4>, Vec_<double, 4>, 1<<16>,
-        sum_<Vec_<int, 4>, Vec_<double, 4> >,
-        sum_<Vec_<float, 4>, Vec_<double, 4> >,
-        sum_<Vec_<double, 4>, Vec_<double, 4> >, 0
+        sumBlock_<Vec<uchar, 2>, Vec<unsigned, 2>, Vec<double, 2>, 1<<24>, 0,
+        sumBlock_<Vec<ushort, 2>, Vec<unsigned, 2>, Vec<double, 2>, 1<<16>,
+        sumBlock_<Vec<short, 2>, Vec<int, 2>, Vec<double, 2>, 1<<16>,
+        sum_<Vec<int, 2>, Vec<double, 2> >,
+        sum_<Vec<float, 2>, Vec<double, 2> >,
+        sum_<Vec<double, 2>, Vec<double, 2> >, 0,
+
+        sumBlock_<Vec<uchar, 3>, Vec<unsigned, 3>, Vec<double, 3>, 1<<24>, 0,
+        sumBlock_<Vec<ushort, 3>, Vec<unsigned, 3>, Vec<double, 3>, 1<<16>,
+        sumBlock_<Vec<short, 3>, Vec<int, 3>, Vec<double, 3>, 1<<16>,
+        sum_<Vec<int, 3>, Vec<double, 3> >,
+        sum_<Vec<float, 3>, Vec<double, 3> >,
+        sum_<Vec<double, 3>, Vec<double, 3> >, 0,
+
+        sumBlock_<Vec<uchar, 4>, Vec<unsigned, 4>, Vec<double, 4>, 1<<24>, 0,
+        sumBlock_<Vec<ushort, 4>, Vec<unsigned, 4>, Vec<double, 4>, 1<<16>,
+        sumBlock_<Vec<short, 4>, Vec<int, 4>, Vec<double, 4>, 1<<16>,
+        sum_<Vec<int, 4>, Vec<double, 4> >,
+        sum_<Vec<float, 4>, Vec<double, 4> >,
+        sum_<Vec<double, 4>, Vec<double, 4> >, 0
     };
 
     Size size = m.size();
@@ -285,26 +285,26 @@ Scalar mean( const Mat& m, const Mat& mask )
         mean_<float, double>,
         mean_<double, double>, 0,
 
-        meanBlock_<Vec_<uchar, 2>, Vec_<unsigned, 2>, Vec_<double, 2>, 1<<24>, 0,
-        meanBlock_<Vec_<ushort, 2>, Vec_<unsigned, 2>, Vec_<double, 2>, 1<<16>,
-        meanBlock_<Vec_<short, 2>, Vec_<int, 2>, Vec_<double, 2>, 1<<16>,
-        mean_<Vec_<int, 2>, Vec_<double, 2> >,
-        mean_<Vec_<float, 2>, Vec_<double, 2> >,
-        mean_<Vec_<double, 2>, Vec_<double, 2> >, 0,
-
-        meanBlock_<Vec_<uchar, 3>, Vec_<unsigned, 3>, Vec_<double, 3>, 1<<24>, 0,
-        meanBlock_<Vec_<ushort, 3>, Vec_<unsigned, 3>, Vec_<double, 3>, 1<<16>,
-        meanBlock_<Vec_<short, 3>, Vec_<int, 3>, Vec_<double, 3>, 1<<16>,
-        mean_<Vec_<int, 3>, Vec_<double, 3> >,
-        mean_<Vec_<float, 3>, Vec_<double, 3> >,
-        mean_<Vec_<double, 3>, Vec_<double, 3> >, 0,
-
-        meanBlock_<Vec_<uchar, 4>, Vec_<unsigned, 4>, Vec_<double, 4>, 1<<24>, 0,
-        meanBlock_<Vec_<ushort, 4>, Vec_<unsigned, 4>, Vec_<double, 4>, 1<<16>,
-        meanBlock_<Vec_<short, 4>, Vec_<int, 4>, Vec_<double, 4>, 1<<16>,
-        mean_<Vec_<int, 4>, Vec_<double, 4> >,
-        mean_<Vec_<float, 4>, Vec_<double, 4> >,
-        mean_<Vec_<double, 4>, Vec_<double, 4> >, 0
+        meanBlock_<Vec<uchar, 2>, Vec<unsigned, 2>, Vec<double, 2>, 1<<24>, 0,
+        meanBlock_<Vec<ushort, 2>, Vec<unsigned, 2>, Vec<double, 2>, 1<<16>,
+        meanBlock_<Vec<short, 2>, Vec<int, 2>, Vec<double, 2>, 1<<16>,
+        mean_<Vec<int, 2>, Vec<double, 2> >,
+        mean_<Vec<float, 2>, Vec<double, 2> >,
+        mean_<Vec<double, 2>, Vec<double, 2> >, 0,
+
+        meanBlock_<Vec<uchar, 3>, Vec<unsigned, 3>, Vec<double, 3>, 1<<24>, 0,
+        meanBlock_<Vec<ushort, 3>, Vec<unsigned, 3>, Vec<double, 3>, 1<<16>,
+        meanBlock_<Vec<short, 3>, Vec<int, 3>, Vec<double, 3>, 1<<16>,
+        mean_<Vec<int, 3>, Vec<double, 3> >,
+        mean_<Vec<float, 3>, Vec<double, 3> >,
+        mean_<Vec<double, 3>, Vec<double, 3> >, 0,
+
+        meanBlock_<Vec<uchar, 4>, Vec<unsigned, 4>, Vec<double, 4>, 1<<24>, 0,
+        meanBlock_<Vec<ushort, 4>, Vec<unsigned, 4>, Vec<double, 4>, 1<<16>,
+        meanBlock_<Vec<short, 4>, Vec<int, 4>, Vec<double, 4>, 1<<16>,
+        mean_<Vec<int, 4>, Vec<double, 4> >,
+        mean_<Vec<float, 4>, Vec<double, 4> >,
+        mean_<Vec<double, 4>, Vec<double, 4> >, 0
     };
     
     if( !mask.data )
@@ -331,23 +331,23 @@ template<typename T, typename SqT> struct SqrC1
 
 template<typename T, typename SqT> struct SqrC2
 {
-    typedef Vec_<T, 2> type1;
-    typedef Vec_<SqT, 2> rtype;
+    typedef Vec<T, 2> type1;
+    typedef Vec<SqT, 2> rtype;
     rtype operator()(const type1& x) const { return rtype((SqT)x[0]*x[0], (SqT)x[1]*x[1]); }
 };
 
 template<typename T, typename SqT> struct SqrC3
 {
-    typedef Vec_<T, 3> type1;
-    typedef Vec_<SqT, 3> rtype;
+    typedef Vec<T, 3> type1;
+    typedef Vec<SqT, 3> rtype;
     rtype operator()(const type1& x) const
     { return rtype((SqT)x[0]*x[0], (SqT)x[1]*x[1], (SqT)x[2]*x[2]); }
 };
 
 template<typename T, typename SqT> struct SqrC4
 {
-    typedef Vec_<T, 4> type1;
-    typedef Vec_<SqT, 4> rtype;
+    typedef Vec<T, 4> type1;
+    typedef Vec<SqT, 4> rtype;
     rtype operator()(const type1& x) const
     { return rtype((SqT)x[0]*x[0], (SqT)x[1]*x[1], (SqT)x[2]*x[2], (SqT)x[3]*x[3]); }
 };
@@ -355,14 +355,14 @@ template<typename T, typename SqT> struct SqrC4
 template<> inline double SqrC1<uchar, double>::operator()(uchar x) const
 { return CV_SQR_8U(x); }
 
-template<> inline Vec_<double, 2> SqrC2<uchar, double>::operator()(const Vec_<uchar, 2>& x) const
-{ return Vec_<double, 2>(CV_SQR_8U(x[0]), CV_SQR_8U(x[1])); }
+template<> inline Vec<double, 2> SqrC2<uchar, double>::operator()(const Vec<uchar, 2>& x) const
+{ return Vec<double, 2>(CV_SQR_8U(x[0]), CV_SQR_8U(x[1])); }
 
-template<> inline Vec_<double, 3> SqrC3<uchar, double>::operator() (const Vec_<uchar, 3>& x) const
-{ return Vec_<double, 3>(CV_SQR_8U(x[0]), CV_SQR_8U(x[1]), CV_SQR_8U(x[2])); }
+template<> inline Vec<double, 3> SqrC3<uchar, double>::operator() (const Vec<uchar, 3>& x) const
+{ return Vec<double, 3>(CV_SQR_8U(x[0]), CV_SQR_8U(x[1]), CV_SQR_8U(x[2])); }
 
-template<> inline Vec_<double, 4> SqrC4<uchar, double>::operator() (const Vec_<uchar, 4>& x) const
-{ return Vec_<double, 4>(CV_SQR_8U(x[0]), CV_SQR_8U(x[1]), CV_SQR_8U(x[2]), CV_SQR_8U(x[3])); }
+template<> inline Vec<double, 4> SqrC4<uchar, double>::operator() (const Vec<uchar, 4>& x) const
+{ return Vec<double, 4>(CV_SQR_8U(x[0]), CV_SQR_8U(x[1]), CV_SQR_8U(x[2]), CV_SQR_8U(x[3])); }
 
 
 template<class SqrOp> static void
index ed99ed2d71111c30d593b8f6f4cb4ac3f3bafdaf..ba8df5c69fef28eca39f220725b358a4b89e1821 100644 (file)
@@ -204,7 +204,7 @@ imread_( const String& filename, int flags, int hdrtype, Mat* mat=0 )
     Mat temp, *data = &temp;
 
     ImageDecoder decoder = findDecoder(filename);
-    if( !decoder.obj )
+    if( decoder.empty() )
         return 0;
     decoder->setSource(filename);
     if( !decoder->readHeader() )
@@ -275,7 +275,7 @@ static bool imwrite_( const String& filename, const Mat& image,
     CV_Assert( image.channels() == 1 || image.channels() == 3 || image.channels() == 4 );
 
     ImageEncoder encoder = findEncoder( filename );
-    if( !encoder.obj )
+    if( encoder.empty() )
         CV_Error( CV_StsError, "could not find a writer for the specified extension" );
 
     if( !encoder->isFormatSupported(image.depth()) )
@@ -314,7 +314,7 @@ imdecode_( const Vector<uchar>& buf, int flags, int hdrtype, Mat* mat=0 )
     const char* filename = 0;
 
     ImageDecoder decoder = findDecoder(buf);
-    if( !decoder.obj )
+    if( decoder.empty() )
         return 0;
 
     if( !decoder->setSource(buf) )
@@ -407,7 +407,7 @@ bool imencode( const String& ext, const Mat& image,
     CV_Assert( channels == 1 || channels == 3 || channels == 4 );
 
     ImageEncoder encoder = findEncoder( ext );
-    if( !encoder.obj )
+    if( encoder.empty() )
         CV_Error( CV_StsError, "could not find encoder for the specified extension" );
 
     if( !encoder->isFormatSupported(image.depth()) )
@@ -461,13 +461,13 @@ CV_IMPL int
 cvHaveImageReader( const char* filename )
 {
     cv::ImageDecoder decoder = cv::findDecoder(filename);
-    return decoder.obj != 0;
+    return !decoder.empty();
 }
 
 CV_IMPL int cvHaveImageWriter( const char* filename )
 {
     cv::ImageEncoder encoder = cv::findEncoder(filename);
-    return encoder.obj != 0;
+    return !encoder.empty();
 }
 
 CV_IMPL IplImage*