module_opencv2.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2012, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 #include "module.hpp"
00036 
00037 using namespace cv;
00038 
00039 // These are sucky, sketchy versions of the real things in OpenCV Python,
00040 // inferior in every way.
00041 
00042 static int failmsg(const char *fmt, ...)
00043 {
00044   char str[1000];
00045 
00046   va_list ap;
00047   va_start(ap, fmt);
00048   vsnprintf(str, sizeof(str), fmt, ap);
00049   va_end(ap);
00050 
00051   PyErr_SetString(PyExc_TypeError, str);
00052   return 0;
00053 }
00054 
00055 static PyObject* opencv_error = 0;
00056 
00057 class PyAllowThreads
00058 {
00059 public:
00060     PyAllowThreads() : _state(PyEval_SaveThread()) {}
00061     ~PyAllowThreads()
00062     {
00063         PyEval_RestoreThread(_state);
00064     }
00065 private:
00066     PyThreadState* _state;
00067 };
00068 
00069 #define ERRWRAP2(expr) \
00070 try \
00071 { \
00072     PyAllowThreads allowThreads; \
00073     expr; \
00074 } \
00075 catch (const cv::Exception &e) \
00076 { \
00077     PyErr_SetString(opencv_error, e.what()); \
00078     return 0; \
00079 }
00080 
00081 // Taken from http://stackoverflow.com/questions/19136944/call-c-opencv-functions-from-python-send-a-cv-mat-to-c-dll-which-is-usi
00082 
00083 
00084 static size_t REFCOUNT_OFFSET = ( size_t )&((( PyObject* )0)->ob_refcnt ) +
00085 ( 0x12345678 != *( const size_t* )"\x78\x56\x34\x12\0\0\0\0\0" )*sizeof( int );
00086 
00087 
00088 static inline PyObject* pyObjectFromRefcount( const int* refcount )
00089 {
00090 return ( PyObject* )(( size_t )refcount - REFCOUNT_OFFSET );
00091 }
00092 
00093 static inline int* refcountFromPyObject( const PyObject* obj )
00094 {
00095 return ( int* )(( size_t )obj + REFCOUNT_OFFSET );
00096 }
00097 
00098 class NumpyAllocator : public cv::MatAllocator
00099 {
00100 public:
00101 NumpyAllocator( ) { }
00102 ~NumpyAllocator( ) { }
00103 
00104 void allocate( int dims, const int* sizes, int type, int*& refcount,
00105 uchar*& datastart, uchar*& data, size_t* step );
00106 
00107 void deallocate( int* refcount, uchar* datastart, uchar* data );
00108 };
00109 
00110 void NumpyAllocator::allocate( int dims, const int* sizes, int type, int*& refcount, uchar*& datastart, uchar*& data, size_t* step )
00111 {
00112     int depth = CV_MAT_DEPTH( type );
00113     int cn = CV_MAT_CN( type );
00114     const int f = ( int )( sizeof( size_t )/8 );
00115     int typenum = depth == CV_8U ? NPY_UBYTE : depth == CV_8S ? NPY_BYTE :
00116                   depth == CV_16U ? NPY_USHORT : depth == CV_16S ? NPY_SHORT :
00117                   depth == CV_32S ? NPY_INT : depth == CV_32F ? NPY_FLOAT :
00118                   depth == CV_64F ? NPY_DOUBLE : f*NPY_ULONGLONG + (f^1)*NPY_UINT;
00119     int i;
00120     npy_intp _sizes[CV_MAX_DIM+1];
00121     for( i = 0; i < dims; i++ )
00122         _sizes[i] = sizes[i];
00123     if( cn > 1 )
00124     {
00125     /*if( _sizes[dims-1] == 1 )
00126          _sizes[dims-1] = cn;
00127     else*/
00128         _sizes[dims++] = cn;
00129     }
00130     PyObject* o = PyArray_SimpleNew( dims, _sizes, typenum );
00131     if( !o )
00132     CV_Error_(CV_StsError, ("The numpy array of typenum=%d, ndims=%d can not be created", typenum, dims));
00133     refcount = refcountFromPyObject(o);
00134     npy_intp* _strides = PyArray_STRIDES((PyArrayObject*) o);
00135     for( i = 0; i < dims - (cn > 1); i++ )
00136         step[i] = (size_t)_strides[i];
00137     datastart = data = (uchar*)PyArray_DATA((PyArrayObject*)o);
00138 
00139 }
00140 
00141 void NumpyAllocator::deallocate( int* refcount, uchar* datastart, uchar* data )
00142 {
00143     if( !refcount )
00144        return;
00145     PyObject* o = pyObjectFromRefcount(refcount);
00146     Py_INCREF(o);
00147     Py_DECREF(o);
00148 }
00149 
00150 // Declare the object
00151 NumpyAllocator g_numpyAllocator;
00152 
00153 int convert_to_CvMat2(const PyObject* o, cv::Mat& m)
00154 {
00155     // to avoid PyArray_Check() to crash even with valid array
00156     do_numpy_import();
00157 
00158     if(!o || o == Py_None)
00159     {
00160         if( !m.data )
00161             m.allocator = &g_numpyAllocator;
00162         return true;
00163     }
00164 
00165     if( !PyArray_Check(o) )
00166     {
00167         failmsg("Not a numpy array");
00168         return false;
00169     }
00170 
00171     // NPY_LONG (64 bit) is converted to CV_32S (32 bit)
00172     int typenum = PyArray_TYPE((PyArrayObject*) o);
00173     int type = typenum == NPY_UBYTE ? CV_8U : typenum == NPY_BYTE ? CV_8S :
00174         typenum == NPY_USHORT ? CV_16U : typenum == NPY_SHORT ? CV_16S :
00175         typenum == NPY_INT || typenum == NPY_LONG ? CV_32S :
00176         typenum == NPY_FLOAT ? CV_32F :
00177         typenum == NPY_DOUBLE ? CV_64F : -1;
00178 
00179     if( type < 0 )
00180     {
00181         failmsg("data type = %d is not supported", typenum);
00182         return false;
00183     }
00184 
00185     int ndims = PyArray_NDIM((PyArrayObject*) o);
00186     if(ndims >= CV_MAX_DIM)
00187     {
00188         failmsg("dimensionality (=%d) is too high", ndims);
00189         return false;
00190     }
00191 
00192     int size[CV_MAX_DIM+1];
00193     size_t step[CV_MAX_DIM+1], elemsize = CV_ELEM_SIZE1(type);
00194     const npy_intp* _sizes = PyArray_DIMS((PyArrayObject*) o);
00195     const npy_intp* _strides = PyArray_STRIDES((PyArrayObject*) o);
00196     bool transposed = false;
00197 
00198     for(int i = 0; i < ndims; i++)
00199     {
00200         size[i] = (int)_sizes[i];
00201         step[i] = (size_t)_strides[i];
00202     }
00203 
00204     if( ndims == 0 || step[ndims-1] > elemsize ) {
00205         size[ndims] = 1;
00206         step[ndims] = elemsize;
00207         ndims++;
00208     }
00209 
00210     if( ndims >= 2 && step[0] < step[1] )
00211     {
00212         std::swap(size[0], size[1]);
00213         std::swap(step[0], step[1]);
00214         transposed = true;
00215     }
00216 
00217     if( ndims == 3 && size[2] <= CV_CN_MAX && step[1] == elemsize*size[2] )
00218     {
00219         ndims--;
00220         type |= CV_MAKETYPE(0, size[2]);
00221     }
00222 
00223     if( ndims > 2 )
00224     {
00225         failmsg("more than 2 dimensions");
00226         return false;
00227     }
00228 
00229     m = cv::Mat(ndims, size, type, PyArray_DATA((PyArrayObject*) o), step);
00230 
00231     if( m.data )
00232     {
00233         m.refcount = refcountFromPyObject(o);
00234         m.addref(); // protect the original numpy array from deallocation
00235         // (since Mat destructor will decrement the reference counter)
00236     };
00237     m.allocator = &g_numpyAllocator;
00238 
00239     if( transposed )
00240     {
00241         cv::Mat tmp;
00242         tmp.allocator = &g_numpyAllocator;
00243         transpose(m, tmp);
00244         m = tmp;
00245     }
00246     return true;
00247 }
00248 
00249 PyObject* pyopencv_from(const Mat& m)
00250 {
00251     if( !m.data )
00252         Py_RETURN_NONE;
00253     Mat temp, *p = (Mat*)&m;
00254     if(!p->refcount || p->allocator != &g_numpyAllocator)
00255     {
00256         temp.allocator = &g_numpyAllocator;
00257         ERRWRAP2(m.copyTo(temp));
00258         p = &temp;
00259     }
00260     p->addref();
00261     return pyObjectFromRefcount(p->refcount);
00262 }


cv_bridge
Author(s): Patrick Mihelich, James Bowman
autogenerated on Wed Aug 9 2017 02:51:41