$search
00001 00010 #include <cob_read_text/text_detect.h> 00011 #include <ros/ros.h> 00012 00013 #include <iostream> 00014 #include <fstream> 00015 #include <stack> 00016 00017 /*#include <sensor_msgs/PointCloud2.h> 00018 #include <pcl/ros/conversions.h> 00019 #include <pcl/point_cloud.h> 00020 #include <pcl/point_types.h>*/ 00021 00022 using namespace cv; 00023 using namespace std; 00024 00025 DetectText::DetectText() : 00026 maxStrokeWidth_(0), initialStrokeWidth_(0), firstPass_(true), result_(COARSE), nComponent_(0), maxLetterHeight_(0), 00027 minLetterHeight_(0), textDisplayOffset_(1), eval(true) 00028 { 00029 } 00030 DetectText::~DetectText() 00031 { 00032 } 00033 00034 void DetectText::detect(string filename) 00035 { 00036 filename_ = filename; 00037 originalImage_ = imread(filename_); 00038 00039 if (!originalImage_.data) 00040 { 00041 ROS_ERROR("Cannot read image input..."); 00042 return; 00043 } 00044 mode_ = IMAGE; 00045 detect(); 00046 } 00047 void DetectText::detect(Mat& image) 00048 { 00049 filename_ = string("streaming.jpg"); 00050 originalImage_ = image; 00051 mode_ = STREAM; 00052 detect(); 00053 } 00054 00055 void DetectText::detect() 00056 { 00057 double start_time; 00058 double time_in_seconds; 00059 start_time = clock(); 00060 00061 Mat imGray(originalImage_.size(), CV_8UC1, Scalar(0)); 00062 cvtColor(originalImage_, imGray, CV_RGB2GRAY); 00063 boundingBoxes_.clear(); 00064 boxesBothSides_.clear(); 00065 wordsBothSides_.clear(); 00066 boxesScores_.clear(); 00067 00068 preprocess(imGray); 00069 firstPass_ = true; 00070 pipeline(1); //bright font 00071 cout << "Second pass" << endl; 00072 firstPass_ = false; 00073 pipeline(-1); //dark font 00074 00075 overlapBoundingBoxes(boundingBoxes_); 00076 ocrRead(boundingBoxes_); 00077 showBoundingBoxes(boxesBothSides_); 00078 std::cout << "1\n"; 00079 overlayText(boxesBothSides_, wordsBothSides_); 00080 std::cout << "1\n"; 00081 00082 if (eval == true) 00083 { 00084 ofstream myfile, myfile2; 00085 std::string textname = outputPrefix_ + ".txt"; 00086 std::string textname2 = outputPrefix_ + "t.txt"; 00087 myfile.open(textname.c_str()); 00088 for (int i = 0; i < boxesBothSides_.size(); i++) 00089 { 00090 myfile << boxesBothSides_[i].x << "\n" << boxesBothSides_[i].y << "\n" << boxesBothSides_[i].width << "\n" 00091 << boxesBothSides_[i].height << "\n"; 00092 } 00093 myfile.close(); 00094 myfile2.open(textname2.c_str()); 00095 for (int i = 0; i < wordsBothSides_.size(); i++) 00096 { 00097 myfile2 << wordsBothSides_[i] << "\n"; 00098 } 00099 myfile2.close(); 00100 00101 } 00102 00103 imwrite(outputPrefix_ + "_detection.jpg", detection_); 00104 00105 time_in_seconds = (clock() - start_time) / (double)CLOCKS_PER_SEC; 00106 cout << time_in_seconds << "s total in process\n" << endl; 00107 00108 textDisplayOffset_ = 1; 00109 } 00110 00111 void DetectText::preprocess(Mat& image) 00112 { 00113 int maxStrokeWidthParameter = 50; 00114 maxLetterHeight_ = 300; 00115 minLetterHeight_ = 5; 00116 00117 cout << "preprocessing: " << filename_ << endl; 00118 cout << "image size:" << image.cols << "X" << image.rows << endl; 00119 00120 //outputPrefix_: without extension 00121 int slashIndex = -1; 00122 int dotIndex = -1; 00123 for (size_t i = filename_.length() - 1; i != 0; i--) 00124 { 00125 if (dotIndex == -1 && filename_[i] == '.') 00126 dotIndex = i; 00127 if (slashIndex == -1 && filename_[i] == '/') 00128 slashIndex = i; 00129 } 00130 outputPrefix_ = filename_.substr(slashIndex + 1, dotIndex - slashIndex - 1); 00131 cout << "outputPrefix: " << outputPrefix_ << endl; 00132 00133 //setting initialStrokeWidth_ for SWT 00134 image_ = image; 00135 00136 // hack: was turned off 00137 // bilateralFilter(image, image_, 7, 20, 50);// prosilica sensor noise 00138 maxStrokeWidth_ = round((float)(max(image.cols, image.rows)) / maxStrokeWidthParameter); 00139 initialStrokeWidth_ = maxStrokeWidth_ * 2; 00140 00141 // 600 pixel side for displaying results 00142 IplImage *img2 = new IplImage(originalImage_); 00143 IplImage *img1 = cvCreateImage(cvSize(image.cols + 600, image.rows), img2->depth, img2->nChannels); 00144 cvSet(img1, cvScalar(0, 0, 0)); 00145 cvSetImageROI(img1, cvRect(0, 0, image.cols, image.rows)); 00146 cvCopy(img2, img1, NULL); 00147 cvResetImageROI(img1); 00148 detection_ = Mat(img1).clone(); 00149 cvReleaseImage(&img1); 00150 delete img1; 00151 delete img2; 00152 } 00153 00154 Mat& DetectText::getDetection() 00155 { 00156 return detection_; 00157 } 00158 vector<string>& DetectText::getWords() 00159 { 00160 return wordsBothSides_; 00161 } 00162 00163 vector<Rect>& DetectText::getBoxesBothSides() 00164 { 00165 return boxesBothSides_; 00166 } 00167 00168 void DetectText::pipeline(int blackWhite) 00169 { 00170 if (blackWhite == 1) 00171 { 00172 fontColor_ = BRIGHT; 00173 } 00174 else if (blackWhite == -1) 00175 { 00176 fontColor_ = DARK; 00177 } 00178 else 00179 { 00180 cout << "blackwhite should only be +/-1" << endl; 00181 assert(false); 00182 } 00183 double start_time; 00184 double time_in_seconds; 00185 00186 start_time = clock(); 00187 Mat swtmap(image_.size(), CV_32FC1, Scalar(initialStrokeWidth_)); 00188 00189 strokeWidthTransform(image_, swtmap, blackWhite); 00190 time_in_seconds = (clock() - start_time) / (double)CLOCKS_PER_SEC; 00191 cout << time_in_seconds << "s in strokeWidthTransform" << endl; 00192 00193 start_time = clock(); 00194 Mat ccmap(image_.size(), CV_32FC1, Scalar(-1)); 00195 componentsRoi_.clear(); 00196 nComponent_ = connectComponentAnalysis(swtmap, ccmap); 00197 time_in_seconds = (clock() - start_time) / (double)CLOCKS_PER_SEC; 00198 cout << time_in_seconds << "s in connectComponentAnalysis" << endl; 00199 00200 start_time = clock(); 00201 identifyLetters(swtmap, ccmap); 00202 time_in_seconds = (clock() - start_time) / (double)CLOCKS_PER_SEC; 00203 cout << time_in_seconds << "s in identifyLetters" << endl; 00204 00205 start_time = clock(); 00206 groupLetters(swtmap, ccmap); 00207 time_in_seconds = (clock() - start_time) / (double)CLOCKS_PER_SEC; 00208 cout << time_in_seconds << "s in groupLetters" << endl; 00209 00210 start_time = clock(); 00211 chainPairs(ccmap); 00212 time_in_seconds = (clock() - start_time) / (double)CLOCKS_PER_SEC; 00213 cout << time_in_seconds << "s in chainPairs" << endl; 00214 00215 start_time = clock(); 00216 //findRotationangles(blackWhite); 00217 time_in_seconds = (clock() - start_time) / (double)CLOCKS_PER_SEC; 00218 cout << time_in_seconds << "s in findRotationsangles" << endl; 00219 00220 /*showEdgeMap(); 00221 showSwtmap(swtmap); 00222 showCcmap(ccmap); 00223 showLetterGroup(); 00224 */ 00225 disposal(); 00226 cout << "finish clean up" << endl; 00227 00228 } 00229 00230 void DetectText::strokeWidthTransform(const Mat& image, Mat& swtmap, int searchDirection) 00231 { 00232 if (firstPass_) 00233 { 00234 // compute edge map 00235 Canny(image_, edgemap_, 50, 120); 00236 00237 // compute partial derivatives 00238 Mat dx, dy; 00239 Sobel(image_, dx, CV_32FC1, 1, 0, 3); 00240 Sobel(image_, dy, CV_32FC1, 0, 1, 3); 00241 00242 theta_ = Mat(image_.size(), CV_32FC1); 00243 00244 if (edgepoints_.size()) 00245 { 00246 edgepoints_.clear(); 00247 } 00248 00249 for (int y = 0; y < edgemap_.rows; y++) 00250 { 00251 for (int x = 0; x < edgemap_.cols; x++) 00252 { 00253 if (edgemap_.at<unsigned char> (y, x) == 255) // In case (x,y) is an edge 00254 { 00255 theta_.at<float> (y, x) = atan2(dy.at<float> (y, x), dx.at<float> (y, x)); //rise = arctan dy/dx 00256 edgepoints_.push_back(Point(x, y)); //Save edge as point in edgepoints 00257 } 00258 } 00259 } 00260 } 00261 // Second Pass (SWT is not performed again): 00262 vector<Point> strokePoints; 00263 updateStrokeWidth(swtmap, edgepoints_, strokePoints, searchDirection, UPDATE); 00264 updateStrokeWidth(swtmap, strokePoints, strokePoints, searchDirection, REFINE); 00265 } 00266 00267 void DetectText::updateStrokeWidth(Mat& swtmap, vector<Point>& startPoints, vector<Point>& strokePoints, 00268 int searchDirection, Purpose purpose) 00269 { 00270 //loop through all edgepoints, compute stroke width 00271 //startPoints = edgepoints_ 00272 vector<Point>::iterator itr = startPoints.begin(); 00273 00274 vector<Point> pointStack; 00275 vector<float> SwtValues; 00276 00277 for (; itr != startPoints.end(); ++itr) 00278 { 00279 pointStack.clear(); 00280 SwtValues.clear(); 00281 float step = 1; 00282 float iy = (*itr).y; 00283 float ix = (*itr).x; 00284 float currY = iy; 00285 float currX = ix; 00286 bool isStroke = false; 00287 float iTheta = theta_.at<float> (*itr); 00288 00289 pointStack.push_back(Point(currX, currY)); 00290 SwtValues.push_back(swtmap.at<float> (currY, currX)); 00291 while (step < maxStrokeWidth_) 00292 { 00293 //going one pixel in the direction of the gradient to check if next pixel is an edge too 00294 float nextY = round(iy + sin(iTheta) * searchDirection * step); 00295 float nextX = round(ix + cos(iTheta) * searchDirection * step); 00296 00297 if (nextY < 0 || nextX < 0 || nextY >= edgemap_.rows || nextX >= edgemap_.cols) 00298 break; 00299 00300 step = step + 1; 00301 00302 if (currY == nextY && currX == nextX) 00303 continue; 00304 00305 currY = nextY; 00306 currX = nextX; 00307 00308 pointStack.push_back(Point(currX, currY)); 00309 SwtValues.push_back(swtmap.at<float> (currY, currX)); 00310 if (edgemap_.at<unsigned char> (currY, currX) == 255) 00311 { 00312 float jTheta = theta_.at<float> (currY, currX); 00313 //if opposite point of stroke is found with roughly opposite gradient Theta: ... 00314 if (abs(abs(iTheta - jTheta) - 3.14) < 3.14 / 2) 00315 { 00316 isStroke = true; 00317 if (purpose == UPDATE) 00318 { 00319 strokePoints.push_back(Point(ix, iy)); 00320 } 00321 } 00322 break; 00323 } 00324 } 00325 00326 // ... then calculate newSwtVal for all Points between the two stroke points 00327 if (isStroke) 00328 { 00329 float newSwtVal; 00330 if (purpose == UPDATE)// update swt based on dist between edges 00331 { 00332 newSwtVal = sqrt((currY - iy) * (currY - iy) + (currX - ix) * (currX - ix)); 00333 } 00334 else if (purpose == REFINE) // refine swt based on median 00335 { 00336 nth_element(SwtValues.begin(), SwtValues.begin() + SwtValues.size() / 2, SwtValues.end()); 00337 newSwtVal = SwtValues[SwtValues.size() / 2]; 00338 } 00339 // set all Points between to the newSwtVal except they are smaller because of another stroke 00340 for (size_t i = 0; i < pointStack.size(); i++) 00341 { 00342 swtmap.at<float> (pointStack[i]) = min(swtmap.at<float> (pointStack[i]), newSwtVal); 00343 //cout << "swtmap.at<float> (" << pointStack[i] << ") = min(" << swtmap.at<float> (pointStack[i]) << ", " << newSwtVal << ");" << endl; 00344 } 00345 } 00346 00347 }// end loop through edge points 00348 00349 // set initial upchanged value back to 0 00350 00351 for (int y = 0; y < swtmap.rows; y++) 00352 { 00353 for (int x = 0; x < swtmap.cols; x++) 00354 { 00355 if (swtmap.at<float> (y, x) == initialStrokeWidth_) 00356 { 00357 swtmap.at<float> (y, x) = 0; 00358 } 00359 } 00360 } 00361 00362 } 00363 00364 int DetectText::connectComponentAnalysis(const Mat& swtmap, Mat& ccmap) 00365 { 00366 00367 int ccmapInitialVal = ccmap.at<float> (0, 0); 00368 int offsetY[] = {-1, -1, -1, 0, 0, 1, 1, 1}; 00369 int offsetX[] = {-1, 0, 1, -1, 1, -1, 0, 1}; 00370 int nNeighbors = 8; 00371 int label = 0; 00372 00373 int vectorSize = ccmap.rows * ccmap.cols; 00374 00375 int *pStack = new int[vectorSize * 2]; 00376 int stackPointer; 00377 00378 int *pVector = new int[vectorSize * 2]; 00379 int vectorPointer; 00380 00381 int currentPointX; 00382 int currentPointY; 00383 00384 for (int y = 0; y < ccmap.rows; y++) 00385 { 00386 for (int x = 0; x < ccmap.cols; x++) 00387 { 00388 bool connected = false; 00389 if (ccmap.at<float> (y, x) == ccmapInitialVal) 00390 { 00391 vectorPointer = 0; 00392 stackPointer = 0; 00393 pStack[stackPointer] = x; 00394 pStack[stackPointer + 1] = y; 00395 00396 while (stackPointer >= 0) 00397 { 00398 currentPointX = pStack[stackPointer]; 00399 currentPointY = pStack[stackPointer + 1]; 00400 stackPointer -= 2; 00401 00402 pVector[vectorPointer] = currentPointX; 00403 pVector[vectorPointer + 1] = currentPointY; 00404 vectorPointer += 2; 00405 //check which one of the neighbors have similiar sw and then label the regions belonging together 00406 for (int i = 0; i < nNeighbors; i++) 00407 { 00408 int ny = currentPointY + offsetY[i]; 00409 int nx = currentPointX + offsetX[i]; 00410 00411 if (ny < 0 || nx < 0 || ny >= ccmap.rows || nx >= ccmap.cols) 00412 continue; 00413 00414 if (swtmap.at<float> (ny, nx) == 0) 00415 { 00416 ccmap.at<float> (ny, nx) = -2; 00417 continue; 00418 } 00419 00420 if (ccmap.at<float> (ny, nx) == ccmapInitialVal) 00421 { 00422 float sw1 = swtmap.at<float> (ny, nx); 00423 float sw2 = swtmap.at<float> (y, x); 00424 00425 if (max(sw1, sw2) / min(sw1, sw2) <= 3) 00426 { 00427 ccmap.at<float> (ny, nx) = label; 00428 stackPointer += 2; 00429 pStack[stackPointer] = nx; 00430 pStack[stackPointer + 1] = ny; 00431 connected = true; 00432 00433 } 00434 } 00435 }// loop through neighbors 00436 } 00437 00438 if (connected) 00439 { 00440 // assert(vectorPointer <= vectorSize); 00441 // assert(vectorPointer > 0); 00442 00443 int minY = ccmap.rows, minX = ccmap.cols, maxY = 0, maxX = 0; 00444 int width, height; 00445 for (int i = 0; i < vectorPointer; i += 2) 00446 { 00447 // ROI for each component 00448 minY = min(minY, pVector[i + 1]); 00449 minX = min(minX, pVector[i]); 00450 maxY = max(maxY, pVector[i + 1]); 00451 maxX = max(maxX, pVector[i]); 00452 } 00453 width = maxX - minX + 1; // width = 1 00454 height = maxY - minY + 1; // height = 1 00455 Rect letterRoi(minX, minY, width, height); 00456 componentsRoi_.push_back(letterRoi); 00457 label++; 00458 } 00459 else 00460 { 00461 ccmap.at<float> (y, x) = -2; 00462 } 00463 } 00464 }// loop through ccmap 00465 } 00466 delete[] pStack; 00467 delete[] pVector; 00468 return label; 00469 } 00470 00471 void DetectText::identifyLetters(const Mat& swtmap, const Mat& ccmap) 00472 { 00473 00474 int showCcmap = 0; 00475 Mat output = originalImage_.clone(); 00476 00477 assert(static_cast<size_t>(nComponent_) == componentsRoi_.size()); 00478 isLetterComponects_ = new bool[nComponent_]; 00479 vector<float> iComponentStrokeWidth; 00480 cout << nComponent_ << "componets" << endl; 00481 bool *innerComponents = new bool[nComponent_]; 00482 00483 for (size_t i = 0; i < nComponent_; i++) 00484 { 00485 float maxStrokeWidth = 0; 00486 float sumStrokeWidth = 0; 00487 float currentStrokeWidth; 00488 bool isLetter = true; 00489 00490 Rect *itr = &componentsRoi_[i]; 00491 00492 // is height enough for being a letter? 00493 if (itr->height > maxLetterHeight_ || itr->height < minLetterHeight_) 00494 { 00495 isLetterComponects_[i] = false; 00496 continue; 00497 } 00498 00499 float maxY = itr->y + itr->height; 00500 float minY = itr->y; 00501 float maxX = itr->x + itr->width; 00502 float minX = itr->x; 00503 float increment = abs(itr->width - itr->height) / 2; 00504 00505 // reset the inner components 00506 memset(innerComponents, 0, nComponent_ * sizeof(bool)); 00507 00508 if (itr->width > itr->height) // increase box height 00509 00510 { 00511 maxY = min(maxY + increment, static_cast<float> (ccmap.rows)); 00512 minY = max(minY - increment, static_cast<float> (0.0)); 00513 } 00514 else // increase box width 00515 00516 { 00517 maxX = min(maxX + increment, static_cast<float> (ccmap.cols)); 00518 minX = max(minX - increment, static_cast<float> (0.0)); 00519 } 00520 00521 for (int y = minY; y < maxY; y++) 00522 for (int x = minX; x < maxX; x++) 00523 { 00524 int component = static_cast<int> (ccmap.at<float> (y, x)); //ccmap-Label = -2 in case no Region; 0,1,2,3... for every region 00525 if (component == static_cast<int> (i)) 00526 00527 { 00528 currentStrokeWidth = swtmap.at<float> (y, x); 00529 iComponentStrokeWidth.push_back(currentStrokeWidth); 00530 maxStrokeWidth = max(maxStrokeWidth, currentStrokeWidth); 00531 sumStrokeWidth += currentStrokeWidth; 00532 } 00533 else if (component >= 0) 00534 innerComponents[component] = true; 00535 } 00536 00537 float pixelCount = static_cast<float> (iComponentStrokeWidth.size()); 00538 float mean = sumStrokeWidth / pixelCount; 00539 float variance = 0; 00540 00541 for (size_t ii = 0; ii < pixelCount; ii++) 00542 { 00543 variance += (iComponentStrokeWidth[ii] - mean, 2) * (iComponentStrokeWidth[ii] - mean, 2); // variance += (SW[i]-mean)²; 00544 } 00545 variance = variance / pixelCount; 00546 00547 // rules & parameters goes here: 00548 00549 isLetter = isLetter && (variance / mean < 1.5); //Variance has to be small, so that for example leaves can be recognized as no letters 00550 00551 isLetter = isLetter && (sqrt(((itr->width) * (itr->width) + (itr->height) * (itr->height))) / maxStrokeWidth < 10); 00552 00553 // additional rules: 00554 isLetter = isLetter && (pixelCount / maxStrokeWidth > 5); 00555 00556 isLetter = isLetter && (itr->width < 2.5 * itr->height); 00557 00558 if (countInnerLetterCandidates(innerComponents) - 1 > 5) 00559 { 00560 isLetter = false; 00561 } 00562 isLetterComponects_[i] = isLetter; 00563 00564 iComponentStrokeWidth.clear(); 00565 } 00566 00567 if (showCcmap == 1) 00568 { 00569 for (size_t i = 0; i < nComponent_; i++) 00570 { 00571 if (isLetterComponects_[i] == true) 00572 { 00573 rectangle(output, Point(componentsRoi_[i].x, componentsRoi_[i].y), Point(componentsRoi_[i].x 00574 + componentsRoi_[i].width, componentsRoi_[i].y + componentsRoi_[i].height), cvScalar((150), (110), (50)), 1); 00575 } 00576 if (fontColor_ == 1) 00577 cv::imshow("identify bright letters=ccmap[after]", output); 00578 else 00579 cv::imshow("identify dark letters=ccmap[after]", output); 00580 } 00581 waitKey(0); 00582 } 00583 delete[] innerComponents; 00584 } 00585 00586 void DetectText::groupLetters(const Mat& swtmap, const Mat& ccmap) 00587 { 00588 int showGroupedLetters = 0; 00589 componentsMeanIntensity_ = new float[nComponent_]; 00590 componentsMedianStrokeWidth_ = new float[nComponent_]; 00591 isGrouped_ = new bool[nComponent_]; 00592 memset(componentsMeanIntensity_, 0, nComponent_ * sizeof(float)); 00593 memset(componentsMedianStrokeWidth_, 0, nComponent_ * sizeof(float)); 00594 memset(isGrouped_, false, nComponent_ * sizeof(bool)); 00595 00596 Mat output = originalImage_.clone(); 00597 00598 for (size_t i = 0; i < nComponent_; i++) 00599 { 00600 if (!isLetterComponects_[i]) //all in groupLetters as not-letters recognized componects ignored 00601 continue; 00602 00603 Rect iRect = componentsRoi_[i]; 00604 00605 float iMeanIntensity = getMeanIntensity(ccmap, iRect, static_cast<int> (i)); 00606 float iMedianStrokeWidth = getMedianStrokeWidth(ccmap, swtmap, iRect, static_cast<int> (i)); 00607 00608 for (size_t j = i + 1; j < nComponent_; j++) 00609 { 00610 if (!isLetterComponects_[j]) 00611 continue; 00612 00613 Rect jRect = componentsRoi_[j]; 00614 00615 // check if horizontal or vertical 00616 bool horizontal = (iRect.y < jRect.y + jRect.height && jRect.y < iRect.y + iRect.height); 00617 bool vertical = (iRect.x < jRect.x + jRect.width && jRect.x < iRect.x + iRect.width); 00618 00619 if ((!horizontal) && (!vertical)) 00620 continue; 00621 00622 // if there is a tie between horizontal/vertical 00623 if (horizontal && vertical) 00624 { 00625 if (abs((iRect.x + iRect.width / 2) - (jRect.x + jRect.width / 2)) >= abs((iRect.y + iRect.height / 2) 00626 - (jRect.y + jRect.height / 2))) 00627 { 00628 horizontal = true; 00629 vertical = false; 00630 } 00631 else 00632 { 00633 horizontal = false; 00634 vertical = true; 00635 } 00636 } 00637 00638 // rule 3: distance between characters 00639 float distance = sqrt((iRect.x + iRect.width / 2 - jRect.x - jRect.width / 2) * (iRect.x + iRect.width / 2 00640 - jRect.x - jRect.width / 2) + (iRect.y + iRect.height / 2 - jRect.y - jRect.height / 2) * (iRect.y 00641 + iRect.height / 2 - jRect.y - jRect.height / 2)); 00642 int distanceRatio = 4; //4 00643 if (horizontal) 00644 { 00645 if (distance / max(iRect.width, jRect.width) > distanceRatio) 00646 continue; 00647 } 00648 else 00649 { 00650 if (distance / max(iRect.height, jRect.height) > distanceRatio) 00651 continue; 00652 } 00653 00654 float jMeanIntensity = getMeanIntensity(ccmap, jRect, static_cast<int> (j)); 00655 float jMedianStrokeWidth = getMedianStrokeWidth(ccmap, swtmap, jRect, static_cast<int> (j)); 00656 00657 bool isGroup = true; 00658 00660 // rule 1: median of stroke width ratio 00661 isGroup = isGroup && (max(iMedianStrokeWidth, jMedianStrokeWidth) / min(iMedianStrokeWidth, jMedianStrokeWidth)) 00662 < 2; 00663 // rule 2: height ratio 00664 isGroup = isGroup && (max(iRect.height, jRect.height) / min(iRect.height, jRect.height)) < 2; 00665 // rule 4: average color of letters 00666 isGroup = isGroup && abs(iMeanIntensity - jMeanIntensity) < 10; 00667 00668 if (isGroup) 00669 { 00670 isGrouped_[i] = true; 00671 isGrouped_[j] = true; 00672 00673 if (horizontal) 00674 { 00675 horizontalLetterGroups_.push_back(Pair(i, j)); 00676 } 00677 00678 //if (vertical) 00679 //{ 00680 // verticalLetterGroups_.push_back(Pair(i, j)); 00681 // verticalLetterGroups are never used again, so the Pairs should be pushed into horizonzalLetterGroups instead 00682 //horizontalLetterGroups_.push_back(Pair(i, j)); 00683 //} 00684 00685 if (showGroupedLetters == 1) 00686 { 00687 rectangle(output, Point(iRect.x, iRect.y), Point(iRect.x + iRect.width, iRect.y + iRect.height), 00688 cvScalar(0, 0, 255), 2); 00689 rectangle(output, Point(jRect.x, jRect.y), Point(jRect.x + jRect.width, jRect.y + jRect.height), 00690 cvScalar(0, 0, 255), 2); 00691 } 00692 00693 } 00694 }// end for loop j 00695 }// end for loop i 00696 00697 if (showGroupedLetters == 1) 00698 { 00699 if (firstPass_) 00700 cv::imshow("bright", output); 00701 else 00702 cv::imshow("dark", output); 00703 waitKey(0); 00704 } 00705 } 00706 00707 void DetectText::chainPairs(Mat& ccmap) 00708 { 00709 int showpairs = 0; 00710 int showchains = 0; 00711 if (showpairs == 1) 00712 { 00713 Mat output = originalImage_.clone(); 00714 for (int i = 0; i < horizontalLetterGroups_.size() - 1; i++) 00715 { 00716 rectangle(output, Point(componentsRoi_.at(horizontalLetterGroups_[i].left).x, 00717 componentsRoi_.at(horizontalLetterGroups_[i].left).y), 00718 Point(componentsRoi_.at(horizontalLetterGroups_[i].left).x 00719 + componentsRoi_.at(horizontalLetterGroups_[i].left).width, 00720 componentsRoi_.at(horizontalLetterGroups_[i].left).y 00721 + componentsRoi_.at(horizontalLetterGroups_[i].left).height), cvScalar(255, 255, 255), 2); 00722 rectangle(output, Point(componentsRoi_.at(horizontalLetterGroups_[i].right).x, 00723 componentsRoi_.at(horizontalLetterGroups_[i].right).y), 00724 Point(componentsRoi_.at(horizontalLetterGroups_[i].right).x 00725 + componentsRoi_.at(horizontalLetterGroups_[i].right).width, 00726 componentsRoi_.at(horizontalLetterGroups_[i].right).y 00727 + componentsRoi_.at(horizontalLetterGroups_[i].right).height), cvScalar(255, 255, 255), 2); 00728 } 00729 cv::imshow("pairs", output); 00730 waitKey(0); 00731 } 00732 00733 mergePairs(horizontalLetterGroups_, horizontalChains_); 00734 00735 // horizontalChains 00736 vector<Rect> initialHorizontalBoxes; 00737 chainToBox(horizontalChains_, initialHorizontalBoxes); //initialHorizontalBoxes contains rects for every chaincomponent with more than to components(letters) 00738 00739 if (showchains == 1) 00740 { 00741 Mat output = originalImage_.clone(); 00742 for (int i = 0; i < initialHorizontalBoxes.size(); i++) 00743 { 00744 rectangle(output, Point(initialHorizontalBoxes[i].x, initialHorizontalBoxes[i].y), 00745 Point(initialHorizontalBoxes[i].x + initialHorizontalBoxes[i].width, initialHorizontalBoxes[i].y 00746 + initialHorizontalBoxes[i].height), cvScalar(155, 55, 255), 2); 00747 } 00748 cv::imshow("chains", output); 00749 waitKey(0); 00750 } 00751 00752 filterBoundingBoxes(initialHorizontalBoxes, ccmap, 4); 00753 00754 // boundingBoxes_ are filled with initialHorizontalBoxes: 00755 boundingBoxes_.insert(boundingBoxes_.end(), initialHorizontalBoxes.begin(), initialHorizontalBoxes.end()); 00756 00757 if (showchains == 1) 00758 { 00759 Mat output = originalImage_.clone(); 00760 for (int i = 0; i < boundingBoxes_.size(); i++) 00761 { 00762 rectangle(output, Point(boundingBoxes_[i].x, boundingBoxes_[i].y), Point(boundingBoxes_[i].x 00763 + boundingBoxes_[i].width, boundingBoxes_[i].y + boundingBoxes_[i].height), cvScalar(0, 55, 105), 2); 00764 } 00765 cv::imshow("chains2", output); 00766 waitKey(0); 00767 } 00768 } 00769 00770 void DetectText::findRotationangles(int blackWhite) 00771 { 00772 int showHistogram = 1; 00773 int showRects = 0; 00774 int padding = 10; 00775 00776 bgr whiteClr; 00777 whiteClr.r = 255; 00778 whiteClr.g = 255; 00779 whiteClr.b = 255; 00780 00781 // Gradient Histogram 00782 //***************************************************************************************************** 00783 00784 cv::Mat canvas; 00785 canvas.create(125, 360, CV_8UC3); 00786 int maxValue = 0, maxAngle = 0, angles = 360; 00787 int hist[angles], newHistogram[angles]; 00788 double scale; 00789 00790 for (unsigned int i = 0; i < boundingBoxes_.size(); i++) 00791 { 00792 // Show boundingBoxes if necessary 00793 if (showRects) 00794 { 00795 cv::Mat output = originalImage_.clone(); 00796 cv::rectangle(output, cv::Point(boundingBoxes_.at(i).x, boundingBoxes_.at(i).y), cv::Point(boundingBoxes_.at(i).x 00797 + boundingBoxes_.at(i).width, boundingBoxes_.at(i).y + boundingBoxes_.at(i).height), cvScalar(250, 210, 150), 00798 2); 00799 cv::imshow("right rectangles", output); 00800 cv::waitKey(0); 00801 } 00802 00803 // Reset Values 00804 maxValue = 0; 00805 maxAngle = 0; 00806 00807 for (int y = 0; y < canvas.rows; y++) 00808 for (int x = 0; x < canvas.cols; x++) 00809 { 00810 canvas.at<bgr> (y, x) = whiteClr; 00811 } 00812 00813 for (int j = 0; j < angles - 1; j++) 00814 hist[j] = 0; 00815 00816 // If there is an edge at (y,x), 00817 // get the angle[-180,180] at (y,x) and add 180 degrees. (because histogram range is [0,360]) 00818 // Then add one point in the histogram at the found angle. 00819 for (int y = boundingBoxes_[i].y; y < boundingBoxes_[i].y + boundingBoxes_[i].height; y++) 00820 { 00821 for (int x = boundingBoxes_[i].x; x < boundingBoxes_[i].x + boundingBoxes_[i].width; x++) 00822 { 00823 if (edgemap_.at<unsigned char> (y, x) == 255) 00824 { 00825 int angle = (int)((180 / 3.141592) * theta_.at<float> (y, x)) + 180; 00826 hist[angle]++; 00827 } 00828 } 00829 } 00830 00831 // Smoothing the histogram 00832 double mask[3]; 00833 mask[0] = 0.25; 00834 mask[1] = 0.5; 00835 mask[2] = 0.25; 00836 00837 for (int bin = 1; bin < 359; bin++) 00838 { 00839 double smoothedValue = 0; 00840 for (int i = 0; i < 3; i++) 00841 { 00842 smoothedValue += hist[bin - 1 + i] * mask[i]; 00843 } 00844 newHistogram[bin] = smoothedValue; 00845 } 00846 00847 newHistogram[0] = hist[0] * (2 / 3) + hist[1] * (1 / 3); 00848 newHistogram[359] = hist[358] * (1 / 3) + hist[359] * (2 / 3); 00849 00850 for (int bin = 1; bin < 360; bin++) 00851 { 00852 hist[bin] = newHistogram[bin]; 00853 } 00854 00855 // Get maxValue and max angle 00856 for (int j = 0; j < angles - 1; j++) 00857 maxValue = hist[j] > maxValue ? hist[j] : maxValue; 00858 00859 for (int j = 0; j < angles - 1; j++) 00860 if (maxValue == hist[j]) 00861 maxAngle = j; 00862 00863 // Fit histogram to the canvas height 00864 scale = maxValue > canvas.rows ? (double)canvas.rows / maxValue : 1.; 00865 00866 //Draw histogram 00867 if (showHistogram) 00868 { 00869 for (int j = 0; j < angles - 1; j++) 00870 { 00871 cv::Point pt1(j, canvas.rows - (hist[j] * scale)); 00872 cv::Point pt2(j, canvas.rows); 00873 if (j == maxAngle) 00874 cv::line(canvas, pt1, pt2, cv::Scalar(200, 160, 100), 2, 8, 0); 00875 else 00876 cv::line(canvas, pt1, pt2, cv::Scalar(250, 210, 150), 1, 8, 0); 00877 } 00878 cv::putText(canvas, "0", cv::Point(180, 122), cv::FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(0, 0, 0, 0), 1.5, 8, 00879 false); 00880 cv::putText(canvas, "-90", cv::Point(90, 122), cv::FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(0, 0, 0, 0), 1.5, 8, 00881 false); 00882 cv::putText(canvas, "-180", cv::Point(0, 122), cv::FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(0, 0, 0, 0), 1.5, 8, 00883 false); 00884 cv::putText(canvas, "90", cv::Point(260, 122), cv::FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(0, 0, 0, 0), 1.5, 8, 00885 false); 00886 cv::putText(canvas, "180", cv::Point(335, 122), cv::FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(0, 0, 0, 0), 1.5, 8, 00887 false); 00888 cv::imshow("Gradients", canvas); 00889 std::cout << "blackWhite:" << blackWhite << endl; 00890 std::cout << "maxAngle:" << maxAngle << "(" << maxAngle - 180 << ")" << endl; 00891 //cv::waitKey(0); 00892 } 00893 00894 // Rotationangles 00895 //***************************************************************************************************** 00896 00897 cv::Rect rectWithPadding; 00898 rectWithPadding.x = max(boundingBoxes_[i].x - padding, 0); 00899 rectWithPadding.y = max(boundingBoxes_[i].y - padding, 0); 00900 boundingBoxes_[i].y + boundingBoxes_[i].height > image_.rows ? rectWithPadding.height = image_.rows 00901 : rectWithPadding.height = boundingBoxes_[i].height + padding; 00902 boundingBoxes_[i].x + boundingBoxes_[i].width > image_.cols ? rectWithPadding.width = image_.cols 00903 : rectWithPadding.width = boundingBoxes_[i].width + padding; 00904 cv::Mat smallImg = image_(rectWithPadding); 00905 00906 // Average of whole image 00907 cv::Scalar averageColor = mean(smallImg); 00908 00909 // Average of background Pixels 00910 00911 std::vector<int> bgColor; 00912 for (int y = 0; y < smallImg.rows; y++) 00913 { 00914 for (int x = 0; x < smallImg.cols; x++) 00915 { 00916 if (blackWhite == 1) //bright text 00917 { 00918 if ((unsigned int)smallImg.at<unsigned char> (y, x) > (unsigned int)averageColor.val[0]) 00919 { 00920 bgColor.push_back((unsigned int)smallImg.at<unsigned char> (y, x)); 00921 } 00922 } 00923 else //dark text 00924 { 00925 if ((unsigned int)smallImg.at<unsigned char> (y, x) < (unsigned int)averageColor.val[0]) 00926 { 00927 bgColor.push_back((unsigned int)smallImg.at<unsigned char> (y, x)); 00928 } 00929 } 00930 } 00931 } 00932 int average_bg = 0; 00933 for (int i = 0; i < bgColor.size(); i++) 00934 { 00935 average_bg += bgColor[i]; 00936 } 00937 average_bg = average_bg / bgColor.size(); 00938 00939 // Rotation 00940 //***************************************************************************************************** 00941 00942 cv::Point2f center; 00943 center.x = smallImg.cols * 0.5; 00944 center.y = smallImg.rows * 0.5; 00945 00946 cv::Mat mapMatrix = cv::getRotationMatrix2D(center, maxAngle - 180, 1.0); 00947 cv::Mat rotatedImage; 00948 rotatedImage.create(smallImg.rows, smallImg.cols, CV_8UC1); 00949 00950 for (int y = 0; y < rotatedImage.rows; y++) 00951 for (int x = 0; x < rotatedImage.cols; x++) 00952 { 00953 rotatedImage.at<unsigned char> (y, x) = average_bg; 00954 } 00955 00956 cv::warpAffine(smallImg, rotatedImage, mapMatrix, smallImg.size(), INTER_CUBIC, BORDER_CONSTANT, 00957 cv::Scalar(average_bg)); 00958 cv::imshow("rotated", rotatedImage); 00959 //cv::waitKey(0); 00960 00961 Rotated * r = new Rotated(rotatedImage, cv::Rect(boundingBoxes_[i].x, boundingBoxes_[i].y, boundingBoxes_[i].width, 00962 boundingBoxes_[i].height)); 00963 rotated.push_back(*r); 00964 } 00965 } 00966 00967 void DetectText::chainToBox(vector<vector<int> >& chain, vector<Rect>& boundingBox) 00968 { 00969 for (size_t i = 0; i < chain.size(); i++) 00970 { 00971 if (chain[i].size() < 3) //Only words with more than 2 letters 00972 { 00973 continue; 00974 } 00975 00976 int minX = image_.cols, minY = image_.rows, maxX = 0, maxY = 0; 00977 int letterAreaSum = 0; 00978 int padding = 5; 00979 00980 for (size_t j = 0; j < chain[i].size(); j++) 00981 { 00982 Rect *itr = &componentsRoi_[chain[i][j]]; 00983 letterAreaSum += itr->width * itr->height; 00984 minX = min(minX, itr->x); 00985 minY = min(minY, itr->y); 00986 maxX = max(maxX, itr->x + itr->width); 00987 maxY = max(maxY, itr->y + itr->height); 00988 } 00989 00990 // add padding around each box 00991 minX = max(0, minX - padding); 00992 minY = max(0, minY - padding); 00993 maxX = min(image_.cols, maxX + padding); 00994 maxY = min(image_.rows, maxY + padding); 00995 00996 boundingBox.push_back(Rect(minX, minY, maxX - minX, maxY - minY)); 00997 } 00998 } 00999 01000 bool DetectText::spaticalOrder(Rect a, Rect b) 01001 { 01002 return a.y < b.y; 01003 } 01004 01005 void DetectText::filterBoundingBoxes(vector<Rect>& boundingBoxes, Mat& ccmap, int rejectRatio) 01006 { 01007 vector<Rect> qualifiedBoxes; 01008 vector<int> components; 01009 01010 for (size_t i = 0; i < boundingBoxes.size(); i++) 01011 { 01012 int isLetterCount = 0; 01013 int letterArea = 0; 01014 int nonLetterArea = 0; 01015 Rect *rect = &boundingBoxes[i]; 01016 01017 float width = static_cast<float> (rect->width); 01018 float height = static_cast<float> (rect->height); 01019 if (width < 20) // Only these rects/words with width > 20 -> maybe to be changed when rotated 01020 continue; 01021 if (max(width, height) / min(width, height) > 20) // maybe to be changed 01022 continue; 01023 01024 for (int y = rect->y; y < rect->y + rect->height; y++) 01025 for (int x = rect->x; x < rect->x + rect->width; x++) 01026 { 01027 int componetIndex = static_cast<int> (ccmap.at<float> (y, x)); 01028 01029 if (componetIndex < 0) //padding has no label 01030 continue; 01031 01032 if (isLetterComponects_[componetIndex]) 01033 letterArea++; 01034 else 01035 nonLetterArea++; 01036 01037 if (find(components.begin(), components.end(), componetIndex) == components.end()) 01038 { 01039 components.push_back(componetIndex); 01040 if (isLetterComponects_[componetIndex]) 01041 isLetterCount++; 01042 } 01043 } 01044 01045 // accept patch with few noise inside 01046 if (letterArea > 3 * nonLetterArea || static_cast<int> (components.size()) < rejectRatio * isLetterCount) 01047 { 01048 qualifiedBoxes.push_back(*rect); 01049 } 01050 components.clear(); 01051 } 01052 boundingBoxes = qualifiedBoxes; 01053 } 01054 01055 void DetectText::overlapBoundingBoxes(vector<Rect>& boundingBoxes) 01056 { 01057 vector<Rect> bigBoxes; 01058 // Merging BoundingBoxes 01059 Mat tempMap(image_.size(), CV_32FC1, Scalar(0)); 01060 for (size_t i = 0; i < boundingBoxes.size(); i++) 01061 { 01062 Rect *rect = &boundingBoxes[i]; 01063 for (int y = rect->y; y < rect->y + rect->height; y++) 01064 for (int x = rect->x; x < rect->x + rect->width; x++) 01065 { 01066 tempMap.at<float> (y, x) = 50; 01067 } 01068 } 01069 01070 for (size_t i = 0; i < boundingBoxes.size(); i++) 01071 { 01072 if (tempMap.at<float> (boundingBoxes[i].y + 1, boundingBoxes[i].x + 1) != 50) 01073 continue; 01074 01075 Rect rect; 01076 floodFill(tempMap, Point(boundingBoxes[i].x, boundingBoxes[i].y), i + 100, &rect); 01077 int padding = 5; 01078 01079 // add padding around each box 01080 int minX = max(0, rect.x - padding); 01081 int minY = max(0, rect.y - padding); 01082 int maxX = min(image_.cols, rect.x + rect.width + padding); 01083 int maxY = min(image_.rows, rect.y + rect.height + padding); 01084 bigBoxes.push_back(Rect(minX, minY, maxX - minX, maxY - minY)); 01085 } 01086 01087 boundingBoxes = bigBoxes; 01088 01089 cout << endl; 01090 cout << "888" << endl; 01091 } 01092 01093 void DetectText::overlayText(vector<Rect>& box, vector<string>& text) 01094 { 01095 assert(box.size() == text.size()); 01096 Scalar color(0, 255, 0); 01097 size_t lineWidth = 25; 01098 int indent = 50; 01099 int count = 1; 01100 for (size_t i = 0; i < box.size(); i++) 01101 { 01102 if (count > 9) 01103 indent = 70; 01104 string output = text[i]; 01105 if (output.compare("") == 0) 01106 continue; 01107 01108 std::string s; 01109 std::stringstream out; 01110 out << count; 01111 count++; 01112 string prefix = "["; 01113 prefix = prefix + out.str() + "]"; 01114 putText(detection_, prefix, Point(box[i].x + box[i].width, box[i].y + box[i].height), FONT_HERSHEY_DUPLEX, 1, 01115 color, 2); 01116 putText(detection_, prefix, Point(image_.cols, textDisplayOffset_ * 35), FONT_HERSHEY_DUPLEX, 1, color, 2); 01117 while (output.length() > lineWidth) 01118 { 01119 putText(detection_, output.substr(0, lineWidth), Point(image_.cols + indent, textDisplayOffset_ * 35), 01120 FONT_HERSHEY_DUPLEX, 1, color, 2); 01121 output = output.substr(lineWidth); 01122 textDisplayOffset_++; 01123 } 01124 putText(detection_, output, Point(image_.cols + indent, textDisplayOffset_ * 35), FONT_HERSHEY_DUPLEX, 1, color, 2); 01125 textDisplayOffset_ += 2; 01126 } 01127 } 01128 01129 void DetectText::ocrRead(vector<Rect>& boundingBoxes) 01130 { 01131 01132 sort(boundingBoxes.begin(), boundingBoxes.end(), DetectText::spaticalOrder); 01133 for (size_t i = 0; i < boundingBoxes.size(); i++) 01134 { 01135 string result; 01136 float score = ocrRead(originalImage_(boundingBoxes[i]), result, -1); 01137 if (score > 0) 01138 { 01139 boxesBothSides_.push_back(boundingBoxes[i]); 01140 wordsBothSides_.push_back(result); 01141 boxesScores_.push_back(score); 01142 } 01143 } 01144 /*rotated 01145 for (size_t i = 0; i < rotated.size() - 1; i++) 01146 { 01147 string result; 01148 //cout << "ROTATION [" << i << "]: "; 01149 01150 float score = ocrRead(rotated.at(i).rotated_img, result, i); 01151 if (score > 0) 01152 { 01153 boxesBothSides_.push_back(rotated.at(i).coords); 01154 wordsBothSides_.push_back(result); 01155 boxesScores_.push_back(score); 01156 } 01157 cout << "score:" << score << endl; 01158 imshow("actual image", rotated.at(i).rotated_img); 01159 //waitKey(0); 01160 } 01161 */ 01162 } 01163 01164 float DetectText::ocrRead(const Mat& imagePatch, string& output, int actual) 01165 { 01166 float score = 0; 01167 Mat scaledImage; 01168 /* 01169 if (actual >= 0) 01170 { 01171 01172 01173 cvPoint 01174 01175 cout << "imGray:" << imGray.cols << "x" << imGray.rows << endl; 01176 01177 for (int y = 0; y < imGray.rows; y++) 01178 { 01179 for (int x = 0; x < imGray.cols; x++) 01180 { 01181 if ((unsigned int)imGray.at<unsigned char> (y, x) != 0) 01182 { 01183 a = x; 01184 b = y; 01185 color = (unsigned int)imGray.at<unsigned char> (y + 3, x + 3); 01186 x = imGray.cols; 01187 y = imGray.rows; 01188 cout << "[" << a << "|" << b << "||" << color << "]" << endl; 01189 } 01190 } 01191 cout << endl; 01192 } 01193 01194 //getcolor 01195 floodFill(imGray, Point(1, 1), color, &rect); 01196 floodFill(imGray, Point(1, 1), 0, &rect); 01197 floodFill(imGray, Point(1, 1), color, &rect); 01198 //s = cvGet2D(img, yy,xx); // get the (i,j) pixel value 01199 //floodFill(tempMap, Point(1, 1), s, &rect); 01200 cv::imshow("OCR", imGray); 01201 waitKey(0); 01202 }*/ 01203 01204 if (imagePatch.rows < 30) 01205 { 01206 double scale = 1.5; 01207 resize(imagePatch, scaledImage, Size(0, 0), scale, scale, INTER_LANCZOS4); 01208 imwrite("patch.tiff", scaledImage); 01209 } 01210 else 01211 { 01212 imwrite("patch.tiff", imagePatch); 01213 } 01214 01215 system("$(cp patch.tiff ~)"); 01216 int result; 01217 result = system("$(rospack find cob_tesseract)/bin/tesseract patch.tiff patch"); //OCR in patch 01218 cout << "result" << result << endl; 01219 assert(!result); 01220 ifstream fin("patch.txt"); 01221 string str; 01222 while (fin >> str) 01223 { 01224 cout << "in ocrRead:" << endl; 01225 cout << "[" << str << "]" << endl; 01226 string tempOutput; 01227 score += spellCheck(str, tempOutput, 2); 01228 output += tempOutput; 01229 } 01230 result = system("$(rm patch.txt patch.tiff)"); 01231 //waitKey(0); 01232 return score; 01233 } 01234 01235 // two option: 1 for aspell, 2 for correlation edit distance 01236 // return the score for the input 01237 float DetectText::spellCheck(string& str, string& output, int method) 01238 { // Example 01239 int letterCount = 0, errorCount = 0, lNoiseCount = 0, digitCount = 0; //str=Day, output=[], method=2 01240 string withoutStrangeMarks; 01241 float score = 0; 01242 str = trim(str); 01243 01244 cout << "in spellCheck" << endl; 01245 01246 for (size_t i = 0; i < str.length(); i++) 01247 { 01248 if (isupper(str[i]) || islower(str[i])) 01249 { 01250 withoutStrangeMarks += str[i]; // withoutStrangeMarks = Day; 01251 letterCount++; //letterCount=3 01252 if (str[i] == 'l' || str[i] == 'L' || str[i] == 'I') 01253 lNoiseCount++; 01254 } 01255 else if (isdigit(str[i])) 01256 { 01257 digitCount++; 01258 // withoutStrangeMarks += str[i]; 01259 } 01260 else if (str[i] == '|' || str[i] == '/' || str[i] == '\\') 01261 { 01262 if ((i && isdigit(str[i - 1])) || ((i < str.length() - 1) && isdigit(str[i + 1]))) // is there a digit following or before the actual letter? 01263 { 01264 withoutStrangeMarks += '1'; //change to an '1' 01265 str[i] = '1'; 01266 digitCount++; 01267 } 01268 else 01269 { 01270 withoutStrangeMarks += 'l'; //else think of the letter as a 'l' 01271 errorCount++; 01272 letterCount++; 01273 } 01274 } 01275 else if (str[i] == '[') 01276 { 01277 withoutStrangeMarks += 'L'; 01278 errorCount++; 01279 letterCount++; 01280 } 01281 else if (str[i] == ']') 01282 { 01283 withoutStrangeMarks += 'I'; 01284 errorCount++; 01285 letterCount++; 01286 } 01287 else 01288 { 01289 str[i] = ' '; 01290 } 01291 } 01292 01293 //Maybe here Rotation 180° in every if and else if (and not in else): 01294 01295 if (digitCount > 0 && letterCount == 0) 01296 { 01297 if (digitCount <= 5) 01298 output = str + " "; 01299 } 01300 else if (letterCount < 2) 01301 { 01302 if (result_ == FINE) 01303 output = str + " "; 01304 } 01305 else if ((errorCount + lNoiseCount) * 2 > letterCount) 01306 { 01307 // do nothing 01308 } 01309 else if (letterCount < static_cast<int> (str.length()) / 2) 01310 { 01311 // don't show up garbbige 01312 } 01313 else 01314 { 01315 if (method == 1) 01316 { 01317 const string command("echo " + withoutStrangeMarks + " | aspell -a >> output"); 01318 int r = system(command.c_str()); 01319 fstream fin("output"); 01320 string result; 01321 int count = 0; 01322 01323 while (fin >> result) 01324 { 01325 if (count) 01326 { 01327 count++; 01328 if (count >= 5) 01329 { 01330 output += result + " "; 01331 } 01332 if (count == 10) 01333 { 01334 if ((output)[output.length() - 2] == ',') 01335 ((output)[output.length() - 2] = ' '); 01336 break; 01337 } 01338 } 01339 if (result[0] == '&') 01340 { 01341 count++; 01342 output += "{"; 01343 } 01344 else if (result[0] == '*') 01345 { 01346 output += " " + str; 01347 break; 01348 } 01349 } 01350 if (count) 01351 output += "}"; 01352 r = system("rm output"); 01353 } 01354 01355 // dictionary search 01356 if (method == 2) 01357 { 01358 cout << "METHOD==2" << endl; 01359 vector<Word> topk; 01360 string nearestWord; 01361 getTopkWords(withoutStrangeMarks, 3, topk); 01362 if (result_ == COARSE) 01363 { 01364 string topWord = topk[0].word; 01365 output = topk[0].word + " "; 01366 01367 if (topWord.length() < 3) 01368 { 01369 if (topk[0].score == 0) 01370 score++; 01371 else 01372 output = ""; 01373 } 01374 else if (topWord.length() < 6) 01375 { 01376 if (topk[0].score * 5 <= topWord.length()) 01377 score++; 01378 else 01379 output = ""; 01380 } 01381 else 01382 { 01383 if (topk[0].score == 0) 01384 score = topWord.length() * 2; 01385 else if (topk[0].score <= topWord.length()) 01386 score = topWord.length(); 01387 } 01388 } 01389 else if (result_ == FINE) 01390 { 01391 if (topk[0].score == 0) 01392 { 01393 output = topk[0].word + " "; 01394 score += topk[0].word.length() * 2; 01395 } 01396 else 01397 { 01398 output = "{" + withoutStrangeMarks + "->"; 01399 // pick top 3 results 01400 for (int i = 0; i < 3; i++) 01401 { 01402 stringstream ss; 01403 ss << topk[i].score; 01404 string s = ss.str(); 01405 output = output + topk[i].word + ":" + s + " "; 01406 } 01407 output += "} "; 01408 } 01409 } 01410 } 01411 } 01412 01413 return score; 01414 } 01415 01416 Mat DetectText::filterPatch(const Mat& patch) 01417 { 01418 Mat result; 01419 Mat element = getStructuringElement(MORPH_ELLIPSE, Size(patch.cols / 3, patch.rows / 3)); 01420 morphologyEx(patch, result, MORPH_TOPHAT, element); 01421 return result; 01422 } 01423 01424 void DetectText::disposal() 01425 { 01426 delete[] isLetterComponects_; 01427 delete[] isGrouped_; 01428 delete[] componentsMeanIntensity_; 01429 delete[] componentsMedianStrokeWidth_; 01430 01431 componentsRoi_.clear(); 01432 innerComponents_.clear(); 01433 horizontalLetterGroups_.clear(); 01434 verticalLetterGroups_.clear(); 01435 horizontalChains_.clear(); 01436 verticalChains_.clear(); 01437 } 01438 01439 /********************* helper functions ***************************/ 01440 /*----------------------------------------- readLetterCorrelation - Correlation in correlation_ einlesen ----------------------------------*/ 01441 void DetectText::readLetterCorrelation(const char* file) 01442 { 01443 std::cout << std::endl; 01444 std::cout << "Correlation:" << file << std::endl; 01445 ifstream fin(file); 01446 correlation_ = Mat(62, 62, CV_32F, Scalar(0)); 01447 float number; 01448 for (int i = 0; i < 62; i++) 01449 for (int j = 0; j < 62; j++) 01450 { 01451 assert(fin >> number); 01452 correlation_.at<float> (i, j) = number; 01453 } 01454 } 01455 01456 /*----------------------------------------- readWordList - Directory in wordList_ einlesen -----------------------------------------------*/ 01457 void DetectText::readWordList(const char* filename) 01458 { 01459 ifstream fin(filename); 01460 string word; 01461 wordList_.clear(); 01462 while (fin >> word) 01463 { 01464 wordList_.push_back(word); 01465 } 01466 assert(wordList_.size()); 01467 cout << "read in " << wordList_.size() << " words from " << string(filename) << endl; 01468 } 01469 01470 string& DetectText::trim(string& str) 01471 { 01472 // Trim Both leading and trailing spaces 01473 01474 // Find the first character position after 01475 // excluding leading blank spaces 01476 size_t startpos = str.find_first_not_of(" \t"); 01477 // Find the first character position from reverse af 01478 size_t endpos = str.find_last_not_of(" \t"); 01479 // if all spaces or empty return an empty string 01480 if ((string::npos == startpos) || (string::npos == endpos)) 01481 str = ""; 01482 else 01483 str = str.substr(startpos, endpos - startpos + 1); 01484 return str; 01485 } 01486 01487 void DetectText::getNearestWord(const string& str, string& nearestWord) 01488 { 01489 cout << "start searching match for " << str << endl; 01490 float score, lowestScore = 100; 01491 int referenceScore; 01492 size_t index = 0; 01493 for (size_t i = 0; i < wordList_.size(); ++i) 01494 { 01495 cout << "matching...." << wordList_[i]; 01496 score = editDistanceFont(str, wordList_[i]); 01497 referenceScore = editDistance(str, wordList_[i]); 01498 cout << " " << score << " " << referenceScore << endl; 01499 if (score < lowestScore) 01500 { 01501 lowestScore = score; 01502 cout << "AHA! better!" << endl; 01503 index = i; 01504 } 01505 } 01506 nearestWord = wordList_[index]; 01507 cout << nearestWord << " got the lowest score: " << lowestScore << endl; 01508 } 01509 01510 void DetectText::getTopkWords(const string& str, const int k, vector<Word>& words) //k=3 01511 { 01512 float score, lowestScore = 100; 01513 words.clear(); 01514 words.resize(k); 01515 01516 cout << "in getTopkWords with [" << str << "]" << endl; 01517 01518 for (size_t i = 0; i < wordList_.size(); i++) 01519 { 01520 score = editDistanceFont(str, wordList_[i]); //compare every word in dictionary, score=0 -> perfect 01521 if (score < lowestScore) 01522 { 01523 Word w = Word(wordList_[i], score); 01524 lowestScore = insertToList(words, w); 01525 } 01526 } 01527 cout << "lowestScore:" << lowestScore << endl; 01528 } 01529 01530 // return lowest score in the list 01531 float DetectText::insertToList(vector<Word>& words, Word& word) // for example word = ("able",3.7) 01532 { 01533 // first search for the position 01534 size_t index = 0; 01535 01536 for (size_t i = 0; i < words.size(); i++) 01537 { 01538 index = i; 01539 if (word.score < words[i].score) //in case score of actual dictionaryword is smaller than any entry in words: break, remember index 01540 { 01541 break; 01542 } 01543 } 01544 if (index != words.size()) 01545 { 01546 for (size_t i = words.size() - 1; i > index; i--) 01547 { 01548 words[i] = words[i - 1]; 01549 } 01550 words[index] = word; 01551 } 01552 return words[words.size() - 1].score; // return last score, the smallest 01553 } 01554 01555 /*--------------------------------------------------------*\ 01556 * display functions 01557 \*--------------------------------------------------------*/ 01558 01559 void DetectText::showEdgeMap() 01560 { 01561 if (firstPass_) 01562 imwrite("edgemap.png", edgemap_); 01563 } 01564 01565 void DetectText::showCcmap(Mat& ccmap) 01566 { 01567 01568 Mat ccmapLetters = ccmap * (1.0 / static_cast<float> (nComponent_)); 01569 for (size_t i = 0; i < nComponent_; ++i) 01570 { 01571 Rect *itr = &componentsRoi_[i]; 01572 rectangle(ccmapLetters, Point(itr->x, itr->y), Point(itr->x + itr->width, itr->y + itr->height), Scalar(0.5)); 01573 } 01574 if (firstPass_) 01575 imwrite("ccmap1.jpg", ccmapLetters * nComponent_); 01576 else 01577 imwrite("ccmap2.jpg", ccmapLetters * nComponent_); 01578 } 01579 01580 void DetectText::showSwtmap(Mat& swtmap) 01581 { 01582 if (firstPass_) 01583 imwrite("swtmap1.jpg", swtmap * 10); 01584 else 01585 imwrite("swtmap2.jpg", swtmap * 10); 01586 } 01587 01588 void DetectText::showLetterDetection() 01589 { 01590 Mat output = originalImage_.clone(); 01591 Scalar scalar; 01592 if (firstPass_) 01593 scalar = Scalar(0, 255, 0); 01594 else 01595 scalar = Scalar(0, 0, 255); 01596 01597 for (size_t i = 0; i < nComponent_; ++i) 01598 { 01599 if (isLetterComponects_[i]) 01600 { 01601 Rect *itr = &componentsRoi_[i]; 01602 rectangle(output, Point(itr->x, itr->y), Point(itr->x + itr->width, itr->y + itr->height), scalar, 2); 01603 stringstream ss; 01604 string s; 01605 ss << i; 01606 s = ss.str() + ".tiff"; 01607 imwrite(s, originalImage_(*itr)); 01608 } 01609 } 01610 if (firstPass_) 01611 imwrite(outputPrefix_ + "_letters1.jpg", output); 01612 else 01613 imwrite(outputPrefix_ + "_letters2.jpg", output); 01614 } 01615 01616 void DetectText::showLetterGroup() 01617 { 01618 Mat output = originalImage_.clone(); 01619 Scalar scalar; 01620 if (firstPass_) 01621 scalar = Scalar(0, 255, 0); 01622 else 01623 scalar = Scalar(0, 0, 255); 01624 01625 for (size_t i = 0; i < nComponent_; ++i) 01626 { 01627 if (isGrouped_[i]) 01628 { 01629 Rect *itr = &componentsRoi_[i]; 01630 rectangle(output, Point(itr->x, itr->y), Point(itr->x + itr->width, itr->y + itr->height), scalar, 2); 01631 } 01632 } 01633 if (firstPass_) 01634 imwrite(outputPrefix_ + "_group1.jpg", output); 01635 else 01636 imwrite(outputPrefix_ + "_group2.jpg", output); 01637 } 01638 01639 void DetectText::showBoundingBoxes(vector<Rect>& boundingBoxes) 01640 { 01641 Scalar scalar(0, 0, 255); 01642 01643 for (size_t i = 0; i < boundingBoxes.size(); i++) 01644 { 01645 Rect *rect = &boundingBoxes[i]; 01646 rectangle(detection_, Point(rect->x, rect->y), Point(rect->x + rect->width, rect->y + rect->height), scalar, 3); 01647 } 01648 } 01649 01650 void DetectText::showBoundingBoxes(vector<Rect>& boundingBoxes, vector<bool>& boxInbox) 01651 { 01652 assert(boundingBoxes.size() == boxInbox.size()); 01653 Scalar scalar; 01654 scalar = Scalar(0, 0, 255); 01655 01656 for (size_t i = 0; i < boundingBoxes.size(); i++) 01657 { 01658 if (boxInbox[i] == true) 01659 continue; 01660 Rect *rect = &boundingBoxes[i]; 01661 rectangle(detection_, Point(rect->x, rect->y), Point(rect->x + rect->width, rect->y + rect->height), scalar, 3); 01662 } 01663 } 01664 01665 inline int DetectText::countInnerLetterCandidates(bool* array) 01666 { 01667 int count = 0; 01668 for (size_t i = 0; i < nComponent_; i++) 01669 { 01670 if (array[i] && isLetterComponects_[i]) 01671 { 01672 count++; 01673 } 01674 } 01675 return count; 01676 } 01677 01678 float DetectText::getMeanIntensity(const Mat& ccmap, const Rect& rect, int element) 01679 { 01680 assert(element >= 0); 01681 if (componentsMeanIntensity_[element] == 0) 01682 { 01683 float sum = 0; 01684 float count = 0; 01685 float felement = static_cast<float> (element); 01686 for (int y = rect.y; y < rect.y + rect.height; y++) 01687 for (int x = rect.x; x < rect.x + rect.width; x++) 01688 { 01689 if (ccmap.at<float> (y, x) == felement) 01690 { 01691 sum += static_cast<float> (image_.at<unsigned char> (y, x)); 01692 count = count + 1; 01693 } 01694 } 01695 componentsMeanIntensity_[element] = sum / count; 01696 } 01697 return componentsMeanIntensity_[element]; 01698 } 01699 01700 float DetectText::getMedianStrokeWidth(const Mat& ccmap, const Mat& swtmap, const Rect& rect, int element) 01701 { 01702 01703 assert(element >= 0); 01704 assert(isLetterComponects_[element]); 01705 if (componentsMedianStrokeWidth_[element] == 0) 01706 { 01707 vector<float> SwtValues; 01708 01709 float felement = static_cast<float> (element); 01710 for (int y = rect.y; y < rect.y + rect.height; y++) 01711 for (int x = rect.x; x < rect.x + rect.width; x++) 01712 { 01713 if (ccmap.at<float> (y, x) == felement) 01714 { 01715 SwtValues.push_back(swtmap.at<float> (y, x)); 01716 } 01717 } 01718 01719 nth_element(SwtValues.begin(), SwtValues.begin() + SwtValues.size() / 2, SwtValues.end()); 01720 01721 componentsMedianStrokeWidth_[element] = SwtValues[SwtValues.size() / 2]; 01722 01723 } 01724 return componentsMedianStrokeWidth_[element]; 01725 } 01726 01727 void DetectText::mergePairs(const vector<Pair>& groups, vector<vector<int> >& chains) 01728 { 01729 /* groups looks like this: 01730 * 4 5 01731 * 12 14 01732 * 44 45 01733 * ... 01734 */ 01735 vector<vector<int> > initialChains; 01736 initialChains.resize(groups.size()); 01737 for (size_t i = 0; i < groups.size(); i++) 01738 { 01739 vector<int> temp; 01740 temp.push_back(groups[i].left); 01741 temp.push_back(groups[i].right); 01742 initialChains[i] = temp; 01743 } 01744 01745 /* initialChains looks like this: 01746 * [0] [1] [2] 01747 * 4 12 44 ... 01748 * 5 14 45 01749 */ 01750 01751 while (mergePairs(initialChains, chains)) 01752 { 01753 initialChains = chains; 01754 chains.clear(); 01755 } 01756 } 01757 01758 bool DetectText::mergePairs(const vector<vector<int> >& initialChains, vector<vector<int> >& chains) 01759 { 01760 if (chains.size()) 01761 chains.clear(); 01762 01763 bool merged = false; 01764 int *mergedToChainBitMap = new int[initialChains.size()]; 01765 memset(mergedToChainBitMap, -1, initialChains.size() * sizeof(int)); 01766 01767 for (size_t i = 0; i < initialChains.size(); i++) 01768 { 01769 if (mergedToChainBitMap[i] != -1) 01770 continue; 01771 01772 for (size_t j = i + 1; j < initialChains.size(); j++) 01773 { 01774 // match elements in chain i,j 01775 for (size_t ki = 0; ki < initialChains[i].size(); ki++) 01776 { 01777 for (size_t kj = 0; kj < initialChains[j].size(); kj++) 01778 { 01779 // found match 01780 if (initialChains[i][ki] == initialChains[j][kj]) // Does any other initialChains[x] contain a identical componect? 01781 { 01782 merged = true; 01783 // j already merged with others 01784 if (mergedToChainBitMap[j] != -1) 01785 { 01786 merge(initialChains[i], chains[mergedToChainBitMap[j]]); 01787 01788 mergedToChainBitMap[i] = mergedToChainBitMap[j]; 01789 } 01790 else // start a new chain 01791 { 01792 vector<int> newChain; 01793 merge(initialChains[i], newChain); 01794 merge(initialChains[j], newChain); 01795 chains.push_back(newChain); 01796 mergedToChainBitMap[i] = chains.size() - 1; 01797 mergedToChainBitMap[j] = chains.size() - 1; 01798 } 01799 break; 01800 } 01801 } 01802 if (mergedToChainBitMap[i] != -1 && mergedToChainBitMap[j] != -1) 01803 break; 01804 } 01805 } 01806 01807 // comparing with all other chains, not found a match 01808 if (mergedToChainBitMap[i] == -1) 01809 { 01810 chains.push_back(initialChains[i]); 01811 mergedToChainBitMap[i] = chains.size() - 1; 01812 } 01813 01814 } 01815 01816 if (!merged) 01817 { 01818 chains = initialChains; 01819 } 01820 // dispose resourse 01821 delete[] mergedToChainBitMap; 01822 return merged; 01823 } 01824 01825 void DetectText::merge(const vector<int>& token, vector<int>& chain) 01826 { 01827 vector<int>::iterator it; 01828 for (size_t i = 0; i < token.size(); i++) 01829 { 01830 it = find(chain.begin(), chain.end(), token[i]); 01831 if (it == chain.end()) 01832 { 01833 chain.push_back(token[i]); 01834 } 01835 } 01836 } 01837 01838 // use correlation as indicator of distance 01839 float DetectText::editDistanceFont(const string& s, const string& t) //s =word, t = dictionary compare word 01840 { 01841 float penalty = 0.7; 01842 int n = s.length(); 01843 int m = t.length(); 01844 01845 if (n == 0) 01846 return m; 01847 if (m == 0) 01848 return n; 01849 01850 float **d = new float*[n + 1]; // float d [][str_laenge+1] = float[4][] 01851 for (int i = 0; i < n + 1; i++) // 4mal 01852 { 01853 d[i] = new float[m + 1]; 01854 memset(d[i], 0, (m + 1) * sizeof(float)); // float d[4][5] 01855 } 01856 01857 for (int i = 0; i < n + 1; i++) 01858 d[i][0] = i; 01859 /*d[0][0] = 0; 01860 d[1][0] = 1; 01861 d[2][0] = 2; 01862 d[3][0] = 3;*/ 01863 for (int j = 0; j < m + 1; j++) 01864 d[0][j] = j; 01865 /*d[0][0] = 0; 01866 d[0][1] = 1; 01867 d[0][2] = 2; 01868 d[0][3] = 3; 01869 d[0][4] = 4;*/ 01870 01871 /* d: 01872 * 0 1 2 3 01873 * 1 0 0 0 01874 * 2 0 0 0 01875 * 3 0 0 0 01876 * 4 0 0 0 01877 */ 01878 01879 for (int i = 1; i < n + 1; i++) 01880 { 01881 char sc = s[i - 1]; // sc = 'D'; 01882 for (int j = 1; j < m + 1; j++) 01883 { 01884 float v = d[i - 1][j - 1]; //v=d[0][0]=0; -> v=d[0][1]=1; 01885 if ((t[j - 1] != sc)) // // t[0]='a' != 'D' -> t[1]='b' != 'D'; 01886 { 01887 // correlate = correlation_.at[0,29] = 0.21212; -> correlate=correlation_at[1,29] = 0.31865 01889 int a = getCorrelationIndex(t[j - 1]); 01890 int b = getCorrelationIndex(sc); 01891 if (a < 0) 01892 { 01893 cout << "Wort:" << t << endl; 01894 } 01895 float correlate = correlation_.at<float> (a, b); 01896 v = v + 1 - correlate; // v=0+1-0.2121=0.78 -> v = 0.78 + 1 - 0.3128 = 1.47 01897 } 01898 d[i][j] = min(min(d[i - 1][j] + penalty, d[i][j - 1] + penalty), v); //d[0][0]=min( min([0][1]+0.7, d[1][0]+0.7), v); -> d[0][2]=min(min[0][2]+0.7,[1][1]+0.7 01899 } //d[0][0]=min( min(1.7, 1.7), 0.78) = 0.78 01900 } 01901 float result = d[n][m]; 01902 for (int i = 0; i < n + 1; i++) 01903 delete[] d[i]; 01904 delete[] d; 01905 return result; 01906 } 01907 01908 // get index in correlation matrix for given char 01909 int DetectText::getCorrelationIndex(char letter) 01910 { 01911 if (islower(letter)) 01912 { 01913 return letter - 'a'; 01914 } 01915 else if (isupper(letter)) 01916 { 01917 return letter - 'A' + 26; 01918 } 01919 else if (isdigit(letter)) 01920 { 01921 return letter - '0' + 52; 01922 } 01923 cout << "illigal letter: " << letter << endl; 01924 // assert(false); 01925 return -1; 01926 } 01927 01928 // regular editDistance 01929 int DetectText::editDistance(const string& s, const string& t) 01930 { 01931 int n = s.length(); 01932 int m = t.length(); 01933 01934 if (n == 0) 01935 return m; 01936 if (m == 0) 01937 return n; 01938 01939 int **d = new int*[n + 1]; 01940 for (int i = 0; i < n + 1; i++) 01941 { 01942 d[i] = new int[m + 1]; 01943 memset(d[i], 0, (m + 1) * sizeof(int)); 01944 } 01945 01946 for (int i = 0; i < n + 1; i++) 01947 d[i][0] = i; 01948 for (int j = 0; j < m + 1; j++) 01949 d[0][j] = j; 01950 01951 for (int i = 1; i < n + 1; i++) 01952 { 01953 char sc = s[i - 1]; 01954 for (int j = 1; j < m + 1; j++) 01955 { 01956 int v = d[i - 1][j - 1]; 01957 if (t[j - 1] != sc) 01958 v++; 01959 d[i][j] = min(min(d[i - 1][j] + 1, d[i][j - 1] + 1), v); 01960 } 01961 } 01962 return d[n][m]; 01963 } 01964 01965 /*------------- test functions-------------------*/ 01966 void DetectText::testGetCorrelationIndex() 01967 { 01968 assert(getCorrelationIndex('a') == 0); 01969 assert(getCorrelationIndex('c') == 2); 01970 assert(getCorrelationIndex('A') == 26); 01971 assert(getCorrelationIndex('0') == 52); 01972 assert(getCorrelationIndex('9') == 61); 01973 cout << "pass getCorrelationIndex test" << endl; 01974 } 01975 01976 void DetectText::testEditDistance() 01977 { 01978 string a("hello"); 01979 string b("helo"); 01980 assert(editDistance(a,b)==1); 01981 string c("hello"); 01982 string d("xello"); 01983 cout << "distance betweeen " << c << " & " << d << ": " << editDistance(c, d) << endl; 01984 cout << "distance with font betweeen " << c << " & " << d << ":" << editDistanceFont(c, d) << endl; 01985 } 01986 01987 void DetectText::testInsertToList() 01988 { 01989 vector<Word> list; 01990 list.resize(10); 01991 01992 for (int i = 0; i < 10; i++) 01993 { 01994 float score = rand() % 50; 01995 Word w = Word("", score); 01996 insertToList(list, w); 01997 for (size_t i = 0; i < 10; i++) 01998 { 01999 cout << list[i].score << " <= "; 02000 } 02001 cout << endl; 02002 } 02003 02004 } 02005 void DetectText::testMergePairs() 02006 { 02007 int a[] = {1, 2, 3}; 02008 int b[] = {2, 3, 9}; 02009 int c[] = {7, 5}; 02010 int d[] = {2, 4, 6}; 02011 02012 vector<vector<int> > initialChain; 02013 vector<vector<int> > outputChain; 02014 vector<int> va(a, a + 3); 02015 vector<int> vb(b, b + 3); 02016 vector<int> vc(c, c + 2); 02017 vector<int> vd(d, d + 3); 02018 initialChain.push_back(va); 02019 initialChain.push_back(vb); 02020 initialChain.push_back(vc); 02021 initialChain.push_back(vd); 02022 02023 while (mergePairs(initialChain, outputChain)) 02024 { 02025 initialChain = outputChain; 02026 outputChain.clear(); 02027 } 02028 02029 for (size_t i = 0; i < outputChain.size(); i++) 02030 { 02031 for (size_t j = 0; j < outputChain[i].size(); j++) 02032 { 02033 cout << outputChain[i][j] << " "; 02034 } 02035 cout << endl; 02036 } 02037 02038 } 02039 02040 void DetectText::testEdgePoints(vector<Point>& edgepoints) 02041 { 02042 Mat temp(edgemap_.size(), CV_8UC1); 02043 vector<Point>::iterator itr = edgepoints.begin(); 02044 for (; itr != edgepoints.end(); ++itr) 02045 { 02046 temp.at<unsigned char> (*itr) = 255; 02047 } 02048 02049 imshow("test edge", temp); 02050 waitKey(); 02051 }