00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042 #include "opencv/cv.h"
00043
00044 namespace V4R {
00045 CV_IMPL void v4rCanny( const void* srcarr, void* dstarr, void* gradientarr, void* directionarr, void* dxarr, void* dyarr,
00046 double low_thresh, double high_thresh,
00047 int aperture_size )
00048 {
00049 cv::AutoBuffer<char> buffer;
00050 std::vector<uchar*> stack;
00051 uchar **stack_top = 0, **stack_bottom = 0;
00052
00053 CvMat srcstub, *src = cvGetMat( srcarr, &srcstub );
00054 CvMat dststub, *dst = cvGetMat( dstarr, &dststub );
00055 CvMat dstgrad, *gra = cvGetMat( gradientarr, &dstgrad );
00056 CvMat dstdir, *dir = cvGetMat( directionarr, &dstdir );
00057 CvMat *dx = cvGetMat( dxarr, &dstgrad );
00058 CvMat *dy = cvGetMat( dyarr, &dstdir );
00059 CvSize size;
00060 int flags = aperture_size;
00061 int low, high;
00062 int* mag_buf[3];
00063 uchar* map;
00064 int mapstep, maxsize;
00065 int i, j;
00066 CvMat mag_row;
00067
00068 if( CV_MAT_TYPE( gra->type ) != CV_16UC1 ||
00069 CV_MAT_TYPE( dir->type ) != CV_16UC1 )
00070 CV_Error( CV_StsUnsupportedFormat, "gradientarr or directionarr are not CV_16UC1" );
00071 if( CV_MAT_TYPE( dx->type ) != CV_16SC1 ||
00072 CV_MAT_TYPE( dy->type ) != CV_16SC1 )
00073 CV_Error( CV_StsUnsupportedFormat, "sobel_dx or sobel_dy are not CV_16SC1" );
00074 if( CV_MAT_TYPE( src->type ) != CV_8UC1 ||
00075 CV_MAT_TYPE( dst->type ) != CV_8UC1 )
00076 CV_Error( CV_StsUnsupportedFormat, "" );
00077
00078 if( !CV_ARE_SIZES_EQ( src, dst ))
00079 CV_Error( CV_StsUnmatchedSizes, "" );
00080
00081 if( low_thresh > high_thresh )
00082 {
00083 double t;
00084 CV_SWAP( low_thresh, high_thresh, t );
00085 }
00086
00087 aperture_size &= INT_MAX;
00088 if( (aperture_size & 1) == 0 || aperture_size < 3 || aperture_size > 7 )
00089 CV_Error( CV_StsBadFlag, "" );
00090
00091 size = cvGetMatSize( src );
00092
00093
00094
00095 cvSobel( src, dx, 1, 0, aperture_size );
00096 cvSobel( src, dy, 0, 1, aperture_size );
00097
00098
00099
00100
00101
00102
00103
00104
00105
00106
00107
00108
00109
00110
00111 if( flags & CV_CANNY_L2_GRADIENT )
00112 {
00113 Cv32suf ul, uh;
00114 ul.f = (float)low_thresh;
00115 uh.f = (float)high_thresh;
00116
00117 low = ul.i;
00118 high = uh.i;
00119 }
00120 else
00121 {
00122 low = cvFloor( low_thresh );
00123 high = cvFloor( high_thresh );
00124 }
00125
00126 buffer.allocate( (size.width+2)*(size.height+2) + (size.width+2)*3*sizeof(int) );
00127
00128 mag_buf[0] = (int*)(char*)buffer;
00129 mag_buf[1] = mag_buf[0] + size.width + 2;
00130 mag_buf[2] = mag_buf[1] + size.width + 2;
00131 map = (uchar*)(mag_buf[2] + size.width + 2);
00132 mapstep = size.width + 2;
00133
00134 maxsize = MAX( 1 << 10, size.width*size.height/10 );
00135 stack.resize( maxsize );
00136 stack_top = stack_bottom = &stack[0];
00137
00138 memset( mag_buf[0], 0, (size.width+2)*sizeof(int) );
00139 memset( map, 1, mapstep );
00140 memset( map + mapstep*(size.height + 1), 1, mapstep );
00141
00142
00143
00144
00145
00146
00147
00148
00149
00150
00151
00152
00153
00154 #define CANNY_PUSH(d) *(d) = (uchar)2, *stack_top++ = (d)
00155 #define CANNY_POP(d) (d) = *--stack_top
00156
00157 mag_row = cvMat( 1, size.width, CV_32F );
00158
00159
00160
00161
00162
00163
00164 for( i = 0; i <= size.height; i++ )
00165 {
00166 int* _mag = mag_buf[(i > 0) + 1] + 1;
00167 float* _magf = (float*)_mag;
00168 const short* _dx = (short*)(dx->data.ptr + dx->step*i);
00169 const short* _dy = (short*)(dy->data.ptr + dy->step*i);
00170 uchar* _map;
00171 int x, y;
00172 int magstep1, magstep2;
00173 int prev_flag = 0;
00174
00175 if( i < size.height )
00176 {
00177 _mag[-1] = _mag[size.width] = 0;
00178
00179 if( !(flags & CV_CANNY_L2_GRADIENT) )
00180 for( j = 0; j < size.width; j++ )
00181 _mag[j] = abs(_dx[j]) + abs(_dy[j]);
00182
00183
00184
00185
00186
00187
00188
00189
00190
00191
00192
00193 else
00194 {
00195 for( j = 0; j < size.width; j++ )
00196 {
00197 x = _dx[j]; y = _dy[j];
00198 _magf[j] = (float)std::sqrt((double)x*x + (double)y*y);
00199 }
00200 }
00201 }
00202 else
00203 memset( _mag-1, 0, (size.width + 2)*sizeof(int) );
00204
00205
00206
00207 if( i == 0 )
00208 continue;
00209
00210 _map = map + mapstep*i + 1;
00211 _map[-1] = _map[size.width] = 1;
00212
00213 _mag = mag_buf[1] + 1;
00214 _dx = (short*)(dx->data.ptr + dx->step*(i-1));
00215 _dy = (short*)(dy->data.ptr + dy->step*(i-1));
00216
00217 magstep1 = (int)(mag_buf[2] - mag_buf[1]);
00218 magstep2 = (int)(mag_buf[0] - mag_buf[1]);
00219
00220 if( (stack_top - stack_bottom) + size.width > maxsize )
00221 {
00222 int sz = (int)(stack_top - stack_bottom);
00223 maxsize = MAX( maxsize * 3/2, maxsize + 8 );
00224 stack.resize(maxsize);
00225 stack_bottom = &stack[0];
00226 stack_top = stack_bottom + sz;
00227 }
00228
00229 for( j = 0; j < size.width; j++ )
00230 {
00231 #define CANNY_SHIFT 15
00232 #define TG22 (int)(0.4142135623730950488016887242097*(1<<CANNY_SHIFT) + 0.5)
00233
00234 x = _dx[j];
00235 y = _dy[j];
00236 int s = x ^ y;
00237 int m = _mag[j];
00238
00239 x = abs(x);
00240 y = abs(y);
00241 if( m > low )
00242 {
00243 int tg22x = x * TG22;
00244 int tg67x = tg22x + ((x + x) << CANNY_SHIFT);
00245
00246 y <<= CANNY_SHIFT;
00247
00248 if( y < tg22x )
00249 {
00250 if( m > _mag[j-1] && m >= _mag[j+1] )
00251 {
00252 if( m > high && !prev_flag && _map[j-mapstep] != 2 )
00253 {
00254 CANNY_PUSH( _map + j );
00255 prev_flag = 1;
00256 }
00257 else
00258 _map[j] = (uchar)0;
00259 continue;
00260 }
00261 }
00262 else if( y > tg67x )
00263 {
00264 if( m > _mag[j+magstep2] && m >= _mag[j+magstep1] )
00265 {
00266 if( m > high && !prev_flag && _map[j-mapstep] != 2 )
00267 {
00268 CANNY_PUSH( _map + j );
00269 prev_flag = 1;
00270 }
00271 else
00272 _map[j] = (uchar)0;
00273 continue;
00274 }
00275 }
00276 else
00277 {
00278 s = s < 0 ? -1 : 1;
00279 if( m > _mag[j+magstep2-s] && m > _mag[j+magstep1+s] )
00280 {
00281 if( m > high && !prev_flag && _map[j-mapstep] != 2 )
00282 {
00283 CANNY_PUSH( _map + j );
00284 prev_flag = 1;
00285 }
00286 else
00287 _map[j] = (uchar)0;
00288 continue;
00289 }
00290 }
00291 }
00292 prev_flag = 0;
00293 _map[j] = (uchar)1;
00294 }
00295
00296
00297 _mag = mag_buf[0];
00298 mag_buf[0] = mag_buf[1];
00299 mag_buf[1] = mag_buf[2];
00300 mag_buf[2] = _mag;
00301 }
00302
00303
00304 while( stack_top > stack_bottom )
00305 {
00306 uchar* m;
00307 if( (stack_top - stack_bottom) + 8 > maxsize )
00308 {
00309 int sz = (int)(stack_top - stack_bottom);
00310 maxsize = MAX( maxsize * 3/2, maxsize + 8 );
00311 stack.resize(maxsize);
00312 stack_bottom = &stack[0];
00313 stack_top = stack_bottom + sz;
00314 }
00315
00316 CANNY_POP(m);
00317
00318 if( !m[-1] )
00319 CANNY_PUSH( m - 1 );
00320 if( !m[1] )
00321 CANNY_PUSH( m + 1 );
00322 if( !m[-mapstep-1] )
00323 CANNY_PUSH( m - mapstep - 1 );
00324 if( !m[-mapstep] )
00325 CANNY_PUSH( m - mapstep );
00326 if( !m[-mapstep+1] )
00327 CANNY_PUSH( m - mapstep + 1 );
00328 if( !m[mapstep-1] )
00329 CANNY_PUSH( m + mapstep - 1 );
00330 if( !m[mapstep] )
00331 CANNY_PUSH( m + mapstep );
00332 if( !m[mapstep+1] )
00333 CANNY_PUSH( m + mapstep + 1 );
00334 }
00335
00336
00337 for( i = 0; i < size.height; i++ )
00338 {
00339 const uchar* _map = map + mapstep*(i+1) + 1;
00340 uchar* _dst = dst->data.ptr + dst->step*i;
00341
00342
00343 unsigned short* _dir = (unsigned short*)(dir->data.ptr + dir->step*i);
00344 unsigned short* _gra = (unsigned short*)(gra->data.ptr + gra->step*i);
00345 const short* _dx = (short*)(dx->data.ptr + dx->step*i);
00346 const short* _dy = (short*)(dy->data.ptr + dy->step*i);
00347
00348 for( j = 0; j < size.width; j++ ){
00349 _dst[j] = (uchar)-(_map[j] >> 1);
00350 if(_dst[j]) {
00351 _dir[j] = (unsigned short) cvFastArctan(_dy[j], _dx[j]);
00352 _gra[j] = cvSqrt(_dx[j]*_dx[j] + _dy[j]*_dy[j]);
00353 } else {
00354 _dir[j] = 0;
00355 _gra[j] = 0;
00356 }
00357 }
00358 }
00359 }
00360
00361 void Canny( const cv::Mat& image, cv::Mat& edges, cv::Mat& gradient, cv::Mat& direction, cv::Mat& sobel_dx, cv::Mat& sobel_dy,
00362 double threshold1, double threshold2,
00363 int apertureSize, bool L2gradient )
00364 {
00365 cv::Mat src = image;
00366 edges.create(src.size(), CV_8U);
00367 gradient.create(src.size(), CV_16UC1);
00368 direction.create(src.size(), CV_16UC1);
00369 sobel_dx.create(src.size(), CV_16SC1);
00370 sobel_dy.create(src.size(), CV_16SC1);
00371 CvMat _src = src, _dst = edges, _gradientarr = gradient, _directionarr = direction, dxarr = sobel_dx, dyarr = sobel_dy;
00372 v4rCanny( &_src, &_dst, &_gradientarr, &_directionarr, &dxarr, &dyarr, threshold1, threshold2,
00373 apertureSize + (L2gradient ? CV_CANNY_L2_GRADIENT : 0));
00374 }
00375 };
00376
00377