42 #include <opencv2/imgproc.hpp>    43 #include <opencv2/core.hpp>    46 CV_IMPL 
void tuwCanny( 
const void* srcarr, 
void* dstarr, 
void* gradientarr, 
void* directionarr, 
void* dxarr, 
void* dyarr,
    47                       double low_thresh, 
double high_thresh,
    50     cv::AutoBuffer<char> buffer;
    51     std::vector<uchar*> stack;
    52     uchar **stack_top = 0, **stack_bottom = 0;
    54     CvMat srcstub, *src = cvGetMat( srcarr, &srcstub );
    55     CvMat dststub, *dst = cvGetMat( dstarr, &dststub );
    56     CvMat dstgrad, *gra = cvGetMat( gradientarr, &dstgrad );  
    57     CvMat dstdir, *dir = cvGetMat( directionarr, &dstdir );  
    58     CvMat *dx = cvGetMat( dxarr, &dstgrad );  
    59     CvMat *dy = cvGetMat( dyarr, &dstdir );  
    61     int flags = aperture_size;
    69     if( CV_MAT_TYPE( gra->type ) != CV_16UC1 || 
    70         CV_MAT_TYPE( dir->type ) != CV_16UC1 ) 
    71         CV_Error( CV_StsUnsupportedFormat, 
"gradientarr or directionarr are not CV_16UC1" ); 
    72     if( CV_MAT_TYPE( dx->type ) != CV_16SC1 || 
    73         CV_MAT_TYPE( dy->type ) != CV_16SC1 ) 
    74         CV_Error( CV_StsUnsupportedFormat, 
"sobel_dx or sobel_dy are not CV_16SC1" ); 
    75     if( CV_MAT_TYPE( src->type ) != CV_8UC1 ||
    76         CV_MAT_TYPE( dst->type ) != CV_8UC1 )
    77         CV_Error( CV_StsUnsupportedFormat, 
"" );
    79     if( !CV_ARE_SIZES_EQ( src, dst ))
    80         CV_Error( CV_StsUnmatchedSizes, 
"" );
    82     if( low_thresh > high_thresh )
    85         CV_SWAP( low_thresh, high_thresh, t );
    88     aperture_size &= INT_MAX;
    89     if( (aperture_size & 1) == 0 || aperture_size < 3 || aperture_size > 7 )
    90         CV_Error( CV_StsBadFlag, 
"" );
    92     size.width = src->cols;
    93     size.height = src->rows;
    97     cvSobel( src, dx, 1, 0, aperture_size );
    98     cvSobel( src, dy, 0, 1, aperture_size );
   113     if( flags & CV_CANNY_L2_GRADIENT )
   116         ul.f = (float)low_thresh;
   117         uh.f = (float)high_thresh;
   124         low = cvFloor( low_thresh );
   125         high = cvFloor( high_thresh );
   128     buffer.allocate( (size.width+2)*(size.height+2) + (size.width+2)*3*
sizeof(
int) );
   130     mag_buf[0] = (
int*)(
char*)buffer;
   131     mag_buf[1] = mag_buf[0] + size.width + 2;
   132     mag_buf[2] = mag_buf[1] + size.width + 2;
   133     map = (uchar*)(mag_buf[2] + size.width + 2);
   134     mapstep = size.width + 2;
   136     maxsize = MAX( 1 << 10, size.width*size.height/10 );
   137     stack.resize( maxsize );
   138     stack_top = stack_bottom = &stack[0];
   140     memset( mag_buf[0], 0, (size.width+2)*
sizeof(
int) );
   141     memset( map, 1, mapstep );
   142     memset( map + mapstep*(size.height + 1), 1, mapstep );
   156     #define CANNY_PUSH(d)    *(d) = (uchar)2, *stack_top++ = (d)   157     #define CANNY_POP(d)     (d) = *--stack_top   159     mag_row = cvMat( 1, size.width, CV_32F );
   166     for( i = 0; i <= size.height; i++ )
   168         int* _mag = mag_buf[(i > 0) + 1] + 1;
   169         float* _magf = (
float*)_mag;
   170         const short* _dx = (
short*)(dx->data.ptr + dx->step*i);
   171         const short* _dy = (
short*)(dy->data.ptr + dy->step*i);
   174         int magstep1, magstep2;
   177         if( i < size.height )
   179             _mag[-1] = _mag[size.width] = 0;
   181             if( !(flags & CV_CANNY_L2_GRADIENT) )
   182                 for( j = 0; j < size.width; j++ )
   183                     _mag[j] = abs(_dx[j]) + abs(_dy[j]);
   197                 for( j = 0; j < size.width; j++ )
   199                     x = _dx[j]; y = _dy[j];
   200                     _magf[j] = (float)std::sqrt((
double)x*x + (double)y*y);
   205             memset( _mag-1, 0, (size.width + 2)*
sizeof(
int) );
   212         _map = map + mapstep*i + 1;
   213         _map[-1] = _map[size.width] = 1;
   215         _mag = mag_buf[1] + 1; 
   216         _dx = (
short*)(dx->data.ptr + dx->step*(i-1));
   217         _dy = (
short*)(dy->data.ptr + dy->step*(i-1));
   219         magstep1 = (int)(mag_buf[2] - mag_buf[1]);
   220         magstep2 = (int)(mag_buf[0] - mag_buf[1]);
   222         if( (stack_top - stack_bottom) + size.width > maxsize )
   224             int sz = (int)(stack_top - stack_bottom);
   225             maxsize = MAX( maxsize * 3/2, maxsize + 8 );
   226             stack.resize(maxsize);
   227             stack_bottom = &stack[0];
   228             stack_top = stack_bottom + sz;
   231         for( j = 0; j < size.width; j++ )
   233             #define CANNY_SHIFT 15   234             #define TG22  (int)(0.4142135623730950488016887242097*(1<<CANNY_SHIFT) + 0.5)   245                 int tg22x = x * 
TG22;
   252                     if( m > _mag[j-1] && m >= _mag[j+1] )
   254                         if( m > high && !prev_flag && _map[j-mapstep] != 2 )
   266                     if( m > _mag[j+magstep2] && m >= _mag[j+magstep1] )
   268                         if( m > high && !prev_flag && _map[j-mapstep] != 2 )
   281                     if( m > _mag[j+magstep2-s] && m > _mag[j+magstep1+s] )
   283                         if( m > high && !prev_flag && _map[j-mapstep] != 2 )
   300         mag_buf[0] = mag_buf[1];
   301         mag_buf[1] = mag_buf[2];
   306     while( stack_top > stack_bottom )
   309         if( (stack_top - stack_bottom) + 8 > maxsize )
   311             int sz = (int)(stack_top - stack_bottom);
   312             maxsize = MAX( maxsize * 3/2, maxsize + 8 );
   313             stack.resize(maxsize);
   314             stack_bottom = &stack[0];
   315             stack_top = stack_bottom + sz;
   339     for( i = 0; i < size.height; i++ )
   341         const uchar* _map = map + mapstep*(i+1) + 1;
   342         uchar* _dst = dst->data.ptr + dst->step*i;
   345         unsigned short* _dir = (
unsigned short*)(dir->data.ptr + dir->step*i); 
   346         unsigned short* _gra = (
unsigned short*)(gra->data.ptr + gra->step*i); 
   347         const short* _dx = (
short*)(dx->data.ptr + dx->step*i); 
   348         const short* _dy = (
short*)(dy->data.ptr + dy->step*i); 
   350         for( j = 0; j < size.width; j++ ){
   351             _dst[j] = (uchar)-(_map[j] >> 1);
   353               _dir[j] = (
unsigned short) cvFastArctan(_dy[j], _dx[j]); 
   354               _gra[j] = cvSqrt(_dx[j]*_dx[j] + _dy[j]*_dy[j]);  
   363 void Canny( 
const cv::Mat& image, cv::Mat& edges, cv::Mat& gradient, cv::Mat& direction, cv::Mat& sobel_dx, cv::Mat& sobel_dy,
   364                 double threshold1, 
double threshold2,
   365                 int apertureSize, 
bool L2gradient )
   368     edges.create(src.size(), CV_8U);
   369     gradient.create(src.size(), CV_16UC1);
   370     direction.create(src.size(), CV_16UC1);
   371     sobel_dx.create(src.size(), CV_16SC1);
   372     sobel_dy.create(src.size(), CV_16SC1);
   373     CvMat _src = src, _dst = edges, _gradientarr = gradient, _directionarr = direction, dxarr = sobel_dx, dyarr = sobel_dy;
   374     tuwCanny( &_src, &_dst, &_gradientarr, &_directionarr, &dxarr, &dyarr, threshold1, threshold2,
   375         apertureSize + (L2gradient ? CV_CANNY_L2_GRADIENT : 0));
 
void tuwCanny(const void *srcarr, void *edgearr, void *gradientarr, void *directionarr, void *dxarr, void *dyarr, double low_thresh, double threshold2, int aperture_size CV_DEFAULT(3))
TFSIMD_FORCE_INLINE const tfScalar & y() const 
void Canny(const cv::Mat &image, cv::Mat &edges, cv::Mat &gradient, cv::Mat &direction, cv::Mat &sobel_dx, cv::Mat &sobel_dy, double threshold1, double threshold2, int apertureSize=3, bool L2gradient=false)
TFSIMD_FORCE_INLINE const tfScalar & x() const