$search
00001 00005 #include "sba.hpp" 00006 00007 void findRelevantIndices(vector<featureTrack>& tracks, vector<unsigned int>& triangulated, vector<unsigned int>& untriangulated, unsigned int last_index, unsigned int new_index) { 00008 00009 //unsigned int min_sightings = max(0, (((int) new_index) - ((int) last_index)) / 2); 00010 00011 for (unsigned int iii = 0; iii < tracks.size(); iii++) { 00012 00013 if (tracks.at(iii).isTriangulated) { 00014 triangulated.push_back(iii); 00015 /* 00016 unsigned int sightings = 0; 00017 00018 for (unsigned int jjj = 0; jjj < tracks.at(iii).locations.size(); jjj++) { 00019 00020 if (tracks.at(iii).locations.at(jjj).imageIndex <= new_index) { 00021 sightings++; 00022 } 00023 00024 } 00025 * */ 00026 00027 /* 00028 if (sightings >= min_sightings) { 00029 triangulated.push_back(iii); 00030 } 00031 * */ 00032 } else { 00033 untriangulated.push_back(iii); 00034 } 00035 00036 00037 00038 } 00039 00040 00041 } 00042 00043 void findIntermediatePoses(vector<featureTrack>& tracks, cameraParameters& camData, Mat *cameras, unsigned int image_idx_1, unsigned int image_idx_2, bool fixBothEnds) { 00044 00045 printf("%s << ENTERED.\n", __FUNCTION__); 00046 00047 vector<unsigned int> activeTrackIndices, fullSpanIndices, untriangulatedIndices; 00048 00049 int subsequence_iters = 10; 00050 00051 getActiveTracks(activeTrackIndices, tracks, image_idx_1, image_idx_2); 00052 filterToCompleteTracks(fullSpanIndices, activeTrackIndices, tracks, image_idx_1, image_idx_2); 00053 00054 reduceActiveToTriangulated(tracks, fullSpanIndices, untriangulatedIndices); 00055 00056 vector<Point2f> pts1, pts2; 00057 getPointsFromTracks(tracks, pts1, pts2, image_idx_1, image_idx_2); 00058 00059 vector<Point3d> ptsInCloud; 00060 //printf("%s << ptsInCloud.size() (pre-update) = %d\n", __FUNCTION__, ptsInCloud.size()); 00061 getActive3dPoints(tracks, fullSpanIndices, ptsInCloud); 00062 //printf("%s << ptsInCloud.size() (post-update) = %d\n", __FUNCTION__, ptsInCloud.size()); 00063 00064 int relativeIndex = image_idx_2 - image_idx_1; 00065 00066 SysSBA subsys; 00067 addPointsToSBA(subsys, ptsInCloud); 00068 00069 addFixedCamera(subsys, camData, cameras[image_idx_1]); 00070 addFixedCamera(subsys, camData, cameras[image_idx_2]); 00071 00072 addProjectionsToSBA(subsys, pts1, 0); // keyframe_idx_1 00073 addProjectionsToSBA(subsys, pts2, 1); 00074 00075 if (fixBothEnds) { 00076 subsys.nFixed = 2; 00077 } else { 00078 subsys.nFixed = 1; 00079 } 00080 00081 00082 for (int jjj = 1; jjj < relativeIndex; jjj++) { 00083 00084 vector<Point2f> latestPoints; 00085 getCorrespondingPoints(tracks, pts1, latestPoints, image_idx_1, image_idx_1+jjj); 00086 00087 00088 00089 vector<Point3f> objectPoints; 00090 Point3f tmpPt; 00091 00092 for (unsigned int kkk = 0; kkk < ptsInCloud.size(); kkk++) { 00093 tmpPt = Point3f((float) ptsInCloud.at(kkk).x, (float) ptsInCloud.at(kkk).y, (float) ptsInCloud.at(kkk).z); 00094 objectPoints.push_back(tmpPt); 00095 } 00096 00097 Mat t, R, Rvec; 00098 00099 //printf("%s << Solving PnP... (%d) (oP.size() = %d; lP.size() = %d)\n", __FUNCTION__, jjj, objectPoints.size(), latestPoints.size()); 00100 00101 //solvePnPRansac(InputArray objectPoints, InputArray imagePoints, InputArray cameraMatrix, InputArray distCoeffs, OutputArray rvec, OutputArray tvec, bool useExtrinsicGuess=false, int iterationsCount=100, float reprojectionError=8.0, int minInliersCount=100, OutputArray inliers=noArray() ); 00102 solvePnPRansac(objectPoints, latestPoints, camData.K, camData.blankCoeffs, Rvec, t); 00103 00104 Rodrigues(Rvec, R); 00105 00106 //cout << __FUNCTION__ << " << [" << jjj << "] R = " << R << endl; 00107 //cout << __FUNCTION__ << " << [" << jjj << "] t = " << t << endl; 00108 00109 Mat newCam; 00110 compileTransform(newCam, R, t); 00111 00112 // Inverting camera "learned" by PnP since it always seems to need to be inverted when passed to 00113 // and from SBA... 00114 00115 Mat newCamC; 00116 projectionToTransformation(newCam, newCamC); 00117 newCamC = newCamC.inv(); 00118 transformationToProjection(newCamC, newCam); 00119 00120 addNewCamera(subsys, camData, newCam); 00121 00122 addProjectionsToSBA(subsys, latestPoints, jjj+1); 00123 00124 //avgError = optimizeSystem(subsys, 1e-4, 10); 00125 //printf("%s << Progressive subsequence BA error = %f.\n", __FUNCTION__, avgError); 00126 00127 //drawGraph2(subsys, camera_pub, points_pub, decimation, bicolor); 00128 00129 } 00130 00131 printf("%s << About to optimize subsystem... (nFixed = %d)\n", __FUNCTION__, subsys.nFixed); 00132 //if (iii == 0) { 00133 00134 double avgError = optimizeSystem(subsys, 1e-4, subsequence_iters); 00135 00136 if (0) { 00137 //drawGraph2(subsys, camera_pub, points_pub, decimation, bicolor); 00138 } 00139 00140 if (avgError < 0.0) { 00141 printf("%s << ERROR! Subsystem optimization failed to converge..\n", __FUNCTION__); 00142 } 00143 00144 printf("%s << Subsystem optimized\n", __FUNCTION__); 00145 00146 00147 00148 00149 00150 retrieveCameraPose(subsys, cameras[image_idx_1], 0); 00151 retrieveCameraPose(subsys, cameras[image_idx_2], 1); 00152 00153 for (unsigned int ttt = 1; ttt < image_idx_2-image_idx_1; ttt++) { 00154 retrieveCameraPose(subsys, cameras[image_idx_1+ttt], ttt+1); 00155 } 00156 00157 ptsInCloud.clear(); 00158 retrieveAllPoints(ptsInCloud, subsys); 00159 00160 updateTriangulatedPoints(tracks, fullSpanIndices, ptsInCloud); 00161 } 00162 00163 double getFeatureMotion(vector<featureTrack>& tracks, vector<unsigned int>& indices, unsigned int idx_1, unsigned int idx_2) { 00164 00165 vector<double> distances, distances_x, distances_y; 00166 00167 for (unsigned int iii = 0; iii < indices.size(); iii++) { 00168 00169 for (unsigned int jjj = 0; jjj < tracks.at(indices.at(iii)).locations.size()-1; jjj++) { 00170 00171 if (tracks.at(indices.at(iii)).locations.at(jjj).imageIndex == int(idx_1)) { 00172 00173 for (unsigned int kkk = jjj+1; kkk < tracks.at(indices.at(iii)).locations.size(); kkk++) { 00174 00175 if (tracks.at(indices.at(iii)).locations.at(kkk).imageIndex == int(idx_2)) { 00176 00177 double dist = distanceBetweenPoints(tracks.at(indices.at(iii)).locations.at(jjj).featureCoord, tracks.at(indices.at(iii)).locations.at(kkk).featureCoord); 00178 00179 double dist_x = tracks.at(indices.at(iii)).locations.at(jjj).featureCoord.x - tracks.at(indices.at(iii)).locations.at(kkk).featureCoord.x; 00180 double dist_y = tracks.at(indices.at(iii)).locations.at(jjj).featureCoord.y - tracks.at(indices.at(iii)).locations.at(kkk).featureCoord.y; 00181 00182 distances_x.push_back(dist_x); 00183 distances_y.push_back(dist_y); 00184 distances.push_back(dist); 00185 00186 } 00187 00188 } 00189 00190 } 00191 00192 00193 } 00194 00195 } 00196 00197 double mean_dist = 0.00, std_dev = 0.00, mean_x = 0.00, mean_y = 0.00, std_x = 0.00, std_y = 0.00; 00198 00199 for (unsigned int iii = 0; iii < distances.size(); iii++) { 00200 mean_dist += (distances.at(iii) / ((double) distances.size())); 00201 mean_x += (distances_x.at(iii) / ((double) distances.size())); 00202 mean_y += (distances_y.at(iii) / ((double) distances.size())); 00203 00204 00205 } 00206 00207 for (unsigned int iii = 0; iii < distances.size(); iii++) { 00208 std_dev += pow(distances.at(iii) - mean_dist, 2.0); 00209 std_x += pow(distances_x.at(iii) - mean_x, 2.0); 00210 std_y += pow(distances_y.at(iii) - mean_y, 2.0); 00211 } 00212 00213 std_dev /= distances.size(); 00214 std_x /= distances.size(); 00215 std_y /= distances.size(); 00216 00217 pow(std_dev, 0.5); 00218 pow(std_x, 0.5); 00219 pow(std_y, 0.5); 00220 00221 00222 //printf("%s << (%f, %f, %f) : (%f, %f, %f)\n", __FUNCTION__, mean_dist, mean_y, mean_x, std_dev, std_x, std_y); 00223 00224 // Need to have some variation in x OR y translation, otherwise it could just be a homography 00225 return ((std_x + std_y) / 2.0); 00226 00227 return mean_dist; 00228 00229 } 00230 00231 void removePoorTracks(vector<featureTrack>& tracks, cameraParameters& camData, Mat *cameras, unsigned int start_cam, unsigned int finish_cam) { 00232 00233 //return; 00234 00235 printf("%s << Entered.\n", __FUNCTION__); 00236 00237 // go through each 3D point and find projection to each camera, if the projection is too far off 00238 // then remove it 00239 00240 00241 00242 SysSBA sys; 00243 00244 for (unsigned int iii = 0; iii <= finish_cam; iii++) { 00245 if (cameras[iii].rows < 3) { 00246 addBlankCamera(sys, camData); 00247 } else { 00248 addNewCamera(sys, camData, cameras[iii]); 00249 //cout << cameras[iii] << endl; 00250 } 00251 00252 00253 } 00254 00255 printf("%s << sys.nodes.size() = %d\n", __FUNCTION__, sys.nodes.size()); 00256 00257 for (unsigned int iii = 0; iii < tracks.size(); iii++) { 00258 if (tracks.at(iii).isTriangulated) { 00259 00260 Vector4d point_3(tracks.at(iii).get3dLoc().x, tracks.at(iii).get3dLoc().y, tracks.at(iii).get3dLoc().z, 1.0); 00261 00262 for (unsigned int jjj = 0; jjj < tracks.at(iii).locations.size(); jjj++) { 00263 00264 unsigned int camIndex = tracks.at(iii).locations.at(jjj).imageIndex; 00265 00266 //printf("%s << Checking (%d)(%d)(%d)...\n", __FUNCTION__, iii, jjj, camIndex); 00267 00268 if ((camIndex >= start_cam) && (camIndex <= finish_cam)) { 00269 00270 // Find 2d projection based on 3d point; compare with 2d loc stored in tracks structure 00271 00272 Vector2d proj; 00273 00274 //printf("%s << nodes(%d) trans = (%f, %f, %f)\n", __FUNCTION__, camIndex, sys.nodes.at(camIndex).trans.x(), sys.nodes.at(camIndex).trans.y(), sys.nodes.at(camIndex).trans.z()); 00275 00276 sys.nodes.at(camIndex).setProjection(); 00277 00278 00279 //printf("%s << w2n = (%f, %f, %f; %f %f %f; ...)\n", __FUNCTION__, sys.nodes.at(camIndex).w2n(0,0), sys.nodes.at(camIndex).w2n(0,1), sys.nodes.at(camIndex).w2n(0,2), sys.nodes.at(camIndex).w2n(1,0), sys.nodes.at(camIndex).w2n(1,1), sys.nodes.at(camIndex).w2n(1,2)); 00280 00281 00282 sys.nodes.at(camIndex).project2im(proj, point_3); 00283 00284 //printf("%s << t(%d)c(%d) = (%f, %f) vs (%f, %f)\n", __FUNCTION__, iii, camIndex, proj.x(), proj.y(), tracks.at(iii).locations.at(jjj).featureCoord.x, tracks.at(iii).locations.at(jjj).featureCoord.y); 00285 00286 } 00287 00288 } 00289 00290 } 00291 } 00292 00293 } 00294 00295 void copySys(const SysSBA& src, SysSBA& dst) { 00296 00297 dst.tracks.clear(); 00298 dst.nodes.clear(); 00299 00300 for (unsigned int iii = 0; iii < src.tracks.size(); iii++) { 00301 dst.tracks.push_back(src.tracks.at(iii)); 00302 } 00303 00304 for (unsigned int iii = 0; iii < src.nodes.size(); iii++) { 00305 dst.nodes.push_back(src.nodes.at(iii)); 00306 } 00307 00308 } 00309 00310 void rescaleSBA(SysSBA& sba, unsigned int idx1, unsigned int idx2) { 00311 00312 // Find the distance from first to last camera 00313 double totalDist = pow(pow(sba.nodes.at(idx2).trans.x() - sba.nodes.at(idx1).trans.x(), 2.0) + pow(sba.nodes.at(idx2).trans.y() - sba.nodes.at(idx1).trans.y(), 2.0) + pow(sba.nodes.at(idx2).trans.z() - sba.nodes.at(idx1).trans.z(), 2.0), 0.5); 00314 00315 printf("%s << totalDist = %f\n", __FUNCTION__, totalDist); 00316 00317 // Scale ALL locations by the ratio of this distance to 1.0 00318 for (unsigned int iii = 0; iii < sba.tracks.size(); iii++) { 00319 sba.tracks.at(iii).point.x() /= totalDist; 00320 sba.tracks.at(iii).point.y() /= totalDist; 00321 sba.tracks.at(iii).point.z() /= totalDist; 00322 } 00323 00324 for (unsigned int iii = 0; iii < sba.nodes.size(); iii++) { 00325 sba.nodes.at(iii).trans.x() /= totalDist; 00326 sba.nodes.at(iii).trans.y() /= totalDist; 00327 sba.nodes.at(iii).trans.z() /= totalDist; 00328 } 00329 00330 printf("%s << Exiting...\n", __FUNCTION__); 00331 00332 } 00333 00334 void renormalizeSBA(SysSBA& sba, Point3d& desiredCenter) { 00335 00336 Point3d centroid, stdDeviation; 00337 00338 // Find current centroid 00339 findCentroid(sba, centroid, stdDeviation); 00340 00341 double largestAxis = 4.0 * max(stdDeviation.x, stdDeviation.z); 00342 double lowestHeight = -2.0 * stdDeviation.y; 00343 00344 // Move everything to center around point (0,0,0) 00345 for (unsigned int iii = 0; iii < sba.tracks.size(); iii++) { 00346 sba.tracks.at(iii).point.x() -= centroid.x; 00347 sba.tracks.at(iii).point.y() -= centroid.y; 00348 sba.tracks.at(iii).point.z() -= centroid.z; 00349 } 00350 00351 for (unsigned int iii = 0; iii < sba.nodes.size(); iii++) { 00352 sba.nodes.at(iii).trans.x() -= centroid.x; 00353 sba.nodes.at(iii).trans.y() -= centroid.y; 00354 sba.nodes.at(iii).trans.z() -= centroid.z; 00355 } 00356 00357 00358 00359 // Re-size to a good scale 00360 for (unsigned int iii = 0; iii < sba.tracks.size(); iii++) { 00361 sba.tracks.at(iii).point.x() /= (largestAxis / 10.0); 00362 sba.tracks.at(iii).point.y() /= (largestAxis / 10.0); 00363 sba.tracks.at(iii).point.z() /= (largestAxis / 10.0); 00364 } 00365 00366 for (unsigned int iii = 0; iii < sba.nodes.size(); iii++) { 00367 sba.nodes.at(iii).trans.x() /= (largestAxis / 10.0); 00368 sba.nodes.at(iii).trans.y() /= (largestAxis / 10.0); 00369 sba.nodes.at(iii).trans.z() /= (largestAxis / 10.0); 00370 } 00371 00372 // Shift up to mostly sit on top of plane 00373 for (unsigned int iii = 0; iii < sba.tracks.size(); iii++) { 00374 sba.tracks.at(iii).point.y() += lowestHeight; 00375 } 00376 00377 for (unsigned int iii = 0; iii < sba.nodes.size(); iii++) { 00378 sba.nodes.at(iii).trans.y() += lowestHeight; 00379 } 00380 00381 // Move everything to desired centroid 00382 for (unsigned int iii = 0; iii < sba.tracks.size(); iii++) { 00383 sba.tracks.at(iii).point.x() += desiredCenter.x; 00384 sba.tracks.at(iii).point.y() += desiredCenter.y; 00385 sba.tracks.at(iii).point.z() += desiredCenter.z; 00386 } 00387 00388 for (unsigned int iii = 0; iii < sba.nodes.size(); iii++) { 00389 sba.nodes.at(iii).trans.x() += desiredCenter.x; 00390 sba.nodes.at(iii).trans.y() += desiredCenter.y; 00391 sba.nodes.at(iii).trans.z() += desiredCenter.z; 00392 } 00393 00394 00395 } 00396 00397 void findCentroid(SysSBA& sba, Point3d& centroid, Point3d& stdDeviation) { 00398 00399 printf("%s << sba.tracks.size() = %d\n", __FUNCTION__, sba.tracks.size()); 00400 00401 centroid = Point3d(0.0, 0.0, 0.0); 00402 stdDeviation = Point3d(0.0, 0.0, 0.0); 00403 00404 for (unsigned int iii = 0; iii < sba.tracks.size(); iii++) { 00405 centroid.x += (sba.tracks.at(iii).point.x() / ((double) sba.tracks.size())); 00406 centroid.y += (sba.tracks.at(iii).point.y() / ((double) sba.tracks.size())); 00407 centroid.z += (sba.tracks.at(iii).point.z() / ((double) sba.tracks.size())); 00408 } 00409 00410 for (unsigned int iii = 0; iii < sba.tracks.size(); iii++) { 00411 stdDeviation.x += (pow((sba.tracks.at(iii).point.x() - centroid.x), 2.0) / ((double) sba.tracks.size())); 00412 stdDeviation.y += (pow((sba.tracks.at(iii).point.y() - centroid.y), 2.0) / ((double) sba.tracks.size())); 00413 stdDeviation.z += (pow((sba.tracks.at(iii).point.z() - centroid.z), 2.0) / ((double) sba.tracks.size())); 00414 } 00415 00416 stdDeviation.x = pow(stdDeviation.x, 0.5); 00417 stdDeviation.y = pow(stdDeviation.y, 0.5); 00418 stdDeviation.z = pow(stdDeviation.z, 0.5); 00419 00420 } 00421 00422 void optimizeFullSystem(vector<featureTrack>& tracks, cameraParameters& camData, Mat *cameras, unsigned int last_index) { 00423 /* 00424 SysSBA fullsys; 00425 00426 vector<unsigned int> camera_indices; 00427 for (unsigned int iii = 0; iii <= last_index; iii++) { 00428 if (cameras[iii].rows == 4) { 00429 camera_indices.push_back(iii); 00430 00431 if (fullsys.nodes.size() == 0) { 00432 addFixedCamera(fullsys, camData, cameras[iii]); 00433 } else { 00434 addNewCamera(fullsys, camData, cameras[iii]); 00435 } 00436 } 00437 } 00438 00439 for (unsigned int iii = 0; iii < tracks.size(); iii++) { 00440 00441 if (tracks.at(iii).isTriangulated) { 00442 00443 for (unsigned int jjj = 0; jjj < tracks.at(iii).locations.size(); jjj++) { 00444 00445 unsigned int cam_idx = tracks.at(iii).locations.at(jjj).imageIndex; 00446 00447 for (unsigned int kkk = 0; kkk < 00448 00449 } 00450 00451 00452 } 00453 00454 } 00455 00456 */ 00457 } 00458 00459 double keyframeBundleAdjustment(cameraParameters& camData, vector<featureTrack>& tracks, Mat *cameras, vector<unsigned int>& indices, unsigned int iterations, bool allFree, bool allFixedExceptLast, unsigned int fixed_cams) { 00460 00461 printf("%s << Entered kBA (1)...\n", __FUNCTION__); 00462 00463 if (indices.size() == 0) { 00464 return -1.00; 00465 } 00466 00467 //printf("%s << indices.size() = %d\n", __FUNCTION__, indices.size()); 00468 00469 vector<unsigned int> activeTrackIndices; 00470 00471 SysSBA sys; 00472 sys.verbose = 0; 00473 00474 unsigned int maxFixedIndex = std::max(1, ((int)indices.size()) - 1); 00475 00476 printf("%s << DEBUG (%02d)\n", __FUNCTION__, 0); 00477 00478 for (unsigned int iii = 0; iii < indices.size(); iii++) { 00479 00480 unsigned int img_idx = indices.at(iii); 00481 00482 //printf("%s << indices.at(iii) = %d\n", __FUNCTION__, img_idx); 00483 //cout << cameras[img_idx] << endl; 00484 00485 if (iii < maxFixedIndex) { 00486 addNewCamera(sys, camData, cameras[img_idx]); 00487 } else { 00488 addNewCamera(sys, camData, cameras[img_idx]); 00489 } 00490 00491 } 00492 00493 printf("%s << DEBUG (%02d)\n", __FUNCTION__, 1); 00494 00495 if (allFree && allFixedExceptLast) { 00496 // Bug to fix ALL points 00497 sys.nFixed = sys.nodes.size(); 00498 } else if (allFree) { 00499 sys.nFixed = 1; 00500 } else if (allFixedExceptLast) { 00501 sys.nFixed = sys.nodes.size()-1; 00502 } else if (fixed_cams != 0) { 00503 sys.nFixed = fixed_cams; 00504 } else { 00505 sys.nFixed = maxFixedIndex; 00506 } 00507 00508 printf("%s << DEBUG (%02d)\n", __FUNCTION__, 2); 00509 00510 //printf("%s << sys.nodes.size() = %d\n", __FUNCTION__, sys.nodes.size()); 00511 00512 for (unsigned int iii = 0; iii < indices.size()-1; iii++) { 00513 00514 printf("%s << Defining kf indices...\n", __FUNCTION__); 00515 unsigned int kf_ind_1 = indices.at(iii); 00516 unsigned int kf_ind_2 = indices.at(iii+1); 00517 00518 vector<unsigned int> tmp_indices, untriangulated; 00519 00520 printf("%s << About to get active tracks...\n", __FUNCTION__); 00521 getActiveTracks(tmp_indices, tracks, kf_ind_1, kf_ind_2); 00522 00523 printf("%s << Reducing active to triangulated...\n", __FUNCTION__); 00524 reduceActiveToTriangulated(tracks, tmp_indices, untriangulated ); 00525 00526 printf("%s << Adding unique to vector...\n", __FUNCTION__); 00527 addUniqueToVector(activeTrackIndices, tmp_indices); 00528 } 00529 00530 printf("%s << DEBUG (%02d)\n", __FUNCTION__, 3); 00531 00532 //printf("%s << activeTrackIndices.size() = %d\n", __FUNCTION__, activeTrackIndices.size()); 00533 00534 vector<Point3d> cloud; 00535 getActive3dPoints(tracks, activeTrackIndices, cloud); 00536 00537 //printf("%s << cloud.size() = %d\n", __FUNCTION__, cloud.size()); 00538 00539 addPointsToSBA(sys, cloud); 00540 00541 printf("%s << DEBUG (%02d)\n", __FUNCTION__, 4); 00542 00543 for (unsigned int iii = 0; iii < activeTrackIndices.size(); iii++) { 00544 // For each active track, see if it has a 2D location in each image 00545 00546 for (unsigned int jjj = 0; jjj < indices.size(); jjj++) { 00547 00548 // what is the image index that you're after? 00549 unsigned int cam_idx_1 = indices.at(jjj); 00550 00551 //printf("%s << Searching for projection in (%d)\n", __FUNCTION__, cam_idx_1); 00552 00553 for (unsigned int kkk = 0; kkk < tracks.at(activeTrackIndices.at(iii)).locations.size(); kkk++) { 00554 00555 if (tracks.at(activeTrackIndices.at(iii)).locations.at(kkk).imageIndex == ((int) cam_idx_1)) { 00556 // Found a projection of track onto this camera 00557 00558 if (iii == 0) { 00559 //printf("%s << Adding projection (%f, %f) of track (%d) to camera (%d)...\n", __FUNCTION__, tracks.at(activeTrackIndices.at(iii)).locations.at(kkk).featureCoord.x, tracks.at(activeTrackIndices.at(iii)).locations.at(kkk).featureCoord.y, iii, kf_store.keyframes.at(validKeyframes.at(jjj)).idx); 00560 } 00561 00562 00563 addProjectionToSBA(sys, tracks.at(activeTrackIndices.at(iii)).locations.at(kkk).featureCoord, iii, jjj); 00564 00565 00566 } 00567 } 00568 00569 00570 00571 } 00572 00573 00574 } 00575 00576 printf("%s << DEBUG (%02d)\n", __FUNCTION__, 5); 00577 00578 double avgError = optimizeSystem(sys, 1e-4, iterations); 00579 00580 //rescaleSBA(sys, 0, sys.nodes.size()-1); 00581 00582 //printf("%s << avgError = %f\n", __FUNCTION__, avgError); 00583 00584 printf("%s << DEBUG (%02d)\n", __FUNCTION__, 51); 00585 00586 for (unsigned int iii = 0; iii < indices.size(); iii++) { 00587 00588 unsigned int img_idx = indices.at(iii); 00589 00590 retrieveCamera(cameras[img_idx], sys, iii); 00591 } 00592 00593 printf("%s << DEBUG (%02d)\n", __FUNCTION__, 6); 00594 00595 for (unsigned int iii = 0; iii < sys.tracks.size(); iii++) { 00596 00597 Point3d new3dLoc(sys.tracks.at(iii).point.x(), sys.tracks.at(iii).point.y(), sys.tracks.at(iii).point.z()); 00598 00599 //if (validKeyframes.size() == 2) { 00600 // Hack to get it to reset locations on first go 00601 tracks.at(activeTrackIndices.at(iii)).reset3dLoc(new3dLoc); 00602 //} else { 00603 // tracks.at(activeTrackIndices.at(iii)).set3dLoc(new3dLoc); 00604 //} 00605 00606 } 00607 00608 printf("%s << DEBUG (%02d)\n", __FUNCTION__, 7); 00609 00610 return avgError; 00611 } 00612 00613 double keyframeBundleAdjustment(cameraParameters& camData, vector<featureTrack>& tracks, keyframeStore& kf_store, Mat *cameras, unsigned int kfIndex, unsigned int iterations) { 00614 00615 printf("%s << Entered kBA (2)...\n", __FUNCTION__); 00616 00617 //unsigned int optIndex = kf_store.keyframes.at(kf_idx).idx; // index of frame to be adjusted 00618 00619 unsigned int kf_idx = kfIndex; 00620 00621 vector<unsigned int> validConnections, validKeyframes; 00622 // Find all connected keyframes, and establish initial camera poses 00623 //kf_store.findStrongConnections(kf_idx, validConnections, kf_idx); 00624 00625 for (unsigned int iii = 0; iii < kf_idx; iii++) { 00626 validConnections.push_back(iii); 00627 } 00628 00629 //printf("%s << validConnections.size() = %d\n", __FUNCTION__, validConnections.size()); 00630 00631 for (unsigned int iii = 0; iii < validConnections.size(); iii++) { 00632 00633 //printf("%s << validConnections.at(%d) = (%d) (%d)\n", __FUNCTION__, iii, kf_store.connections.at(validConnections.at(iii)).idx1, kf_store.connections.at(validConnections.at(iii)).idx2); 00634 00635 bool kf1added = false, kf2added = false; 00636 00637 for (unsigned int jjj = 0; jjj < validKeyframes.size(); jjj++) { 00638 00639 if (kf_store.connections.at(validConnections.at(iii)).idx1 == validKeyframes.at(jjj)) { 00640 kf1added = true; 00641 } 00642 00643 if (kf_store.connections.at(validConnections.at(iii)).idx2 == validKeyframes.at(jjj)) { 00644 kf2added = true; 00645 } 00646 00647 } 00648 00649 if (!kf1added) { 00650 validKeyframes.push_back(kf_store.connections.at(validConnections.at(iii)).idx1); 00651 } 00652 00653 if (!kf2added) { 00654 validKeyframes.push_back(kf_store.connections.at(validConnections.at(iii)).idx2); 00655 } 00656 00657 00658 } 00659 00660 //printf("%s << Valid keyframes size: %d\n", __FUNCTION__, validKeyframes.size()); 00661 00662 00663 // For each connection, find any tracks that have been triangulated 00664 00665 vector<unsigned int> activeTrackIndices; 00666 00667 SysSBA sys; 00668 sys.verbose = 0; 00669 00670 //printf("%s << Before 2-frame BA: \n", __FUNCTION__); 00671 00672 for (unsigned int iii = 0; iii < validKeyframes.size(); iii++) { 00673 00674 unsigned int img_idx = kf_store.keyframes.at(validKeyframes.at(iii)).idx; 00675 00676 //Mat C_mat; 00677 //printf("%s << validKeyframes.at(%d) = %d\n", __FUNCTION__, iii, validKeyframes.at(iii)); 00678 //(kf_store.keyframes.at(validKeyframes.at(iii)).pose).copyTo(C_mat); 00679 00680 00681 if (iii == validKeyframes.size()-1) { 00682 addNewCamera(sys, camData, cameras[img_idx]); 00683 } else { 00684 addFixedCamera(sys, camData, cameras[img_idx]); // addFixedCamera(sys, camData, C_mat); 00685 sys.nodes.at(iii).isFixed = true; 00686 //addNewCamera(sys, camData, cameras[img_idx]); 00687 00688 //printf("%s << sys.nFixed = %d\n", __FUNCTION__, sys.nFixed); 00689 } 00690 00691 00692 00693 if (int(iii) >= max(((int) 0), ((int) validKeyframes.size())-4)) { 00694 //cout << __FUNCTION__ << " << C(" << img_idx << ") = " << endl << cameras[img_idx] << endl; 00695 } 00696 00697 00698 } 00699 00700 int minUnfixed = 5; 00701 00702 sys.nFixed = max(1, ((int) validKeyframes.size())-minUnfixed); 00703 00704 00705 for (unsigned int iii = 0; iii < validConnections.size(); iii++) { 00706 00707 unsigned int kf_ind_1 = kf_store.connections.at(validConnections.at(iii)).idx1; 00708 unsigned int kf_ind_2 = kf_store.connections.at(validConnections.at(iii)).idx2; 00709 00710 vector<unsigned int> tmp_indices; 00711 00712 //printf("%s << indexes = (%d, %d)\n", __FUNCTION__, kf_store.keyframes.at(kf_ind_1).idx, kf_store.keyframes.at(kf_ind_2).idx); 00713 00714 getActiveTracks(tmp_indices, tracks, kf_store.keyframes.at(kf_ind_1).idx, kf_store.keyframes.at(kf_ind_2).idx); 00715 00716 //printf("%s << active tracks for (%d, %d) = %d\n", __FUNCTION__, kf_store.keyframes.at(kf_ind_1).idx, kf_store.keyframes.at(kf_ind_2).idx, tmp_indices.size()); 00717 00718 vector<unsigned int> untriangulated; 00719 reduceActiveToTriangulated(tracks, tmp_indices, untriangulated); 00720 00721 //printf("%s << after triangulation (%d, %d) = %d\n", __FUNCTION__, kf_store.keyframes.at(kf_ind_1).idx, kf_store.keyframes.at(kf_ind_2).idx, tmp_indices.size()); 00722 // 193 have been triangulated... 00723 00724 //vector<Point3d> cloud; 00725 //getActive3dPoints(tracks, tmp_indices, cloud); 00726 00727 00728 00729 //addPointsToSBA(subsys, ptsInCloud); 00730 //addProjectionsToSBA(subsys, pts1, 0); 00731 00732 addUniqueToVector(activeTrackIndices, tmp_indices); 00733 } 00734 00735 //printf("%s << activeTrackIndices.size() = %d\n", __FUNCTION__, activeTrackIndices.size()); 00736 00737 //reduceActiveToTriangulated(tracks, activeTrackIndices); 00738 00739 //printf("%s << triangulatedIndices.size() = %d\n", __FUNCTION__, activeTrackIndices.size()); 00740 00741 // Get projections and 3D locations for these tracks relative to the relevant cameras 00742 00743 vector<Point3d> cloud; 00744 getActive3dPoints(tracks, activeTrackIndices, cloud); 00745 00746 //printf("%s << cloud.size() = %d (tracks.size() = %d; activeTrackIndices.size() = %d)\n", __FUNCTION__, cloud.size(), tracks.size(), activeTrackIndices.size()); 00747 00748 addPointsToSBA(sys, cloud); 00749 //drawGraph(sys, camera_pub, points_pub); 00750 00751 for (unsigned int iii = 0; iii < activeTrackIndices.size(); iii++) { 00752 // For each active track, see if it has a 2D location in each image 00753 00754 for (unsigned int jjj = 0; jjj < validKeyframes.size(); jjj++) { 00755 00756 // what is the image index that you're after? 00757 unsigned int cam_idx_1 = kf_store.keyframes.at(validKeyframes.at(jjj)).idx; 00758 00759 //printf("%s << Searching for projection in (%d)\n", __FUNCTION__, cam_idx_1); 00760 00761 for (unsigned int kkk = 0; kkk < tracks.at(activeTrackIndices.at(iii)).locations.size(); kkk++) { 00762 00763 if (tracks.at(activeTrackIndices.at(iii)).locations.at(kkk).imageIndex == ((int) cam_idx_1)) { 00764 // Found a projection of track onto this camera 00765 00766 if (iii == 0) { 00767 //printf("%s << Adding projection (%f, %f) of track (%d) to camera (%d)...\n", __FUNCTION__, tracks.at(activeTrackIndices.at(iii)).locations.at(kkk).featureCoord.x, tracks.at(activeTrackIndices.at(iii)).locations.at(kkk).featureCoord.y, iii, kf_store.keyframes.at(validKeyframes.at(jjj)).idx); 00768 } 00769 00770 00771 addProjectionToSBA(sys, tracks.at(activeTrackIndices.at(iii)).locations.at(kkk).featureCoord, iii, jjj); 00772 00773 00774 } 00775 } 00776 00777 00778 00779 } 00780 00781 00782 } 00783 00784 //sys.setupSys(1.0e-4); 00785 00786 // Bundle adjust this system, with only the "kf_index" camera unfixed 00787 // what about the 3D points? might it change some of their positions? 00788 // perhaps this will be handled by the overall BA.... 00789 00790 //printf("%s << Cameras (nodes): %d, Points: %d [iters = %d]\n", __FUNCTION__, (int)sys.nodes.size(), (int)sys.tracks.size(), iterations); 00791 00792 double avgError = optimizeSystem(sys, 1e-4, iterations); 00793 //printf("%s << avgError = %f.\n", __FUNCTION__, avgError); 00794 00795 //printf("%s << () sys.nFixed = %d\n", __FUNCTION__, sys.nFixed); 00796 00797 // Then need to update locations of 3D points and location of camera 00798 00799 //unsigned int img_idx = kf_store.keyframes.at(validKeyframes.size()-1).idx; 00800 00801 //retrieveCamera(cameras[img_idx], sys, validKeyframes.size()-1); 00802 00803 00804 00805 00806 //retrieveCamera(kf_store.keyframes.at(validKeyframes.size()-1).pose, sys, validKeyframes.size()-1); 00807 00808 //printf("%s << After 2-frame BA: \n", __FUNCTION__); 00809 //cout << P0 << endl; 00810 //cout << kf_store.keyframes.at(validKeyframes.size()-1).pose << endl; 00811 00812 for (unsigned int iii = 0; iii < validKeyframes.size(); iii++) { 00813 00814 unsigned int img_idx = kf_store.keyframes.at(iii).idx; 00815 00816 retrieveCamera(cameras[img_idx], sys, iii); 00817 00818 if (int(iii) >= max(((int) 0), ((int) validKeyframes.size())-4)) { 00819 //cout << __FUNCTION__ << " << C(" << img_idx << ") = " << endl << cameras[img_idx] << endl; 00820 } 00821 00822 00823 //cout << "C = " << endl << cameras[kf_store.keyframes.at(validKeyframes.at(iii)).idx] << endl; 00824 } 00825 00826 00827 for (unsigned int iii = 0; iii < sys.tracks.size(); iii++) { 00828 00829 Point3d new3dLoc(sys.tracks.at(iii).point.x(), sys.tracks.at(iii).point.y(), sys.tracks.at(iii).point.z()); 00830 00831 if (validKeyframes.size() == 2) { 00832 // Hack to get it to reset locations on first go 00833 tracks.at(activeTrackIndices.at(iii)).reset3dLoc(new3dLoc); 00834 } else { 00835 tracks.at(activeTrackIndices.at(iii)).set3dLoc(new3dLoc); 00836 } 00837 00838 } 00839 00840 return avgError; 00841 } 00842 00843 void retrievePartialSystem(SysSBA& sys, Mat *C, vector<featureTrack>& tracks, vector<unsigned int>& indices) { 00844 00845 for (unsigned int iii = 0; iii < indices.size(); iii++) { 00846 00847 if (C[indices.at(iii)].rows == 4) { 00848 retrieveCamera(C[indices.at(iii)], sys, iii); 00849 } 00850 00851 } 00852 00853 unsigned int trackIndex = 0; 00854 00855 for (unsigned int iii = 0; iii < sys.tracks.size(); iii++) { 00856 00857 while (!tracks.at(trackIndex).isTriangulated) { 00858 trackIndex++; 00859 00860 if (trackIndex >= tracks.size()) { 00861 break; 00862 } 00863 } 00864 00865 Point3d new3dLoc(sys.tracks.at(iii).point.x(), sys.tracks.at(iii).point.y(), sys.tracks.at(iii).point.z()); 00866 tracks.at(trackIndex).reset3dLoc(new3dLoc); 00867 00868 trackIndex++; 00869 00870 if (trackIndex >= tracks.size()) { 00871 break; 00872 } 00873 00874 } 00875 00876 } 00877 00878 void getActiveCameras(Mat *C, vector<unsigned int>& indices, unsigned int min_index, unsigned int max_index) { 00879 for (unsigned int iii = min_index; iii <= max_index; iii++) { 00880 if (C[iii].rows == 4) { 00881 indices.push_back(iii); 00882 } 00883 } 00884 } 00885 00886 void getActiveTracks(vector<featureTrack>& tracks, vector<unsigned int>& cameras, vector<unsigned int>& indices) { 00887 00888 printf("%s << Entered.\n", __FUNCTION__); 00889 00890 for (unsigned int iii = 0; iii < tracks.size(); iii++) { 00891 00892 bool isAdded = false; 00893 00894 if (tracks.at(iii).isTriangulated) { 00895 00896 for (unsigned int jjj = 0; jjj < cameras.size(); jjj++) { 00897 00898 for (unsigned int kkk = 0; kkk < tracks.at(iii).locations.size(); kkk++) { 00899 00900 printf("%s << about to access tracks(%d / %d)(%d / %d) & cameras(%d / %d)\n", __FUNCTION__, iii, tracks.size(), kkk, tracks.at(iii).locations.size(), jjj, cameras.size()); 00901 if (tracks.at(iii).locations.at(kkk).imageIndex == int(cameras.at(jjj))) { 00902 indices.push_back(iii); 00903 isAdded = true; 00904 break; 00905 } 00906 00907 } 00908 00909 if (isAdded) { 00910 break; 00911 } 00912 00913 } 00914 00915 } 00916 00917 } 00918 00919 printf("%s << Exiting.\n", __FUNCTION__); 00920 00921 } 00922 00923 void retrieveFullSystem(SysSBA& sys, Mat *C, vector<featureTrack>& tracks, unsigned int start_cam, unsigned int final_cam) { 00924 00925 //vector<unsigned int> camera_indices; 00926 00927 00928 for (unsigned int iii = 0; iii < sys.nodes.size(); iii++) { 00929 00930 retrieveCamera(C[start_cam+iii], sys, iii); 00931 00932 } 00933 00934 00935 /* 00936 for (unsigned int jjj = start_cam; jjj <= final_cam; jjj++) { 00937 00938 if (C[jjj].rows == 4) { 00939 retrieveCamera(C[camera_indices.size()], sys, jjj); 00940 00941 camera_indices.push_back(jjj); 00942 } 00943 00944 } 00945 */ 00946 00947 // The way the tracks are being retrived is incorrect!!! 00948 for (unsigned int iii = 0; iii < sys.tracks.size(); iii++) { 00949 00950 // Only want to retrieve relevant tracks! 00951 00952 Point3d new3dLoc(sys.tracks.at(iii).point.x(), sys.tracks.at(iii).point.y(), sys.tracks.at(iii).point.z()); 00953 tracks.at(iii).reset3dLoc(new3dLoc); 00954 } 00955 } 00956 00957 double optimizeSubsystem(cameraParameters& camData, Mat *C, vector<unsigned int>& c_i, vector<featureTrack>& tracks, vector<unsigned int>& t_i, unsigned int iterations) { 00958 00959 SysSBA sys; 00960 sys.verbose = 0; 00961 00962 vector<Point3d> cloud; 00963 00964 getActive3dPoints(tracks, t_i, cloud); 00965 00966 printf("%s << active points (%d) out of (%d) valid tracks..\n", __FUNCTION__, cloud.size(), t_i.size()); 00967 00968 addPointsToSBA(sys, cloud); 00969 00970 // Add first and last cameras as fixed 00971 printf("%s << Adding (%d) and (%d) as fixed cameras...\n", __FUNCTION__, c_i.at(0), c_i.at(c_i.size()-1)); 00972 addFixedCamera(sys, camData, C[c_i.at(0)]); 00973 addFixedCamera(sys, camData, C[c_i.at(c_i.size()-1)]); 00974 00975 for (unsigned int iii = 1; iii < c_i.size()-1; iii++) { 00976 addNewCamera(sys, camData, C[c_i.at(iii)]); 00977 } 00978 00979 for (unsigned int iii = 0; iii < c_i.size(); iii++) { 00980 00981 //printf("%s << (%d) : %d\n", __FUNCTION__, iii, c_i.at(iii)); 00982 00983 // the node that corresponds to the camera 00984 00985 unsigned int sysIndex; 00986 00987 if (iii == 0) { 00988 sysIndex = 0; 00989 } else if (iii == c_i.size()-1) { 00990 sysIndex = 1; 00991 } else { 00992 sysIndex = iii + 1; 00993 } 00994 00995 00996 00997 //cout << C[c_i.at(iii)] << endl; 00998 00999 for (unsigned int jjj = 0; jjj < t_i.size(); jjj++) { 01000 01001 for (unsigned int kkk = 0; kkk < tracks.at(t_i.at(jjj)).locations.size(); kkk++) { 01002 01003 if (tracks.at(t_i.at(jjj)).locations.at(kkk).imageIndex == ((int) c_i.at(iii))) { 01004 01005 Vector2d proj; 01006 01007 proj.x() = tracks.at(t_i.at(jjj)).locations.at(kkk).featureCoord.x; 01008 proj.y() = tracks.at(t_i.at(jjj)).locations.at(kkk).featureCoord.y; 01009 01010 sys.addMonoProj(sysIndex, jjj, proj); 01011 } 01012 } 01013 01014 } 01015 01016 01017 01018 } 01019 01020 sys.nFixed = 2; 01021 01022 unsigned int numFixed = sys.nFixed; 01023 01024 printf("%s << nodes = %d; tracks = %d (nFixed = %d)\n", __FUNCTION__, sys.nodes.size(), sys.tracks.size(), numFixed); 01025 01026 double avgError = optimizeSystem(sys, 1e-4, iterations); 01027 01028 printf("%s << avgError = %f\n", __FUNCTION__, avgError); 01029 01030 printf("%s << Retrieving 0 -> %d; and 1 -> %d\n", __FUNCTION__, c_i.at(0), c_i.at(c_i.size()-1)); 01031 01032 retrieveCamera(C[c_i.at(0)], sys, 0); 01033 retrieveCamera(C[c_i.at(c_i.size()-1)], sys, 1); 01034 01035 for (unsigned int iii = 1; iii < c_i.size()-1; iii++) { 01036 retrieveCamera(C[c_i.at(iii)], sys, iii+1); 01037 } 01038 01039 for (unsigned int iii = 0; iii < sys.tracks.size(); iii++) { 01040 01041 Point3d new3dLoc(sys.tracks.at(iii).point.x(), sys.tracks.at(iii).point.y(), sys.tracks.at(iii).point.z()); 01042 01043 tracks.at(t_i.at(iii)).set3dLoc(new3dLoc); 01044 } 01045 01046 01047 return avgError; 01048 01049 } 01050 01051 double optimizeKeyframePair(vector<featureTrack>& tracks, cameraParameters& camData, int idx1, int idx2, Mat *cameras) { 01052 01053 vector<Point2f> pts1, pts2; 01054 getPointsFromTracks(tracks, pts1, pts2, idx1, idx2); 01055 01056 vector<Point3d> cloud; 01057 vector<Point2f> corresp; 01058 01059 for (unsigned int iii = 0; iii < 10; iii++) { 01060 //printf("%s << pt(%d) = (%f, %f) & (%f, %f)\n", __FUNCTION__, iii, pts1.at(iii).x, pts1.at(iii).y, pts2.at(iii).x, pts2.at(iii).y); 01061 } 01062 //if (debug) { 01063 printf("%s << Before 2-frame BA: \n", __FUNCTION__); 01064 cout << cameras[idx1] << endl; 01065 cout << cameras[idx2] << endl; 01066 //} 01067 01068 TriangulatePoints(pts1, pts2, camData.K, camData.K.inv(), cameras[idx1], cameras[idx2], cloud, corresp); 01069 01070 double twoErr = twoViewBundleAdjustment(camData, cameras[idx1], cameras[idx2], cloud, pts1, pts2, 1000); 01071 01072 //if (debug) { 01073 printf("%s << After 2-frame BA: \n", __FUNCTION__); 01074 cout << cameras[idx1] << endl; 01075 cout << cameras[idx2] << endl; 01076 //} 01077 01078 01079 return twoErr; 01080 01081 } 01082 01083 void assignPartialSystem(SysSBA &sba, vector<featureTrack>& tracks, cameraParameters& camData, Mat *cameras, vector<unsigned int>& indices, bool assignProjections) { 01084 01085 sba.tracks.clear(); 01086 sba.nodes.clear(); 01087 01088 vector<unsigned int> added_indices; 01089 01090 for (unsigned int jjj = 0; jjj < indices.size(); jjj++) { 01091 01092 if (cameras[indices.at(jjj)].rows == 4) { 01093 if (jjj == 0) { 01094 addFixedCamera(sba, camData, cameras[indices.at(jjj)]); 01095 } else { 01096 addNewCamera(sba, camData, cameras[indices.at(jjj)]); 01097 } 01098 added_indices.push_back(indices.at(jjj)); 01099 } 01100 01101 } 01102 01103 unsigned int addedTracks = -1; 01104 01105 for (unsigned int iii = 0; iii < tracks.size(); iii++) { 01106 01107 if (tracks.at(iii).isTriangulated) { 01108 01109 Vector4d temppoint(tracks.at(iii).get3dLoc().x, tracks.at(iii).get3dLoc().y, tracks.at(iii).get3dLoc().z, 1.0); 01110 sba.addPoint(temppoint); 01111 addedTracks++; 01112 01113 if (assignProjections) { 01114 01115 for (unsigned int jjj = 0; jjj < tracks.at(iii).locations.size(); jjj++) { 01116 01117 unsigned int cam_index = tracks.at(iii).locations.at(jjj).imageIndex; 01118 01119 for (unsigned int kkk = 0; kkk < added_indices.size(); kkk++) { 01120 01121 if (added_indices.at(kkk) == cam_index) { 01122 //printf("%s << adding projection (%f, %f) to (cam: %d, track: %d)\n", __FUNCTION__, tracks.at(iii).locations.at(jjj).featureCoord.x, tracks.at(iii).locations.at(jjj).featureCoord.y, kkk, iii); 01123 addProjectionToSBA(sba, tracks.at(iii).locations.at(jjj).featureCoord, addedTracks, kkk); 01124 01125 break; 01126 } 01127 01128 } 01129 01130 01131 01132 } 01133 01134 } 01135 } 01136 01137 01138 01139 } 01140 01141 01142 01143 } 01144 01145 double adjustFullSystem(vector<featureTrack>& tracks, cameraParameters& camData, Mat *cameras, unsigned int min_index, unsigned int max_index, unsigned int its) { 01146 SysSBA fullsys; 01147 01148 Mat eye4 = Mat::eye(4, 4, CV_64FC1); 01149 01150 for (unsigned int iii = 0; iii < max_index; iii++) { 01151 if (cameras[iii].rows == 4) { 01152 //estimatePoseFromKnownPoints(cameras[iii], camData, tracks, iii, eye4); 01153 } 01154 } 01155 01156 // Get active cameras 01157 vector<unsigned int> active_camera_indices; 01158 getActiveCameras(cameras, active_camera_indices, min_index, max_index); 01159 01160 // Get active tracks 01161 vector<unsigned int> active_track_indices; 01162 getActiveTracks(tracks, active_camera_indices, active_track_indices); 01163 01164 assignSystem(fullsys, tracks, camData, cameras, active_camera_indices, active_track_indices); 01165 01166 double avgError; 01167 01168 avgError = optimizeSystem(fullsys, 1e-4, its ); 01169 //retrievePartialSystem(sys, ACM, featureTrackVector, keyframeIndices); 01170 01171 retrieveSystem(fullsys, tracks, camData, cameras, active_camera_indices, active_track_indices); 01172 01173 return avgError; 01174 01175 01176 } 01177 01178 void retrieveSystem(SysSBA &sba, vector<featureTrack>& tracks, cameraParameters& camData, Mat *cameras, vector<unsigned int>& camera_indices, vector<unsigned int>& track_indices) { 01179 01180 for (unsigned int iii = 0; iii < camera_indices.size(); iii++) { 01181 retrieveCameraPose(sba, cameras[camera_indices.at(iii)], iii); 01182 } 01183 01184 for (unsigned int iii = 0; iii < track_indices.size(); iii++) { 01185 Point3d new3dLoc(sba.tracks.at(iii).point.x(), sba.tracks.at(iii).point.y(), sba.tracks.at(iii).point.z()); 01186 tracks.at(track_indices.at(iii)).reset3dLoc(new3dLoc); 01187 } 01188 01189 } 01190 01191 void assignSystem(SysSBA &sba, vector<featureTrack>& tracks, cameraParameters& camData, Mat *cameras, vector<unsigned int>& camera_indices, vector<unsigned int>& track_indices) { 01192 01193 sba.tracks.clear(); 01194 sba.nodes.clear(); 01195 01196 printf("%s << DEBUG [%d]\n", __FUNCTION__, 0); 01197 01198 for (unsigned int iii = 0; iii < camera_indices.size(); iii++) { 01199 if (sba.nodes.size() == 0) { 01200 addFixedCamera(sba, camData, cameras[camera_indices.at(iii)]); 01201 } else { 01202 addNewCamera(sba, camData, cameras[camera_indices.at(iii)]); 01203 } 01204 } 01205 01206 printf("%s << DEBUG [%d]\n", __FUNCTION__, 1); 01207 01208 for (unsigned int iii = 0; iii < track_indices.size(); iii++) { 01209 01210 Vector4d temppoint(tracks.at(track_indices.at(iii)).get3dLoc().x, tracks.at(track_indices.at(iii)).get3dLoc().y, tracks.at(track_indices.at(iii)).get3dLoc().z, 1.0); 01211 sba.addPoint(temppoint); 01212 01213 for (unsigned int jjj = 0; jjj < tracks.at(track_indices.at(iii)).locations.size(); jjj++) { 01214 01215 for (unsigned int kkk = 0; kkk < camera_indices.size(); kkk++) { 01216 if (int(camera_indices.at(kkk)) == tracks.at(track_indices.at(iii)).locations.at(jjj).imageIndex) { 01217 01218 Vector2d proj; 01219 01220 proj.x() = tracks.at(track_indices.at(iii)).locations.at(jjj).featureCoord.x; 01221 proj.y() = tracks.at(track_indices.at(iii)).locations.at(jjj).featureCoord.y; 01222 01223 //printf("%s << Adding mono projection: (cam: %d / %d, track: %d / %d) = (%f, %f)\n", __FUNCTION__, tracks.at(iii).locations.at(jjj).imageIndex, sys.nodes.size(), sys.tracks.size()-1, sys.tracks.size(), proj.x(), proj.y()); 01224 sba.addMonoProj(kkk, iii, proj); 01225 } 01226 } 01227 01228 } 01229 01230 01231 } 01232 01233 printf("%s << DEBUG [%d]\n", __FUNCTION__, 2); 01234 01235 } 01236 01237 void assignFullSystem(SysSBA &sba, vector<featureTrack>& tracks, cameraParameters& camData, Mat *cameras, unsigned int start_index, unsigned int finish_index, bool dummy) { 01238 01239 sba.tracks.clear(); 01240 sba.nodes.clear(); 01241 01242 vector<unsigned int> camera_indices; 01243 01244 for (unsigned int jjj = start_index; jjj <= finish_index; jjj++) { 01245 01246 if (cameras[jjj].rows == 4) { 01247 if (sba.nodes.size() == 0) { 01248 addFixedCamera(sba, camData, cameras[jjj]); 01249 } else { 01250 addNewCamera(sba, camData, cameras[jjj]); 01251 } 01252 01253 camera_indices.push_back(jjj); 01254 } 01255 01256 } 01257 01258 for (unsigned int iii = 0; iii < tracks.size(); iii++) { 01259 01260 if (tracks.at(iii).isTriangulated) { 01261 01262 Vector4d temppoint(tracks.at(iii).get3dLoc().x, tracks.at(iii).get3dLoc().y, tracks.at(iii).get3dLoc().z, 1.0); 01263 sba.addPoint(temppoint); 01264 01265 for (unsigned int jjj = 0; jjj < tracks.at(iii).locations.size(); jjj++) { 01266 01267 // Only want to add projections for active nodes 01268 01269 if (!dummy) { 01270 if ((((unsigned int) tracks.at(iii).locations.at(jjj).imageIndex) >= start_index) && (((unsigned int) tracks.at(iii).locations.at(jjj).imageIndex) <= (finish_index))) { 01271 01272 for (unsigned int kkk = 0; kkk < camera_indices.size(); kkk++) { 01273 01274 if (int(camera_indices.at(kkk)) == tracks.at(iii).locations.at(jjj).imageIndex) { 01275 Vector2d proj; 01276 01277 proj.x() = tracks.at(iii).locations.at(jjj).featureCoord.x; 01278 proj.y() = tracks.at(iii).locations.at(jjj).featureCoord.y; 01279 01280 //printf("%s << Adding mono projection: (cam: %d / %d, track: %d / %d) = (%f, %f)\n", __FUNCTION__, tracks.at(iii).locations.at(jjj).imageIndex, sys.nodes.size(), sys.tracks.size()-1, sys.tracks.size(), proj.x(), proj.y()); 01281 sba.addMonoProj(kkk, sba.tracks.size()-1, proj); 01282 } 01283 01284 } 01285 01286 //printf("%s << Assembling projection (%d)(%d)\n", __FUNCTION__, iii, jjj); 01287 01288 01289 01290 } 01291 } 01292 01293 01294 01295 01296 01297 } 01298 01299 } 01300 01301 } 01302 01303 01304 01305 } 01306 01307 bool reconstructFreshSubsequencePair(vector<featureTrack>& tracks, vector<Point3d>& ptCloud, vector<unsigned int>& triangulatedIndices, Mat& real_C0, Mat& real_C1, cameraParameters camData, int idx1, int idx2) { 01308 01309 if ((camData.K.rows != 3) || (camData.K.cols != 3) || (camData.K_inv.rows != 3) || (camData.K_inv.cols != 3)) { 01310 printf("%s << ERROR! Camera intrinsics dimensions are invalid.\n", __FUNCTION__); 01311 return false; 01312 } 01313 01314 01315 //printf("%s << DEBUG [%d]\n", __FUNCTION__, 0); 01316 01317 Mat real_P0, real_P1; 01318 01319 vector<Point2f> pts1_, pts2_, pts1, pts2; 01320 01321 printf("%s << Getting pts from tracks: (%d), (%d, %d), (%d, %d)\n", __FUNCTION__, tracks.size(), pts1_.size(), pts2_.size(), idx1, idx2); 01322 getPointsFromTracks(tracks, pts1_, pts2_, idx1, idx2); 01323 01324 //subselectPoints(pts1_, pts1, pts2_, pts2); 01325 pts1.insert(pts1.end(), pts1_.begin(), pts1_.end()); 01326 pts2.insert(pts2.end(), pts2_.begin(), pts2_.end()); 01327 01328 printf("%s << Checking pts size... (%d)\n", __FUNCTION__, pts1.size()); 01329 01330 if (pts1.size() < 8) { 01331 printf("%s << ERROR! Too few corresponding points (%d)\n", __FUNCTION__, pts1.size()); 01332 return false; 01333 } 01334 01335 vector<unsigned int> activeTrackIndices, fullSpanIndices; 01336 getActiveTracks(activeTrackIndices, tracks, idx1, idx2); 01337 filterToCompleteTracks(fullSpanIndices, activeTrackIndices, tracks, idx1, idx2); 01338 01339 //printf("%s << DEBUG [%d]\n", __FUNCTION__, 2); 01340 01341 Mat F, matchesMask_F_matrix; 01342 F = findFundamentalMat(Mat(pts1), Mat(pts2), FM_RANSAC, 1.00, 0.99, matchesMask_F_matrix); 01343 01344 Mat E = camData.K.t() * F * camData.K; 01345 Mat CX[4]; 01346 findFourTransformations(CX, E, camData.K, pts1, pts2); 01347 01348 //printf("%s << DEBUG [%d]\n", __FUNCTION__, 3); 01349 01350 Mat C; 01351 int validPts = findBestCandidate(CX, camData.K, pts1, pts2, C); 01352 01353 if (validPts < ((int) (0.5 * ((double) pts1.size())))) { 01354 printf("%s << ERROR! too few tracks (%d / %d) in best transform are in front of camera.\n", __FUNCTION__, validPts, pts1.size()); 01355 return false; 01356 } 01357 01358 //printf("%s << DEBUG [%d]\n", __FUNCTION__, 4); 01359 01360 Mat P1, R1, t1, Rvec; 01361 transformationToProjection(C, P1); 01362 decomposeTransform(C, R1, t1); 01363 Rodrigues(R1, Rvec); 01364 01365 //printf("%s << DEBUG [%d]\n", __FUNCTION__, 5); 01366 01367 real_C1 = C * real_C0; // real_C1 = C * real_C0; 01368 01369 //real_C1 = C.inv() * real_C0; 01370 01371 transformationToProjection(real_C0, real_P0); 01372 transformationToProjection(real_C1, real_P1); 01373 01374 /* 01375 printf("%s << Putative camera poses (%d & %d)\n", __FUNCTION__, idx1, idx2); 01376 cout << "real_C0 = " << endl; 01377 cout << real_C0 << endl; 01378 cout << "real_C1 = " << endl; 01379 cout << real_C1 << endl; 01380 */ 01381 01382 //printf("%s << DEBUG [%d]\n", __FUNCTION__, 6); 01383 01384 //cout << camData.K << endl; 01385 //cout << camData.K_inv << endl; 01386 01387 vector<Point2f> correspPoints; 01388 TriangulatePoints(pts1, pts2, camData.K, camData.K_inv, real_C0, real_C1, ptCloud, correspPoints); 01389 //TriangulatePoints(pts1_, pts2_, camData.K, camData.K_inv, real_C1.inv(), real_C0.inv(), ptCloud, correspPoints); 01390 //TriangulatePoints(pts1, pts2, camData.K, camData.K_inv, real_P0, real_P1, ptCloud, correspPoints); 01391 //printf("%s << %d points triangulated.\n", __FUNCTION__, ptsInCloud.size()); 01392 01393 //printf("%s << DEBUG [%d]\n", __FUNCTION__, 7); 01394 01395 triangulatedIndices.clear(); 01396 triangulatedIndices.insert(triangulatedIndices.end(), fullSpanIndices.begin(), fullSpanIndices.end()); 01397 01398 //printf("%s << triangulatedIndices.size() = %d\n", __FUNCTION__, triangulatedIndices.size()); 01399 01400 updateTriangulatedPoints(tracks, triangulatedIndices, ptCloud); 01401 01402 //printf("%s << DEBUG [%d]\n", __FUNCTION__, 8); 01403 01404 //real_C1 = real_C1.inv(); 01405 01406 return true; 01407 } 01408 01409 void subselectPoints(const vector<Point2f>& src1, vector<Point2f>& dst1, const vector<Point2f>& src2, vector<Point2f>& dst2) { 01410 01411 vector<Point2f> new_src_1, new_src_2; 01412 new_src_1.insert(new_src_1.end(), src1.begin(), src1.end()); 01413 new_src_2.insert(new_src_2.end(), src2.begin(), src2.end()); 01414 01415 int aimedPoints = 48; 01416 01417 if (int(src1.size()) <= aimedPoints) { 01418 dst1.insert(dst1.end(), src1.begin(), src1.end()); 01419 dst2.insert(dst2.end(), src2.begin(), src2.end()); 01420 01421 return; 01422 } 01423 01424 // Find centroid 01425 Point2f centroid_1, centroid_2; 01426 01427 for (unsigned int iii = 0; iii < src1.size(); iii++) { 01428 centroid_1.x += src1.at(iii).x / ((double) src1.size()); 01429 centroid_1.y += src1.at(iii).y / ((double) src1.size()); 01430 01431 centroid_2.x += src2.at(iii).x / ((double) src2.size()); 01432 centroid_2.y += src2.at(iii).y / ((double) src2.size()); 01433 } 01434 01435 printf("%s << Centroids: (%f, %f) & (%f, %f)\n", __FUNCTION__, centroid_1.x, centroid_1.y, centroid_2.x, centroid_2.y); 01436 01437 // First add most central point 01438 unsigned int mostCentralIndex; 01439 float bestDistance = 9e99; 01440 01441 for (unsigned int iii = 0; iii < src1.size(); iii++) { 01442 01443 float dist = distanceBetweenPoints(src1.at(iii), centroid_1) + distanceBetweenPoints(src2.at(iii), centroid_2); 01444 01445 if ((dist < bestDistance) || (iii == 0)) { 01446 bestDistance = dist; 01447 mostCentralIndex = iii; 01448 } 01449 01450 } 01451 01452 dst1.push_back(new_src_1.at(mostCentralIndex)); 01453 dst2.push_back(new_src_2.at(mostCentralIndex)); 01454 01455 // Correct centroid by removing contribution of removed point, multiplying by old size divided by new size 01456 centroid_1.x -= new_src_1.at(mostCentralIndex).x / ((double) src1.size()); 01457 centroid_1.x *= ((double) src1.size()) / ((double) new_src_1.size()); 01458 01459 centroid_2.x -= new_src_2.at(mostCentralIndex).x / ((double) src2.size()); 01460 centroid_2.x *= ((double) src2.size()) / ((double) new_src_2.size()); 01461 01462 new_src_1.erase(new_src_1.begin() + mostCentralIndex); 01463 new_src_2.erase(new_src_2.begin() + mostCentralIndex); 01464 01465 printf("%s << Most central index: %d\n", __FUNCTION__, mostCentralIndex); 01466 01467 for (int iii = 0; iii < aimedPoints-1; iii++) { 01468 01469 Point2f centroid_1, centroid_2; 01470 01471 float largestDist; 01472 unsigned int largestIndex; 01473 01474 for (unsigned int jjj = 0; jjj < new_src_1.size(); jjj++) { 01475 01476 float dist = distanceBetweenPoints(new_src_1.at(jjj), centroid_1) + distanceBetweenPoints(new_src_2.at(jjj), centroid_2); 01477 01478 if ((jjj == 0) || (dist > largestDist)) { 01479 largestDist = dist; 01480 largestIndex = jjj; 01481 } 01482 01483 } 01484 01485 centroid_1.x -= new_src_1.at(largestIndex).x / ((double) new_src_1.size()); 01486 centroid_1.x *= ((double) new_src_1.size()) / ((double) new_src_1.size() - 1); 01487 01488 centroid_2.x -= new_src_2.at(mostCentralIndex).x / ((double) new_src_2.size()); 01489 centroid_2.x *= ((double) new_src_2.size()) / ((double) new_src_2.size() - 1); 01490 01491 dst1.push_back(new_src_1.at(largestIndex)); 01492 dst2.push_back(new_src_2.at(largestIndex)); 01493 01494 new_src_1.erase(new_src_1.begin() + largestIndex); 01495 new_src_2.erase(new_src_2.begin() + largestIndex); 01496 01497 } 01498 01499 //dst1.insert(dst1.end(), src1.begin(), src1.end()); 01500 //dst2.insert(dst2.end(), src2.begin(), src2.end()); 01501 01502 } 01503 01504 int estimatePoseBetweenCameras(cameraParameters& camData, vector<Point2f>& pts1, vector<Point2f>& pts2, Mat& C) { 01505 Mat F, matchesMask_F_matrix; 01506 01507 F = findFundamentalMat(Mat(pts1), Mat(pts2), FM_RANSAC, 1.00, 0.99, matchesMask_F_matrix); 01508 01509 Mat E = camData.K.t() * F * camData.K; 01510 01511 Mat CX[4]; 01512 01513 findFourTransformations(CX, E, camData.K, pts1, pts2); 01514 01515 int validPts = findBestCandidate(CX, camData.K, pts1, pts2, C); 01516 01517 return validPts; 01518 } 01519 01520 double testKeyframePair(vector<featureTrack>& tracks, cameraParameters& camData, double *scorecard[], int idx1, int idx2, double *score, Mat& pose, bool evaluate, bool debug) { 01521 01522 //printf("%s << Entered.\n", __FUNCTION__); 01523 01524 //if (debug) { 01525 //printf("%s << Testing frames (%d) & (%d)\n", __FUNCTION__, idx1, idx2); 01526 //} 01527 01528 double keyframeScore; 01529 01530 for (unsigned int iii = 0; iii < 5; iii++) { 01531 score[iii] = -1.0; 01532 } 01533 01534 vector<Point2f> pts1_, pts2_, pts1, pts2; 01535 getPointsFromTracks(tracks, pts1, pts2, idx1, idx2); 01536 01537 //printf("%s << A: pts1.size() = %d; pts2.size() = %d\n", __FUNCTION__, pts1.size(), pts2.size()); 01538 01539 subselectPoints(pts1_, pts1, pts2_, pts2); 01540 01541 pts1.insert(pts1.end(), pts1_.begin(), pts1_.end()); 01542 pts2.insert(pts2.end(), pts2_.begin(), pts2_.end()); 01543 01544 //printf("%s << B: pts1.size() = %d; pts2.size() = %d\n", __FUNCTION__, pts1.size(), pts2.size()); 01545 01546 unsigned int min_pts = std::min(pts1.size(), pts2.size()); 01547 01548 if (min_pts < 16) { 01549 printf("%s << Returning with (-1); insufficient points.\n", __FUNCTION__); 01550 return -1.00; 01551 } 01552 01553 Mat matchesMask_F_matrix, matchesMask_H_matrix; 01554 01555 Mat F = findFundamentalMat(Mat(pts1), Mat(pts2), FM_RANSAC, 1.00, 0.99, matchesMask_F_matrix); 01556 Mat H = findHomography(Mat(pts1), Mat(pts2), FM_RANSAC, 1.00, matchesMask_H_matrix); 01557 01558 //int inliers_H = countNonZero(matchesMask_H_matrix); 01559 //int inliers_F = countNonZero(matchesMask_F_matrix); 01560 01561 //double new_F_score = calcInlierGeometryDistance(pts1, pts2, F, matchesMask_F_matrix, SAMPSON_DISTANCE); 01562 //double new_H_score = calcInlierGeometryDistance(pts1, pts2, H, matchesMask_H_matrix, LOURAKIS_DISTANCE); 01563 01564 //double geometryScore = calcGeometryScore(inliers_H, inliers_F, new_H_score, new_F_score); 01565 01566 // gric score 01567 double fGric, hGric; 01568 double gricScore = normalizedGRICdifference(pts1, pts2, F, H, matchesMask_F_matrix, matchesMask_H_matrix, fGric, hGric); 01569 gricScore = fGric / hGric; 01570 //double gricIdeal = 2.0, gricMax = 10.0, gricMin = 1.0; 01571 double nGRIC = asymmetricGaussianValue(gricScore, scorecard[1][0], scorecard[1][2], scorecard[1][2]); 01572 //printf("%s << SCORES: geom (%f), conv (%f), gric (%f / [%d / %d]), pts (%f)\n", __FUNCTION__, geometryScore, twoErr, gricScore, (int) fGric, (int) hGric, infrontScore); 01573 01574 score[1] = gricScore; 01575 01576 //else if (geometryScore < 1.00) { 01577 // geometryScore = -1.00; 01578 //} 01579 01580 if (nGRIC == 0.00) { 01581 if (!evaluate) { 01582 printf("%s << Returning with (0); nGric = 0.00.\n", __FUNCTION__); 01583 return 0.00; 01584 } 01585 } 01586 01587 Mat E = camData.K.t() * F * camData.K; 01588 Mat CX[4], C; 01589 findFourTransformations(CX, E, camData.K, pts1, pts2); 01590 int validPts = findBestCandidate(CX, camData.K, pts1, pts2, C); 01591 01592 // infrontScore 01593 //double infrontIdeal = 1.00, infrontMax = 1.00, infrontMin = 0.90; 01594 double infrontScore = ((double) validPts) / ((double) pts1.size()); 01595 double nIFS = asymmetricGaussianValue(infrontScore, scorecard[2][0], scorecard[2][2], scorecard[2][1]); 01596 01597 score[2] = infrontScore; 01598 01599 // Now correct if amt in front is greater than mean: 01600 if (infrontScore >= scorecard[2][0]) { 01601 nIFS = 1.00; 01602 } 01603 01604 if (nIFS == 0) { 01605 if (!evaluate) { 01606 printf("%s << Returning with (0); nIFS = 0.00.\n", __FUNCTION__); 01607 return 0.00; 01608 } 01609 } 01610 01611 Mat absolute_C0, P0, P1; 01612 absolute_C0 = Mat::eye(4, 4, CV_64FC1); 01613 01614 transformationToProjection(absolute_C0, P0); 01615 transformationToProjection(C, P1); 01616 //pose.copyTo(P1); 01617 01618 vector<Point3d> cloud; 01619 vector<Point2f> corresp; 01620 01621 if (debug) { 01622 /* 01623 printf("%s << Before triangulation: \n", __FUNCTION__); 01624 cout << P0 << endl; 01625 cout << P1 << endl; 01626 */ 01627 } 01628 01629 TriangulatePoints(pts1, pts2, camData.K, camData.K.inv(), P0, P1, cloud, corresp); 01630 01631 //printf("%s << Before 2-frame BA: \n", __FUNCTION__); 01632 //cout << P0 << endl; 01633 //cout << P1 << endl; 01634 01635 if (debug) { 01636 /* 01637 printf("%s << Before 2-frame BA: \n", __FUNCTION__); 01638 cout << P0 << endl; 01639 cout << P1 << endl; 01640 */ 01641 } 01642 01643 // convergence 01644 //double convIdeal = 0.30, convMax = 0.80, convMin = 0.10; 01645 double twoErr = twoViewBundleAdjustment(camData, P0, P1, cloud, pts1, pts2, 10); 01646 01647 score[0] = twoErr; 01648 01649 if (debug) { 01650 /* 01651 printf("%s << After 2-frame BA: \n", __FUNCTION__); 01652 cout << P0 << endl; 01653 cout << P1 << endl; 01654 */ 01655 for (unsigned int iii = 0; iii < 10; iii++) { 01656 //printf("%s << pt(%d) = (%f, %f) & (%f, %f)\n", __FUNCTION__, iii, pts1.at(iii).x, pts1.at(iii).y, pts2.at(iii).x, pts2.at(iii).y); 01657 } 01658 } 01659 01660 double nCONV = asymmetricGaussianValue(twoErr, scorecard[0][0], scorecard[0][2], scorecard[0][1]); 01661 01662 if (nCONV == 0.00) { 01663 if (!evaluate) { 01664 printf("%s << Returning with (0); nCONV = 0.00.\n", __FUNCTION__); 01665 return 0.00; 01666 } 01667 } 01668 01669 projectionToTransformation(P1, C); 01670 01671 // break it down to get Z component and angle... 01672 Mat R, t; 01673 decomposeTransform(C, R, t); 01674 01675 // translation score 01676 //double transIdeal = 3.00, transMax = 5.00, transMin = 1.00; 01677 double tScore = (abs(t.at<double>(0,0)) + abs(t.at<double>(1,0))) / abs(t.at<double>(2,0)); 01678 01679 score[3] = tScore; 01680 01681 double nTRN = asymmetricGaussianValue(tScore, scorecard[3][0], scorecard[3][2], scorecard[3][1]); 01682 01683 if (nTRN == 0.00) { 01684 if (!evaluate) { 01685 return 0.00; 01686 } 01687 } 01688 01689 // angle score 01690 //double angleIdeal = 10.0, angleMax = 15.0, angleMin = 5.0; 01691 double dScore = getRotationInDegrees(R); 01692 01693 score[4] = dScore; 01694 01695 double nANG = asymmetricGaussianValue(dScore, scorecard[4][0], scorecard[4][2], scorecard[4][1]); 01696 01697 if (nANG == 0.00) { 01698 if (!evaluate) { 01699 printf("%s << Returning with (0); nANG = 0.00.\n", __FUNCTION__); 01700 return 0.00; 01701 } 01702 } 01703 01704 //double homographyScore = 0.00; // later this will be replaced by a method for determining FOV change / rot angle 01705 01706 // Followed by checks to set homography score to be less than zero (not enough view change, H-score too low etc) 01707 01708 01709 01710 01711 01712 01713 01714 //cout << t << endl; 01715 01716 //printf("%s << Convergence score = %f\n", __FUNCTION__, twoErr); 01717 01718 unsigned int numTerms = 5; 01719 keyframeScore = pow(nCONV * nGRIC * nIFS * nTRN * nANG, 1.0 / ((double) numTerms)); 01720 01721 //if (debug) { 01722 printf("%s << [%f]: conv (%1.2f, %1.2f), gric (%1.2f, %1.2f), if (%1.2f, %1.2f), trans (%1.2f, %1.2f), ang (%02.1f, %1.2f)\n", __FUNCTION__, keyframeScore, twoErr, nCONV, gricScore, nGRIC, infrontScore, nIFS, tScore, nTRN, dScore, nANG); 01723 //} 01724 01725 01726 P1.copyTo(pose); 01727 01728 //printf("%s << Exiting.\n", __FUNCTION__); 01729 01730 return keyframeScore; 01731 01732 } 01733 01734 01735 //double testKeyframePair(vector<featureTrack>& tracks, cameraParameters& camData, int idx1, int idx2, double *score, Mat& pose, bool evaluate, bool debug) { 01736 01737 //printf("%s << Entered.\n", __FUNCTION__); 01738 01740 //printf("%s << Testing frames (%d) & (%d)\n", __FUNCTION__, idx1, idx2); 01742 01743 //double keyframeScore; 01744 01745 //for (unsigned int iii = 0; iii < 5; iii++) { 01746 //score[iii] = -1.0; 01747 //} 01748 01749 //vector<Point2f> pts1_, pts2_, pts1, pts2; 01750 //getPointsFromTracks(tracks, pts1, pts2, idx1, idx2); 01751 01752 //printf("%s << A: pts1.size() = %d; pts2.size() = %d\n", __FUNCTION__, pts1.size(), pts2.size()); 01753 01754 //subselectPoints(pts1_, pts1, pts2_, pts2); 01755 01756 //pts1.insert(pts1.end(), pts1_.begin(), pts1_.end()); 01757 //pts2.insert(pts2.end(), pts2_.begin(), pts2_.end()); 01758 01759 //printf("%s << B: pts1.size() = %d; pts2.size() = %d\n", __FUNCTION__, pts1.size(), pts2.size()); 01760 01761 //unsigned int min_pts = std::min(pts1.size(), pts2.size()); 01762 01763 //if (min_pts < 16) { 01764 //return -1.00; 01765 //} 01766 01767 //Mat matchesMask_F_matrix, matchesMask_H_matrix; 01768 01769 //Mat F = findFundamentalMat(Mat(pts1), Mat(pts2), FM_RANSAC, 1.00, 0.99, matchesMask_F_matrix); 01770 //Mat H = findHomography(Mat(pts1), Mat(pts2), FM_RANSAC, 1.00, matchesMask_H_matrix); 01771 01774 01777 01779 01781 //double fGric, hGric; 01782 //double gricScore = normalizedGRICdifference(pts1, pts2, F, H, matchesMask_F_matrix, matchesMask_H_matrix, fGric, hGric); 01783 //gricScore = fGric / hGric; 01784 //double gricIdeal = 2.0, gricMax = 10.0, gricMin = 1.0; 01785 //double nGRIC = asymmetricGaussianValue(gricScore, gricIdeal, gricMin, gricMax); 01787 01791 01792 //if (nGRIC == 0.00) { 01793 //if (!evaluate) { 01794 //return 0.00; 01795 //} 01796 //} 01797 01798 //Mat E = camData.K.t() * F * camData.K; 01799 //Mat CX[4], C; 01800 //findFourTransformations(CX, E, camData.K, pts1, pts2); 01801 //int validPts = findBestCandidate(CX, camData.K, pts1, pts2, C); 01802 01804 //double infrontIdeal = 1.00, infrontMax = 1.00, infrontMin = 0.90; 01805 //double infrontScore = ((double) validPts) / ((double) pts1.size()); 01806 //double nIFS = asymmetricGaussianValue(infrontScore, infrontIdeal, infrontMin, infrontMax); 01807 01808 //if (nIFS == 0) { 01809 //if (!evaluate) { 01810 //return 0.00; 01811 //} 01812 //} 01813 01814 //Mat absolute_C0, P0, P1; 01815 //absolute_C0 = Mat::eye(4, 4, CV_64FC1); 01816 01817 //transformationToProjection(absolute_C0, P0); 01818 //transformationToProjection(C, P1); 01820 01821 //vector<Point3d> cloud; 01822 //vector<Point2f> corresp; 01823 01824 //if (debug) { 01826 //printf("%s << Before triangulation: \n", __FUNCTION__); 01827 //cout << P0 << endl; 01828 //cout << P1 << endl; 01829 //*/ 01830 //} 01831 01832 //TriangulatePoints(pts1, pts2, camData.K, camData.K.inv(), P0, P1, cloud, corresp); 01833 01837 01838 //if (debug) { 01840 //printf("%s << Before 2-frame BA: \n", __FUNCTION__); 01841 //cout << P0 << endl; 01842 //cout << P1 << endl; 01843 //*/ 01844 //} 01845 01847 //double convIdeal = 0.30, convMax = 0.80, convMin = 0.10; 01848 //double twoErr = twoViewBundleAdjustment(camData, P0, P1, cloud, pts1, pts2, 10); 01849 01850 01851 01852 //if (debug) { 01854 //printf("%s << After 2-frame BA: \n", __FUNCTION__); 01855 //cout << P0 << endl; 01856 //cout << P1 << endl; 01857 //*/ 01858 //for (unsigned int iii = 0; iii < 10; iii++) { 01860 //} 01861 //} 01862 01863 //double nCONV = asymmetricGaussianValue(twoErr, convIdeal, convMin, convMax); 01864 01865 //if (nCONV == 0.00) { 01866 //if (!evaluate) { 01867 //return 0.00; 01868 //} 01869 //} 01870 01871 //projectionToTransformation(P1, C); 01872 01874 //Mat R, t; 01875 //decomposeTransform(C, R, t); 01876 01878 //double transIdeal = 3.00, transMax = 5.00, transMin = 1.00; 01879 //double tScore = (abs(t.at<double>(0,0)) + abs(t.at<double>(1,0))) / abs(t.at<double>(2,0)); 01880 //double nTRN = asymmetricGaussianValue(tScore, transIdeal, transMin, transMax); 01881 01882 //if (nTRN == 0.00) { 01883 //if (!evaluate) { 01884 //return 0.00; 01885 //} 01886 //} 01887 01889 //double angleIdeal = 10.0, angleMax = 15.0, angleMin = 5.0; 01890 //double dScore = getRotationInDegrees(R); 01891 //double nANG = asymmetricGaussianValue(dScore, angleIdeal, angleMin, angleMax); 01892 01893 //if (nANG == 0.00) { 01894 //if (!evaluate) { 01895 //return 0.00; 01896 //} 01897 //} 01898 01900 01902 01903 //score[0] = twoErr; 01904 //score[1] = gricScore; 01905 //score[2] = infrontScore; 01906 //score[3] = tScore; 01907 //score[4] = dScore; 01908 01910 01912 01913 //unsigned int numTerms = 5; 01914 //keyframeScore = pow(nCONV * nGRIC * nIFS * nTRN * nANG, 1.0 / ((double) numTerms)); 01915 01917 //printf("%s << [%f]: conv (%1.2f, %1.2f), gric (%1.2f, %1.2f), if (%1.2f, %1.2f), trans (%1.2f, %1.2f), ang (%02.1f, %1.2f)\n", __FUNCTION__, keyframeScore, twoErr, nCONV, gricScore, nGRIC, infrontScore, nIFS, tScore, nTRN, dScore, nANG); 01919 01920 01921 //P1.copyTo(pose); 01922 01923 //printf("%s << Exiting.\n", __FUNCTION__); 01924 01925 //return keyframeScore; 01926 01927 //} 01928 01929 01930 double optimizeSystem(SysSBA &sba, double err, int iterations) { 01931 01932 printf("%s << ENTERED.\n", __FUNCTION__); 01933 01934 double error = -1.0, prevError = -1.0; 01935 sba.verbose = 0; 01936 01937 printf("%s << DEBUG (%d)\n", __FUNCTION__, 0); 01938 01939 for (int iii = 0; iii < iterations/5; iii++) { 01940 01941 printf("%s << DEBUG (%d)(%d) : (%d, %d)\n", __FUNCTION__, iii, 0, sba.nodes.size(), sba.tracks.size()); 01942 01943 if (!sba.doSBA(5, err, SBA_SPARSE_CHOLESKY)) { 01944 return 9e99; 01945 } 01946 01947 printf("%s << DEBUG (%d)(%d)\n", __FUNCTION__, iii, 1); 01948 01949 error = sba.calcAvgError(); 01950 01951 printf("%s << DEBUG (%d)(%d)\n", __FUNCTION__, iii, 2); 01952 01953 if (error == prevError) { 01954 return error; 01955 } else { 01956 prevError = error; 01957 } 01958 01959 printf("%s << DEBUG (%d)(%d)\n", __FUNCTION__, iii, 3); 01960 //printf("%s << error(%d) = %f\n", __FUNCTION__, iii, error); 01961 } 01962 01963 printf("%s << DEBUG (%d)\n", __FUNCTION__, 1); 01964 01965 //int iterationsPerformed = sba.doSBA(iterations, err, SBA_SPARSE_CHOLESKY); 01966 //printf("%s << its performed = %d\n", __FUNCTION__, iterationsPerformed); 01967 01968 // sba.doSBA(iterations, err, SBA_SPARSE_CHOLESKY); 01969 constrainDodgyPoints(sba); 01970 01971 printf("%s << EXITING.\n", __FUNCTION__); 01972 01973 return error; 01974 } 01975 01976 double twoViewBundleAdjustment(cameraParameters cam_data, Mat& cam1, Mat& cam2, vector<Point3d>& cloud, vector<Point2f>& pts1, vector<Point2f>& pts2, int iterations) { 01977 01978 SysSBA sys; 01979 01980 sys.verbose = 0; 01981 01982 addFixedCamera(sys, cam_data, cam1); 01983 addNewCamera(sys, cam_data, cam2); 01984 01985 addPointsToSBA(sys, cloud); 01986 01987 addProjectionsToSBA(sys, pts1, 0); 01988 addProjectionsToSBA(sys, pts2, 1); 01989 01990 // printf("%s << nodes = %d; tracks = %d\n", __FUNCTION__, sys.nodes.size(), sys.tracks.size()); 01991 01992 double avgError = optimizeSystem(sys, 1e-4, iterations); 01993 01994 retrieveCameraPose(sys, cam2, 1); 01995 cloud.clear(); 01996 retrieveAllPoints(cloud, sys); 01997 01998 return avgError; 01999 02000 } 02001 02002 void addPointsToSBA(SysSBA& sba, vector<Point3d>& cloud) { 02003 02004 Vector2d proj; 02005 02006 for (unsigned int iii = 0; iii < cloud.size(); iii++) { 02007 02008 Vector4d temppoint(cloud.at(iii).x, cloud.at(iii).y, cloud.at(iii).z, 1.0); 02009 02010 sba.addPoint(temppoint); 02011 02012 /* 02013 proj.x() = loc1.at(iii).x; 02014 proj.y() = loc1.at(iii).y; 02015 02016 sba.addMonoProj(idx0, iii, proj); 02017 02018 proj.x() = loc2.at(iii).x; 02019 proj.y() = loc2.at(iii).y; 02020 02021 sba.addMonoProj(idx1, iii, proj); 02022 * */ 02023 } 02024 } 02025 02026 void addProjectionToSBA(SysSBA& sba, Point2f& loc, unsigned int trackNo, unsigned int camNo) { 02027 02028 Vector2d proj; 02029 proj.x() = loc.x; 02030 proj.y() = loc.y; 02031 sba.addMonoProj(camNo, trackNo, proj); 02032 } 02033 02034 void addProjectionsToSBA(SysSBA& sba, vector<Point2f>& loc, int idx) { 02035 02036 Vector2d proj; 02037 02038 // printf("%s << ENTERED.\n", __FUNCTION__); 02039 02040 for (unsigned int iii = 0; iii < loc.size(); iii++) { 02041 02042 if (iii >= sba.tracks.size()) { 02043 printf("%s << WARNING! provided locations exceed number of tracks in system...\n", __FUNCTION__); 02044 break; 02045 } 02046 02047 //printf("%s << it(%d)\n", __FUNCTION__, iii); 02048 proj.x() = loc.at(iii).x; 02049 proj.y() = loc.at(iii).y; 02050 02051 //printf("%s << Adding projection... (%d / %d) : (%d / %d)\n", __FUNCTION__, iii, sba.tracks.size(), idx, sba.nodes.size()); 02052 sba.addMonoProj(idx, iii, proj); 02053 02054 //printf("%s << Projection added. (%d)\n", __FUNCTION__, iii); 02055 } 02056 02057 printf("%s << EXITING.\n", __FUNCTION__); 02058 } 02059 02060 void extractPointCloud(const SysSBA &sba, pcl::PointCloud<pcl::PointXYZ>& point_cloud) { 02061 02062 for (unsigned int kkk = 0; kkk < sba.tracks.size(); kkk++) { 02063 02064 Vector4d pt = sba.tracks[kkk].point; 02065 02066 pcl::PointXYZ pclPt(pt(2), -pt(0), -pt(1)); 02067 point_cloud.points.push_back(pclPt); 02068 //printf("%s << cloud_pt(%d) = (%f, %f, %f)\n", __FUNCTION__, kkk, pointCloud.at(kkk).x, pointCloud.at(kkk).y, pointCloud.at(kkk).z); 02069 } 02070 } 02071 02072 void extractCameras(const SysSBA &sba, visualization_msgs::MarkerArray& cameraArray, visualization_msgs::Marker& marker_path) { 02073 02074 uint32_t shape = visualization_msgs::Marker::ARROW; 02075 02076 cameraArray.markers.clear(); 02077 02078 visualization_msgs::Marker marker; 02079 marker.header.frame_id = "/pgraph"; 02080 marker.ns = "cameras"; 02081 marker.type = shape; 02082 marker.action = visualization_msgs::Marker::ADD; 02083 marker.scale.x = 0.5; 02084 marker.scale.y = 0.5; 02085 marker.scale.z = 0.5; 02086 02087 // And adjust path... 02088 02089 marker_path.points.clear(); 02090 02091 marker_path.header.frame_id = "/pgraph"; 02092 marker_path.header.stamp = ros::Time(); 02093 marker_path.ns = "camera_path"; 02094 marker_path.id = 0; 02095 marker_path.type = visualization_msgs::Marker::LINE_STRIP; 02096 marker_path.action = visualization_msgs::Marker::ADD; 02097 02098 marker_path.pose.position.x = 0.0; 02099 marker_path.pose.position.y = 0.0; 02100 marker_path.pose.position.z = 0.0; 02101 02102 marker_path.pose.orientation.x = 0.0; 02103 marker_path.pose.orientation.y = 0.0; 02104 marker_path.pose.orientation.z = 0.0; 02105 marker_path.pose.orientation.w = 1.0; 02106 02107 marker_path.scale.x = 0.02; 02108 02109 marker_path.color.a = 1.0; 02110 marker_path.color.r = 0.0; 02111 marker_path.color.g = 0.0; 02112 marker_path.color.b = 1.0; 02113 02114 marker_path.lifetime = ros::Duration(); 02115 02116 geometry_msgs::Point p; 02117 02118 for (unsigned int iii = 0; iii < sba.nodes.size(); iii++) { 02119 02120 printf("%s << Adding node #%d\n", __FUNCTION__, iii); 02121 marker.header.stamp = ros::Time(); 02122 marker.id = iii; 02123 02124 02125 02126 marker.pose.position.x = sba.nodes.at(iii).trans.x(); 02127 marker.pose.position.y = sba.nodes.at(iii).trans.y(); 02128 marker.pose.position.z = sba.nodes.at(iii).trans.z(); 02129 02130 p.x = sba.nodes.at(iii).trans.x(); 02131 p.y = sba.nodes.at(iii).trans.y(); 02132 p.z = sba.nodes.at(iii).trans.z(); 02133 02134 printf("%s << New co-ordinates = [%f, %f, %f]\n", __FUNCTION__, p.x, p.y, p.z); 02135 02136 marker.pose.orientation.x = sba.nodes.at(iii).qrot.x(); 02137 marker.pose.orientation.y = sba.nodes.at(iii).qrot.y(); 02138 marker.pose.orientation.z = sba.nodes.at(iii).qrot.z(); 02139 marker.pose.orientation.w = 1.0; 02140 02141 printf("%s << New rotations are = [%f, %f, %f]\n", __FUNCTION__, marker.pose.orientation.x, marker.pose.orientation.y, marker.pose.orientation.z); 02142 02143 marker_path.points.push_back(p); 02144 02145 cameraArray.markers.push_back( marker ); 02146 } 02147 02148 } 02149 02150 void initializeFrameCamera(frame_common::CamParams& cam_params, const Mat& newCamMat, int& maxx, int& maxy, const Size& cameraSize) { 02151 02152 cam_params.fx = newCamMat.at<double>(0,0); // Focal length in x 02153 cam_params.fy = newCamMat.at<double>(1,1); // Focal length in y 02154 cam_params.cx = newCamMat.at<double>(0,2); // X position of principal point 02155 cam_params.cy = newCamMat.at<double>(1,2); // Y position of principal point 02156 cam_params.tx = 0; // Baseline (no baseline since this is monocular) 02157 02158 // Define dimensions of the image. 02159 maxx = cameraSize.width; 02160 maxy = cameraSize.height; 02161 } 02162 02163 void drawGraph2(const SysSBA &sba, const ros::Publisher &camera_pub, 02164 const ros::Publisher &point_pub, const ros::Publisher &path_pub, int decimation, int bicolor, double scale) 02165 { 02166 int num_points = sba.tracks.size(); 02167 int num_cameras = sba.nodes.size(); 02168 if (num_points == 0 && num_cameras == 0) return; 02169 02170 visualization_msgs::Marker camera_marker, point_marker, path_marker; 02171 camera_marker.header.frame_id = "/pgraph"; 02172 camera_marker.header.stamp = ros::Time::now(); 02173 camera_marker.ns = "pgraph"; 02174 camera_marker.id = 0; 02175 camera_marker.action = visualization_msgs::Marker::ADD; 02176 camera_marker.pose.position.x = 0; 02177 camera_marker.pose.position.y = 0; 02178 camera_marker.pose.position.z = 0; 02179 camera_marker.pose.orientation.x = 0.0; 02180 camera_marker.pose.orientation.y = 0.0; 02181 camera_marker.pose.orientation.z = 0.0; 02182 camera_marker.pose.orientation.w = 1.0; 02183 camera_marker.scale.x = 0.02; 02184 camera_marker.scale.y = 0.02; 02185 camera_marker.scale.z = 0.02; 02186 camera_marker.color.r = 1.0f; 02187 camera_marker.color.g = 0.0f; 02188 camera_marker.color.b = 0.0f; 02189 camera_marker.color.a = 1.0f; 02190 camera_marker.lifetime = ros::Duration(); 02191 camera_marker.type = visualization_msgs::Marker::LINE_LIST; 02192 02193 point_marker = camera_marker; 02194 point_marker.color.r = 0.5f; 02195 point_marker.color.g = 0.5f; 02196 point_marker.color.b = 1.0f; 02197 point_marker.color.a = 1.0f; // 0.5f 02198 point_marker.scale.x = scale; 02199 point_marker.scale.y = scale; 02200 point_marker.scale.z = scale; 02201 point_marker.type = visualization_msgs::Marker::POINTS; 02202 02203 path_marker = point_marker; 02204 path_marker.color.r = 0.0f; 02205 path_marker.color.g = 0.5f; 02206 path_marker.color.b = 0.0f; 02207 path_marker.color.a = 1.0f; 02208 path_marker.scale.x = 0.03; 02209 path_marker.type = visualization_msgs::Marker::LINE_STRIP; 02210 02211 02212 double maxPt = 0.00, maxPt2 = 0.00; 02213 02214 // draw points, decimated 02215 point_marker.points.resize((int)(num_points/(double)decimation + 0.5)); 02216 point_marker.colors.resize((int)(num_points/(double)decimation + 0.5)); 02217 for (int i=0, ii=0; i < num_points; i += decimation, ii++) 02218 { 02219 //const Vector4d &pt = sba.tracks[i].point; 02220 Vector4d pt(sba.tracks[i].point); 02221 //point_marker.colors[ii].r = 1.0f; 02222 //if (bicolor > 0 && i >= bicolor) 02223 //point_marker.colors[ii].g = 1.0f; 02224 //else 02225 //point_marker.colors[ii].g = 0.0f; 02226 //point_marker.colors[ii].b = 0.0f; 02227 02228 maxPt = max(maxPt, abs(pt(2))); 02229 maxPt = max(maxPt, abs(pt(1))); 02230 maxPt = max(maxPt, abs(pt(0))); 02231 02232 if (abs(pt(2)) > MAX_RVIZ_DISPLACEMENT) { 02233 pt(2) = 0.0; 02234 } 02235 02236 if (abs(pt(0)) > MAX_RVIZ_DISPLACEMENT) { 02237 pt(0) = 0.0; 02238 } 02239 02240 if (abs(pt(1)) > MAX_RVIZ_DISPLACEMENT) { 02241 pt(1) = 0.0; 02242 } 02243 02244 maxPt2 = max(maxPt2, abs(pt(2))); 02245 maxPt2 = max(maxPt2, abs(pt(1))); 02246 maxPt2 = max(maxPt2, abs(pt(0))); 02247 02248 point_marker.points[ii].x = pt(2); 02249 point_marker.points[ii].y = -pt(0); 02250 point_marker.points[ii].z = -pt(1); 02251 } 02252 02253 //hajmig 02254 //printf("%s << maxPt = (%f, %f)\n", __FUNCTION__, maxPt, maxPt2); 02255 02256 // draw cameras 02257 camera_marker.points.resize(num_cameras*6); 02258 camera_marker.colors.resize(num_cameras*6); 02259 02260 double y_length = 0.00, x_length = 0.00, z_length = 0.30; 02261 02262 02263 double maxCam = 0.00, maxCam2 = 0.00; 02264 double maxOpt = 0.00, maxOpt2 = 0.00; 02265 02266 02267 02268 for (int i=0, ii=0; i < num_cameras; i++) 02269 { 02270 02271 float rv = ((float) (((float) i) / ((float) num_cameras)) * 1.0f); 02272 float bv = ((float) (((float) (num_cameras - i)) / ((float) num_cameras)) * 1.0f); 02273 02274 //const Node &nd = sba.nodes[i]; 02275 Node nd(sba.nodes[i]); 02276 Vector3d opt; 02277 Matrix<double,3,4> tr; 02278 transformF2W(tr,nd.trans,nd.qrot); 02279 02280 maxCam = max(maxCam, abs(nd.trans.z())); 02281 maxCam = max(maxCam, abs(nd.trans.x())); 02282 maxCam = max(maxCam, abs(nd.trans.y())); 02283 02284 if (abs(nd.trans.z()) > MAX_RVIZ_DISPLACEMENT) { 02285 nd.trans.z() = 0.0; 02286 } 02287 02288 if (abs(nd.trans.x()) > MAX_RVIZ_DISPLACEMENT) { 02289 nd.trans.x() = 0.0; 02290 } 02291 02292 if (abs(nd.trans.y()) > MAX_RVIZ_DISPLACEMENT) { 02293 nd.trans.y() = 0.0; 02294 } 02295 02296 maxCam2 = max(maxCam2, abs(nd.trans.z())); 02297 maxCam2 = max(maxCam2, abs(nd.trans.x())); 02298 maxCam2 = max(maxCam2, abs(nd.trans.y())); 02299 02300 camera_marker.colors[ii].r = rv; 02301 camera_marker.colors[ii].b = bv; 02302 02303 camera_marker.points[ii].x = nd.trans.z(); 02304 camera_marker.points[ii].y = -nd.trans.x(); 02305 camera_marker.points[ii++].z = -nd.trans.y(); 02306 02307 camera_marker.colors[ii].r = rv; 02308 camera_marker.colors[ii].b = bv; 02309 02310 opt = tr*Vector4d(0,0,z_length,1); 02311 02312 maxOpt = max(maxOpt, abs(opt.z())); 02313 maxOpt = max(maxOpt, abs(opt.x())); 02314 maxOpt = max(maxOpt, abs(opt.y())); 02315 02316 if (abs(opt.z()) > MAX_RVIZ_DISPLACEMENT) { 02317 opt.z() = 0.0; 02318 } 02319 02320 if (abs(opt.x()) > MAX_RVIZ_DISPLACEMENT) { 02321 opt.x() = 0.0; 02322 } 02323 02324 if (abs(opt.y()) > MAX_RVIZ_DISPLACEMENT) { 02325 opt.y() = 0.0; 02326 } 02327 02328 maxOpt2 = max(maxOpt2, abs(opt.z())); 02329 maxOpt2 = max(maxOpt2, abs(opt.x())); 02330 maxOpt2 = max(maxOpt2, abs(opt.y())); 02331 02332 02333 camera_marker.points[ii].x = opt.z(); 02334 camera_marker.points[ii].y = -opt.x(); 02335 camera_marker.points[ii++].z = -opt.y(); 02336 02337 camera_marker.colors[ii].r = rv; 02338 camera_marker.colors[ii].b = bv; 02339 02340 camera_marker.points[ii].x = nd.trans.z(); 02341 camera_marker.points[ii].y = -nd.trans.x(); 02342 camera_marker.points[ii++].z = -nd.trans.y(); 02343 02344 camera_marker.colors[ii].r = rv; 02345 camera_marker.colors[ii].b = bv; 02346 02347 opt = tr*Vector4d(x_length,0,0,1); 02348 02349 if (abs(opt.z()) > MAX_RVIZ_DISPLACEMENT) { 02350 opt.z() = 0.0; 02351 } 02352 02353 if (abs(opt.x()) > MAX_RVIZ_DISPLACEMENT) { 02354 opt.x() = 0.0; 02355 } 02356 02357 if (abs(opt.y()) > MAX_RVIZ_DISPLACEMENT) { 02358 opt.y() = 0.0; 02359 } 02360 02361 camera_marker.points[ii].x = opt.z(); 02362 camera_marker.points[ii].y = -opt.x(); 02363 camera_marker.points[ii++].z = -opt.y(); 02364 02365 02366 camera_marker.colors[ii].r = rv; 02367 camera_marker.colors[ii].b = bv; 02368 02369 02370 camera_marker.points[ii].x = nd.trans.z(); 02371 camera_marker.points[ii].y = -nd.trans.x(); 02372 camera_marker.points[ii++].z = -nd.trans.y(); 02373 02374 camera_marker.colors[ii].r = rv; 02375 camera_marker.colors[ii].b = bv; 02376 02377 opt = tr*Vector4d(0,y_length,0,1); 02378 02379 if (abs(opt.z()) > MAX_RVIZ_DISPLACEMENT) { 02380 opt.z() = 0.0; 02381 } 02382 02383 if (abs(opt.x()) > MAX_RVIZ_DISPLACEMENT) { 02384 opt.x() = 0.0; 02385 } 02386 02387 if (abs(opt.y()) > MAX_RVIZ_DISPLACEMENT) { 02388 opt.y() = 0.0; 02389 } 02390 02391 camera_marker.points[ii].x = opt.z(); 02392 camera_marker.points[ii].y = -opt.x(); 02393 camera_marker.points[ii++].z = -opt.y(); 02394 02395 02396 } 02397 02398 //hajmig 02399 // printf("%s << maxCam = (%f, %f)\n", __FUNCTION__, maxCam, maxCam2); 02400 // printf("%s << maxOpt = (%f, %f)\n", __FUNCTION__, maxOpt, maxOpt2); 02401 02402 // Draw path 02403 path_marker.points.resize(num_cameras); 02404 path_marker.colors.resize(num_cameras); 02405 02406 //Matrix<double,3,4> pr; 02407 02408 for (int ii=0; ii < num_cameras; ii++) 02409 { 02410 02411 float rv = ((float) (((float) ii) / ((float) num_cameras)) * 1.0f); 02412 float bv = ((float) (((float) (num_cameras - ii)) / ((float) num_cameras)) * 1.0f); 02413 02414 const Node &nd = sba.nodes[ii]; 02415 Vector3d opt; 02416 Matrix<double,3,4> tr; 02417 transformF2W(tr,nd.trans,nd.qrot); 02418 02419 path_marker.points[ii].x = nd.trans.z(); 02420 path_marker.points[ii].y = -nd.trans.x(); 02421 path_marker.points[ii].z = -nd.trans.y(); 02422 02423 path_marker.colors[ii].r = rv; 02424 path_marker.colors[ii].b = bv; 02425 02426 } 02427 02428 // draw point-plane projections 02429 //int num_tracks = sba.tracks.size(); 02430 //int ii = camera_marker.points.size(); 02431 02432 /* 02433 for (int i=0; i < num_tracks; i++) 02434 { 02435 const ProjMap &prjs = sba.tracks[i].projections; 02436 for (ProjMap::const_iterator itr = prjs.begin(); itr != prjs.end(); itr++) 02437 { 02438 const Proj &prj = (*itr).second; 02439 if (prj.pointPlane) // have a ptp projection 02440 { 02441 camera_marker.points.resize(ii+2); 02442 sba::Point pt0 = sba.tracks[i].point; 02443 Vector3d plane_point = prj.plane_point; 02444 Vector3d plane_normal = prj.plane_normal; 02445 Eigen::Vector3d w = pt0.head<3>()-plane_point; 02446 // Eigen::Vector3d projpt = plane_point+(w.dot(plane_normal))*plane_normal; 02447 Eigen::Vector3d projpt = pt0.head<3>() - (w.dot(plane_normal))*plane_normal; 02448 // Vector3d pt1 = pt0.head<3>()+0.1*plane_normal; 02449 Vector3d pt1 = projpt; 02450 02451 camera_marker.points[ii].x = pt0.z(); 02452 camera_marker.points[ii].y = -pt0.x(); 02453 camera_marker.points[ii++].z = -pt0.y(); 02454 camera_marker.points[ii].x = pt1.z(); 02455 camera_marker.points[ii].y = -pt1.x(); 02456 camera_marker.points[ii++].z = -pt1.y(); 02457 } 02458 } 02459 } 02460 */ 02461 02462 path_pub.publish(path_marker); 02463 camera_pub.publish(camera_marker); 02464 point_pub.publish(point_marker); 02465 } 02466 02467 void finishTracks(vector<featureTrack>& tracks, vector<Point2f>& pts, double retainProp, unsigned int maxOccurrences) { 02468 02469 if (maxOccurrences == 0) { 02470 return; 02471 } 02472 02473 if (tracks.size() == 0) { 02474 return; 02475 } 02476 02477 if (pts.size() == 0) { 02478 return; 02479 } 02480 02481 vector<unsigned char> invalidFlags; 02482 02483 for (unsigned int jjj = 0; jjj < tracks.size(); jjj++) { 02484 02485 if (tracks.at(jjj).locations.size() >= maxOccurrences) { 02486 02487 for (unsigned int iii = 0; iii < pts.size(); iii++) { 02488 02489 cout << pts.at(iii) << endl; 02490 cout << tracks.at(jjj).locations.size() << endl; 02491 cout << tracks.at(jjj).locations.at(tracks.at(jjj).locations.size()-1).featureCoord.x << endl; 02492 02493 if (pts.at(iii) == tracks.at(jjj).locations.at(tracks.at(jjj).locations.size()-1).featureCoord) { 02494 printf("%s << Found feature! (%d, %d)\n", __FUNCTION__, iii, jjj); 02495 02496 invalidFlags.push_back(iii); 02497 02498 02499 } 02500 02501 } 02502 } 02503 02504 } 02505 02506 if (invalidFlags.size() == 0) { 02507 return; 02508 } 02509 02510 double origSize = ((double) pts.size()); 02511 02512 while (((double) pts.size()) > (retainProp * origSize)) { 02513 02514 unsigned int index = rand() % invalidFlags.size(); 02515 02516 pts.erase(pts.begin() + invalidFlags.at(index)); 02517 invalidFlags.erase(invalidFlags.begin() + index); 02518 02519 } 02520 02521 02522 }