$search
00001 00005 #include "stereo.hpp" 00006 00007 void depthFromContours(vector<vector<vector<Point> > >& c1, vector<vector<vector<Point> > >& c2, Mat& disp) { 00008 00009 for (unsigned int iii = 0; iii < c1.size(); iii++) { 00010 00011 } 00012 00013 00014 for (unsigned int iii = 0; iii < disp.rows; iii++) { 00015 00016 } 00017 00018 } 00019 00020 void getContours(const Mat& src, vector<vector<vector<Point> > >& contours) { 00021 00022 contours.clear(); 00023 00024 Mat blurredIm, workingIm; 00025 00026 GaussianBlur(src, blurredIm, Size(25,25), 7.0, 7.0); 00027 00028 for (unsigned int iii = 0; iii < 244; iii++) { 00029 cv::threshold(blurredIm, workingIm, iii, 255, CV_THRESH_BINARY); 00030 00031 vector<vector<Point> > c; 00032 00033 // CV_RETR_TREE - can use this for heirarchical tree... 00034 cv::findContours( workingIm, c, CV_RETR_LIST, CV_CHAIN_APPROX_NONE ); 00035 00036 contours.push_back(c); 00037 00038 } 00039 } 00040 00041 void drawContours(const Mat& src, Mat& dst) { 00042 00043 double minVal, maxVal; 00044 00045 00046 00047 // http://stackoverflow.com/questions/8449378/finding-contours-in-opencv 00048 00049 Mat blurredIm, workingIm, contourImage(src.size(), CV_8UC3, cv::Scalar(0,0,0)); 00050 00051 cv::Scalar colors[3]; 00052 colors[0] = cv::Scalar(255, 0, 0); 00053 colors[1] = cv::Scalar(0, 255, 0); 00054 colors[2] = cv::Scalar(0, 0, 255); 00055 00056 GaussianBlur(src, blurredIm, Size(25,25), 7.0, 7.0); 00057 00058 minMaxLoc(blurredIm, &minVal, &maxVal); 00059 00060 //dst = Mat::zeros(src.size(), CV_8UC3); 00061 00062 printf("%s << min/max = (%f / %f)\n", __FUNCTION__, minVal, maxVal); 00063 00064 for (unsigned int iii = minVal; iii < maxVal; iii++) { 00065 cv::threshold(blurredIm, workingIm, iii, 255, CV_THRESH_BINARY); 00066 00067 std::vector<std::vector<cv::Point> > contours; 00068 cv::Mat contourOutput = workingIm.clone(); 00069 cv::findContours( contourOutput, contours, CV_RETR_LIST, CV_CHAIN_APPROX_NONE ); 00070 00071 //Draw the contours 00072 00073 for (size_t idx = 0; idx < contours.size(); idx++) { 00074 cv::drawContours(contourImage, contours, idx, colors[idx % 3]); 00075 } 00076 00077 00078 } 00079 00080 imshow("workingIm", contourImage); 00081 waitKey(1); 00082 00083 } 00084 00085 double findBestAlpha(const Mat& K1, const Mat& K2, const Mat& coeff1, const Mat& coeff2, const Size& camSize, const Mat& R0, const Mat& R1) { 00086 00087 Mat newCamMat_1, newCamMat_2; 00088 00089 Rect roi1, roi2; 00090 00091 double alpha = 0.00; 00092 bool centerPrincipalPoint = true; 00093 00094 Mat map11, map12, map21, map22; 00095 00096 unsigned int protectionCounter = 0; 00097 00098 while (1) { 00099 00100 // printf("%s << alpha = (%f)\n", __FUNCTION__, alpha); 00101 00102 Mat white = Mat::ones(camSize, CV_8UC1); 00103 Mat mapped_1, mapped_2; 00104 00105 newCamMat_1 = getOptimalNewCameraMatrix(K1, coeff1, camSize, alpha, camSize, &roi1, centerPrincipalPoint); 00106 newCamMat_2 = getOptimalNewCameraMatrix(K2, coeff2, camSize, alpha, camSize, &roi2, centerPrincipalPoint); 00107 00108 initUndistortRectifyMap(K1, coeff1, R0, newCamMat_1, camSize, CV_32FC1, map11, map12); 00109 initUndistortRectifyMap(K2, coeff2, R1, newCamMat_2, camSize, CV_32FC1, map21, map22); 00110 00111 double minVal, maxVal; 00112 00113 remap(white, mapped_1, map11, map12, INTER_LINEAR, BORDER_CONSTANT, 0); 00114 00115 minMaxLoc(mapped_1, &minVal, &maxVal); 00116 00117 if (minVal == 1.0) { 00118 remap(white, mapped_2, map11, map12, INTER_LINEAR, BORDER_CONSTANT, 0); 00119 minMaxLoc(mapped_1, &minVal, &maxVal); 00120 00121 if (minVal == 1.0) { 00122 break; 00123 } 00124 } 00125 00126 if (protectionCounter == 100) { 00127 alpha = 0.0; 00128 break; 00129 } 00130 00131 alpha -= 0.01; 00132 00133 } 00134 00135 return alpha; 00136 00137 } 00138 00139 void drawEpipolarLines(Mat& im1, Mat& im2, Mat& F) { 00140 00141 vector<Point2f> inputPoints; 00142 vector<Point3f> outputLines[2]; 00143 00144 for (unsigned int iii = 0; iii < 8; iii++) { 00145 inputPoints.push_back(Point2f(320.0, 60.0*double(iii)+30.0)); 00146 } 00147 00148 computeCorrespondEpilines(inputPoints, 1, F, outputLines[0]); 00149 computeCorrespondEpilines(inputPoints, 2, F, outputLines[1]); 00150 00151 for (unsigned int iii = 0; iii < inputPoints.size(); iii++) { 00152 00153 for (unsigned int jjj = 0; jjj < 2; jjj++) { 00154 if (outputLines[jjj].at(iii).y != 0.0) { 00155 00156 Point2f start, end; 00157 00158 start.x = 0.0; 00159 start.y = -outputLines[jjj].at(iii).z / outputLines[jjj].at(iii).y; 00160 00161 end.x = 640.0; 00162 end.y = (-outputLines[jjj].at(iii).z - outputLines[jjj].at(iii).x*end.x) / outputLines[jjj].at(iii).y; 00163 00164 start *= 16.0; 00165 end *= 16.0; 00166 00167 if (jjj == 0) { 00168 line(im2, start, end, CV_RGB(0,0,255), 1, CV_AA, 4); 00169 } else { 00170 line(im1, start, end, CV_RGB(0,0,255), 1, CV_AA, 4); 00171 } 00172 00173 00174 } 00175 } 00176 00177 00178 00179 } 00180 00181 } 00182 00183 bool relevelImages(const Mat& im1, const Mat& im2, const Mat& old_depth, const Mat& R1, const Mat& R2, const Mat& t, const Mat& Q1, const Mat& Q2, Mat& pim1, Mat& pim2, const Mat& map11, const Mat& map12, const Mat& map21, const Mat& map22) { 00184 00185 Mat _8bit1, _8bit2, mapped1, mapped2; 00186 00187 double minVal_1, maxVal_1, minVal_2, maxVal_2, minVal, maxVal; 00188 00189 minMaxLoc(im1, &minVal_1, &maxVal_1); 00190 minMaxLoc(im2, &minVal_2, &maxVal_2); 00191 00192 // ROS_WARN("minVal_(1/2) = (%f / %f); maxVal_(1/2) = (%f / %f)", minVal_1, minVal_2, maxVal_1, maxVal_2); 00193 00194 minVal = min(minVal_1, minVal_2); 00195 maxVal = max(maxVal_1, maxVal_2); 00196 00197 // ROS_WARN("minVal = (%f); maxVal = (%f)", minVal, maxVal); 00198 00199 if (old_depth.rows == 0) { 00200 00201 adaptiveDownsample(im1, _8bit1); 00202 adaptiveDownsample(im2, _8bit2); 00203 00204 remap(_8bit1, mapped1, map11, map12, INTER_LINEAR); 00205 GaussianBlur(mapped1, pim1, Size(7,7), 0.5, 0.5); 00206 00207 remap(_8bit2, mapped2, map21, map22, INTER_LINEAR); 00208 GaussianBlur(mapped2, pim2, Size(7,7), 0.5, 0.5); 00209 00210 } else { 00211 00212 printf("%s << Using existing depth map to radiometrically calibrate...\n", __FUNCTION__); 00213 00214 Mat mapped16_1, mapped16_2; 00215 remap(im1, mapped16_1, map11, map12, INTER_LINEAR); 00216 remap(im2, mapped16_2, map21, map22, INTER_LINEAR); 00217 00218 double grad, shift; 00219 00220 findRadiometricMapping2(mapped16_1, mapped16_2, old_depth, R1, R2, t, Q1, Q2, grad, shift); 00221 00222 applyIntensityShift(im1, _8bit1, im2, _8bit2, grad, shift); 00223 00224 /* 00225 adaptiveDownsample(im1, _8bit1); 00226 adaptiveDownsample(im2, _8bit2); 00227 */ 00228 00229 remap(_8bit1, mapped1, map11, map12, INTER_LINEAR); 00230 GaussianBlur(mapped1, pim1, Size(7,7), 0.5, 0.5); 00231 00232 remap(_8bit2, mapped2, map21, map22, INTER_LINEAR); 00233 GaussianBlur(mapped2, pim2, Size(7,7), 0.5, 0.5); 00234 00235 } 00236 00237 00238 00239 00240 00241 } 00242 00243 double fitFixedLine(vector<unsigned short>& x, vector<unsigned short>& y, double grad) { 00244 00245 double shift; 00246 00247 // Find min and max values... 00248 00249 if (x.size() == 0) { 00250 return 0.0; 00251 } 00252 00253 unsigned short minVal = x.at(0); 00254 unsigned short maxVal = x.at(0); 00255 00256 for (unsigned int iii = 0; iii < x.size(); iii++) { 00257 00258 if (x.at(iii) < minVal) { 00259 minVal = x.at(iii); 00260 } 00261 00262 if (x.at(iii) > maxVal) { 00263 maxVal = x.at(iii); 00264 } 00265 00266 if (y.at(iii) < minVal) { 00267 minVal = y.at(iii); 00268 } 00269 00270 if (y.at(iii) > maxVal) { 00271 maxVal = y.at(iii); 00272 } 00273 00274 00275 } 00276 00277 printf("%s << minVal = (%d); maxVal = (%d)\n", __FUNCTION__, minVal, maxVal); 00278 00279 00280 double bestError = 9e99; 00281 unsigned int bestCount = 0; 00282 00283 //for (double t_shift = -abs(maxVal-minVal); t_shift < abs(maxVal-minVal); t_shift += 0.5) { 00284 00285 for (double t_shift = -500; t_shift < 500; t_shift += 0.5) { 00286 00287 double totalError = 0.0; 00288 unsigned int totalCount = 0; 00289 00290 for (unsigned int iii = 0; iii < x.size(); iii++) { 00291 00292 double err = abs(x.at(iii) - (grad * double(y.at(iii)) + t_shift)); 00293 totalError += err / double(x.size()); 00294 00295 if (err < 5.0) { 00296 totalCount++; 00297 } 00298 00299 } 00300 00301 if (totalError < bestError) { 00302 //printf("%s << totalError with (%f) is (%f)\n", __FUNCTION__, t_shift, totalError); 00303 bestError = totalError; 00304 //shift = t_shift; 00305 } 00306 00307 if (totalCount > bestCount) { 00308 bestCount = totalCount; 00309 shift = t_shift; 00310 //printf("%s << best count so far of (%d) with shift of (%f)\n", __FUNCTION__, bestCount, shift); 00311 } 00312 00313 } 00314 00315 return shift; 00316 00317 } 00318 00319 void findRadiometricMapping2(const Mat& im1, const Mat& im2, const Mat& depth, const Mat& R1, const Mat& R2, const Mat& t, const Mat& Q1, const Mat& Q2, double& grad, double& shift) { 00320 00321 vector<Point> pts[2]; 00322 vector<unsigned short> intensities[2]; 00323 00324 unsigned short val; 00325 float f_val; 00326 00327 Mat xyz; 00328 reprojectImageTo3D(depth, xyz, Q1, true); 00329 00330 //printf("%s << xyz.size() = (%d, %d)\n", __FUNCTION__, xyz.rows, xyz.cols); 00331 // saveXYZ(point_cloud_filename, xyz); 00332 00333 /* 00334 Mat debug1, debug2, debug1_, debug2_; 00335 00336 adaptiveDownsample(im1, debug1); 00337 adaptiveDownsample(im2, debug2); 00338 00339 cvtColor(debug1, debug1_, CV_GRAY2RGB); 00340 cvtColor(debug2, debug2_, CV_GRAY2RGB); 00341 */ 00342 00343 for (unsigned int iii = 0; iii < depth.rows; iii += 1) { 00344 for (unsigned int jjj = 0; jjj < depth.cols; jjj += 1) { 00345 00346 val = depth.at<unsigned short>(iii,jjj); 00347 00348 f_val = xyz.at<Vec3f>(iii,jjj)[2]; 00349 00350 if ((f_val != 10000) && (!isinf(f_val))) { // ((f_val < FLT_MAX) && (f_val > FLT_MIN) && (f_val != 10000)) { 00351 //printf("%s << xyz(%d, %d) = (%f, %f, %f)\n", __FUNCTION__, iii, jjj, xyz.at<Vec3f>(iii,jjj)[0], xyz.at<Vec3f>(iii,jjj)[1], xyz.at<Vec3f>(iii,jjj)[2]); 00352 00353 // Get x, y for camera (1) back... 00354 00355 // [x y d 1]' = Q.inv() * [X Y Z W]' 00356 // [x/W y/W d/W 1/W]' = Q.inv() * [3d.x 3d.y 3d.z 1]'; 00357 00358 00359 Mat _3dLoc = Mat::zeros(4, 1, CV_64FC1); 00360 _3dLoc.at<double>(0,0) = xyz.at<Vec3f>(iii,jjj)[0]; 00361 _3dLoc.at<double>(1,0) = xyz.at<Vec3f>(iii,jjj)[1]; 00362 _3dLoc.at<double>(2,0) = xyz.at<Vec3f>(iii,jjj)[2]; 00363 _3dLoc.at<double>(3,0) = 1.0; 00364 00365 Mat coords_1 = Q1.inv() * _3dLoc; 00366 Mat coords_2 = Q2.inv() * _3dLoc; 00367 00368 Point reproj_1, reproj_2; 00369 unsigned short redist_1, redist_2; 00370 00371 if ((coords_1.at<double>(3,0) != 0.0) && (coords_2.at<double>(3,0) != 0.0)) { 00372 00373 reproj_1.y = coords_1.at<double>(1,0) / coords_1.at<double>(3,0); 00374 reproj_1.x = coords_1.at<double>(0,0) / coords_1.at<double>(3,0); 00375 redist_1 = coords_1.at<double>(2,0) / coords_1.at<double>(3,0); 00376 00377 reproj_2.y = coords_2.at<double>(1,0) / coords_2.at<double>(3,0); 00378 reproj_2.x = coords_2.at<double>(0,0) / coords_2.at<double>(3,0); 00379 redist_2 = coords_2.at<double>(2,0) / coords_2.at<double>(3,0); 00380 00381 //printf("%s << reproj_1 = (%d, %d, %d) vs pt = (%d, %d, %d)\n", __FUNCTION__, reproj_1.x, reproj_1.y, redist_1, iii, jjj, val); 00382 //printf("%s << reproj_2 = (%d, %d, %d)\n", __FUNCTION__, reproj_2.x, reproj_2.y, redist_2); 00383 00384 00385 00386 //circle(debug1_, reproj_1, 1, CV_RGB(255, 0, 0), 1, CV_AA, 0); 00387 //circle(debug2_, reproj_2, 1, CV_RGB(255, 0, 0), 1, CV_AA, 0); 00388 00389 00390 00391 // perspectiveTransform(InputArray src, OutputArray dst, InputArray m); 00392 vector<Point3d> inputLoc; 00393 inputLoc.push_back(Point3d(_3dLoc.at<double>(0,0), _3dLoc.at<double>(1,0), _3dLoc.at<double>(2,0))); 00394 vector<Point3d> outputLoc; 00395 //perspectiveTransform(inputLoc, outputLoc, Q1.inv()); 00396 perspectiveTransform(inputLoc, outputLoc, Q2.inv()); 00397 //printf("%s << reproj_2b = (%f, %f, %f)\n", __FUNCTION__, outputLoc.at(0).x, outputLoc.at(0).y, outputLoc.at(0).z); 00398 00399 } 00400 00401 00402 00403 //printf("%s << coord = (%d, %d, %d) vs pt = (%d, %d, %d)\n", __FUNCTION__, coords.at<double>(0,0), coords.at<double>(1,0), coords.at<double>(2,0), coords.at<double>(3,0), iii, jjj); 00404 00405 int buffer = 40; 00406 00407 if ((reproj_1.y > buffer) && (reproj_1.y < 480-buffer) && (reproj_1.x > buffer) && (reproj_1.x < 640-buffer)) { 00408 if ((reproj_2.y > buffer) && (reproj_2.y < 480-buffer) && (reproj_2.x > buffer) && (reproj_2.x < 640-buffer)) { 00409 00410 if ((im1.at<unsigned short>(reproj_1.y, reproj_1.x) != 0) && (im2.at<unsigned short>(reproj_2.y, reproj_2.x) != 0)) { 00411 intensities[0].push_back(im1.at<unsigned short>(reproj_1.y, reproj_1.x)); 00412 //intensities[1].push_back(im2.at<unsigned short>(reproj_2.y, reproj_2.x)); 00413 intensities[1].push_back(im2.at<unsigned short>(reproj_2.y, reproj_2.x)); 00414 } 00415 00416 } 00417 } 00418 00419 00420 } 00421 00422 } 00423 } 00424 00425 shift = fitFixedLine(intensities[0], intensities[1], 1.0); 00426 00427 Mat dispMat; 00428 00429 double percentileVals[1] = { 0.500 }; 00430 double intensityVals[2][1]; 00431 findPercentiles(im1, intensityVals[0], percentileVals, 1); 00432 findPercentiles(im2, intensityVals[1], percentileVals, 1); 00433 00434 00435 00436 00437 00438 /* 00439 imshow("debug_1", debug1_); 00440 waitKey(1); 00441 imshow("debug_2", debug2_); 00442 waitKey(1); 00443 */ 00444 00445 printf("%s << intensities[0].size() = %d\n", __FUNCTION__, intensities[0].size()); 00446 00447 // Simple median-based equation estimation: 00448 grad = 1.00; 00449 //shift = (intensityVals[0][0] - intensityVals[1][0]); 00450 00451 plotPoints(dispMat, intensities[0], intensities[1], intensityVals[0][0], intensityVals[1][0], grad, shift); 00452 00453 imshow("intensities", dispMat); 00454 waitKey(1); 00455 00456 printf("%s << Estimated equation = (%f) * m + (%f)\n", __FUNCTION__, grad, shift); 00457 00458 } 00459 00460 void plotPoints(Mat& dispMat, vector<unsigned short>& i1, vector<unsigned short>& i2, unsigned short median_1, unsigned short median_2, double grad, double shift) { 00461 00462 dispMat = Mat::zeros(480, 640, CV_8UC3); 00463 00464 for (unsigned int iii = 0; iii < dispMat.rows; iii++) { 00465 for (unsigned int jjj = 0; jjj < dispMat.cols; jjj++) { 00466 00467 dispMat.at<Vec3b>(iii,jjj)[0] = 255; 00468 dispMat.at<Vec3b>(iii,jjj)[1] = 255; 00469 dispMat.at<Vec3b>(iii,jjj)[2] = 255; 00470 00471 } 00472 } 00473 00474 if (i1.size() == 0) { 00475 return; 00476 } 00477 00478 unsigned short minVal_1 = i1.at(0); 00479 unsigned short maxVal_1 = i1.at(0); 00480 00481 unsigned short minVal_2 = i2.at(0); 00482 unsigned short maxVal_2 = i2.at(0); 00483 00484 for (unsigned int iii = 0; iii < i1.size(); iii++) { 00485 00486 if (i1.at(iii) < minVal_1) { 00487 minVal_1 = i1.at(iii); 00488 } 00489 00490 if (i2.at(iii) < minVal_2) { 00491 minVal_2 = i2.at(iii); 00492 } 00493 00494 if (i1.at(iii) > maxVal_1) { 00495 maxVal_1 = i1.at(iii); 00496 } 00497 00498 if (i2.at(iii) > maxVal_2) { 00499 maxVal_2 = i2.at(iii); 00500 } 00501 00502 } 00503 00504 //minVal = 7000; 00505 //maxVal = 9000; 00506 00507 printf("%s << minVal/maxVal = (%d, %d) : (%d, %d)\n", __FUNCTION__, minVal_1, maxVal_1, minVal_2, maxVal_2); 00508 00509 00510 00511 int row, col; 00512 00513 for (unsigned int iii = 0; iii < i1.size(); iii++) { 00514 00515 00516 row = 480.0 * (double(i1.at(iii) - minVal_1) / double(maxVal_1 - minVal_1)); 00517 col = 640.0 * (double(i2.at(iii) - minVal_2) / double(maxVal_2 - minVal_2)); 00518 00519 if (iii == 50) { 00520 //printf("%s << row = (%d); col = (%d)\n", __FUNCTION__, row, col); 00521 //printf("%s << i1 = (%d); i2 = (%d)\n", __FUNCTION__, i1.at(iii), i2.at(iii)); 00522 } 00523 00524 circle(dispMat, Point(col,row), 1, CV_RGB(255, 0, 0), 1, CV_AA, 0); 00525 00526 //dispMat.at<Vec3b>(row,col)[0] = 0; 00527 //dispMat.at<Vec3b>(row,col)[1] = 0; 00528 00529 } 00530 00531 // draw a line assuming equal gradient and a shift of the median difference 00532 if ((median_1 != 0) && (median_2 != 0)) { 00533 printf("%s << Median comparison = (%d vs %d)\n", __FUNCTION__, median_1, median_2); 00534 } 00535 00536 int row_disp = (median_2 - median_1) / 480.0; 00537 00538 Point p1, p2; 00539 00540 unsigned int basic_pt_x = minVal_2; 00541 unsigned int basic_pt_y = grad * minVal_2 + shift; 00542 00543 row = 480.0 * (double(basic_pt_y - minVal_1) / double(maxVal_1 - minVal_1)); 00544 col = 640.0 * (double(basic_pt_x - minVal_2) / double(maxVal_2 - minVal_2)); 00545 00546 p1 = Point(col,row); 00547 00548 unsigned int new_pt_x = maxVal_2; 00549 unsigned int new_pt_y = grad * maxVal_2 + shift; 00550 00551 row = 480.0 * (double(new_pt_y - minVal_1) / double(maxVal_1 - minVal_1)); 00552 col = 640.0 * (double(new_pt_x - minVal_2) / double(maxVal_2 - minVal_2)); 00553 00554 p2 = Point(col,row); 00555 00556 printf("%s << Drawing line from (%d, %d) to (%d, %d)\n", __FUNCTION__, p1.x, p1.y, p2.x, p2.y); 00557 line(dispMat, p1, p2, CV_RGB(0,0,255), 2, CV_AA, 0); 00558 00559 00560 } 00561 00562 /* 00563 bool findRadiometricMapping(const Mat& im1, const Mat& im2, double& grad, double& shift, const Mat& pim1, const Mat& pim2) { 00564 00565 Ptr<FeatureDetector> detector; 00566 detector = new SurfFeatureDetector( 5.00 ); 00567 00568 vector<KeyPoint> kp1, kp2; 00569 detector -> detect(pim1, kp1); 00570 detector -> detect(pim2, kp2); 00571 00572 Ptr<DescriptorExtractor> extractor; 00573 extractor = DescriptorExtractor::create( "SURF" ); 00574 00575 Mat d1, d2; 00576 extractor->compute(pim1, kp1, d1); 00577 extractor->compute(pim2, kp2, d2); 00578 00579 Ptr<DescriptorMatcher> descriptorMatcher; 00580 descriptorMatcher = DescriptorMatcher::create("BruteForce"); 00581 double ransacReprojThreshold = 1.0; 00582 00583 vector<DMatch> filteredMatches; 00584 00585 crossCheckMatching( descriptorMatcher, d1, d2, filteredMatches, 1 ); 00586 00587 Mat drawImg; 00588 00589 int matchesFlag = DrawMatchesFlags::NOT_DRAW_SINGLE_POINTS; 00590 00591 00592 00593 00594 00595 vector<int> queryIdxs( filteredMatches.size() ), trainIdxs( filteredMatches.size() ); 00596 for( size_t i = 0; i < filteredMatches.size(); i++ ) 00597 { 00598 queryIdxs[i] = filteredMatches[i].queryIdx; 00599 trainIdxs[i] = filteredMatches[i].trainIdx; 00600 } 00601 00602 vector<Point2f> pts1, pts2; 00603 00604 KeyPoint::convert(kp1, pts1, queryIdxs); 00605 KeyPoint::convert(kp2, pts2, trainIdxs); 00606 00607 printf("%s << filteredMatches.size() = (%d)\n", __FUNCTION__, filteredMatches.size()); 00608 // printf("%s << pts1.size() = (%d)\n", __FUNCTION__, pts1.size()); 00609 00610 00611 00612 00613 //int validMatches = countNonZero(validityMask); 00614 //cout << "validMatches = " << validMatches << endl; 00615 00616 // Can make more efficient by implementing the threshold at the matching stage 00617 double thresh = 15.0; 00618 00619 for (unsigned int iii = 0; iii < pts1.size(); iii++) { 00620 00621 if (abs(pts1.at(iii).y - pts2.at(iii).y) > thresh) { 00622 pts1.erase(pts1.begin() + iii); 00623 pts2.erase(pts2.begin() + iii); 00624 iii--; 00625 } 00626 00627 } 00628 00629 //displayKeypoints(pim1, pts1, drawImg, CV_RGB(255, 0, 0)); 00630 //displayKeypoints(drawImg, pts2, drawImg, CV_RGB(0, 0, 255)); 00631 00632 showMatches(pim1, pts1, pim2, pts2, drawImg); 00633 00634 // drawMatches( pim1, kp1, pim2, kp2, filteredMatches, drawImg, CV_RGB(0, 0, 255), CV_RGB(255, 0, 0), vector<char>(), matchesFlag ); 00635 00636 imshow("display", drawImg); 00637 waitKey(1); 00638 00639 vector<Point2f> sampleValues; 00640 00641 for (unsigned int iii = 0; iii < pts1.size(); iii++) { 00642 00643 Point coord_1(pts1.at(iii).x, pts1.at(iii).y); 00644 Point coord_2(pts2.at(iii).x, pts2.at(iii).y); 00645 00646 Point2f sample; 00647 00648 if ((coord_1.x >= 0) && (coord_1.y >= 0) && (coord_1.x < 640) && (coord_1.y < 480)) { 00649 00650 if ((coord_2.x >= 0) && (coord_2.y >= 0) && (coord_2.x < 640) && (coord_2.y < 480)) { 00651 00652 //printf("%s << coord_1 = (%d, %d); coord_2 = (%d, %d)\n", __FUNCTION__, coord_1.x, coord_1.y, coord_2.x, coord_2.y); 00653 00654 sample.x = float(im1.at<unsigned short>(coord_1.y, coord_1.x)); 00655 sample.y = float(im2.at<unsigned short>(coord_2.y, coord_2.x)); 00656 00657 //printf("%s << sample = (%f, %f)\n", __FUNCTION__, sample.x, sample.y); 00658 00659 sampleValues.push_back(sample); 00660 00661 } 00662 00663 00664 } 00665 00666 00667 00668 } 00669 00670 Mat samplePlot = Mat::ones(480, 640, CV_8UC1); 00671 samplePlot *= 255; 00672 } 00673 */