$search
00001 00005 #include "features.hpp" 00006 00007 /* 00008 draws keypoints to scale with coloring proportional to feature strength 00009 */ 00010 void drawRichKeypoints(const cv::Mat& src, std::vector<cv::KeyPoint>& kpts, cv::Mat& dst) { 00011 00012 cv::Mat grayFrame; 00013 cvtColor(src, grayFrame, CV_RGB2GRAY); 00014 00015 dst = Mat::zeros(src.size(), src.type()); 00016 00017 00018 if (kpts.size() == 0) { 00019 return; 00020 } 00021 00022 std::vector<cv::KeyPoint> kpts_cpy, kpts_sorted; 00023 00024 kpts_cpy.insert(kpts_cpy.end(), kpts.begin(), kpts.end()); 00025 00026 double maxResponse = kpts_cpy.at(0).response; 00027 double minResponse = kpts_cpy.at(0).response; 00028 00029 while (kpts_cpy.size() > 0) { 00030 00031 double maxR = 0.0; 00032 unsigned int idx = 0; 00033 00034 for (unsigned int iii = 0; iii < kpts_cpy.size(); iii++) { 00035 00036 if (kpts_cpy.at(iii).response > maxR) { 00037 maxR = kpts_cpy.at(iii).response; 00038 idx = iii; 00039 } 00040 00041 if (kpts_cpy.at(iii).response > maxResponse) { 00042 maxResponse = kpts_cpy.at(iii).response; 00043 } 00044 00045 if (kpts_cpy.at(iii).response < minResponse) { 00046 minResponse = kpts_cpy.at(iii).response; 00047 } 00048 } 00049 00050 kpts_sorted.push_back(kpts_cpy.at(idx)); 00051 kpts_cpy.erase(kpts_cpy.begin() + idx); 00052 00053 } 00054 00055 int thickness = 1; 00056 cv::Point center; 00057 cv::Scalar colour; 00058 int red = 0, blue = 0, green = 0; 00059 int radius; 00060 double normalizedScore; 00061 00062 if (minResponse == maxResponse) { 00063 colour = CV_RGB(255, 0, 0); 00064 } 00065 00066 for (int iii = kpts_sorted.size()-1; iii >= 0; iii--) { 00067 00068 if (minResponse != maxResponse) { 00069 normalizedScore = pow((kpts_sorted.at(iii).response - minResponse) / (maxResponse - minResponse), 0.25); 00070 red = int(255.0 * normalizedScore); 00071 green = int(255.0 - 255.0 * normalizedScore); 00072 colour = CV_RGB(red, green, blue); 00073 } 00074 00075 center = kpts_sorted.at(iii).pt; 00076 center.x *= 16.0; 00077 center.y *= 16.0; 00078 00079 radius = 16.0 * (double(kpts_sorted.at(iii).size)/2.0); 00080 00081 if (radius > 0) { 00082 circle(dst, center, radius, colour, -1, CV_AA, 4); 00083 } 00084 00085 } 00086 00087 fadeImage(src, dst); 00088 //cvtColor(grayFrame, dst, CV_GRAY2RGB); 00089 00090 for (int iii = kpts_sorted.size()-1; iii >= 0; iii--) { 00091 00092 if (minResponse != maxResponse) { 00093 normalizedScore = pow((kpts_sorted.at(iii).response - minResponse) / (maxResponse - minResponse), 0.25); 00094 red = int(255.0 * normalizedScore); 00095 green = int(255.0 - 255.0 * normalizedScore); 00096 colour = CV_RGB(red, green, blue); 00097 } 00098 00099 center = kpts_sorted.at(iii).pt; 00100 center.x *= 16.0; 00101 center.y *= 16.0; 00102 00103 radius = 16.0 * (double(kpts_sorted.at(iii).size)/2.0); 00104 00105 if (radius > 0) { 00106 circle(dst, center, radius, colour, thickness, CV_AA, 4); 00107 } 00108 00109 } 00110 00111 00112 00113 } 00114 00115 void fadeImage(const Mat& src, Mat& dst) { 00116 00117 double frac = 0.65; 00118 00119 #pragma omp parallel for 00120 for (unsigned int iii = 0; iii < src.rows; iii++) { 00121 for (unsigned int jjj = 0; jjj < src.cols; jjj++) { 00122 00123 if ((src.at<Vec3b>(iii,jjj)[0] != 0) && (src.at<Vec3b>(iii,jjj)[1] != 0) && (src.at<Vec3b>(iii,jjj)[2] != 0)) { 00124 for (unsigned int kkk = 0; kkk < 3; kkk++) { 00125 00126 // check val first 00127 dst.at<Vec3b>(iii,jjj)[0] = (unsigned char) ((1-frac) * double(src.at<Vec3b>(iii,jjj)[0]) + frac * double(dst.at<Vec3b>(iii,jjj)[0])) / 1.0; 00128 dst.at<Vec3b>(iii,jjj)[1] = (unsigned char) ((1-frac) * double(src.at<Vec3b>(iii,jjj)[1]) + frac * double(dst.at<Vec3b>(iii,jjj)[1])) / 1.0; 00129 dst.at<Vec3b>(iii,jjj)[2] = (unsigned char) ((1-frac) * double(src.at<Vec3b>(iii,jjj)[2]) + frac * double(dst.at<Vec3b>(iii,jjj)[2])) / 1.0; 00130 00131 } 00132 } else { 00133 dst.at<Vec3b>(iii,jjj)[0] = src.at<Vec3b>(iii,jjj)[0]; 00134 dst.at<Vec3b>(iii,jjj)[1] = src.at<Vec3b>(iii,jjj)[1]; 00135 dst.at<Vec3b>(iii,jjj)[2] = src.at<Vec3b>(iii,jjj)[2]; 00136 } 00137 00138 00139 } 00140 } 00141 00142 00143 } 00144 00145 /* 00146 Removes surplus features and those with invalid size 00147 */ 00148 void filterKeypoints(std::vector<cv::KeyPoint>& kpts, int maxSize, int maxFeatures) { 00149 00150 if (maxSize == 0) { 00151 return; 00152 } 00153 00154 sortKeypoints(kpts); 00155 00156 for (unsigned int iii = 0; iii < kpts.size(); iii++) { 00157 00158 if (kpts.at(iii).size > float(maxSize)) { 00159 kpts.erase(kpts.begin() + iii); 00160 iii--; 00161 } 00162 } 00163 00164 if ((maxFeatures != 0) && (kpts.size() > maxFeatures)) { 00165 kpts.erase(kpts.begin()+maxFeatures, kpts.end()); 00166 } 00167 00168 } 00169 00170 void showMatches(const Mat& pim1, vector<Point2f>& pts1, const Mat& pim2, vector<Point2f>& pts2, Mat& drawImg) { 00171 00172 drawImg = Mat::zeros(pim1.rows, pim1.cols + pim2.cols, CV_8UC3); 00173 00174 #pragma omp parallel for 00175 for (int iii = 0; iii < pim1.rows; iii++) { 00176 for (int jjj = 0; jjj < pim1.cols; jjj++) { 00177 00178 drawImg.at<Vec3b>(iii,jjj)[0] = pim1.at<unsigned char>(iii,jjj); 00179 drawImg.at<Vec3b>(iii,jjj)[1] = pim1.at<unsigned char>(iii,jjj); 00180 drawImg.at<Vec3b>(iii,jjj)[2] = pim1.at<unsigned char>(iii,jjj); 00181 00182 drawImg.at<Vec3b>(iii,640+jjj)[0] = pim2.at<unsigned char>(iii,jjj); 00183 drawImg.at<Vec3b>(iii,640+jjj)[1] = pim2.at<unsigned char>(iii,jjj); 00184 drawImg.at<Vec3b>(iii,640+jjj)[2] = pim2.at<unsigned char>(iii,jjj); 00185 } 00186 } 00187 00188 Point pt1, pt2; 00189 int radius = 4; 00190 int thickness = 1; 00191 00192 radius *= 16.0; 00193 for (unsigned int iii = 0; iii < pts1.size(); iii++) { 00194 00195 pt1.x = 16.0 * pts1.at(iii).x; 00196 pt1.y = 16.0 * pts1.at(iii).y; 00197 00198 pt2.x = 16.0 * (pts2.at(iii).x + 640.0); 00199 pt2.y = 16.0 * pts2.at(iii).y; 00200 00201 circle(drawImg, pt1, radius, CV_RGB(255, 0, 0), thickness, CV_AA, 4); 00202 circle(drawImg, pt2, radius, CV_RGB(255, 0, 0), thickness, CV_AA, 4); 00203 line(drawImg, pt1, pt2, CV_RGB(0, 0, 255), thickness, CV_AA, 4); 00204 } 00205 00206 } 00207 00208 void crossCheckMatching( Ptr<DescriptorMatcher>& descriptorMatcher, 00209 const Mat& descriptors1, const Mat& descriptors2, 00210 vector<DMatch>& filteredMatches12, int knn ) 00211 { 00212 00213 //printf("%s << ENTERED.\n", __FUNCTION__); 00214 00215 filteredMatches12.clear(); 00216 00217 //printf("%s << DEBUG %d.\n", __FUNCTION__, 0); 00218 //vector<vector<DMatch> > matches12, matches21; 00219 vector<vector<DMatch> > matches12, matches21; 00220 00221 00222 //printf("%s << DEBUG %d.\n", __FUNCTION__, 1); 00223 00224 //printf("%s << descriptors1.size() = (%d, %d).\n", __FUNCTION__, descriptors1.rows, descriptors1.cols); 00225 //printf("%s << descriptors2.size() = (%d, %d).\n", __FUNCTION__, descriptors2.rows, descriptors2.cols); 00226 00227 00228 00229 descriptorMatcher->knnMatch( descriptors1, descriptors2, matches12, knn ); 00230 00231 00232 //printf("%s << DEBUG %d.\n", __FUNCTION__, 2); 00233 descriptorMatcher->knnMatch( descriptors2, descriptors1, matches21, knn ); 00234 00235 //printf("%s << matches12.size() = %d.\n", __FUNCTION__, matches12.size()); 00236 00237 for( size_t m = 0; m < matches12.size(); m++ ) 00238 { 00239 bool findCrossCheck = false; 00240 00241 //printf("%s << matches12[%d].size() = %d.\n", __FUNCTION__, m, matches12[m].size()); 00242 00243 for( size_t fk = 0; fk < matches12[m].size(); fk++ ) 00244 { 00245 DMatch forward = matches12[m][fk]; 00246 00247 //printf("%s << matches21[%d].size() = %d.\n", __FUNCTION__, forward.trainIdx, matches21[forward.trainIdx].size()); 00248 00249 for( size_t bk = 0; bk < matches21[forward.trainIdx].size(); bk++ ) 00250 { 00251 DMatch backward = matches21[forward.trainIdx][bk]; 00252 if( backward.trainIdx == forward.queryIdx ) 00253 { 00254 filteredMatches12.push_back(forward); 00255 findCrossCheck = true; 00256 break; 00257 } 00258 } 00259 if( findCrossCheck ) break; 00260 } 00261 } 00262 00263 } 00264 00265 void filterTrackingsByRadialProportion(vector<Point2f>& pts1, vector<Point2f>& pts2, Mat& K, Mat& newCamMat, Mat& distCoeffs, Size& imSize, double prop) { 00266 //cout << "filterTrackingsByRadialProportion: " << imSize.width << " " << imSize.height << endl; 00267 00268 vector<Point2f> newPts; 00269 redistortPoints(pts2, newPts, K, distCoeffs, newCamMat); 00270 00271 Point2f centrePt = Point2f(double(imSize.width)/2.0,double(imSize.height)/2.0); 00272 double maxDist = prop * double(imSize.width)/2.0; 00273 00274 double dist; 00275 00276 unsigned int iii = 0; 00277 00278 while (iii < pts1.size()) { 00279 00280 dist = distBetweenPts2f(pts2.at(iii), centrePt); 00281 00282 if (dist > maxDist) { 00283 00284 pts1.erase(pts1.begin() + iii); 00285 pts2.erase(pts2.begin() + iii); 00286 00287 } else { 00288 iii++; 00289 } 00290 00291 } 00292 00293 00294 } 00295 00296 void reduceEdgyFeatures(vector<KeyPoint>& keypoints, cameraParameters& camData) { 00297 00298 vector<Point2f> candidates; 00299 00300 KeyPoint::convert(keypoints, candidates); 00301 00302 vector<Point2f> redistortedPoints; 00303 float minBorderDist = 2.0; 00304 00305 redistortPoints(candidates, redistortedPoints, camData.Kx, camData.distCoeffs, camData.expandedCamMat); 00306 00307 for (int iii = candidates.size()-1; iii >= 0; iii--) { 00308 00309 float xDist = min(abs(((float) camData.expandedSize.width) - redistortedPoints.at(iii).x), abs(redistortedPoints.at(iii).x)); 00310 float yDist = min(abs(((float) camData.expandedSize.height) - redistortedPoints.at(iii).y), abs(redistortedPoints.at(iii).y)); 00311 float dist = min(xDist, yDist) - keypoints.at(iii).size; 00312 00313 if (dist < minBorderDist) { 00314 keypoints.erase(keypoints.begin() + iii); 00315 } 00316 00317 } 00318 00319 } 00320 00321 void reduceEdgyCandidates(vector<Point2f>& candidates, cameraParameters& camData) { 00322 00323 vector<Point2f> redistortedPoints; 00324 float minBorderDist = 2.0; 00325 00326 redistortPoints(candidates, redistortedPoints, camData.Kx, camData.distCoeffs, camData.expandedCamMat); 00327 00328 for (int iii = candidates.size()-1; iii >= 0; iii--) { 00329 00330 float xDist = min(abs(((float) camData.expandedSize.width) - redistortedPoints.at(iii).x), abs(redistortedPoints.at(iii).x)); 00331 float yDist = min(abs(((float) camData.expandedSize.height) - redistortedPoints.at(iii).y), abs(redistortedPoints.at(iii).y)); 00332 float dist = min(xDist, yDist); 00333 if (dist < minBorderDist) { 00334 candidates.erase(candidates.begin() + iii); 00335 } 00336 00337 } 00338 00339 } 00340 00341 bool checkRoomForFeature(vector<Point2f>& pts, Point2f& candidate, double dist) { 00342 00343 double distance; 00344 00345 for (unsigned int iii = 0; iii < pts.size(); iii++) { 00346 00347 distance = distanceBetweenPoints(pts.at(iii), candidate); 00348 00349 if (distance < dist) { 00350 return false; 00351 } 00352 00353 } 00354 00355 return true; 00356 00357 } 00358 00359 void reduceUnrefinedCandidates(vector<Point2f>& candidates) { 00360 00361 if (candidates.size() == 0) { 00362 return; 00363 } 00364 00365 for (int iii = candidates.size()-1; iii >= 0; iii--) { 00366 00367 if (((candidates.at(iii).x - floor(candidates.at(iii).x)) == 0.0) && ((candidates.at(iii).y - floor(candidates.at(iii).y)) == 0.0)) { 00368 printf("%s << erasing: (%f, %f)\n", __FUNCTION__, candidates.at(iii).x, candidates.at(iii).y); 00369 candidates.erase(candidates.begin() + iii); 00370 } 00371 } 00372 00373 } 00374 00375 void reduceProximalCandidates(vector<Point2f>& existing, vector<Point2f>& candidates) { 00376 00377 for (unsigned int iii = 0; iii < candidates.size(); iii++) { 00378 00379 bool isValid = checkRoomForFeature(existing, candidates.at(iii), 3.0); 00380 00381 if (!isValid) { 00382 candidates.erase(candidates.begin() + iii); 00383 iii--; 00384 } 00385 00386 } 00387 00388 } 00389 00390 void concatenateWithExistingPoints(vector<Point2f>& pts, vector<Point2f>& kps, int size, double min_sep) { 00391 00392 //printf("%s << 00393 00394 size = std::min(size, ((int) pts.size()) + ((int) kps.size())); 00395 00396 // printf("%s << ready...\n", __FUNCTION__); 00397 00398 for (unsigned int iii = 0; iii < kps.size(); iii++) { 00399 00400 if (int(pts.size()) >= size) { 00401 continue; 00402 } 00403 00404 bool isValid = checkRoomForFeature(pts, kps.at(iii), min_sep); 00405 00406 if (isValid) { 00407 pts.push_back(kps.at(iii)); 00408 } 00409 00410 } 00411 00412 } 00413 00414 void initializeDrawingColors(Scalar* kColors, Scalar* tColors, int num) { 00415 00416 for (int iii = 0; iii < num; iii++) { 00417 switch (iii) { 00418 case 0: 00419 tColors[iii] = CV_RGB(255, 128, 128); 00420 kColors[iii] = CV_RGB(255, 0, 0); 00421 break; 00422 case 1: 00423 tColors[iii] = CV_RGB(128, 128, 255); 00424 kColors[iii] = CV_RGB(0, 0, 255); 00425 break; 00426 case 2: 00427 tColors[iii] = CV_RGB(128, 255, 128); 00428 kColors[iii] = CV_RGB(0, 255, 0); 00429 break; 00430 case 3: 00431 tColors[iii] = CV_RGB(128, 255, 255); 00432 kColors[iii] = CV_RGB(0, 255, 255); 00433 break; 00434 case 4: 00435 tColors[iii] = CV_RGB(128, 128, 255); 00436 kColors[iii] = CV_RGB(255, 0, 255); 00437 break; 00438 case 5: 00439 tColors[iii] = CV_RGB(255, 255, 128); 00440 kColors[iii] = CV_RGB(255, 255, 0); 00441 break; 00442 default: 00443 tColors[iii] = CV_RGB(128, 128, 255); 00444 kColors[iii] = CV_RGB(255, 255, 255); 00445 break; 00446 00447 } 00448 } 00449 00450 } 00451 00452 void transformPoints(vector<Point2f>& pts1, Mat& H) { 00453 Mat ptCol(3, 1, CV_64FC1), newPos(3, 1, CV_64FC1); 00454 00455 //vector<Point2f> tempPoints; 00456 //tempPoints.insert(tempPoints.end(), finishingPoints[kkk].begin(), finishingPoints[kkk].end()); 00457 00458 for (unsigned int mmm = 0; mmm < pts1.size(); mmm++) { 00459 00460 ptCol.at<double>(0,0) = pts1.at(mmm).x; 00461 ptCol.at<double>(1,0) = pts1.at(mmm).y; 00462 ptCol.at<double>(2,0) = 1.0; 00463 00464 newPos = H * ptCol; 00465 00466 //printf("%s::%s << Changing point [%d][%d] from (%f, %f) to (%f, %f)\n", __PROGRAM__, __FUNCTION__, kkk, mmm, finishingPoints[kkk].at(mmm).x, finishingPoints[kkk].at(mmm).y, newPos.at<double>(0,0), newPos.at<double>(1,0)); 00467 00468 pts1.at(mmm).x = ((float) newPos.at<double>(0,0) / newPos.at<double>(2,0)); 00469 pts1.at(mmm).y = ((float) newPos.at<double>(1,0) / newPos.at<double>(2,0)); 00470 00471 } 00472 } 00473 00474 void reduceWeakFeatures(Mat& im, vector<KeyPoint>& feats, double minResponse) { 00475 00476 // assignMinimumRadii(feats); 00477 00478 vector<float> responseLevels; 00479 00480 for (unsigned int iii = 0; iii < feats.size(); iii++) { 00481 00482 if (feats.at(iii).response == 0.0) { 00483 feats.at(iii).response = estimateSalience(im, feats.at(iii).pt, ((double) feats.at(iii).size / 2.0)); 00484 responseLevels.push_back(feats.at(iii).response); 00485 } 00486 00487 //printf("%s << (%d) (%f, %f, %d)\n", __FUNCTION__, iii, feats.at(iii).size, feats.at(iii).response, feats.at(iii).octave); 00488 00489 } 00490 00491 sort(responseLevels.begin(), responseLevels.end()); 00492 00493 //printf("%s << minResponse = %f; maxResponse = %f; medianResponse = %f\n", __FUNCTION__, responseLevels.at(0), responseLevels.at(responseLevels.size()-1), responseLevels.at(responseLevels.size()/2)); 00494 00495 //cin.get(); 00496 00497 for (int iii = feats.size()-1; iii >= 0; iii--) { 00498 00499 // responseLevels.at(responseLevels.size()-5) 00500 if (feats.at(iii).response < minResponse) { // 80.0 00501 feats.erase(feats.begin() + iii); 00502 } 00503 00504 00505 } 00506 00507 } 00508 00509 void trackPoints(const Mat& im1, const Mat& im2, vector<Point2f>& pts1, vector<Point2f>& pts2, int distanceConstraint, double thresh, vector<unsigned int>& lostIndices, Mat H12, cameraParameters camData) { 00510 00511 //struct timeval test_timer; 00512 //double testTime; 00513 00514 bool debugFlag = false; 00515 00516 if (debugFlag) { 00517 printf("%s << ENTERED!\n", __FUNCTION__); 00518 } 00519 00520 //testTime = timeElapsedMS(test_timer, true); 00521 //printf("%s << ENTERED.\n", __FUNCTION__); 00522 00523 if (pts1.size() == 0) { 00524 return; 00525 } 00526 00527 if ((distanceConstraint % 2) == 0) { 00528 distanceConstraint++; 00529 } 00530 00531 //testTime = timeElapsedMS(test_timer, false); 00532 //printf("XDebug 0a: (%f)\n", testTime); 00533 00534 Size winSize = Size(distanceConstraint, distanceConstraint); 00535 int maxLevel = 3; 00536 TermCriteria criteria = TermCriteria( TermCriteria::COUNT+TermCriteria::EPS, 30, 0.01); 00537 double derivLambda = 0.5; 00538 int opticalFlowFlags; 00539 00540 bool guiding = false; 00541 00542 Mat im1b; 00543 vector<Point2f> pts1b; 00544 00545 vector<uchar> statusVec; 00546 vector<float> err; 00547 00548 Mat mask, blank; 00549 blank = Mat::ones(im1.size(), CV_8UC1); 00550 blank *= 255; 00551 00552 //testTime = timeElapsedMS(test_timer, false); 00553 //printf("XDebug 0b: (%f)\n", testTime); 00554 00555 //printf("%s << DEBUG A\n", __FUNCTION__); 00556 00557 /* 00558 double orig_vals[4], new_vals[4]; 00559 findIntensityValues(orig_vals, im1, blank); 00560 // findIntensityValues(orig_vals, im1b, mask); 00561 findIntensityValues(new_vals, im2, blank); 00562 */ 00563 00564 //testTime = timeElapsedMS(test_timer, false); 00565 //printf("XDebug 0c: (%f)\n", testTime); 00566 00567 //printf("%s << Vals (%f, %f, %f) vs (%f, %f, %f)\n", __FUNCTION__, orig_vals[0], orig_vals[1], orig_vals[2], new_vals[0], new_vals[1], new_vals[2]); 00568 00569 vector<Point2f> originalPts; 00570 originalPts.insert(originalPts.end(), pts1.begin(), pts1.end()); 00571 00572 //testTime = timeElapsedMS(test_timer, false); 00573 //printf("XDebug 1: (%f)\n", testTime); 00574 00575 if ((H12.rows != 0) && (pts2.size() == pts1.size())) { 00576 00577 // More aggressive shift for NUC handling 00578 /* 00579 double scale_shift = (new_vals[1] - new_vals[0]) / (orig_vals[1] - orig_vals[0]); 00580 double vert_shift = new_vals[0] - orig_vals[0]; 00581 double down_shift = orig_vals[0]; 00582 */ 00583 00584 guiding = true; 00585 //printf("%s << Using initial guesses... (distanceConstraint = %d)\n", __FUNCTION__, distanceConstraint); 00586 opticalFlowFlags = OPTFLOW_USE_INITIAL_FLOW; 00587 00588 pts1b.insert(pts1b.end(), pts1.begin(), pts1.end()); 00589 transformPoints(pts1b, H12); 00590 warpPerspective(im1, im1b, H12, im1.size()); 00591 00592 //shiftIntensities(im1b, scale_shift, vert_shift, down_shift); 00593 00594 warpPerspective(blank, mask, H12, blank.size()); 00595 00596 00597 } else { 00598 00599 /* 00600 double scale_shift = 1.0; 00601 double vert_shift = new_vals[3] - orig_vals[3]; 00602 double down_shift = 0.0; 00603 */ 00604 00605 im1b = Mat(im1); // .copyTo(im1b); 00606 // shiftIntensities(im1b, scale_shift, vert_shift, down_shift); 00607 00608 // Need to make sure that black border stays as black, and only valid pixels are sampled... 00609 00610 pts2.clear(); 00611 opticalFlowFlags = 0; 00612 } 00613 00614 //testTime = timeElapsedMS(test_timer, false); 00615 //printf("XDebug 2: (%f)\n", testTime); 00616 00617 if (guiding) { 00618 //calcOpticalFlowPyrLK(im1b, im2, pts1b, pts2, statusVec, err, winSize, maxLevel, criteria, derivLambda, opticalFlowFlags); 00619 calcOpticalFlowPyrLK(im1b, im2, pts1b, pts2, statusVec, err, winSize, maxLevel, criteria, opticalFlowFlags, thresh); 00620 //markStationaryPoints(pts1b, pts2, statusVec); 00621 00622 00623 markAbsentPoints(pts1b, pts2, statusVec, im1.size()); 00624 00625 } else { 00626 00627 //printf("%s << Initial features: %d, %d\n", __FUNCTION__, pts1.size(), pts2.size()); 00628 00629 pts2.insert(pts2.end(), pts1.begin(), pts1.end()); 00630 00631 //for (unsigned int iii = 0; iii < pts1.size(); iii++) { 00632 //printf("%s << pt(%d) = (%f, %f) vs (%f, %f)\n", __FUNCTION__, iii, pts1.at(iii).x, pts1.at(iii).y, pts2.at(iii).x, pts2.at(iii).y); 00633 //} 00634 // CV_LKFLOW_GET_MIN_EIGENVALS 00635 int opticalFlowFlags = OPTFLOW_USE_INITIAL_FLOW + CV_LKFLOW_GET_MIN_EIGENVALS; // + OPTFLOW_LK_GET_MIN_EIGENVALS; 00636 //double minEigThreshold = 1e-4; 00637 // calcOpticalFlowPyrLK(im1b, im2, pts1, pts2, statusVec, err, winSize, maxLevel, criteria, derivLambda, opticalFlowFlags, minEigThreshold); // opticalFlowFlags 00638 00639 /* 00640 Mat im1b_x; 00641 im1b_x = Mat::zeros(im1b.size(), CV_8UC1); 00642 00643 for (unsigned int iii = 0; iii < 475; iii++) { 00644 for (unsigned int jjj = 0; jjj < 635; jjj++) { 00645 im1b_x.at<unsigned char>(iii+5,jjj+5) = im1b.at<unsigned char>(iii,jjj); 00646 } 00647 } 00648 * */ 00649 // im1b_x = im1b(Range(5, 479), Range(5, 639)); 00650 00651 //pts2.clear(); 00652 00653 calcOpticalFlowPyrLK(im1b, im2, pts1, pts2, statusVec, err, winSize, maxLevel, criteria, opticalFlowFlags, thresh); 00654 //calcOpticalFlowPyrLK(im1b, im2, pts1, pts2, statusVec, err, winSize, maxLevel, criteria, derivLambda, opticalFlowFlags); // opticalFlowFlags 00655 00656 00657 00658 if (debugFlag) { 00659 00660 printf("%s << winSize = (%d, %d)\n", __FUNCTION__, winSize.width, winSize.height); 00661 00662 Mat a, b; 00663 00664 displayKeypoints(im1b, pts1, a, CV_RGB(255,0,0), 0); 00665 displayKeypoints(im2, pts2, b, CV_RGB(255,0,0), 0); 00666 00667 while (1) { 00668 00669 imshow("test", a); 00670 waitKey(500); 00671 imshow("test", b); 00672 waitKey(500); 00673 00674 printf("%s << After flow: %d / %d\n", __FUNCTION__, countNonZero(statusVec), statusVec.size()); 00675 } 00676 00677 //for (unsigned int iii = 0; iii < pts1.size(); iii++) { 00678 // printf("%s << pts1.at(%d) = [%f, %f]; pts2.at(%d) = [%f, %f]\n", __FUNCTION__, iii, pts1.at(iii).x, pts1.at(iii).y, iii, pts2.at(iii).x, pts2.at(iii).y); 00679 //} 00680 00681 00682 } 00683 00684 //for (unsigned int iii = 0; iii < pts1.size(); iii++) { 00685 //printf("%s << pt(%d) = (%f, %f) vs (%f, %f)\n", __FUNCTION__, iii, pts1.at(iii).x, pts1.at(iii).y, pts2.at(iii).x, pts2.at(iii).y); 00686 //} 00687 00688 //testTime = timeElapsedMS(test_timer, false); 00689 //printf("XDebug 2b: (%f)\n", testTime); 00690 00691 //markStationaryPoints(pts1, pts2, statusVec); 00692 00693 //printf("%s << After stationary: %d\n", __FUNCTION__, countNonZero(statusVec)); 00694 00695 markAbsentPoints(pts1, pts2, statusVec, im1.size()); 00696 00697 if (debugFlag) { 00698 printf("%s << After absent: %d\n", __FUNCTION__, countNonZero(statusVec)); 00699 } 00700 00701 00702 } 00703 00704 //testTime = timeElapsedMS(test_timer, false); 00705 //printf("XDebug 3: (%f)\n", testTime); 00706 00707 00708 if (camData.Kx.rows != 0) { 00709 markEdgyTracks(pts2, statusVec, camData); 00710 00711 //printf("%s << After edge filtering: %d\n", __FUNCTION__, countNonZero(statusVec)); 00712 } 00713 00714 //testTime = timeElapsedMS(test_timer, false); 00715 //printf("XDebug 4: (%f)\n", testTime); 00716 00717 //markBlandTracks(im2, pts2, statusVec, 1.0); 00718 00719 //testTime = timeElapsedMS(test_timer, false); 00720 //printf("XDebug 5: (%f)\n", testTime); 00721 00722 //printf("%s << After bland filtering: %d\n", __FUNCTION__, countNonZero(statusVec)); 00723 00724 //markUnrefinedPoints(pts2, statusVec); 00725 00726 //printf("%s << After unrefined filtering: %d\n", __FUNCTION__, countNonZero(statusVec)); 00727 00728 if (guiding) { 00729 filterVectors(pts1, pts2, statusVec, ((double) std::max(im1.rows, im1.cols)), true); 00730 00731 if (0) { 00732 00733 Mat im1x, im2x; 00734 //warpPerspective(grayImageBuffer[(current_idx-1) % MAXIMUM_FRAMES_TO_STORE], im2, H12, grayImageBuffer[(current_idx-1) % MAXIMUM_FRAMES_TO_STORE].size()); 00735 00736 im1.copyTo(im1x); 00737 im2.copyTo(im2x); 00738 00739 displayKeypoints(im1, pts1, im1x, CV_RGB(255,0,0), 0); 00740 displayKeypoints(im2x, pts2, im2x, CV_RGB(255,0,0), 0); 00741 00742 //warpPerspective(im1, im1b, H12, im1.size()); 00743 00744 while (1) { 00745 00746 imshow("temp_disp", im1x); // Previous image with features 00747 waitKey(500); 00748 imshow("temp_disp", im2x); // Current image 00749 waitKey(500); 00750 00751 } 00752 } 00753 } else { 00754 //printf("%s << pts1.size() = %d [before filtering]\n", __FUNCTION__, pts1.size()); 00755 //printf("%s << passed distanceConstraint = %d\n", __FUNCTION__, distanceConstraint); 00756 filterVectors(pts1, pts2, statusVec, ((double) distanceConstraint)); 00757 //printf("%s << pts1.size() = %d [after filtering]\n", __FUNCTION__, pts1.size()); 00758 00759 //printf("%s << After full filtering: %d\n", __FUNCTION__, pts2.size()); 00760 00761 if (0) { // (pts2.size() < 5) { 00762 00763 Mat im1x, im2x; 00764 //warpPerspective(grayImageBuffer[(current_idx-1) % MAXIMUM_FRAMES_TO_STORE], im2, H12, grayImageBuffer[(current_idx-1) % MAXIMUM_FRAMES_TO_STORE].size()); 00765 00766 cvtColor(im1b, im1x, CV_GRAY2RGB); 00767 cvtColor(im2, im2x, CV_GRAY2RGB); 00768 00769 displayKeypoints(im1x, originalPts, im1x, CV_RGB(255,0,0), 0); 00770 displayKeypoints(im2x, pts2, im2x, CV_RGB(255,0,0), 0); 00771 00772 //warpPerspective(im1, im1b, H12, im1.size()); 00773 00774 while (1) { 00775 00776 imshow("temp_disp", im1b); // Previous image with features 00777 waitKey(1500); 00778 imshow("temp_disp", im2x); // Current image 00779 waitKey(500); 00780 00781 } 00782 } 00783 00784 } 00785 00786 //testTime = timeElapsedMS(test_timer, false); 00787 //printf("XDebug 6: (%f)\n", testTime); 00788 00789 for (unsigned int iii = 0; iii < statusVec.size(); iii++) { 00790 if (statusVec.at(iii) == 0) { 00791 lostIndices.push_back(iii); 00792 } 00793 } 00794 00795 //testTime = timeElapsedMS(test_timer, false); 00796 //printf("XDebug 7: (%f)\n", testTime); 00797 00798 } 00799 00800 //HGH 00801 void trackPoints2(const Mat& im1, const Mat& im2, vector<Point2f>& pts1, vector<Point2f>& pts2, int distanceConstraint, double thresh, vector<unsigned int>& lostIndices, const Size patternSize, double& errorThreshold) { 00802 00803 00804 int corners = patternSize.width * patternSize.height; 00805 00806 bool debugFlag = false; 00807 00808 if (debugFlag) { 00809 printf("%s << ENTERED!\n", __FUNCTION__); 00810 } 00811 00812 if (pts1.size() == 0) { 00813 return; 00814 } 00815 00816 if ((distanceConstraint % 2) == 0) { 00817 distanceConstraint++; 00818 } 00819 00820 Size winSize = Size(distanceConstraint, distanceConstraint); 00821 int maxLevel = 3; 00822 TermCriteria criteria = TermCriteria( TermCriteria::COUNT+TermCriteria::EPS, 30, 0.01); 00823 00824 Mat im1b; 00825 Mat blank; 00826 00827 vector<uchar> statusVec; 00828 vector<float> err; 00829 00830 blank = Mat::ones(im1.size(), CV_8UC1); 00831 blank *= 255; 00832 00833 00834 vector<Point2f> originalPts; 00835 originalPts.insert(originalPts.end(), pts1.begin(), pts1.end()); 00836 00837 im1b = Mat(im1); // .copyTo(im1b); 00838 00839 pts2.clear(); 00840 pts2.insert(pts2.end(), pts1.begin(), pts1.end()); 00841 00842 int opticalFlowFlags = OPTFLOW_USE_INITIAL_FLOW + CV_LKFLOW_GET_MIN_EIGENVALS; // + OPTFLOW_LK_GET_MIN_EIGENVALS; 00843 00844 calcOpticalFlowPyrLK(im1b, im2, pts1, pts2, statusVec, err, winSize, maxLevel, criteria, opticalFlowFlags, thresh); 00845 00846 if (corners != statusVec.size() || corners != err.size()){ 00847 lostIndices.push_back(-1); 00848 } 00849 00850 //cout << *max_element(err.begin(),err.end()) << endl; 00851 for (unsigned int iii = 0; iii < err.size(); iii++) { 00852 00853 if (err.at(iii) > errorThreshold && errorThreshold != 0.0){ 00854 //cout << err.at(iii) << " for " << iii << endl; 00855 lostIndices.push_back(-2); 00856 } 00857 } 00858 00859 for (unsigned int iii = 0; iii < statusVec.size(); iii++) { 00860 if (statusVec.at(iii) == 0) { 00861 lostIndices.push_back(iii); 00862 } 00863 } 00864 00865 00866 } 00867 00868 void markAbsentPoints(vector<Point2f>&pts1, vector<Point2f>&pts2, vector<uchar>&statusVec, cv::Size imSize) { 00869 00870 float buffer = 2.0; 00871 00872 #pragma omp parallel for 00873 for (unsigned int iii = 0; iii < statusVec.size(); iii++) { 00874 00875 if (statusVec.at(iii) != 0) { 00876 00877 if ((pts1.at(iii).x < buffer) || (pts1.at(iii).x > imSize.width - buffer)) { 00878 statusVec.at(iii) = 0; 00879 } else if ((pts2.at(iii).x < buffer) || (pts2.at(iii).x > imSize.width - buffer)) { 00880 statusVec.at(iii) = 0; 00881 } else if ((pts1.at(iii).y < buffer) || (pts1.at(iii).y > imSize.height - buffer)) { 00882 statusVec.at(iii) = 0; 00883 } else if ((pts2.at(iii).y < buffer) || (pts2.at(iii).y > imSize.height - buffer)) { 00884 statusVec.at(iii) = 0; 00885 } 00886 00887 } 00888 00889 } 00890 00891 } 00892 00893 bool constructPatch(Mat& img, Mat& patch, Point2f& center, double radius, int cells) { 00894 00895 //printf("%s << ENTERED.\n", __FUNCTION__); 00896 00897 patch.release(); 00898 00899 if ((cells % 2) == 0) { 00900 cells++; 00901 } 00902 00903 patch = Mat::zeros(cells, cells, CV_64FC1); 00904 00905 int range = (cells-1)/2; 00906 00907 for (int iii = -range; iii <= +range; iii++) { 00908 for (int jjj = -range; jjj <= +range; jjj++) { 00909 00910 Point2f currPt = Point2f(center.x + ((double) iii)*radius, center.y + ((double) jjj)*radius); 00911 00912 //printf("%s << currPt = (%f, %f)\n", __FUNCTION__, currPt.x, currPt.y); 00913 00914 if ((currPt.x <= 0.0) || (currPt.x >= ((double) img.cols)) || (currPt.y >= ((double) img.rows)) || (currPt.y <= 0.0)) { 00915 return false; 00916 } 00917 00918 //printf("%s << Extracting (%f, %f) of (%d, %d)\n", __FUNCTION__, currPt.x, currPt.y, img.cols, img.rows); 00919 double val = getInterpolatedVal(img, currPt); 00920 //printf("%s << Assigning (%d, %d) of (%d, %d)\n", __FUNCTION__, iii+range, jjj+range, cells, cells); 00921 patch.at<double>(iii+range,jjj+range) = val; 00922 00923 } 00924 } 00925 00926 //printf("%s << EXITING.\n", __FUNCTION__); 00927 00928 return true; 00929 00930 } 00931 00932 00933 void extendKeypoints(Mat& img, vector<KeyPoint>& pts, bool updateStrength, bool updateLocation) { 00934 00935 if (updateLocation) { 00936 // Use cornersubpix to refine locations 00937 00938 vector<Point2f> candidates; 00939 KeyPoint::convert(pts, candidates); 00940 00941 cornerSubPix(img, candidates, Size(1,1), Size(-1,-1), cvTermCriteria(CV_TERMCRIT_EPS+CV_TERMCRIT_ITER, 15, 0.1)); 00942 00943 #pragma omp parallel for 00944 for (unsigned int iii = 0; iii < candidates.size(); iii++) { 00945 pts.at(iii).pt = candidates.at(iii); 00946 } 00947 00948 } 00949 00950 if (updateStrength) { 00951 00952 00953 #pragma omp parallel for 00954 for (unsigned int iii = 0; iii < pts.size(); iii++) { 00955 double radius = ((double) pts.at(iii).size) / 2.0; 00956 double salience = estimateSalience(img, pts.at(iii).pt, radius); 00957 pts.at(iii).response = salience; 00958 } 00959 00960 } 00961 00962 } 00963 00964 double estimateSalience(Mat& img, Point2f& center, double radius) { 00965 00966 // Assumes 8-bit image 00967 double salience = 0.0; 00968 00969 00970 00971 // Find center 00972 //cv::Point center = Point(((int) kp.pt.x), ((int) kp.pt.y)); 00973 00974 // Find radius 00975 00976 00977 if (((center.x - radius) < 0) || ((center.y - radius) < 0) || ((center.x + radius) >= img.cols) || ((center.y + radius) >= img.rows)) { 00978 return salience; 00979 } 00980 00981 Mat patch; 00982 int patchSize = radius * 2; 00983 if ((patchSize % 2) == 0) { 00984 //patchSize++; 00985 } 00986 00987 constructPatch(img, patch, center, radius, patchSize); 00988 //cout << patch << endl; 00989 00990 salience = getValueFromPatch(patch); 00991 00992 00993 return salience; 00994 00995 } 00996 00997 double getValueFromPatch(Mat& patch) { 00998 00999 Mat convertedPatch = Mat::zeros(patch.size(), CV_32FC1); 01000 01001 #pragma omp parallel for 01002 for (int iii = 0; iii < patch.rows; iii++) { 01003 for (int jjj = 0; jjj < patch.cols; jjj++) { 01004 convertedPatch.at<float>(iii,jjj) = ((float) patch.at<double>(iii,jjj)); 01005 } 01006 } 01007 01008 Mat eigenMat; 01009 cornerMinEigenVal(convertedPatch, eigenMat, patch.rows, CV_SCHARR); 01010 01011 double eigenValue = 0.0, blankVal; 01012 01013 minMaxLoc(eigenMat, &blankVal, &eigenValue); 01014 01015 /* 01016 for (int iii = 0; iii < patch.rows; iii++) { 01017 for (int jjj = 0; jjj < patch.cols; jjj++) { 01018 //eigenValue += eigenMat.at<float>(iii,jjj) / ((float) (eigenMat.rows * eigenMat.cols)); 01019 } 01020 } 01021 */ 01022 return eigenValue; 01023 01024 } 01025 01026 void markUnrefinedPoints(vector<Point2f>& pts, vector<uchar>&statusVec) { 01027 01028 if (pts.size() == 0) { 01029 return; 01030 } 01031 01032 #pragma omp parallel for 01033 for (unsigned int iii = 0; iii < statusVec.size(); iii++) { 01034 01035 if (statusVec.at(iii) != 0) { 01036 01037 if (((pts.at(iii).x - floor(pts.at(iii).x)) == 0.0) && ((pts.at(iii).y - floor(pts.at(iii).y)) == 0.0)) { 01038 statusVec.at(iii) = 0; 01039 } 01040 01041 } 01042 } 01043 01044 } 01045 01046 01047 void markBlandTracks(Mat& img, vector<Point2f>& pts, vector<uchar>& statusVec, double thresh) { 01048 01049 if (pts.size() == 0) { 01050 return; 01051 } 01052 01053 Mat patch; 01054 01055 for (unsigned int iii = 0; iii < statusVec.size(); iii++) { 01056 01057 if (statusVec.at(iii) != 0) { 01058 01059 constructPatch(img, patch, pts.at(iii), 1.5); 01060 //cout << patch << endl; 01061 01062 double salience = getValueFromPatch(patch); 01063 01064 //printf("%s << pts.at(%d).response = %f (%f)\n", __FUNCTION__, iii, pts.at(iii).response, thresh); 01065 01066 if (salience < thresh) { 01067 statusVec.at(iii) = 0; 01068 } 01069 01070 01071 } 01072 } 01073 01074 01075 } 01076 01077 void filterBlandKeypoints(Mat& img, vector<KeyPoint>& pts, double thresh) { 01078 01079 if (pts.size() == 0) { 01080 return; 01081 } 01082 01083 for (int iii = pts.size()-1; iii >= 0; iii--) { 01084 01085 //printf("%s << pts.at(%d).response = %f (%f)\n", __FUNCTION__, iii, pts.at(iii).response, thresh); 01086 01087 if (pts.at(iii).response < thresh) { 01088 pts.erase(pts.begin() + iii); 01089 } 01090 01091 } 01092 01093 } 01094 01095 void markStationaryPoints(vector<Point2f>&pts1, vector<Point2f>&pts2, vector<uchar>&statusVec) { 01096 01097 #pragma omp parallel for 01098 for (unsigned int iii = 0; iii < statusVec.size(); iii++) { 01099 01100 if (statusVec.at(iii) != 0) { 01101 01102 double absDifference = pow(pow(pts1.at(iii).x - pts2.at(iii).x, 2.0) + pow(pts1.at(iii).y - pts2.at(iii).y, 2.0), 0.5); 01103 01104 //printf("%s << absDifference = %f\n", __FUNCTION__, absDifference); 01105 01106 if (absDifference == 0.0) { 01107 statusVec.at(iii) = 0; 01108 } 01109 01110 } 01111 } 01112 01113 } 01114 01115 void displayKeypoints(const Mat& image, const vector<KeyPoint>& keypoints, Mat& outImg, const Scalar& color, int thickness) { 01116 01117 bool randomColours = (color == Scalar::all(-1)); 01118 01119 Scalar newColour; 01120 01121 if (!randomColours) { 01122 newColour = color; 01123 } 01124 01125 image.copyTo(outImg); 01126 01127 //printf("%s << DEBUG %d\n", __FUNCTION__, 0); 01128 01129 /* 01130 if (image.channels() < 3) { 01131 cvtColor(image, outImg, CV_GRAY2RGB); 01132 } else { 01133 image.copyTo(outImg); 01134 } 01135 01136 */ 01137 01138 //printf("%s << DEBUG %d\n", __FUNCTION__, 1); 01139 01140 Point centerPt; 01141 01142 int radius, crossLength; //, aimedSize; 01143 01144 if (thickness == 0) { 01145 thickness = 1; 01146 } 01147 01148 // New method: 01149 for (unsigned int i = 0; i < keypoints.size(); i++) { 01150 //int colorCoeff = (int)( (255.0 * ((double) keypoints.size() - (double)i)) / (double) keypoints.size()); 01151 01152 //printf("%s << %d: c = %d\n", __FUNCTION__, i, colorCoeff); 01153 //cin.get(); 01154 newColour = color; // CV_RGB(255, 255-colorCoeff, 0); 01155 01156 //printf("%s << DEBUG %d_%d\n", __FUNCTION__, 2, i); 01157 01158 centerPt = keypoints.at(i).pt; 01159 01160 centerPt.x *= 16.0; 01161 centerPt.y *=16.0; 01162 01163 //aimedSize = 6 - ((int) 4.0*((double) i / (double) pts.size())); 01164 01165 01166 //radius = keypoints.at(i).size/2; 01167 01168 //aimedSize = 6 - ((int) 4.0*((double) i / (double) keypoints.size())); 01169 radius = 16.0 * (keypoints.at(i).size/2.0); // 2 01170 //thickness = 3 - ((int) 2.0*((double) i / (double) keypoints.size())); 01171 //crossLength = int (1.5 * (double) aimedSize); 01172 crossLength = 2 * 16.0; 01173 01174 if (radius > 0) { 01175 circle(outImg, centerPt, radius, newColour, thickness, CV_AA, 4); 01176 } 01177 01178 line(outImg, Point(centerPt.x-crossLength, centerPt.y), Point(centerPt.x+crossLength, centerPt.y), newColour, thickness, CV_AA, 4); 01179 line(outImg, Point(centerPt.x, centerPt.y-crossLength), Point(centerPt.x, centerPt.y+crossLength), newColour, thickness, CV_AA, 4); 01180 01181 //printf("%s << DEBUG %d_X_%d\n", __FUNCTION__, 2, i); 01182 01183 //imshow("tempWin", outImg); 01184 01185 //waitKey(200); 01186 01187 } 01188 01189 return; 01190 01191 } 01192 01193 void displayKeypoints(const Mat& image, const vector<Point2f>& pts, Mat& outImg, const Scalar& color, int thickness) { 01194 01195 bool randomColours = (color == Scalar::all(-1)); 01196 01197 Scalar newColour; 01198 01199 if (!randomColours) { 01200 newColour = color; 01201 } 01202 01203 image.copyTo(outImg); 01204 01205 Point centerPt; 01206 01207 if (thickness == 0) { 01208 thickness = 1; 01209 } 01210 01211 int crossLength; //, aimedSize; 01212 01213 // New method: 01214 for (unsigned int i = 0; i < pts.size(); i++) { 01215 01216 centerPt.x = pts.at(i).x * 16.0; 01217 centerPt.y = pts.at(i).y * 16.0; 01218 01219 //aimedSize = 6 - ((int) 4.0*((double) i / (double) pts.size())); 01220 crossLength = 2 * 16.0; 01221 01222 01223 line(outImg, Point(centerPt.x-crossLength, centerPt.y), Point(centerPt.x+crossLength, centerPt.y), color, thickness, CV_AA, 4); 01224 line(outImg, Point(centerPt.x, centerPt.y-crossLength), Point(centerPt.x, centerPt.y+crossLength), color, thickness, CV_AA, 4); 01225 01226 01227 } 01228 01229 return; 01230 01231 } 01232 01233 void sortKeypoints(vector<KeyPoint>& keypoints, unsigned int maxKeypoints) { 01234 vector<KeyPoint> sortedKeypoints; 01235 01236 if (keypoints.size() <= 1) { 01237 return; 01238 } 01239 01240 // Add the first one 01241 sortedKeypoints.push_back(keypoints.at(0)); 01242 01243 for (unsigned int i = 1; i < keypoints.size(); i++) { 01244 01245 unsigned int j = 0; 01246 bool hasBeenAdded = false; 01247 01248 while ((j < sortedKeypoints.size()) && (!hasBeenAdded)) { 01249 01250 if (abs(keypoints.at(i).response) > abs(sortedKeypoints.at(j).response)) { 01251 sortedKeypoints.insert(sortedKeypoints.begin() + j, keypoints.at(i)); 01252 01253 hasBeenAdded = true; 01254 } 01255 01256 j++; 01257 } 01258 01259 if (!hasBeenAdded) { 01260 sortedKeypoints.push_back(keypoints.at(i)); 01261 } 01262 01263 } 01264 01265 01266 01267 keypoints.swap(sortedKeypoints); 01268 01269 if ((maxKeypoints != -1) && (maxKeypoints < int(keypoints.size()))) { 01270 keypoints.erase(keypoints.begin()+maxKeypoints, keypoints.end()); 01271 } 01272 01273 return; 01274 01275 } 01276 01277 void sortMatches(vector<vector<DMatch> >& matches1to2) { 01278 vector<vector<DMatch> > matchesCpy, newMatches; 01279 01280 if (matches1to2.size() <= 1) { 01281 return; 01282 } 01283 01284 matchesCpy.assign(matches1to2.begin(), matches1to2.end()); 01285 01286 while (matchesCpy.size() > 0) { 01287 double bestDistance = matchesCpy.at(0).at(0).distance; 01288 int bestIndex = 0; 01289 01290 for (unsigned int iii = 0; iii < matchesCpy.size(); iii++) { 01291 01292 if (matchesCpy.at(iii).at(0).distance <= bestDistance) { 01293 bestDistance = matchesCpy.at(iii).at(0).distance; 01294 bestIndex = iii; 01295 } 01296 } 01297 01298 newMatches.push_back(matchesCpy.at(bestIndex)); 01299 matchesCpy.erase(matchesCpy.begin() + bestIndex); 01300 } 01301 01302 newMatches.swap(matches1to2); 01303 } 01304 01305 void filterMatches(vector<vector<DMatch> >& matches1to2, double threshold) { 01306 01307 if (matches1to2.size() == 0) { 01308 return; 01309 } 01310 01311 int currIndex = matches1to2.size() - 1; 01312 01313 while (matches1to2.at(currIndex).at(0).distance > threshold) { 01314 currIndex--; 01315 01316 if (currIndex == -1) { 01317 matches1to2.clear(); 01318 return; 01319 } 01320 } 01321 01322 if (currIndex < ((int) matches1to2.size() - 1)) { 01323 matches1to2.erase(matches1to2.begin() + currIndex + 1, matches1to2.end()); 01324 } 01325 01326 01327 } 01328 01329 double distanceBetweenPoints(const Point2f& pt1, const Point2f& pt2) { 01330 double retVal; 01331 01332 retVal = pow(pow(pt1.x - pt2.x, 2.0) + pow(pt1.y - pt2.y, 2.0), 0.5); 01333 01334 return retVal; 01335 01336 } 01337 01338 double distanceBetweenPoints(const KeyPoint& pt1, const KeyPoint& pt2) { 01339 double retVal; //, a, b, c, d; 01340 01341 /* 01342 a = pow(pt1.pt.x - pt2.pt.x, 2.0); 01343 b = pow(pt1.pt.y - pt2.pt.y, 2.0); 01344 c = pt1.pt.x - pt2.pt.x; 01345 d = pt1.pt.y - pt2.pt.y; 01346 */ 01347 01348 //printf("%s << %f %f %f %f %f\n", __FUNCTION__, retVal, a, b, c, d); 01349 01350 retVal = pow(pow(pt1.pt.x - pt2.pt.x, 2.0) + pow(pt1.pt.y - pt2.pt.y, 2.0), 0.5); 01351 01352 return retVal; 01353 } 01354 01355 void constrainMatchingMatrix(Mat& matchingMatrix, vector<KeyPoint>& kp1, vector<KeyPoint>& kp2, int distanceConstraint, double sizeConstraint) { 01356 01357 01358 01359 #pragma omp parallel for 01360 for (unsigned int iii = 0; iii < kp1.size(); iii++) { 01361 for (unsigned int jjj = 0; jjj < kp2.size(); jjj++) { 01362 // Check distance constraint 01363 01364 int distanceBetween; 01365 01366 distanceBetween = (int) distanceBetweenPoints(kp1.at(iii), kp2.at(jjj)); 01367 //printf("%s << distance (%d, %d) = %d (%f) vs %d\n", __FUNCTION__, iii, jjj, distanceBetween, distanceBetweenPoints(kp1.at(iii), kp2.at(jjj)), distanceConstraint); 01368 01369 if (distanceBetween > distanceConstraint) { 01370 matchingMatrix.at<double>(iii,jjj) = -1; 01371 } 01372 01373 //printf("%s << diameter = %f vs %f\n", __FUNCTION__, kp1.at(iii).size, kp2.at(jjj).size); 01374 01375 if (max(kp1.at(iii).size/kp2.at(jjj).size, kp2.at(jjj).size/kp1.at(iii).size) > (1.00 + sizeConstraint)) { 01376 matchingMatrix.at<double>(iii,jjj) = -1; 01377 } 01378 01379 //cin.get(); 01380 } 01381 01382 //cin.get(); 01383 } 01384 01385 01386 } 01387 01388 void twoWayPriorityMatching(Mat& matchingMatrix, vector<vector<DMatch> >& bestMatches) { 01389 01390 bestMatches.clear(); 01391 01392 // void getPriorityScores(Mat& matchingMatrix, vector<vector<double> >& priorityScores, vector<vector<int> >& priorityMatches); 01393 01394 // Potentially more efficient way of doing things: 01395 // Just search matrix for lowest match score, and record the next best in that 'cross' and blank out that cross, 01396 // then search for the lowest match score remaining in the matrix and so on and so forth... 01397 // 01398 // Actually many-many, 1-many, 1-1 can all use this basic approach, but just with different "blanking" strategies 01399 // e.g. 1-many would blank out the entire column, but not row 01400 // only many-many would not be able to record a valid "second best" score 01401 // and many-many would also have N^2 matches rather than just N for the others... 01402 01403 bool rowsStillRemain = false; 01404 int remainingRows = 0; 01405 01406 //printf("%s << Entered function.\n", __FUNCTION__); 01407 01408 01409 for (int iii = 0; iii < matchingMatrix.rows; iii++) { 01410 bool anyInThisRow = false; 01411 for (int jjj = 0; jjj < matchingMatrix.cols; jjj++) { 01412 if (matchingMatrix.at<double>(iii,jjj) >= 0) { 01413 rowsStillRemain = true; 01414 anyInThisRow = true; 01415 } 01416 } 01417 01418 if (anyInThisRow) { 01419 remainingRows++; 01420 } 01421 01422 } 01423 01424 //printf("%s << remainingRows = %d\n", __FUNCTION__, remainingRows); 01425 01426 while (rowsStillRemain) { 01427 01428 double bestScore = 9e99; 01429 int bestRow = -1, bestCol = -1; 01430 01431 for (int iii = 0; iii < matchingMatrix.rows; iii++) { 01432 for (int jjj = 0; jjj < matchingMatrix.cols; jjj++) { 01433 if ((matchingMatrix.at<double>(iii,jjj) <= bestScore) && (matchingMatrix.at<double>(iii,jjj) >= 0)) { 01434 bestScore = matchingMatrix.at<double>(iii,jjj); 01435 bestRow = iii; 01436 bestCol = jjj; 01437 } 01438 } 01439 } 01440 01441 if ((bestScore < 0) || (bestScore == 9e99)) { 01442 rowsStillRemain = false; 01443 break; 01444 } 01445 01446 matchingMatrix.at<double>(bestRow,bestCol) = -1.0; 01447 //matchingMatrixCpy.at<double>(bestRow,bestCol) = -1.0; 01448 01449 DMatch currentMatch; 01450 vector<DMatch> currentMatchVector; 01451 01452 currentMatch.queryIdx = bestRow; 01453 currentMatch.trainIdx = bestCol; 01454 01455 double secondScore = 9e99; 01456 //int secondRow = -1, secondCol = -1; 01457 01458 for (int iii = 0; iii < matchingMatrix.rows; iii++) { 01459 if ((matchingMatrix.at<double>(iii,bestCol) <= secondScore) && (matchingMatrix.at<double>(iii,bestCol) >= 0)) { 01460 secondScore = matchingMatrix.at<double>(iii,bestCol); 01461 //secondRow = iii; 01462 //secondCol = bestCol; 01463 } 01464 matchingMatrix.at<double>(iii,bestCol) = -1; 01465 } 01466 01467 for (int iii = 0; iii < matchingMatrix.cols; iii++) { 01468 if ((matchingMatrix.at<double>(bestRow,iii) <= secondScore) && (matchingMatrix.at<double>(bestRow,iii) >= 0)) { 01469 secondScore = matchingMatrix.at<double>(bestRow,iii); 01470 //secondRow = bestRow; 01471 //secondCol = iii; 01472 } 01473 matchingMatrix.at<double>(bestRow,iii) = -1; 01474 } 01475 01476 // If it is literally the last match available, it won't have a second best score... 01477 if (secondScore == 9e99) { 01478 secondScore = bestScore; 01479 } 01480 01481 // Then normalize the "distance" based on this ratio, or can just use the ratio... 01482 //currentMatch.distance = bestScore; 01483 currentMatch.distance = bestScore / secondScore; 01484 //double gradient = -1.42; 01485 //double shift[3] = {1.86, 1.04, 0.21}; 01486 01487 //currentMatch.distance = reweightDistanceWithLinearSVM(bestScore, (bestScore/secondScore), gradient, shift); 01488 01489 currentMatchVector.push_back(currentMatch); 01490 bestMatches.push_back(currentMatchVector); 01491 01492 01493 } 01494 01495 //printf("%s << bestMatches.size() = %d\n", __FUNCTION__, bestMatches.size()); 01496 //cin.get(); 01497 01498 } 01499 01500 double calcDistance(double dist, double ratio, double *coeffs) { 01501 double retVal = 0.0; 01502 01503 retVal = abs(coeffs[0] * dist - ratio + coeffs[2]) / sqrt(pow(coeffs[0], 2) + 1); 01504 01505 return retVal; 01506 } 01507 01508 double reweightDistanceWithLinearSVM(double dist, double ratio, double gradient) { 01509 double retVal = 0.0; // ratio 01510 01511 retVal = dist - (1.0 / gradient) * ratio; 01512 01513 return retVal; 01514 // 01515 // double LineNeg1[3], LineZero[3], LinePos1[3]; 01516 // 01517 // LineNeg1[0] = LineZero[0] = LinePos1[0] = gradient; 01518 // LineNeg1[1] = LineZero[1] = LinePos1[1] = -1; 01519 // LineNeg1[2] = shift[0]; 01520 // LineZero[2] = shift[1]; 01521 // LinePos1[2] = shift[2]; 01522 // 01523 // // Find distance between lines 01524 // //double negSeg = calcLinePerpDistance(LineNeg1, LineZero); 01525 // //double posSeg = calcLinePerpDistance(LinePos1, LineZero); 01526 // 01527 // //printf("%s << Distances between lines = (%f, %f)\n", __FUNCTION__, negSeg, posSeg); 01528 // 01529 // // Find distance from point to negative line 01530 // double negDist = calcDistance(dist, ratio, LineNeg1); 01531 // 01532 // // Find distance from point to neutral line 01533 // double zeroDist = calcDistance(dist, ratio, LineZero); 01534 // 01535 // // Find distance from point to positive line 01536 // double posDist = calcDistance(dist, ratio, LinePos1); 01537 // 01538 // //printf("%s << distances = (%f, %f, %f)\n", __FUNCTION__, negDist, zeroDist, posDist); 01539 // //cin.get(); 01540 // 01541 // if (posDist < negDist) { 01542 // retVal = -1.0 * zeroDist; 01543 // } else { 01544 // retVal = +1.0 * zeroDist; 01545 // } 01546 // 01547 // retVal = pow(2.0, retVal); 01548 // 01549 // // Assign total score 01550 // //printf("%s << dist/ratio = (%f, %f), retVal = %f\n", __FUNCTION__, dist, ratio, retVal); 01551 // //cin.get(); 01552 // 01553 // 01554 // return retVal; 01555 } 01556 01557 void createMatchingMatrix(Mat& matchingMatrix, const Mat& desc1, const Mat& desc2) { 01558 01559 vector<vector<DMatch> > matches1to2, matches2to1; 01560 01561 Ptr<DescriptorMatcher> dmatcher; 01562 01563 if (desc1.type() == CV_8UC1) { 01564 dmatcher = DescriptorMatcher::create("BruteForce-Hamming"); 01565 } else if ((desc1.type() == CV_64FC1) || (desc1.type() == CV_32FC1)) { 01566 dmatcher = DescriptorMatcher::create("BruteForce"); 01567 } else { 01568 printf("%s << ERROR! desc1.type() (%d) unrecognized.\n", __FUNCTION__, desc1.type()); 01569 } 01570 01571 01572 //printf("%s << desc1.rows = %d; desc2.rows = %d\n", __FUNCTION__, desc1.rows, desc2.rows); 01573 01574 dmatcher->knnMatch( desc1, desc2, matches1to2, desc1.rows ); 01575 dmatcher->knnMatch( desc2, desc1, matches2to1, desc2.rows ); 01576 01577 /* 01578 Mat matMatDisp; 01579 matMatDisp = normForDisplay(matchingMatrix); 01580 imshow("testWin", matMatDisp); 01581 waitKey(); 01582 */ 01583 01584 matchingMatrix = Mat::zeros(matches1to2.size(), matches2to1.size(), CV_64FC1); 01585 01586 Mat countMat = Mat::zeros(matches1to2.size(), matches2to1.size(), CV_64FC1); 01587 01588 // IM 1 to IM 2 01589 for (unsigned int iii = 0; iii < matches1to2.size(); iii++) { 01590 for (unsigned int jjj = 0; jjj < matches1to2[iii].size(); jjj++) { 01591 matchingMatrix.at<double>(iii, matches1to2.at(iii).at(jjj).trainIdx) += matches1to2.at(iii).at(jjj).distance; 01592 countMat.at<double>(iii, matches1to2.at(iii).at(jjj).trainIdx) += 1.0; 01593 } 01594 } 01595 01596 // IM 2 to IM 1 01597 for (unsigned int iii = 0; iii < matches2to1.size(); iii++) { 01598 for (unsigned int jjj = 0; jjj < matches2to1[iii].size(); jjj++) { 01599 matchingMatrix.at<double>(matches2to1.at(iii).at(jjj).trainIdx, iii) += matches2to1.at(iii).at(jjj).distance; 01600 countMat.at<double>(matches2to1.at(iii).at(jjj).trainIdx, iii) += 1.0; 01601 } 01602 } 01603 01604 /* 01605 Mat matMatDisp = normForDisplay(countMat); 01606 imshow("testWin", matMatDisp); 01607 waitKey(); 01608 */ 01609 01610 matchingMatrix /= 2.0; 01611 01612 } 01613 01614 void filterTrackedPoints(vector<uchar>& statusVec, vector<float>& err, double maxError) { 01615 01616 for (unsigned int iii = 0; iii < statusVec.size(); iii++) { 01617 if (err.at(iii) > maxError) { 01618 statusVec.at(iii) = 0; 01619 } 01620 } 01621 01622 } 01623 01624 void randomlyReducePoints(vector<Point2f>& pts, int maxFeatures) { 01625 01626 srand (time(NULL) ); 01627 01628 if (((int) pts.size()) <= maxFeatures) { 01629 return; 01630 } 01631 01632 int randIndex; 01633 01634 while (((int) pts.size()) > maxFeatures) { 01635 randIndex = rand() % pts.size(); 01636 pts.erase(pts.begin() + randIndex); 01637 } 01638 01639 } 01640 01641 void filterVectors(vector<Point2f>& pts1, vector<Point2f>& pts2, vector<uchar>& statusVec, double distanceConstraint, bool epipolarCheck) { 01642 01643 //printf("%s << sizes = (%d, %d)\n", __FUNCTION__, pts1.size(), pts2.size()); 01644 01645 double totalDist, xDist, yDist; 01646 01647 for (int iii = statusVec.size()-1; iii >= 0; iii--) { 01648 if (statusVec.at(iii) == 0) { 01649 pts1.erase(pts1.begin() + iii); 01650 pts2.erase(pts2.begin() + iii); 01651 } else { 01652 // distance check 01653 xDist = pts1.at(iii).x - pts2.at(iii).x; 01654 yDist = pts1.at(iii).y - pts2.at(iii).y; 01655 totalDist = pow((pow((xDist), 2.0) + pow((yDist), 2.0)), 0.5); 01656 01657 //printf("%s << totalDist (%f) ([%f, %f]) vs distanceConstraint (%f)\n", __FUNCTION__, totalDist, xDist, yDist, distanceConstraint); 01658 01659 if (totalDist > distanceConstraint) { 01660 01661 01662 01663 pts1.erase(pts1.begin() + iii); 01664 pts2.erase(pts2.begin() + iii); 01665 } 01666 } 01667 } 01668 01669 //printf("%s << sizes2 = (%d, %d)\n", __FUNCTION__, pts1.size(), pts2.size()); 01670 01671 // Then some kind of epipolar geometry check: 01672 01673 if (epipolarCheck) { 01674 Mat F, matchesMask_F_matrix; 01675 F = findFundamentalMat(Mat(pts1), Mat(pts2), FM_RANSAC, 1.00, 0.99, matchesMask_F_matrix); 01676 01677 for (int iii = matchesMask_F_matrix.rows-1; iii >= 0; iii--) { 01678 //printf("%s << matchesMask_F_matrix(%d,0) = %d\n", __FUNCTION__, iii, matchesMask_F_matrix.at<unsigned char>(iii,0)); 01679 if (matchesMask_F_matrix.at<unsigned char>(iii,0) == 0) { 01680 pts1.erase(pts1.begin() + iii); 01681 pts2.erase(pts2.begin() + iii); 01682 } 01683 } 01684 01685 //printf("%s << sizes3 = (%d, %d)\n", __FUNCTION__, pts1.size(), pts2.size()); 01686 } 01687 01688 01689 } 01690 01691 bool checkSufficientFeatureSpread(vector<Point2f>& pts, Size matSize, int minFeaturesInImage) { 01692 01693 Mat countMat; 01694 int horizontalDivisions = 4, verticalDivisions = 3; 01695 countMat = Mat::zeros(3, 4, CV_16UC1); 01696 int minPerSegment = minFeaturesInImage / (8 * horizontalDivisions * verticalDivisions); 01697 01698 //printf("%s << minPerSegment = %d\n", __FUNCTION__, minPerSegment); 01699 01700 for (unsigned int iii = 0; iii < pts.size(); iii++) { 01701 int r, c; 01702 r = (horizontalDivisions * pts.at(iii).x) / matSize.width; 01703 c = (verticalDivisions * pts.at(iii).y) / matSize.height; 01704 countMat.at<unsigned short>(r, c) += 1; 01705 } 01706 01707 int badSegments = 0; 01708 01709 for (int iii = 0; iii < countMat.rows; iii++) { 01710 for (int jjj = 0; jjj < countMat.cols; jjj++) { 01711 if (countMat.at<unsigned short>(iii, jjj) < minPerSegment) { 01712 badSegments++; 01713 } 01714 } 01715 } 01716 01717 //printf("%s << badSegments = %d\n", __FUNCTION__, badSegments); 01718 01719 if (badSegments > (horizontalDivisions * verticalDivisions / 2)) { 01720 return false; 01721 } 01722 01723 return true; 01724 01725 } 01726 01727 void drawMatchPaths(Mat& src, Mat& dst, vector<Point2f>& kp1, vector<Point2f>& kp2, const Scalar& color) { 01728 01729 src.copyTo(dst); 01730 Point a, b; 01731 01732 for (unsigned int iii = 0; iii < kp1.size(); iii++) { 01733 01734 a = Point(kp1.at(iii).x * 16.0, kp1.at(iii).y * 16.0); 01735 b = Point(kp2.at(iii).x * 16.0, kp2.at(iii).y * 16.0); 01736 01737 line(dst, a, b, color, 1, CV_AA, 4); 01738 01739 // a = b; 01740 01741 } 01742 } 01743 01744 void drawMatchPaths(Mat& src, Mat& dst, vector<KeyPoint>& kp1, vector<KeyPoint>& kp2, vector<vector<DMatch> >& matches1to2) { 01745 01746 //src.copyTo(dst); 01747 01748 Point a, b; 01749 01750 /* 01751 if (matches1to2.size() == 0) { 01752 printf("%s << No matches provided. Assuming all corresponding points match.\n", __FUNCTION__); 01753 01754 for (int iii = 0; iii < kp1.size(); iii++) { 01755 a = Point(kp1.at(iii).pt.x * 8, kp1.at(iii).pt.y * 8); 01756 b = Point(kp2.at(iii).pt.x * 8, kp2.at(iii).pt.y * 8); 01757 01758 line(dst, a, b, CV_RGB(0,0,255), 1, CV_AA, 3); 01759 } 01760 01761 return; 01762 01763 } 01764 */ 01765 01766 for (unsigned int iii = 0; iii < matches1to2.size(); iii++) { 01767 for (unsigned int jjj = 0; jjj < matches1to2.at(iii).size(); jjj++) { 01768 01769 //printf("%s << (%f,%f) vs (%f,%f)\n", __FUNCTION__, kp1.at(iii).pt.x, kp1.at(iii).pt.y, kp2.at(iii).pt.x, kp2.at(iii).pt.y); 01770 01771 //printf("%s << (%d, %d) - (%d, %d) / %f\n", __FUNCTION__, iii, jjj, matches1to2.at(iii).at(jjj).trainIdx, matches1to2.at(iii).at(jjj).queryIdx, matches1to2.at(iii).at(jjj).distance); 01772 //cin.get(); 01773 // matches1to2.at(iii).at(jjj).trainIdx 01774 01775 a = Point(kp1.at(matches1to2.at(iii).at(jjj).queryIdx).pt.x * 16.0, kp1.at(matches1to2.at(iii).at(jjj).queryIdx).pt.y * 16.0); 01776 b = Point(kp2.at(matches1to2.at(iii).at(jjj).trainIdx).pt.x * 16.0, kp2.at(matches1to2.at(iii).at(jjj).trainIdx).pt.y * 16.0); 01777 01778 line(dst, a, b, CV_RGB(0,0,255), 1, CV_AA, 4); 01779 01780 circle(dst, b, 1, CV_RGB(255, 0, 0), 1, CV_AA, 4); 01781 01782 } 01783 01784 } 01785 //cin.get(); 01786 } 01787 01788 void markEdgyTracks(vector<Point2f>& pts, vector<uchar>& statusVec, cameraParameters& camData) { 01789 01790 vector<Point2f> rpts; 01791 01792 float minBorderDist = 15.0; 01793 01794 01795 redistortPoints(pts, rpts, camData.Kx, camData.distCoeffs, camData.expandedCamMat); 01796 01797 Mat tmpDisp; 01798 01799 tmpDisp = Mat::zeros(camData.expandedSize, CV_8UC3); 01800 01801 Mat testMat; 01802 displayKeypoints(tmpDisp, rpts, tmpDisp, CV_RGB(0,255,0), 0); 01803 01804 unsigned int edgyMarks = 0; 01805 01806 float xDist, yDist, dist; 01807 01808 for (int iii = pts.size()-1; iii >= 0; iii--) { 01809 01810 xDist = min(((float) camData.expandedSize.width) - rpts.at(iii).x, rpts.at(iii).x); 01811 yDist = min(((float) camData.expandedSize.height) - rpts.at(iii).y, rpts.at(iii).y); 01812 dist = min(xDist, yDist); 01813 01814 if (dist < minBorderDist) { 01815 01816 if (statusVec.at(iii) != 0) { 01817 edgyMarks++; 01818 } 01819 statusVec.at(iii) = 0; 01820 rpts.erase(rpts.begin() + iii); 01821 } 01822 01823 } 01824 01825 displayKeypoints(tmpDisp, rpts, tmpDisp, CV_RGB(0,0,255), 0); 01826 01827 //imshow("tmpDisp", tmpDisp); 01828 //waitKey(1); 01829 01830 //printf("%s << edgyMarks = %d / %d\n", __FUNCTION__, edgyMarks, pts.size()); 01831 //cout << "camData.Kx = " << camData.Kx << endl; 01832 01833 } 01834 01835 double estimateStability(Mat& img, Point2f& center, double radius) { 01836 double stability = 0.0; 01837 01838 if (((center.x - radius) < 0) || ((center.y - radius) < 0) || ((center.x + radius) >= img.cols) || ((center.y + radius) >= img.rows)) { 01839 //printf("%s << Returning, error.\n", __FUNCTION__); 01840 return stability; 01841 } 01842 01843 Mat patch; 01844 constructPatch(img, patch, center, radius, 15); 01845 01846 double minVal, maxVal; 01847 minMaxLoc(patch, &minVal, &maxVal); 01848 01849 double variance = getPatchVariance(patch); 01850 01851 Mat largerMat; 01852 //patch /= maxVal; 01853 //resize(patch, largerMat, Size(patch.rows*4, patch.cols*4), 0, 0, INTER_NEAREST); 01854 01855 // largerMat /= 01856 01857 01858 //imshow("patch", largerMat); 01859 //waitKey(); 01860 01861 //printf("%s << variance = %f\n", __FUNCTION__, variance); 01862 01863 stability = 1 / variance; 01864 01865 return stability; 01866 01867 } 01868 01869 double getPatchVariance(const Mat& patch) { 01870 double mean = 0.0; 01871 double sigma = 0.0; 01872 01873 for (int iii = 0; iii < patch.rows; iii++) { 01874 for (int jjj = 0; jjj < patch.cols; jjj++) { 01875 mean += patch.at<double>(iii,jjj) / ((double) (patch.rows * patch.cols)); 01876 } 01877 } 01878 01879 for (int iii = 0; iii < patch.rows; iii++) { 01880 for (int jjj = 0; jjj < patch.cols; jjj++) { 01881 //printf("%s << (%f vs %f)\n", __FUNCTION__, patch.at<double>(iii,jjj), mean); 01882 sigma += pow((patch.at<double>(iii,jjj) - mean), 2.0) / ((double) (patch.rows * patch.cols)); 01883 } 01884 } 01885 01886 sigma = pow(sigma, 0.5); 01887 01888 return sigma; 01889 }