$search
00001 00005 #include "monoslam.hpp" 00006 00007 struct timeval cycle_timer; 00008 //double elapsedTime; 00009 00010 int main(int argc, char** argv) { 00011 00012 ROS_INFO("Node launched."); 00013 00014 ros::init(argc, argv, "thermal_slam"); 00015 00016 ros::NodeHandle private_node_handle("~"); 00017 00018 slamData startupData; 00019 00020 bool inputIsValid = startupData.obtainStartingData(private_node_handle); 00021 00022 startupData.read_addr = argv[0]; 00023 startupData.read_addr = startupData.read_addr.substr(0, startupData.read_addr.size()-12); 00024 00025 if (!inputIsValid) { 00026 ROS_INFO("Configuration invalid."); 00027 } 00028 00029 ROS_INFO("Startup data processed."); 00030 00031 //ros::Rate loop_rate(25); 00032 00033 ros::NodeHandle nh; 00034 00035 boost::shared_ptr < slamNode > slam_node (new slamNode (nh, startupData)); 00036 00037 globalNodePtr = &slam_node; 00038 00039 signal(SIGINT, mySigintHandler); 00040 00041 ROS_INFO("Node configured."); 00042 00043 ros::AsyncSpinner spinner(2); 00044 00045 spinner.start(); 00046 00047 ros::waitForShutdown(); 00048 00049 ROS_INFO("Exiting."); 00050 00051 return 0; 00052 00053 } 00054 00055 void slamNode::processScorecard() { 00056 00057 // Open up file 00058 00059 if ((configData.initializationScorecard[0] == '.') && (configData.initializationScorecard[1] == '.')) { 00060 configData.initializationScorecard = configData.read_addr + "nodes/monoslam/config/" + configData.initializationScorecard; 00061 } 00062 00063 //ROS_ERROR("Opening scorecard file: (%s)", configData.initializationScorecard.c_str()); 00064 00065 ifstream ifs(configData.initializationScorecard.c_str()); 00066 00067 for (int iii = 0; iii < INITIALIZATION_SCORING_PARAMETERS; iii++) { 00068 ifs >> scorecardParams[iii][0]; 00069 } 00070 00071 for (int iii = 0; iii < INITIALIZATION_SCORING_PARAMETERS; iii++) { 00072 ifs >> scorecardParams[iii][1]; 00073 } 00074 00075 for (int iii = 0; iii < INITIALIZATION_SCORING_PARAMETERS; iii++) { 00076 ifs >> scorecardParams[iii][2]; 00077 } 00078 00079 ifs.close(); 00080 00081 for (int iii = 0; iii < INITIALIZATION_SCORING_PARAMETERS; iii++) { 00082 ROS_INFO("Criteria (%d) = (%f, %f, %f)", iii, scorecardParams[iii][0], scorecardParams[iii][1], scorecardParams[iii][2]); 00083 } 00084 00085 } 00086 00087 bool slamData::obtainStartingData(ros::NodeHandle& nh) { 00088 00089 nh.param<std::string>("stream", stream, "null"); 00090 00091 if (stream != "null") { 00092 ROS_INFO("Tracker stream (%s) selected.", stream.c_str()); 00093 } else { 00094 ROS_ERROR("No tracker stream specified."); 00095 return false; 00096 } 00097 00098 nh.param<bool>("logErrors", logErrors, true); 00099 00100 nh.param<bool>("keyframeEvaluationMode", keyframeEvaluationMode, false); 00101 00102 nh.param<int>("maxTestsPerFrame", maxTestsPerFrame, 10); 00103 00104 nh.param<int>("maxInitializationFrames", maxInitializationFrames, 30); 00105 00106 nh.param<int>("minStartingSeparation", minStartingSeparation, 4); 00107 nh.param<int>("maxStartingSeparation", maxStartingSeparation, 12); 00108 00109 00110 nh.param<string>("initializationScorecard", initializationScorecard, "../config/default_scorecard.txt"); 00111 00112 return true; 00113 } 00114 00115 bool slamNode::checkForKeyframe() { 00116 unsigned int image_idx_2 = currentPoseIndex + 1; 00117 unsigned int previousKeyframe = keyframe_store.keyframes.at(keyframe_store.keyframes.size()-1).idx; 00118 bool keyframeAdded = false; 00119 bool hasReverted = false; 00120 00121 // IF CURRENT FRAME IS NOT A KEYFRAME, CHECK TO SEE IF IT SHOULD BE 00122 if (keyframe_store.keyframes.at(keyframe_store.keyframes.size()-1).idx != image_idx_2) { 00123 00124 vector<unsigned int> tempIndices, maintainedIndices; 00125 00126 getActiveTracks(tempIndices, featureTrackVector, previousKeyframe, image_idx_2); 00127 filterToCompleteTracks(maintainedIndices, tempIndices, featureTrackVector, previousKeyframe, image_idx_2); 00128 00129 double motionScore = getFeatureMotion(featureTrackVector, maintainedIndices, previousKeyframe, image_idx_2); 00130 00131 vector<unsigned int> untriangulatedIndices; 00132 unsigned int trackedSinceLast = maintainedIndices.size(); 00133 reduceActiveToTriangulated(featureTrackVector, maintainedIndices, untriangulatedIndices); 00134 00135 //printf("%s::%s << Tracked since last keyframe (%d, %d): %d / %d", __PROGRAM__, __FUNCTION__, previousKeyframe, image_idx_2, trackedSinceLast, startingTracksCount); 00136 00137 bool lowProportionTracked = false; 00138 if (trackedSinceLast < ((unsigned int) (((double) startingTracksCount) * configData.requiredTrackFrac))) { 00139 lowProportionTracked = true; 00140 //printf("%s::%s << Low proportion tracked: (%d / %d).", __PROGRAM__, __FUNCTION__, trackedSinceLast, startingTracksCount); 00141 } 00142 00143 // Low feature count will only trigger new keyframe selection if the PROPORTION is also low... 00144 00145 if (motionScore > configData.motionThreshold) { 00146 keyframe_store.addKeyframe(image_idx_2-1, blank); 00147 keyframeAdded = true; 00148 currentPoseIndex--; 00149 hasReverted = true; 00150 //printf("%s::%s << Marking (%d) as keyframe (large feature motion).", __PROGRAM__, __FUNCTION__, image_idx_2, motionScore); 00151 } else if ((image_idx_2 - previousKeyframe) == configData.maxKeyframeSeparation) { 00152 keyframe_store.addKeyframe(image_idx_2, blank); 00153 keyframeAdded = true; 00154 //printf("%s::%s << Marking (%d) as keyframe (max frames between).", __PROGRAM__, __FUNCTION__, image_idx_2); 00155 } else if (lowProportionTracked && (trackedSinceLast < configData.minTrackedFeatures) && (keyframe_store.keyframes.at(keyframe_store.keyframes.size()-1).idx != (image_idx_2-1))) { 00156 // test to see if too few features, and if previous frame is NOT a keyframe, then it should be set as one 00157 // ((initialPoints2.size() < configData.minTrackedFeatures) && (keyframe_store.keyframes.at(keyframe_store.count-1).idx != (iii-1))) { 00158 keyframe_store.addKeyframe(image_idx_2-1, blank); 00159 currentPoseIndex--; 00160 hasReverted = true; 00161 //printf("%s::%s << Marking (%d) [prev] as keyframe (too few features).", __PROGRAM__, __FUNCTION__, image_idx_2-1); 00162 keyframeAdded = true; 00163 //return false; 00164 //isKeyframe = true; 00165 //iii--; 00166 //keyframe_type = KF_TYPE_EXHAUSTED; 00167 } else if (lowProportionTracked && (trackedSinceLast < configData.minTrackedFeatures)) { 00168 keyframe_store.addKeyframe(image_idx_2, blank); 00169 keyframeAdded = true; 00170 // test to see if too few features since last keyframe, and if previous frame IS a keyframe, then current should be set as one 00171 //(initialPoints2.size() < configData.minTrackedFeatures) { 00172 //isKeyframe = true; 00173 //keyframe_type = KF_TYPE_WEAK; 00174 //printf("%s::%s << Marking (%d) as keyframe (too few features).", __PROGRAM__, __FUNCTION__, image_idx_2); 00175 } else if ((maintainedIndices.size() < configData.min3dPtsForPnP) && (keyframe_store.keyframes.at(keyframe_store.keyframes.size()-1).idx != (image_idx_2-1))) { 00176 // If there literally are not enough points to perform PNP for next frame 00177 keyframe_store.addKeyframe(image_idx_2-1, blank); 00178 currentPoseIndex--; 00179 hasReverted = true; 00180 keyframeAdded = true; 00181 //printf("%s::%s << Marking (%d) [prev] as keyframe (too few 3d points).", __PROGRAM__, __FUNCTION__, image_idx_2-1); 00182 //return false; 00183 } else if (maintainedIndices.size() < configData.min3dPtsForPnP) { 00184 //printf("%s::%s << ERROR! Too few 3d points for PnP but previous frame already added...", __PROGRAM__, __FUNCTION__); 00185 00186 } 00187 00188 } else { 00189 00190 } 00191 00192 return hasReverted; 00193 00194 if (hasReverted) { 00195 // Return true if the current frame is a keyframe 00196 return true; 00197 } 00198 00199 if (keyframeAdded) { 00200 ROS_INFO("Added frame (%d) as Keyframe [%d]", keyframe_store.keyframes.at(keyframe_store.keyframes.size()-1).idx, currentPoseIndex); 00201 //return true; 00202 } else { 00203 //currentPoseIndex++; 00204 //printf("%s << Skipping...", __FUNCTION__); 00205 //return false; 00206 } 00207 00208 return false; 00209 } 00210 00211 void slamNode::show_poses() { 00212 00213 for (int iii = 0; iii < currentPoseIndex; iii++) { 00214 if (ACM[iii].rows == 4) { 00215 00216 Mat temp; 00217 00218 estimatePoseFromKnownPoints(temp, configData.cameraData, featureTrackVector, iii, eye4); 00219 00220 ROS_INFO("EST[%d] = ", iii); 00221 cout << temp << endl; 00222 00223 estimatePoseFromKnownPoints(temp, configData.cameraData, featureTrackVector, iii, ACM[iii]); 00224 00225 ROS_INFO("ES2[%d] = ", iii); 00226 cout << temp << endl; 00227 00228 ROS_INFO("ACM[%d] = ", iii); 00229 cout << ACM[iii] << endl; 00230 } 00231 } 00232 00233 } 00234 00235 void slamNode::getGuidingPose(Mat *srcs, Mat& dst, unsigned int idx) { 00236 00237 Mat eye4 = Mat::eye(4, 4, CV_64FC1); 00238 00239 unsigned int maxGuides = std::min(((int) idx), configData.maxGuides); 00240 00241 if (srcs[idx].rows == 4) { 00242 // Already has an estimate 00243 srcs[idx].copyTo(dst); 00244 } else if (idx == 0) { 00245 // First frame so use identity 00246 eye4.copyTo(dst); 00247 } else if (srcs[idx-1].rows != 4) { 00248 // No previous frame at all so just use identity as guide 00249 eye4.copyTo(dst); 00250 } else { 00251 // Weighted combo of previous frames 00252 00253 //printf("%s::%s << Estimating frame (%d) using previous frame poses...", __PROGRAM__, __FUNCTION__, idx); 00254 00255 Mat R_dev, t_dev; 00256 R_dev = Mat::zeros(3, 1, CV_64FC1); 00257 t_dev = Mat::zeros(3, 1, CV_64FC1); 00258 00259 double total_contrib = 0.0; 00260 00261 for (unsigned int iii = idx-maxGuides; iii < idx-1; iii++) { 00262 00263 double contrib = ((double) idx) - ((double) iii); 00264 total_contrib += contrib; 00265 00266 //printf("%s::%s << Using frame (%d:%d) [contrib = %f]", __PROGRAM__, __FUNCTION__, iii, iii+1, contrib); 00267 00268 // For each pair of frames (iii & iii+1) 00269 00270 Mat R1, R2, t1, t2, rv1, rv2, rd, td; 00271 00272 // Decompose into R-vec and t-vec 00273 decomposeTransform(srcs[iii], R1, t1); 00274 Rodrigues(R1, rv1); 00275 decomposeTransform(srcs[iii+1], R2, t2); 00276 Rodrigues(R2, rv2); 00277 00278 // Find the derivative 00279 rd = rv2-rv1; 00280 00281 // Need to make sure derivative is represented as minimum angular change 00282 for (unsigned int jjj = 0; jjj < 3; jjj++) { 00283 00284 while (rd.at<double>(jjj, 0) > M_PI) { 00285 rd.at<double>(jjj, 0) -= 2*M_PI; 00286 } 00287 00288 while (rd.at<double>(jjj, 0) < -M_PI) { 00289 rd.at<double>(jjj, 0) += 2*M_PI; 00290 } 00291 } 00292 00293 //cout << "Deriv rotation = " << rd << endl; 00294 00295 td = t2-t1; 00296 00297 //cout << "Deriv translation = " << td << endl; 00298 00299 // Add a weighted version of the derivative to R_dev & t_dev 00300 R_dev += pow(0.5, contrib) * rd; 00301 t_dev += pow(0.5, contrib) * td; 00302 00303 } 00304 00305 // Re-weight R_dev and t_dev 00306 R_dev /= total_contrib; 00307 t_dev /= total_contrib; 00308 00309 //cout << "Weighted rotation = " << R_dev << endl; 00310 //cout << "Weighted translation = " << t_dev << endl; 00311 00312 // Add R_dev & t_dev to the previous pose 00313 Mat R_n, t_n, rv_n; 00314 decomposeTransform(srcs[idx-1], R_n, t_n); 00315 Rodrigues(R_n, rv_n); 00316 00317 rv_n += R_dev; 00318 Rodrigues(rv_n, R_n); 00319 t_n += t_dev; 00320 00321 //cout << "New rotation = " << rv_n << endl; 00322 //cout << "New translation = " << t_n << endl; 00323 00324 compileTransform(dst, R_n, t_n); 00325 00326 //cout << "Compiled transform = " << dst << endl; 00327 00328 } 00329 } 00330 00331 void mySigintHandler(int sig) 00332 { 00333 wantsToShutdown = true; 00334 ROS_WARN("Requested shutdown... terminating feeds..."); 00335 00336 (*globalNodePtr)->prepareForTermination(); 00337 } 00338 00339 void slamNode::estimatePose(vector<unsigned int>& basisNodes, unsigned int idx) { 00340 00341 //bool alreadyEstimated = false; 00342 00343 //ROS_INFO("Estimating pose (%d)...", idx); 00344 00345 if (ACM[idx].rows != 4) { 00346 00347 if (configData.timeDebug) poseEstimationTime.startRecording(); 00348 00349 Mat guidePose; 00350 getGuidingPose(ACM, guidePose, idx); 00351 00352 00353 00354 00355 //ROS_INFO("Guided pose gathered (%d)", idx); 00356 estimatePoseFromKnownPoints(ACM[idx], configData.cameraData, featureTrackVector, idx, guidePose); 00357 //cout << "guidePose = " << guidePose << endl; 00358 00359 if (configData.timeDebug) poseEstimationTime.stopRecording(); 00360 00361 if (ACM[idx-1].rows != 4) { 00362 //printf("%s::%s << Estimating pose (%d) with no guidance...", __PROGRAM__, __FUNCTION__, currentPoseIndex+1); 00363 //estimatePoseFromKnownPoints(ACM[idx], configData.cameraData, featureTrackVector, idx, eye4); 00364 } else { 00365 //printf("%s::%s << Estimating pose (%d) with (%d) to guide...", __PROGRAM__, __FUNCTION__, currentPoseIndex+1, currentPoseIndex); 00366 00367 00368 00369 //estimatePoseFromKnownPoints(ACM[idx], configData.cameraData, featureTrackVector, idx, ACM[idx-1]); 00370 } 00371 00372 } else { 00373 //printf("%s::%s << Pose (%d) already estimated...", __PROGRAM__, __FUNCTION__, currentPoseIndex+1); 00374 //alreadyEstimated = true; 00375 //return; 00376 } 00377 00378 //cout << "estPose = " << ACM[idx] << endl; 00379 00380 // Some kind of subsystem BA to go here... 00381 00382 if (1) { // (!alreadyEstimated) { 00383 double avgError; 00384 00385 if (configData.timeDebug) bundleAdjustmentTime.startRecording(); 00386 if (basisNodes.size() <= ((unsigned int) (configData.adjustmentFrames/2))) { 00387 //ROS_INFO("Basis nodes size is low: %d (%d)", basisNodes.size(), configData.flowback); 00388 avgError = keyframeBundleAdjustment(configData.cameraData, featureTrackVector, ACM, basisNodes, configData.poseEstimateIterations, false, false, 1); 00389 } else if (basisNodes.size()-configData.flowback > 0) { 00390 //for (unsigned int iii = 0; iii < basisNodes.size(); iii++) { 00391 //cout << basisNodes.at(iii) << endl; 00392 //} 00393 //ROS_INFO("Basis nodes size is a bit larger: %d (%d)", basisNodes.size(), configData.flowback); 00394 avgError = keyframeBundleAdjustment(configData.cameraData, featureTrackVector, ACM, basisNodes, configData.poseEstimateIterations, false, false, basisNodes.size()-configData.flowback); 00395 } else { 00396 //printf("Basis nodes size is poor: %d (%d)", basisNodes.size(), configData.flowback); 00397 avgError = keyframeBundleAdjustment(configData.cameraData, featureTrackVector, ACM, basisNodes, configData.poseEstimateIterations, false, false, 1); 00398 } 00399 if (configData.timeDebug) bundleAdjustmentTime.stopRecording(); 00400 //cout << "refinedPose = " << ACM[idx] << endl; 00401 00402 //printf("Error adjusting latest pose (%d) estimate: %f", idx, avgError); 00403 00404 if (configData.logErrors) { 00405 error_file << idx << " " << avgError << endl; 00406 } 00407 } 00408 00409 } 00410 00411 void slamNode::getBasisNodes(vector<unsigned int>& basisNodes, unsigned int idx) { 00412 00413 printf("%s << ENTERED.\n", __FUNCTION__); 00414 00415 basisNodes.clear(); 00416 00417 if (idx < keyframe_store.keyframes.at(0).idx) { 00418 ROS_WARN("ERROR! IDX too low (%d / %d)", idx, keyframe_store.keyframes.at(0).idx); 00419 return; 00420 } 00421 00422 int activeCameras = ((int) idx) + 1 - ((int) keyframe_store.keyframes.at(0).idx); 00423 00424 if (activeCameras < 2) { 00425 return; 00426 } 00427 00428 printf("%s << DEBUG [%0d]\n", __FUNCTION__, 0); 00429 00430 if (activeCameras <= configData.adjustmentFrames) { 00431 00432 printf("%s << DEBUG [%0d]\n", __FUNCTION__, 1); 00433 00434 unsigned int firstNode = keyframe_store.keyframes.at(0).idx; 00435 00436 for (unsigned int iii = firstNode; iii <= idx; iii++) { 00437 basisNodes.push_back(iii); 00438 } 00439 00440 printf("%s << DEBUG [%0d]\n", __FUNCTION__, 2); 00441 00442 00443 } else { 00444 // Need to come up with some kind of subsequence to help estimate latest pose 00445 00446 // Want to use same number of cameras, but spread them out a bit 00447 00448 // How many MORE cameras than acceptable are there? 00449 00450 printf("%s << DEBUG [%0d]\n", __FUNCTION__, 3); 00451 00452 unsigned int surplus = activeCameras - configData.adjustmentFrames; 00453 unsigned int spread = surplus / configData.keyframeSpacing; 00454 00455 spread = std::min(spread, ((unsigned int) (configData.adjustmentFrames-configData.flowback))); 00456 00457 //printf("%s::%s << idx = %d; activeCameras = %d; adjFrames = %d; surplus = %d; spread = %d", __PROGRAM__, __FUNCTION__, idx, activeCameras, configData.adjustmentFrames, surplus, spread); 00458 00459 // For every 6 in surplus, stretch out the early ones 00460 unsigned int starting_cam = idx - configData.adjustmentFrames + spread + 2; // this will be first used frame 00461 starting_cam = starting_cam - (starting_cam % configData.keyframeSpacing); // going down to nearest'5' mult 00462 starting_cam -= configData.keyframeSpacing*(spread-1); 00463 00464 //printf("%s::%s << starting_cam = %d; spread = %d; absolute limit = %d", __PROGRAM__, __FUNCTION__, starting_cam, spread, keyframe_store.keyframes.at(0).idx); 00465 00466 printf("%s << DEBUG (%04d)\n", __FUNCTION__, 4); 00467 00468 for (unsigned int iii = starting_cam; iii < (idx - configData.adjustmentFrames + spread); iii += configData.keyframeSpacing) { 00469 //printf("%s << node: %d", __FUNCTION__, iii); 00470 basisNodes.push_back(iii); 00471 00472 } 00473 00474 printf("%s << DEBUG (%04d)\n", __FUNCTION__, 5); 00475 00476 //idx - (configData.adjustmentFrames - spread) 00477 starting_cam = idx - configData.adjustmentFrames + 1 + spread + 1; 00478 for (unsigned int iii = starting_cam; iii <= idx; iii++) { 00479 //printf("%s << node: %d", __FUNCTION__, iii); 00480 basisNodes.push_back(iii); 00481 } 00482 00483 printf("%s << DEBUG (%04d)\n", __FUNCTION__, 6); 00484 00485 } 00486 00487 printf("%s << EXITING.\n", __FUNCTION__); 00488 00489 } 00490 00491 void slamNode::processNextFrame() { 00492 00493 double avgError; 00494 00495 //ROS_INFO("About to process frame (%d)", currentPoseIndex); 00496 00497 //ROS_INFO("Checking first frame (%d)", keyframe_store.keyframes.at(0).idx); 00498 00499 if (!matricesAreEqual(ACM[keyframe_store.keyframes.at(0).idx], eye4)) { 00500 //ROS_ERROR("First camera (%d) corrupted...", keyframe_store.keyframes.at(0).idx); 00501 while (1) {} 00502 } 00503 00504 vector<unsigned int> basisNodes; 00505 00506 00507 // Try triangulating points and fixing new camera at the same time... 00508 if (1) { 00509 00510 if (configData.timeDebug) triangulationTime.startRecording(); 00511 unsigned int triangulationIndex = currentPoseIndex-configData.flowback; 00512 00513 ROS_INFO("Getting basis nodes..."); 00514 getBasisNodes(basisNodes, triangulationIndex); 00515 00516 if (basisNodes.size() > 0) { 00517 00518 ROS_INFO("Finding relevant indices..."); 00519 00520 vector<unsigned int> triangulatedIndices, untriangulatedIndices; 00521 findRelevantIndices(featureTrackVector, triangulatedIndices, untriangulatedIndices, basisNodes.at(0), triangulationIndex); 00522 00523 // unsigned int points_in_3d; 00524 if (untriangulatedIndices.size() > 0) { 00525 00526 vector<unsigned int> triangulatableIndices; 00527 findTriangulatableTracks(featureTrackVector, triangulatableIndices, triangulationIndex, configData.framesForTriangulation); 00528 00529 if (triangulatableIndices.size() > 0) { 00530 //ROS_INFO("About to triangulate (%d) new tracks...", triangulatableIndices.size()); 00531 triangulateTracks(featureTrackVector, triangulatableIndices, configData.cameraData, ACM, basisNodes.at(0), triangulationIndex); 00532 //ROS_INFO("Tracks triangulated."); 00533 //double avgError = keyframeBundleAdjustment(configData.cameraData, featureTrackVector, ACM, basisNodes, configData.keyframeIterations, false, false, basisNodes.size()-3); 00534 //printf("%s::%s << F(%d) Adjustment error with newly triangulated points = %f (k = %d)", __PROGRAM__, __FUNCTION__, currentPoseIndex, avgError, basisNodes.size()); 00535 00536 if (currentPoseIndex > 60) { 00537 //while (1) {} 00538 } 00539 00540 } 00541 00542 00543 } 00544 00545 if (configData.timeDebug) triangulationTime.stopRecording(); 00546 00547 00548 ROS_INFO("Performing adjustment... (%d)", basisNodes.size()); 00549 00550 for (unsigned int iii = 0; iii < basisNodes.size(); iii++) { 00551 //ROS_INFO("basisNodes.at(%d) = (%d)", iii, basisNodes.at(iii)); 00552 } 00553 00554 for (unsigned int iii = 0; iii < featureTrackVector.size(); iii++) { 00555 00556 if (featureTrackVector.at(iii).locations.size() > 0) { 00557 //ROS_INFO("featureTrackVector.at(%d).locations.at(%d) = (%d)", iii, featureTrackVector.at(iii).locations.size()-1, featureTrackVector.at(iii).locations.at(featureTrackVector.at(iii).locations.size()-1).imageIndex); 00558 } 00559 00560 } 00561 00562 if (configData.timeDebug) bundleAdjustmentTime.startRecording(); 00563 double avgError = keyframeBundleAdjustment(configData.cameraData, featureTrackVector, ACM, basisNodes, configData.keyframeIterations, false, false, basisNodes.size()); 00564 ROS_INFO("F(%d) Adjustment error with newly triangulated points = %f (k = %d)", currentPoseIndex, avgError, basisNodes.size()); 00565 if (configData.timeDebug) bundleAdjustmentTime.stopRecording(); 00566 } 00567 00568 00569 } 00570 00571 00572 00573 // Make sure previous pose has been estimated 00574 00575 /* 00576 getBasisNodes(basisNodes, currentPoseIndex-1); 00577 00578 avgError = keyframeBundleAdjustment(configData.cameraData, featureTrackVector, ACM, basisNodes, configData.keyframeIterations, false, false, std::max(1, ((int)basisNodes.size())-10)); 00579 printf("%s::%s << F(%d) Free adjustment error with = %f (k = %d)", __PROGRAM__, __FUNCTION__, currentPoseIndex, avgError, basisNodes.size()); 00580 */ 00581 00582 ROS_INFO("Getting more basis nodes..."); 00583 getBasisNodes(basisNodes, currentPoseIndex); 00584 ROS_INFO("Estimating pose..."); 00585 estimatePose(basisNodes, currentPoseIndex); 00586 00587 if (configData.timeDebug) { 00588 if ((currentPoseIndex % configData.timeSpacing) == 0) { 00589 //double factor; 00590 trackHandlingTime.calcParameters(); 00591 triangulationTime.calcParameters(); 00592 poseEstimationTime.calcParameters(); 00593 bundleAdjustmentTime.calcParameters(); // * ((double) trackHandlingTime.cycles) / ((double) currentPoseIndex) 00594 ROS_WARN("Showing timing summary:"); 00595 ROS_INFO("Track summary: (%d, %f, %f)", trackHandlingTime.cycles, trackHandlingTime.average * ((double) trackHandlingTime.cycles) / ((double) currentPoseIndex), trackHandlingTime.sigma* ((double) trackHandlingTime.cycles) / ((double) currentPoseIndex)); 00596 ROS_INFO("Triangulation summary: (%d, %f, %f)", triangulationTime.cycles, triangulationTime.average* ((double) triangulationTime.cycles) / ((double) currentPoseIndex), triangulationTime.sigma* ((double) triangulationTime.cycles) / ((double) currentPoseIndex)); 00597 ROS_INFO("Pose summary: (%d, %f, %f)", poseEstimationTime.cycles, poseEstimationTime.average* ((double) poseEstimationTime.cycles) / ((double) currentPoseIndex), poseEstimationTime.sigma* ((double) poseEstimationTime.cycles) / ((double) currentPoseIndex)); 00598 ROS_INFO("Bundle summary: (%d, %f, %f)", bundleAdjustmentTime.cycles, bundleAdjustmentTime.average* ((double) bundleAdjustmentTime.cycles) / ((double) currentPoseIndex), bundleAdjustmentTime.sigma* ((double) bundleAdjustmentTime.cycles) / ((double) currentPoseIndex)); 00599 00600 } 00601 } 00602 00603 00604 if (1) { 00605 update_display(); 00606 currentPoseIndex++; 00607 return; 00608 } 00609 00610 if (0) { 00611 vector<unsigned int> triangulatedIndices, untriangulatedIndices; 00612 findRelevantIndices(featureTrackVector, triangulatedIndices, untriangulatedIndices, keyframe_store.keyframes.at(0).idx, currentPoseIndex); 00613 00614 //unsigned int points_in_3d; 00615 if (untriangulatedIndices.size() > 0) { 00616 00617 vector<unsigned int> triangulatableIndices; 00618 findTriangulatableTracks(featureTrackVector, triangulatableIndices, currentPoseIndex, configData.framesForTriangulation); 00619 00620 if (triangulatableIndices.size() > 0) { 00621 //ROS_INFO("About to triangulate (%d) new tracks...", triangulatableIndices.size()); 00622 triangulateTracks(featureTrackVector, triangulatableIndices, configData.cameraData, ACM, keyframe_store.keyframes.at(0).idx, currentPoseIndex); 00623 double avgError = keyframeBundleAdjustment(configData.cameraData, featureTrackVector, ACM, basisNodes, configData.keyframeIterations, false, false, basisNodes.size()-3); 00624 //ROS_INFO("F(%d) Adjustment error with newly triangulated points = %f (k = %d)", currentPoseIndex, avgError, basisNodes.size()); 00625 } 00626 00627 00628 } 00629 } 00630 00631 00632 00633 // Checks next frame to determine keyframe 00634 if (checkForKeyframe()) { 00635 00636 if ((currentPoseIndex+1) == keyframe_store.keyframes.at(keyframe_store.keyframes.size()-1).idx) { 00637 // reverted 00638 //ROS_INFO("Keyframe found (reverted); processing (%d)", currentPoseIndex+1); 00639 } else { 00640 // Not a keyframe 00641 update_display(); 00642 currentPoseIndex++; 00643 return; 00644 } 00645 00646 00647 } else { 00648 00649 if ((currentPoseIndex+1) == keyframe_store.keyframes.at(keyframe_store.keyframes.size()-1).idx) { 00650 // not reverted 00651 //ROS_INFO("Keyframe found (non-reverted); processing (%d)", currentPoseIndex+1); 00652 basisNodes.clear(); 00653 getBasisNodes(basisNodes, currentPoseIndex+1); 00654 estimatePose(basisNodes, currentPoseIndex+1); 00655 } else { 00656 // Not a keyframe 00657 update_display(); 00658 currentPoseIndex++; 00659 return; 00660 } 00661 00662 } 00663 00664 if (0) { 00665 update_display(); 00666 currentPoseIndex++; 00667 return; 00668 } 00669 00670 // This block is used to get a decent initial estimate of the latest pose 00671 00672 00673 unsigned int image_idx_1 = keyframe_store.keyframes.at(keyframe_store.keyframes.size()-2).idx; 00674 unsigned int image_idx_2 = keyframe_store.keyframes.at(keyframe_store.keyframes.size()-1).idx; 00675 00676 //ROS_INFO("Currently processing frame (%d:%d) as Keyframe", image_idx_1, image_idx_2); 00677 00678 vector<Point2f> pts1, pts2; 00679 vector<Point3f> objectPoints; 00680 getTriangulatedFullSpanPoints(featureTrackVector, pts1, pts2, image_idx_1, image_idx_2, objectPoints); 00681 00682 00683 //estimatePoseFromKnownPoints(ACM[image_idx_2], configData.cameraData, featureTrackVector, image_idx_2, eye4); 00684 00685 00686 vector<unsigned int> adjustableKeyframeIndices; 00687 /* 00688 for (unsigned int iii = 0; iii < keyframe_store.keyframes.size(); iii++) { 00689 adjustableKeyframeIndices.push_back(keyframe_store.keyframes.at(iii).idx); 00690 } 00691 00692 while (adjustableKeyframeIndices.size() > (MAX_CAMERAS_FOR_POSE_EST_BA / 2)) { 00693 adjustableKeyframeIndices.erase(adjustableKeyframeIndices.begin()); 00694 } 00695 * */ 00696 00697 vector<unsigned int> keyframe_indices, tmp_indices, subseq_indices; 00698 00699 for (unsigned int iii = 0; iii < keyframe_store.keyframes.size()-1; iii++) { 00700 keyframe_indices.push_back(keyframe_store.keyframes.at(iii).idx); 00701 } 00702 00703 // Risky mod 00704 //while (keyframe_indices.size() > (DEFAULT_ADJUSTMENT_FRAMES / 2)) { 00705 while (keyframe_indices.size() > (configData.adjustmentFrames / 2)) { 00706 keyframe_indices.erase(keyframe_indices.begin()); 00707 } 00708 00709 for (int iii = keyframe_store.keyframes.at(keyframe_store.keyframes.size()-1).idx+1; iii < currentPoseIndex+1; iii++) { 00710 tmp_indices.push_back(iii); 00711 } 00712 00713 // Risky mod 00714 //randomSelection(tmp_indices, subseq_indices, (DEFAULT_ADJUSTMENT_FRAMES / 2)); 00715 randomSelection(tmp_indices, subseq_indices, (configData.adjustmentFrames / 2)); 00716 00717 00718 //unsigned int fixed_cameras = keyframe_indices.size(); 00719 00720 adjustableKeyframeIndices.insert(adjustableKeyframeIndices.end(), keyframe_indices.begin(), keyframe_indices.end()); 00721 adjustableKeyframeIndices.insert(adjustableKeyframeIndices.end(), subseq_indices.begin(), subseq_indices.end()); 00722 adjustableKeyframeIndices.push_back(image_idx_2); 00723 00724 //cout << "Estimated pose: " << ACM[image_idx_2] << endl; 00725 00726 //printf("%s::%s << DEBUG [%d]", __PROGRAM__, __FUNCTION__, 5); 00727 00728 //unsigned int startingPoseForFullSys = ((unsigned int) std::max(((int) image_idx_2)-CAMERAS_PER_SYS, ((int) lastBasePose))); 00729 00730 //unsigned int startingPoseForFullSys = keyframe_store.keyframes.at(0).idx; 00731 00732 //printf("%s::%s << DEBUG [%d]", __PROGRAM__, __FUNCTION__, 51); 00733 00734 // DETERMINE NUMBER OF TRIANGULATED POINTS CURRENTLY BEING TRACKED 00735 //numTriangulatedPoints = countActiveTriangulatedTracks(fullSpanIndices, featureTrackVector); 00736 00737 // ADJUST THE MINIMUM NUMBER OF FRAMES SO THAT YOU GET A SUFFICIENT AMOUNT 00738 00739 //avgError = keyframeBundleAdjustment(configData.cameraData, featureTrackVector, ACM, basisNodes, configData.keyframeIterations, false, true); 00740 //avgError = keyframeBundleAdjustment(configData.cameraData, featureTrackVector, ACM, adjustableKeyframeIndices, configData.keyframeIterations, false, false, fixed_cameras); 00741 00742 if (ACM[currentPoseIndex+2].rows == 4) { 00743 //printf("%s::%s << Pose (%d) somehow estimated at this point [%d]", __PROGRAM__, __FUNCTION__, currentPoseIndex+2, 2); 00744 } 00745 00746 //ROS_INFO("F(%d) Initial adjustment error = %f (k = %d)", image_idx_2, avgError, adjustableKeyframeIndices.size()); 00747 00748 if (0) { 00749 update_display(); 00750 currentPoseIndex++; 00751 return; 00752 } 00753 00754 //cout << "After kF adjustment: " << ACM[image_idx_2] << endl; 00755 /* 00756 for (unsigned int iii = 0; iii < keyframe_store.keyframes.size(); iii++) { 00757 00758 cout << "(" << iii << ") Actual pose: " << ACM[keyframe_store.keyframes.at(iii).idx] << endl; 00759 00760 Mat tmp; 00761 estimatePoseFromKnownPoints(tmp, configData.cameraData, featureTrackVector, keyframe_store.keyframes.at(iii).idx, ACM[keyframe_store.keyframes.at(iii).idx]); 00762 00763 cout << "(" << iii << ") Re-estimated pose: " << tmp << endl; 00764 } 00765 */ 00766 00767 vector<unsigned int> triangulatedIndices, untriangulatedIndices; 00768 00769 //reduceActiveToTriangulated(featureTrackVector, triangulatedIndices, untriangulatedIndices); 00770 00771 findRelevantIndices(featureTrackVector, triangulatedIndices, untriangulatedIndices, image_idx_1, image_idx_2); 00772 00773 //printf("%s::%s << untriangulatedIndices.size() = %d vs %d", __PROGRAM__, __FUNCTION__, untriangulatedIndices.size(), triangulatedIndices.size()); 00774 00775 //unsigned int points_in_3d; 00776 if (untriangulatedIndices.size() > 0) { 00777 00778 vector<unsigned int> triangulatableIndices; 00779 findTriangulatableTracks(featureTrackVector, triangulatableIndices, image_idx_2, configData.framesForTriangulation); // (image_idx_2-image_idx_1)/2 00780 00781 if (triangulatableIndices.size() > 0) { 00782 //ROS_INFO("About to triangulate (%d) new tracks...", triangulatableIndices.size()); 00783 triangulateTracks(featureTrackVector, triangulatableIndices, configData.cameraData, ACM, image_idx_1, image_idx_2); 00784 //avgError = keyframeBundleAdjustment(configData.cameraData, featureTrackVector, ACM, adjustableKeyframeIndices, configData.keyframeIterations, false, true); 00785 //ROS_INFO("F(%d) Adjustment error with newly triangulated points = %f (k = %d)", image_idx_2, avgError, adjustableKeyframeIndices.size()); 00786 } 00787 00788 00789 } 00790 00791 if (1) { 00792 update_display(); 00793 currentPoseIndex++; 00794 return; 00795 } 00796 00797 ROS_INFO("Establishing new adjustment indices..."); 00798 00799 vector<unsigned int> newAdjustmentIndices; 00800 for (unsigned int iii = 0; iii < keyframe_store.keyframes.size(); iii++) { 00801 00802 newAdjustmentIndices.push_back(keyframe_store.keyframes.at(iii).idx); 00803 00804 if (keyframe_store.keyframes.at(iii).idx == image_idx_1) { 00805 for (unsigned int jjj = image_idx_1+1; jjj < image_idx_2; jjj++) { 00806 newAdjustmentIndices.push_back(jjj); 00807 } 00808 } 00809 } 00810 00811 update_display(); 00812 currentPoseIndex++; 00813 } 00814 00815 void slamNode::update_display() { 00816 00817 if (currentPoseIndex != -1) { 00818 if (ACM[currentPoseIndex].rows == 4) { 00819 assignPose(currentPose, ACM[currentPoseIndex]); 00820 pose_pub.publish(currentPose); 00821 } 00822 00823 vector<unsigned int> displayIndices; 00824 for (int iii = 0; iii <= currentPoseIndex; iii++) { 00825 if (ACM[iii].rows == 4) { 00826 displayIndices.push_back(iii); 00827 } 00828 } 00829 00830 for (unsigned int iii = 0; iii < displayIndices.size(); iii++) { 00831 //cout << "ACM[" << displayIndices.at(iii) << "] = " << ACM[displayIndices.at(iii)] << endl; 00832 } 00833 00834 assignPartialSystem(display_sys, featureTrackVector, configData.cameraData, ACM, displayIndices, false); 00835 00836 00837 00838 } else { 00839 assignPose(currentPose, eye4); 00840 pose_pub.publish(currentPose); 00841 00842 display_sys.nodes.clear(); 00843 display_sys.tracks.clear(); 00844 } 00845 00846 drawGraph2(display_sys, camera_pub, points_pub, path_pub, decimation, bicolor); 00847 00848 00849 } 00850 00851 void slamNode::update_cameras_to_pnp() { 00852 00853 #pragma omp parallel for 00854 for (int iii = 0; iii < currentPoseIndex; iii++) { 00855 if (ACM[iii].rows == 4) { 00856 estimatePoseFromKnownPoints(ACM[iii], configData.cameraData, featureTrackVector, iii, eye4); 00857 } 00858 } 00859 00860 } 00861 00862 void slamNode::handle_tracks(const thermalvis::feature_tracksConstPtr& msg) { 00863 00864 ROS_INFO("Handling projections (%d)...", msg->projection_count); 00865 00866 if (!infoProcessed) { 00867 //return; 00868 } 00869 00870 if (msg->indices.size() == 0) { 00871 ROS_WARN("No new tracks."); 00872 return; 00873 } 00874 00875 ROS_WARN("XY (%d)", 0); 00876 00877 if (configData.timeDebug) trackHandlingTime.startRecording(); 00878 00879 main_mutex.lock(); 00880 00881 featureTrack blankTrack; 00882 00883 ROS_WARN("XY (%d)", 1); 00884 00885 unsigned int newest_track = 0; 00886 00887 for (unsigned int iii = 0; iii < msg->projection_count; iii++) { 00888 00889 ROS_WARN("XY [%d] (%d)", iii, 0); 00890 00891 if (msg->indices[iii] > newest_track) { 00892 newest_track = msg->indices[iii]; 00893 } 00894 00895 } 00896 00897 ROS_INFO("Newest track = (%d)", newest_track); 00898 00899 if (newest_track >= featureTrackVector.size()) { 00900 for (unsigned int iii = featureTrackVector.size(); iii <= newest_track; iii++) { 00901 featureTrackVector.push_back(blankTrack); 00902 } 00903 } 00904 00905 //ROS_INFO("Active tracks = (%d)", featureTrackVector.size()); 00906 00907 for (unsigned int iii = 0; iii < msg->projection_count; iii++) { 00908 00909 bool alreadyAdded = false; 00910 00911 //ROS_INFO("%d vs %d", msg->cameras.at(iii), latestFrame); 00912 00913 if (((int) msg->cameras.at(iii)) > latestFrame) { 00914 latestFrame = msg->cameras.at(iii); 00915 } 00916 00917 00918 //ROS_INFO("Checking projection (%d) = (index: %d / %d)", iii, msg->indices.at(iii), featureTrackVector.size()); 00919 00920 for (unsigned int jjj = 0; jjj < featureTrackVector.at(msg->indices.at(iii)).locations.size(); jjj++) { 00921 00922 //ROS_INFO("Checking feature track loc (%d)", jjj); 00923 00924 if (featureTrackVector.at(msg->indices.at(iii)).locations.at(jjj).imageIndex == ((int) msg->cameras.at(iii))) { 00925 //ROS_WARN("Already exists"); 00926 alreadyAdded = true; 00927 break; 00928 } 00929 00930 00931 00932 } 00933 00934 if (!alreadyAdded) { 00935 //ROS_WARN("Adding..."); 00936 00937 Point2f proj(((float) msg->projections_x.at(iii)), ((float) msg->projections_y.at(iii))); 00938 00939 indexedFeature newFeature(msg->cameras.at(iii), proj); 00940 00941 featureTrackVector.at(msg->indices.at(iii)).addFeature(newFeature); 00942 00943 //ROS_WARN("Added."); 00944 } 00945 00946 } 00947 00948 Mat trackMatrix; 00949 00950 if (0) { 00951 if (featureTrackVector.size() > 0) { 00952 // ROS_WARN("Creating track matrix..."); 00953 if (createTrackMatrix(featureTrackVector, trackMatrix)) { 00954 //ROS_WARN("Track matrix created."); 00955 imshow("trackMatrix_received", trackMatrix); 00956 waitKey(1); 00957 } 00958 00959 } 00960 } 00961 00962 00963 00964 00965 if (configData.timeDebug) trackHandlingTime.stopRecording(); 00966 00967 00968 //elapsedTime = timeElapsedMS(cycle_timer); 00969 00970 main_mutex.unlock(); 00971 } 00972 00973 void slamNode::main_loop(const ros::TimerEvent& event) { 00974 00975 if (configData.keyframeEvaluationMode && evaluationCompleted) { 00976 return; 00977 } 00978 00979 if (firstIteration) { 00980 main_mutex.lock(); 00981 update_display(); 00982 main_mutex.unlock(); 00983 firstIteration = false; 00984 } 00985 00986 if (!infoProcessed) { 00987 //printf("%s << info not processed!", __FUNCTION__); 00988 return; 00989 } 00990 00991 if (!structureValid) { 00992 if ((!configData.keyframeEvaluationMode) || (latestFrame >= configData.maxInitializationFrames)) { 00993 main_mutex.lock(); 00994 structureValid = findStartingFrames(); 00995 main_mutex.unlock(); 00996 return; 00997 } else if (!f1 && configData.keyframeEvaluationMode) { 00998 f1 = true; 00999 ROS_INFO("Waiting for sufficient frames for evaluation..."); 01000 } 01001 01002 } 01003 01004 if (!structureValid) { 01005 return; 01006 } else if (!structureFormed) { 01007 main_mutex.lock(); 01008 structureFormed = formInitialStructure(); 01009 putativelyEstimatedFrames = currentPoseIndex-1; 01010 main_mutex.unlock(); 01011 } 01012 01013 if (!structureFormed) { 01014 return; 01015 } 01016 01017 01018 01019 01020 //while ((currentPoseIndex < latestFrame) && (keyframe_store.keyframes.size() <= 7)) { 01021 while (currentPoseIndex < latestFrame) { 01022 main_mutex.lock(); 01023 01024 processNextFrame(); 01025 01026 if (currentPoseIndex == ((int) keyframe_store.keyframes.at(keyframe_store.keyframes.size()-1).idx)) { 01027 //refreshPoses(); 01028 } 01029 01030 /* 01031 if (keyframe_store.keyframes.size() == 3) { 01032 adjustFullSystem(featureTrackVector, configData.cameraData, ACM, currentPoseIndex, 20); 01033 } else if (keyframe_store.keyframes.size() == 4) { 01034 adjustFullSystem(featureTrackVector, configData.cameraData, ACM, currentPoseIndex, 10); 01035 } else if (keyframe_store.keyframes.size() == 5) { 01036 adjustFullSystem(featureTrackVector, configData.cameraData, ACM, currentPoseIndex, 5); 01037 } else { 01038 adjustFullSystem(featureTrackVector, configData.cameraData, ACM, currentPoseIndex, 3); 01039 } 01040 */ 01041 01042 //update_display(); 01043 01044 //show_poses(); 01045 01046 main_mutex.unlock(); 01047 } 01048 01049 if (keyframe_store.keyframes.size() > 3) { 01050 01051 //update_cameras_to_pnp(); 01052 01053 } 01054 01055 //bool doneRefinement = false; 01056 01057 //while (0) { 01058 //while (currentPoseIndex == latestFrame) { 01059 //if ((keyframe_store.keyframes.size() > 3) && (!doneRefinement)) { 01060 //printf("%s << currentPoseIndex = %d (%d)", __FUNCTION__, currentPoseIndex, latestFrame); 01061 if (0) { // ((elapsedTime > 5000.0) && (currentPoseIndex == latestFrame)) { 01062 01063 //main_mutex.lock(); 01064 01065 if (keyframe_store.keyframes.size() > 2) { 01066 01067 unsigned int starting_cam = keyframe_store.keyframes.at(0).idx; //((unsigned int) max(0, ((int) currentPoseIndex-50))); 01068 01069 vector<unsigned int> allIndices; 01070 for (int iii = starting_cam; iii <= currentPoseIndex; iii++) { 01071 if (ACM[iii].rows == 4) { 01072 allIndices.push_back(iii); 01073 } 01074 } 01075 01076 double avgError; 01077 01078 ROS_INFO("About to full-system adjust (%d)", currentPoseIndex); 01079 01080 avgError = keyframeBundleAdjustment(configData.cameraData, featureTrackVector, ACM, allIndices, 5, true); 01081 01082 ROS_INFO("Full-system (%d) adjustment error = %f (k = %d)", currentPoseIndex, avgError, allIndices.size()); 01083 01084 //avgError = adjustFullSystem(featureTrackVector, configData.cameraData, ACM, starting_cam, currentPoseIndex, 1); 01085 01086 //retrieveFullSystem(fullsys, ACM, featureTrackVector, currentPoseIndex); 01087 //printf("%s::%s << Full-sys can be optimized to: %f", __PROGRAM__, __FUNCTION__, avgError); 01088 01089 update_display(); 01090 01091 //doneRefinement = true; 01092 01093 /* 01094 // optimizeFullSystem(sys, featureTrackVector, configData.cameraData, ACM, currentPoseIndex); 01095 01096 //keyframes_sem.lock(); 01097 vector<unsigned int> keyframeIndices; 01098 for (unsigned int iii = 0; iii < keyframe_store.keyframes.size(); iii++) { 01099 keyframeIndices.push_back(keyframe_store.keyframes.at(iii).idx); 01100 01101 } 01102 01103 //printf("%s << keyframeIndices.size() = %d", __FUNCTION__, keyframeIndices.size()); 01104 01105 //keyframes_sem.unlock(); 01106 double avgError; 01107 01108 01109 assignPartialSystem(sys, featureTrackVector, configData.cameraData, ACM, keyframeIndices, true); 01110 01111 printf("%s << sys.nodes() = %d; sys.tracks() = %d", __FUNCTION__, sys.nodes.size(), sys.tracks.size()); 01112 01113 avgError = optimizeSystem(sys, 1e-4, 1 ); 01114 retrievePartialSystem(sys, ACM, featureTrackVector, keyframeIndices); 01115 01116 01117 //retrieveFullSystem(sys, ACM, featureTrackVector, keyframe_store.keyframes.at(0).idx); 01118 printf("%s::%s << Optimizing full system while waiting... (%f)", __PROGRAM__, __FUNCTION__, avgError); 01119 */ 01120 } 01121 01122 //main_mutex.unlock(); 01123 01124 01125 } 01126 01127 /* 01128 if (currentPoseIndex < latestFrame) { 01129 printf("%s << DEBUG [%d]", __FUNCTION__, 12); 01130 repetitionNoted = false; 01131 processNextFrame(); 01132 printf("%s << DEBUG [%d]", __FUNCTION__, 13); 01133 } else { 01134 if (!repetitionNoted) { 01135 printf("%s << CurrentPose at latestFrame [%d]", __FUNCTION__, latestFrame); 01136 } else { 01137 repetitionNoted = true; 01138 } 01139 01140 } 01141 */ 01142 01143 } 01144 01145 void slamNode::handle_info(const sensor_msgs::CameraInfoConstPtr& info_msg) { 01146 01147 //printf("%s::%s << Entered.", __PROGRAM__, __FUNCTION__); 01148 01149 drawGraph2(display_sys, camera_pub, points_pub, path_pub, decimation, bicolor); 01150 01151 if (!infoProcessed) { 01152 01153 ROS_INFO("Handling camera info."); 01154 01155 try { 01156 01157 configData.cameraData.K = Mat::eye(3, 3, CV_64FC1); 01158 01159 for (unsigned int mmm = 0; mmm < 3; mmm++) { 01160 for (unsigned int nnn = 0; nnn < 3; nnn++) { 01161 configData.cameraData.K.at<double>(mmm, nnn) = info_msg->K[3*mmm + nnn]; 01162 } 01163 } 01164 01165 cout << configData.cameraData.K << endl; 01166 01167 01168 01169 configData.cameraData.K_inv = configData.cameraData.K.inv(); 01170 01171 01172 01173 configData.cameraData.cameraSize.width = info_msg->width; 01174 configData.cameraData.cameraSize.height = info_msg->height; 01175 01176 //printf("%s << (%d, %d)", __FUNCTION__, configData.cameraData.cameraSize.width, configData.cameraData.cameraSize.height); 01177 01178 unsigned int maxDistortionIndex; 01179 if (info_msg->distortion_model == "plumb_bob") { 01180 maxDistortionIndex = 5; 01181 } else if (info_msg->distortion_model == "rational_polynomial") { 01182 maxDistortionIndex = 8; 01183 } 01184 01185 configData.cameraData.distCoeffs = Mat::zeros(1, maxDistortionIndex, CV_64FC1); 01186 configData.cameraData.blankCoeffs = Mat::zeros(1, maxDistortionIndex, CV_64FC1); 01187 01188 for (unsigned int iii = 0; iii < maxDistortionIndex; iii++) { 01189 configData.cameraData.distCoeffs.at<double>(0, iii) = info_msg->D[iii]; 01190 } 01191 01192 cout << configData.cameraData.distCoeffs << endl; 01193 01194 configData.cameraData.newCamMat = Mat::zeros(3, 3, CV_64FC1); 01195 01196 Rect* validPixROI = 0; 01197 01198 double alpha = 0.00; 01199 bool centerPrincipalPoint = true; 01200 01201 configData.cameraData.newCamMat = getOptimalNewCameraMatrix(configData.cameraData.K, configData.cameraData.distCoeffs, configData.cameraData.cameraSize, alpha, configData.cameraData.cameraSize, validPixROI, centerPrincipalPoint); 01202 01203 //(configData.cameraData.newCamMat).copyTo(configData.cameraData.K); 01204 01205 cout << configData.cameraData.newCamMat << endl; 01206 01207 infoProcessed = true; 01208 01209 addFixedCamera(display_sys, configData.cameraData, eye4); 01210 01211 drawGraph2(display_sys, camera_pub, points_pub, path_pub, decimation, bicolor); 01212 01213 assignPose(currentPose, eye4); 01214 pose_pub.publish(currentPose); 01215 01216 } catch (sensor_msgs::CvBridgeException& e) { 01217 ROS_ERROR("Some failure in reading in the camera parameters..."); 01218 } 01219 01220 ROS_INFO("Camera information processed."); 01221 01222 } 01223 01224 01225 01226 01227 } 01228 01229 void slamNode::refreshPoses() { 01230 01231 /* 01232 for (unsigned int iii = keyframe_store.keyframes.at(0).idx; iii < keyframe_store.keyframes.at(keyframe_store.keyframes.size()-1).idx; iii++) { 01233 01234 //estimatePoseFromKnownPoints(ACM[iii], configData.cameraData, featureTrackVector, iii, eye4); 01235 01236 if (ACM[iii].rows == 4) { 01237 Mat test; 01238 estimatePoseFromKnownPoints(test, configData.cameraData, featureTrackVector, iii, eye4); 01239 01240 //cout << "est[" << iii << "] = " << test << endl; 01241 //cout << "acm[" << iii << "] = " << ACM[iii] << endl; 01242 } 01243 01244 } 01245 */ 01246 01247 /* 01248 for (unsigned int iii = 0; iii < currentPoseIndex; iii++) { 01249 01250 estimatePoseFromKnownPoints(ACM[iii], configData.cameraData, featureTrackVector, iii, eye4); 01251 01252 if (ACM[iii].rows == 4) { 01253 Mat test; 01254 estimatePoseFromKnownPoints(test, configData.cameraData, featureTrackVector, iii, eye4); 01255 01256 //cout << "est[" << iii << "] = " << test << endl; 01257 //cout << "acm[" << iii << "] = " << ACM[iii] << endl; 01258 } 01259 01260 } 01261 */ 01262 for (unsigned int iii = 0; iii < keyframe_store.keyframes.size(); iii++) { 01263 //estimatePoseFromKnownPoints(ACM[keyframe_store.keyframes.at(iii).idx], configData.cameraData, featureTrackVector, keyframe_store.keyframes.at(iii).idx, eye4); 01264 } 01265 01266 } 01267 01268 void slamNode::prepareForTermination() { 01269 return; 01270 } 01271 01272 bool slamNode::findStartingFrames() { 01273 01274 //ROS_INFO("Finding initial keyframes (latest frame = %d)", latestFrame); 01275 01276 //printf("%s::%s << Finding initial keyframes...", __PROGRAM__, __FUNCTION__); 01277 01278 bool foundStartingPair = false; 01279 01280 if (latestFrame < 1) { 01281 return foundStartingPair; 01282 } 01283 01284 double keyframe_scores[5]; 01285 Mat startingTrans; 01286 01287 Mat blankMat = Mat::zeros(80, 640, CV_8UC3); 01288 01289 if ((configData.keyframeEvaluationMode) && (!evaluationStream.is_open())) { 01290 ROS_WARN("Opening evaluation summary stream..."); 01291 evaluationStream.open(configData.evaluationFile.c_str(), ios::out | ios::app); 01292 } 01293 01294 for (unsigned int jjj = configData.minStartingSeparation; jjj < min(latestFrame+1, configData.maxInitializationFrames); jjj++) { 01295 01296 //ROS_INFO("Checking up to frame (%d) : (%d /%d)", jjj, latestFrame+1, configData.maxInitializationFrames); 01297 01298 vector<unsigned int> startersToTest; 01299 01300 for (unsigned int iii = max(0, ((int)jjj)-configData.maxStartingSeparation); iii < jjj-configData.minStartingSeparation; iii++) { 01301 startersToTest.push_back(iii); 01302 } 01303 01304 01305 while (startersToTest.size() > configData.maxTestsPerFrame) { 01306 01307 unsigned int randIndex = rand() % startersToTest.size(); 01308 startersToTest.erase(startersToTest.begin() + randIndex); 01309 01310 } 01311 01312 01313 //#pragma omp parallel for 01314 for (unsigned int iii = 0; iii < startersToTest.size(); iii++) { 01315 01316 if ((foundStartingPair) && (!configData.keyframeEvaluationMode)) { 01317 break; 01318 } 01319 01320 if (keyframeTestFlags.at<unsigned char>(startersToTest.at(iii),jjj) == 0) { 01321 01322 vector<unsigned int> activeTracks; 01323 getActiveTracks(activeTracks, featureTrackVector, startersToTest.at(iii), jjj); 01324 01325 //ROS_ERROR("About to test frames (%d) & (%d)", startersToTest.at(iii), jjj); 01326 startingTrans = Mat(); 01327 keyframeTestScores.at<double>(startersToTest.at(iii),jjj) = testKeyframePair(featureTrackVector, configData.cameraData, scorecardParams, startersToTest.at(iii), jjj, keyframe_scores, startingTrans, true /*configData.keyframeEvaluationMode*/, true); 01328 //ROS_INFO("Frames tested"); 01329 01330 if (keyframeTestScores.at<double>(startersToTest.at(iii),jjj) > 0.0) { 01331 //ROS_INFO("score (%d) -> (%d) = (%f)", startersToTest.at(iii), jjj, keyframeTestScores.at<double>(startersToTest.at(iii),jjj)); 01332 } 01333 01334 if (configData.keyframeEvaluationMode) { 01335 01336 clearSystem(); 01337 01338 bool result = true; 01339 char outputString[256]; 01340 01341 ROS_INFO("Assigning as starting frames (%d, %d)...", startersToTest.at(iii), jjj); 01342 assignStartingFrames(startersToTest.at(iii), jjj, keyframe_scores, startingTrans); 01343 ROS_INFO("Starting frames assigned."); 01344 01345 if (startingTrans.rows > 0) { 01346 01347 //cout << "startingTrans = " << startingTrans << endl; 01348 formInitialStructure(); 01349 01350 ROS_INFO("Initial structure formed."); 01351 01352 char response = ' '; 01353 01354 blankMat = Mat(blankMat.size(), blankMat.type(), CV_RGB(0,255,0)); 01355 01356 //while (0) { 01357 while ((response != 'y') && (response != 'n')) { 01358 imshow("readybar", blankMat); 01359 response = waitKey(); 01360 } 01361 01362 blankMat = Mat(blankMat.size(), blankMat.type(), CV_RGB(255,0,0)); 01363 imshow("readybar", blankMat); 01364 waitKey(1); 01365 01366 if (response == 'y') { 01367 result = true; 01368 } else { 01369 result = false; 01370 } 01371 } else { 01372 ROS_INFO("Initial starting transformation invalid, returning failure."); 01373 result = false; 01374 } 01375 01376 01377 01378 ROS_INFO("Preparing string..."); 01379 sprintf(outputString, "%06d %06d %+02.2f %+02.2f %+02.2f %+02.2f %+02.2f %1.2f %d", startersToTest.at(iii), jjj, keyframe_scores[0], keyframe_scores[1], keyframe_scores[2], keyframe_scores[3], keyframe_scores[4], keyframeTestScores.at<double>(startersToTest.at(iii),jjj), (result ? 1 : 0)); 01380 ROS_INFO("String written."); 01381 /* 01382 evaluationStream << startersToTest.at(iii) << " " << jjj; 01383 evaluationStream << " " << keyframe_scores[0]; 01384 evaluationStream << " " << keyframe_scores[1]; 01385 evaluationStream << " " << keyframe_scores[2]; 01386 evaluationStream << " " << keyframe_scores[3]; 01387 evaluationStream << " " << keyframe_scores[4]; 01388 evaluationStream << " " << 1 << endl; 01389 */ 01390 01391 evaluationStream << outputString << endl; 01392 } 01393 01394 01395 keyframeTestFlags.at<unsigned char>(startersToTest.at(iii),jjj) = 1; 01396 01397 if (keyframeTestScores.at<double>(startersToTest.at(iii),jjj) >= configData.minStartupScore) { 01398 //ROS_INFO("Valid keyframe pair found at (%d, %d) [%f] > [%f]", startersToTest.at(iii), jjj, keyframeTestScores.at<double>(startersToTest.at(iii),jjj), configData.minStartupScore); 01399 01400 foundStartingPair = true; 01401 01402 } 01403 01404 ROS_INFO("Keyframe pair (%03d, %03d) initialization score = [%f] {%1.2f, %1.2f, %1.2f, %1.2f, %1.2f}", startersToTest.at(iii), jjj, keyframeTestScores.at<double>(startersToTest.at(iii),jjj), keyframe_scores[0], keyframe_scores[1], keyframe_scores[2], keyframe_scores[3], keyframe_scores[4]); 01405 01406 } 01407 01408 } 01409 01410 if ((foundStartingPair) && (!configData.keyframeEvaluationMode)) { 01411 break; 01412 } 01413 01414 } 01415 01416 if (configData.keyframeEvaluationMode) { 01417 evaluationStream.close(); 01418 evaluationCompleted = true; 01419 ROS_INFO("Keyframe evaluation results finalize. (CTRL + C) to terminate."); 01420 01421 blankMat = Mat(blankMat.size(), blankMat.type(), CV_RGB(0,0,255)); 01422 imshow("readybar", blankMat); 01423 waitKey(); 01424 return false; 01425 } 01426 01427 if (foundStartingPair) { 01428 01429 double a, b; 01430 cv::Point min_coord, max_coord; 01431 unsigned int best_iii, best_jjj; 01432 minMaxLoc(keyframeTestScores, &a, &b, &min_coord, &max_coord); //, keyframeTestFlags); 01433 01434 best_iii = max_coord.y; 01435 best_jjj = max_coord.x; 01436 01437 assignStartingFrames(best_iii, best_jjj, keyframe_scores, startingTrans); 01438 01439 //nextFrame = best_jjj+1; 01440 } 01441 01442 return foundStartingPair; 01443 01444 01445 } 01446 01447 void slamNode::clearSystem() { 01448 01449 keyframe_store.connections.clear(); 01450 keyframe_store.keyframes.clear(); 01451 keyframe_store.count = 0; 01452 01453 for (int iii = 0; iii < featureTrackVector.size(); iii++) { 01454 featureTrackVector.at(iii).isTriangulated = false; 01455 } 01456 01457 int finalIndex; 01458 01459 if (configData.keyframeEvaluationMode) { 01460 finalIndex = configData.maxInitializationFrames + 1; 01461 } else { 01462 finalIndex = latestFrame + 1; 01463 } 01464 for (int iii = 0; iii < finalIndex; iii++) { 01465 ACM[iii] = Mat(); 01466 } 01467 01468 } 01469 01470 double slamNode::assignStartingFrames(unsigned int best_iii, unsigned int best_jjj, double* keyframe_scores, Mat& startingTrans) { 01471 01472 printf("%s << Adding (%d) & (%d) to keyframe store... (already (%d) large)", __FUNCTION__, best_iii, best_jjj, keyframe_store.keyframes.size()); 01473 01474 keyframe_store.addKeyframe(best_iii, blank); 01475 keyframe_store.addKeyframe(best_jjj, blank); 01476 01477 double kfScore = testKeyframePair(featureTrackVector, configData.cameraData, scorecardParams, best_iii, best_jjj, keyframe_scores, startingTrans, configData.keyframeEvaluationMode, true); 01478 01479 ACM[best_iii] = Mat::eye(4, 4, CV_64FC1); 01480 startingTrans.copyTo(ACM[best_jjj]); 01481 01482 ROS_INFO("kfScore = %f (%d, %d)", kfScore, best_iii, best_jjj); 01483 cout << ACM[best_iii] << endl; 01484 cout << ACM[best_jjj] << endl; 01485 01486 //while (1) {} 01487 01488 keyframe_store.addConnection(keyframe_store.count-2, keyframe_store.count-1, KF_CONNECTION_GEOMETRIC, F_arr[best_iii]); 01489 01490 return kfScore; 01491 01492 } 01493 01494 bool slamNode::formInitialStructure() { 01495 01496 //ROS_INFO("Entered <formInitialStructure> (%d).", baseConnectionNum); 01497 01498 //cout << "ACM[0] = " << ACM[0] << endl; 01499 01500 double keyframe_scores[5]; 01501 Mat startingTrans; 01502 bool formedInitialStructure = false; 01503 01504 int keyframe_idx_1 = keyframe_store.connections.at(baseConnectionNum).idx1; 01505 int keyframe_idx_2 = keyframe_store.connections.at(baseConnectionNum).idx2; 01506 01507 //printf("%s << keyframe_idx = (%d, %d) [%d]", __FUNCTION__, keyframe_idx_1, keyframe_idx_2, keyframe_store.connections.size()); 01508 01509 unsigned int image_idx_1 = keyframe_store.keyframes.at(keyframe_idx_1).idx; 01510 unsigned int image_idx_2 = keyframe_store.keyframes.at(keyframe_idx_2).idx; 01511 01512 //printf("%s << image_idx = (%d, %d)", __FUNCTION__, image_idx_1, image_idx_2); 01513 01514 lastBasePose = image_idx_1; 01515 01516 vector<Point2f> pts1, pts2; 01517 getPointsFromTracks(featureTrackVector, pts1, pts2, image_idx_1, image_idx_2); 01518 01519 vector<unsigned int> activeTrackIndices, fullSpanIndices, triangulatedIndices; 01520 01521 getActiveTracks(activeTrackIndices, featureTrackVector, image_idx_1, image_idx_2); 01522 filterToCompleteTracks(fullSpanIndices, activeTrackIndices, featureTrackVector, image_idx_1, image_idx_2); 01523 01524 startingTracksCount = fullSpanIndices.size(); 01525 01526 //printf("%s << Active indices for this subsequence: %d", __FUNCTION__, activeTrackIndices.size()); 01527 //printf("%s << Full-span indices for this subsequence: %d", __FUNCTION__, fullSpanIndices.size()); 01528 01529 int numTriangulatedPoints = countActiveTriangulatedTracks(fullSpanIndices, featureTrackVector); 01530 01531 //printf("%s << Number of triangulated full-span tracks for this subsequence = %d", __FUNCTION__, numTriangulatedPoints); 01532 01533 vector<Point3d> ptsInCloud; 01534 Mat P1, R1, t1; //, CX[4]; 01535 Mat Rvec, C; 01536 vector<Point2f> correspPoints; 01537 01538 //ROS_INFO("Reconstructing initialization pair with (%d) & (%d)...", image_idx_1, image_idx_2); 01539 01540 //cout << "ACM[0] = " << ACM[0] << endl; 01541 01542 bool worked = reconstructFreshSubsequencePair(featureTrackVector, ptsInCloud, triangulatedIndices, ACM[image_idx_1], ACM[image_idx_2], configData.cameraData, image_idx_1, image_idx_2); 01543 01544 //ROS_INFO("Initial fresh cameras:"); 01545 //cout << ACM[image_idx_1] << endl; 01546 //cout << ACM[image_idx_2] << endl; 01547 01548 if (!worked) { 01549 ROS_ERROR("2-Frame reconstruction didn't work."); 01550 } 01551 01552 //cam_mutex.unlock(); 01553 01554 //printf("%s::%s << DEBUG [%d]", __PROGRAM__, __FUNCTION__, 0); 01555 01556 double keyframeError; 01557 keyframeError = testKeyframePair(featureTrackVector, configData.cameraData, scorecardParams, image_idx_1, image_idx_2, keyframe_scores, startingTrans, configData.keyframeEvaluationMode); 01558 01559 //printf("%s::%s << DEBUG [%d]", __PROGRAM__, __FUNCTION__, 1); 01560 01561 //cout << "(" << keyframeError << ") = " << startingTrans << endl; 01562 startingTrans.copyTo(ACM[image_idx_2]); 01563 //cam_mutex.lock(); 01564 //printf("%s << Pre-optimized initialization cameras:", __FUNCTION__); 01565 //ROS_INFO("Initial keyframe cameras:"); 01566 //cout << ACM[image_idx_1] << endl; 01567 //cout << ACM[image_idx_2] << endl; 01568 01569 //cout << "ACM[0] = " << ACM[0] << endl; 01570 /* 01571 keyframeError = optimizeKeyframePair(featureTrackVector, configData.cameraData, image_idx_1, image_idx_2, ACM); 01572 printf("%s << Freshly reconstructed initial cameras:", __FUNCTION__); 01573 cout << ACM[image_idx_1] << endl; 01574 cout << ACM[image_idx_2] << endl; 01575 */ 01576 //cam_mutex.unlock(); 01577 01578 double twoViewError; 01579 01580 vector<unsigned int> adjustableKeyframeIndices; 01581 01582 adjustableKeyframeIndices.push_back(image_idx_1); 01583 adjustableKeyframeIndices.push_back(image_idx_2); 01584 01585 //cam_mutex.lock(); 01586 01587 keyframeError = keyframeBundleAdjustment(configData.cameraData, featureTrackVector, ACM, adjustableKeyframeIndices, configData.initialStructureIterations, false, false, 1); 01588 ROS_INFO("Adjusted error: %f", keyframeError); 01589 //cout << ACM[image_idx_1] << endl; 01590 //cout << ACM[image_idx_2] << endl; 01591 01592 //cam_mutex.unlock(); 01593 01594 01595 //real_C0.copyTo(ACM[image_idx_1]); 01596 //real_C1.copyTo(ACM[image_idx_2]); 01597 01598 if (!worked) { 01599 ROS_ERROR("Reconstruction of fresh subsequence pair failed."); 01600 return false; 01601 } 01602 01603 ROS_INFO("Getting active 3d points..."); 01604 01605 //printf("%s << ptsInCloud.size() (pre-update) = %d", __FUNCTION__, ptsInCloud.size()); 01606 getActive3dPoints(featureTrackVector, triangulatedIndices, ptsInCloud); 01607 //printf("%s << ptsInCloud.size() (post-update) = %d", __FUNCTION__, ptsInCloud.size()); 01608 01609 ROS_INFO("Points acquired. GT."); 01610 01611 int relativeIndex = image_idx_2-image_idx_1; 01612 01613 printf("%s << DEBUG (%04d)\n", __FUNCTION__, 0); 01614 01615 SysSBA subsys; 01616 addPointsToSBA(subsys, ptsInCloud); 01617 01618 printf("%s << DEBUG (%04d)\n", __FUNCTION__, 1); 01619 01620 //cam_mutex.lock(); 01621 addFixedCamera(subsys, configData.cameraData, ACM[image_idx_1]); 01622 01623 printf("%s << DEBUG (%04d)\n", __FUNCTION__, 2); 01624 01625 addNewCamera(subsys, configData.cameraData, ACM[image_idx_2]); 01626 01627 //cam_mutex.unlock(); 01628 01629 printf("%s << DEBUG (%04d)\n", __FUNCTION__, 3); 01630 01631 subsys.nFixed = 1; 01632 01633 addProjectionsToSBA(subsys, pts1, 0); // keyframe_idx_1 01634 01635 printf("%s << DEBUG (%04d)\n", __FUNCTION__, 4); 01636 01637 addProjectionsToSBA(subsys, pts2, 1); 01638 01639 ROS_INFO("Going through relative indices..."); 01640 01641 for (int jjj = 1; jjj < relativeIndex; jjj++) { 01642 01643 vector<Point2f> latestPoints; 01644 01645 printf("%s << About to get corresponding points (%d)...\n", __FUNCTION__, jjj); 01646 getCorrespondingPoints(featureTrackVector, pts1, latestPoints, image_idx_1, image_idx_1+jjj); 01647 printf("%s << Corresponding points acquired (%d)\n", __FUNCTION__, jjj); 01648 01649 01650 vector<Point3f> objectPoints; 01651 Point3f tmpPt; 01652 01653 for (unsigned int kkk = 0; kkk < ptsInCloud.size(); kkk++) { 01654 tmpPt = Point3f((float) ptsInCloud.at(kkk).x, (float) ptsInCloud.at(kkk).y, (float) ptsInCloud.at(kkk).z); 01655 objectPoints.push_back(tmpPt); 01656 } 01657 01658 Mat t, R, Rvec; 01659 01660 printf("%s << DEBUG (%03d)\n", __FUNCTION__, 0); 01661 01662 printf("%s << Solving PnP... (%d) (oP.size() = %d; lP.size() = %d)\n", __FUNCTION__, jjj, objectPoints.size(), latestPoints.size()); 01663 01664 if (objectPoints.size() != latestPoints.size()) { 01665 ROS_ERROR("Unable to find proper corresponding points!"); 01666 continue; 01667 } 01668 //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() ); 01669 solvePnPRansac(objectPoints, latestPoints, configData.cameraData.K, configData.cameraData.blankCoeffs, Rvec, t); 01670 01671 printf("%s << DEBUG (%03d)\n", __FUNCTION__, 1); 01672 01673 Rodrigues(Rvec, R); 01674 01675 //cout << __FUNCTION__ << " << [" << jjj << "] R = " << R << endl; 01676 //cout << __FUNCTION__ << " << [" << jjj << "] t = " << t << endl; 01677 01678 Mat newCam; 01679 compileTransform(newCam, R, t); 01680 01681 // Inverting camera "learned" by PnP since it always seems to need to be inverted when passed to 01682 // and from SBA... 01683 01684 Mat newCamC; 01685 projectionToTransformation(newCam, newCamC); 01686 newCamC = newCamC.inv(); 01687 transformationToProjection(newCamC, newCam); 01688 01689 addNewCamera(subsys, configData.cameraData, newCam); 01690 01691 addProjectionsToSBA(subsys, latestPoints, jjj+1); 01692 01693 printf("%s << DEBUG (%03d)\n", __FUNCTION__, 2); 01694 01695 //avgError = optimizeSystem(subsys, 1e-4, 10); 01696 //printf("%s << Progressive subsequence BA error = %f.", __FUNCTION__, avgError); 01697 01698 //drawGraph2(subsys, camera_pub, points_pub, path_pub, decimation, bicolor); 01699 01700 } 01701 01702 //printf("%s << About to optimize subsystem... (nFixed = %d)", __FUNCTION__, subsys.nFixed); 01703 //ROS_INFO("About to optimize starting sequence..."); 01704 01705 //cout << "ACM[0] = " << ACM[0] << endl; 01706 //if (iii == 0) { 01707 01708 subsys.nFixed = 1; 01709 ROS_INFO("About to rescale (1)"); 01710 rescaleSBA(subsys, 0, 1); 01711 ROS_INFO("About to optimize between rescalings..."); 01712 double avgError = optimizeSystem(subsys, 1e-4, configData.subsequenceIterations); 01713 ROS_INFO("About to rescale (2)"); 01714 rescaleSBA(subsys, 0, 1); 01715 ROS_INFO("Rescaling done"); 01716 01717 01718 if (avgError < 0.0) { 01719 ROS_ERROR("Subsystem optimization failed to converge.."); 01720 } 01721 01722 //ROS_INFO("Subsystem optimized; err = %f", avgError); 01723 01724 01725 //cout << "ACM[0] = " << ACM[0] << endl; 01726 //printf("%s << DEBUG [%d] looking for crash...", __FUNCTION__, 0); 01727 01728 //cam_mutex.lock(); 01729 retrieveCameraPose(subsys, ACM[image_idx_1], 0); 01730 retrieveCameraPose(subsys, ACM[image_idx_2], 1); 01731 01732 //ROS_INFO("Starting sequence cameras ="); 01733 //cout << ACM[image_idx_1] << endl; 01734 01735 01736 //printf("%s << DEBUG [%d] looking for crash...", __FUNCTION__, 1); 01737 01738 #pragma omp parallel for 01739 for (unsigned int ttt = 1; ttt < image_idx_2-image_idx_1; ttt++) { 01740 retrieveCameraPose(subsys, ACM[image_idx_1+ttt], ttt+1); 01741 //cout << "ACM[0]" << ACM[image_idx_1+ttt] << endl; 01742 } 01743 01744 //cout << ACM[image_idx_2] << endl; 01745 01746 //cout << "ACM[0] = " << ACM[0] << endl; 01747 01748 //cam_mutex.unlock(); 01749 01750 01751 ptsInCloud.clear(); 01752 retrieveAllPoints(ptsInCloud, subsys); 01753 01754 updateTriangulatedPoints(featureTrackVector, triangulatedIndices, ptsInCloud); 01755 01756 vector<unsigned int> basisNodes; 01757 01758 for (unsigned int iii = image_idx_1; iii <= image_idx_2; iii++) { 01759 basisNodes.push_back(iii); 01760 } 01761 01762 keyframeError = keyframeBundleAdjustment(configData.cameraData, featureTrackVector, ACM, basisNodes, configData.keyframeIterations, false, false, 1); 01763 //ROS_INFO("Full-sys error 1: %f", keyframeError); 01764 // So by here you've done all basic triangulation.. 01765 /* 01766 assignFullSystem(sys, featureTrackVector, configData.cameraData, ACM, image_idx_1, image_idx_2); 01767 printf("%s << SYS: nodes = %d; tracks = %d", __FUNCTION__, sys.nodes.size(), sys.tracks.size()); 01768 sys.nFixed = 1; 01769 rescaleSBA(sys, 0, sys.nodes.size()-1); 01770 avgError = optimizeSystem(sys, 1e-4, 10); 01771 rescaleSBA(sys, 0, sys.nodes.size()-1); 01772 printf("%s << retrieving full system with image (%d) to start with", __FUNCTION__, image_idx_1); 01773 retrieveFullSystem(sys, ACM, featureTrackVector, image_idx_1, image_idx_2); 01774 sys.nodes.clear(); 01775 sys.tracks.clear(); 01776 //currentPoseIndex = image_idx_2; 01777 //formedInitialStructure = true; 01778 //printf("%s::%s << Initial structure formed.", __PROGRAM__, __FUNCTION__); 01779 //return formedInitialStructure; 01780 */ 01781 01782 01783 01784 //getBasisNodes(basisNodes, currentPoseIndex); 01785 01786 if (1) { 01787 01788 vector<unsigned int> triangulatedIndices, untriangulatedIndices; 01789 findRelevantIndices(featureTrackVector, triangulatedIndices, untriangulatedIndices, image_idx_1, image_idx_2); 01790 01791 unsigned int points_in_3d; 01792 if (untriangulatedIndices.size() > 0) { 01793 01794 vector<unsigned int> triangulatableIndices; 01795 findTriangulatableTracks(featureTrackVector, triangulatableIndices, image_idx_2, configData.framesForTriangulation); 01796 01797 if (triangulatableIndices.size() > 0) { 01798 //ROS_INFO("About to triangulate (%d) new tracks...", triangulatableIndices.size()); 01799 triangulateTracks(featureTrackVector, triangulatableIndices, configData.cameraData, ACM, image_idx_1, image_idx_2); 01800 //ROS_INFO("Tracks triangulated."); 01801 //double avgError = keyframeBundleAdjustment(configData.cameraData, featureTrackVector, ACM, basisNodes, configData.keyframeIterations, false, false, basisNodes.size()-3); 01802 //printf("%s::%s << F(%d) Adjustment error with newly triangulated points = %f (k = %d)", __PROGRAM__, __FUNCTION__, currentPoseIndex, avgError, basisNodes.size()); 01803 01804 if (currentPoseIndex > 60) { 01805 //while (1) {} 01806 } 01807 01808 } 01809 01810 01811 } 01812 } 01813 01814 //cout << "ACM[0] = " << ACM[0] << endl; 01815 01816 keyframeError = keyframeBundleAdjustment(configData.cameraData, featureTrackVector, ACM, basisNodes, configData.keyframeIterations, false, false, 1); 01817 //ROS_INFO("Full-sys error 2: %f", keyframeError); 01818 /* 01819 assignFullSystem(sys, featureTrackVector, configData.cameraData, ACM, image_idx_1, image_idx_2); 01820 //printf("%s << SYS: nodes = %d; tracks = %d", __FUNCTION__, sys.nodes.size(), sys.tracks.size()); 01821 printf("%s::%s << Optimizing with triangulated points...", __PROGRAM__, __FUNCTION__); 01822 sys.nFixed = 1; 01823 rescaleSBA(sys, 0, sys.nodes.size()-1); 01824 avgError = optimizeSystem(sys, 1e-4, 10); 01825 rescaleSBA(sys, 0, sys.nodes.size()-1); 01826 printf("%s::%s << Final error = %f", __PROGRAM__, __FUNCTION__, avgError); 01827 01828 cout << "ACM[0] = " << ACM[0] << endl; 01829 //printf("%s << retrieving full system with image (%d) to start with", __FUNCTION__, image_idx_1); 01830 retrieveFullSystem(sys, ACM, featureTrackVector, image_idx_1, image_idx_2); 01831 */ 01832 currentPoseIndex = image_idx_2; 01833 formedInitialStructure = true; 01834 //ROS_INFO("Initial structure formed."); 01835 //cout << "ACM[0] = " << ACM[0] << endl; 01836 01837 for (unsigned int iii = image_idx_1; iii <= image_idx_2; iii++) { 01838 //cout << "ACM[" << iii << "] = " << ACM[iii] << endl; 01839 } 01840 01841 01842 if (1) { 01843 update_display(); 01844 } 01845 01846 //while (1) { } 01847 01848 01849 return formedInitialStructure; 01850 01851 ROS_ERROR("What!? How did I get here??"); 01852 cin.get(); 01853 01854 //updateTriangulatedPoints(featureTrackVector, triangulatedIndices, ptsInCloud); 01855 01857 //vector<unsigned int> secondTierIndices; 01858 01860 01861 //getIndicesForTriangulation(secondTierIndices, activeTrackIndices, triangulatedIndices); 01862 01863 01864 //Point3d *secondTierPoints; 01865 //int *triangulationsCount; 01866 //triangulationsCount = new int[secondTierIndices.size()]; 01867 //secondTierPoints = new Point3d[secondTierIndices.size()]; 01868 01869 //#pragma omp parallel for 01870 //for (unsigned int rrr = 0; rrr < secondTierIndices.size(); rrr++) { 01872 //triangulationsCount[rrr] = 0; 01873 //secondTierPoints[rrr] = Point3d(0.0, 0.0, 0.0); 01874 //} 01875 01876 //unsigned int startIndex = image_idx_1; 01877 //unsigned int finishIndex = image_idx_2; 01878 01880 01882 01883 //for (unsigned int ttt = 0; ttt < secondTierIndices.size(); ttt++) { 01884 01886 //for (unsigned int rrr = startIndex; rrr < finishIndex; rrr++) { 01887 01889 //Mat temp_C0; 01890 01892 01893 01894 //ACM[rrr].copyTo(temp_C0); 01895 01896 01897 01899 01901 01902 01903 //for (unsigned int sss = rrr + 1; sss <= finishIndex; sss++) { 01904 01905 01906 01907 //Mat temp_C1; 01908 01910 01911 //ACM[sss].copyTo(temp_C1); 01912 01914 01916 01918 01920 01921 //vector<unsigned int> activeTrackIndices_t, fullSpanIndices_t, triangulatedIndices_t; 01922 //getActiveTracks(activeTrackIndices_t, featureTrackVector, rrr, sss); 01923 //filterToCompleteTracks(fullSpanIndices_t, activeTrackIndices_t, featureTrackVector, rrr, sss); 01924 01926 01928 01929 01931 01932 //unsigned int uuu = 0; 01933 01935 01936 //while ((uuu < fullSpanIndices_t.size()) && (fullSpanIndices_t.at(uuu) < secondTierIndices.at(ttt))) { 01937 //uuu++; 01938 //} 01939 01940 //if (uuu == fullSpanIndices_t.size()) { 01942 //break; 01943 //} 01944 01945 //if (fullSpanIndices_t.at(uuu) == secondTierIndices.at(ttt)) { 01946 01949 //Point2f pt1_, pt2_; 01950 //Point3d pt3d_; 01951 01953 01954 //pt1_ = featureTrackVector.at(secondTierIndices.at(ttt)).getCoord(rrr); 01955 //pt2_ = featureTrackVector.at(secondTierIndices.at(ttt)).getCoord(sss); 01956 01959 01960 01961 01962 //Triangulate(pt1_, pt2_, configData.cameraData.K, configData.cameraData.K_inv, temp_C1, temp_C0, pt3d_, false); 01963 01964 //if (ttt == 0) { 01968 //} 01969 01970 01972 //secondTierPoints[ttt].x += pt3d_.x; 01973 //secondTierPoints[ttt].y += pt3d_.y; 01974 //secondTierPoints[ttt].z += pt3d_.z; 01975 //triangulationsCount[ttt]++; 01977 01978 //} 01979 01980 //} 01981 01984 01985 //} 01986 01987 //} 01988 01989 01991 01992 //#pragma omp parallel for 01993 //for (unsigned int rrr = 0; rrr < secondTierIndices.size(); rrr++) { 01994 01995 //if (triangulationsCount[rrr] > 0) { 01996 //secondTierPoints[rrr].x /= ((double) triangulationsCount[rrr]); 01997 //secondTierPoints[rrr].y /= ((double) triangulationsCount[rrr]); 01998 //secondTierPoints[rrr].z /= ((double) triangulationsCount[rrr]); 01999 02001 02002 02003 02004 //featureTrackVector.at(secondTierIndices.at(rrr)).set3dLoc(secondTierPoints[rrr]); 02005 //} 02006 02007 //} 02008 02009 02010 //vector<unsigned int> activeCameraIndices; 02011 //activeCameraIndices.clear(); 02012 02013 //for (unsigned int rrr = startIndex; rrr <= finishIndex; rrr++) { 02014 //activeCameraIndices.push_back(rrr); 02015 //} 02016 02017 //double newError = optimizeSubsystem(configData.cameraData, ACM, activeCameraIndices, featureTrackVector, activeTrackIndices, configData.subsequenceIterations); 02018 02019 //ROS_INFO("Subsystem error including intermediate points: %f", newError); 02020 02021 //assignFullSystem(sys, featureTrackVector, configData.cameraData, ACM, image_idx_1, image_idx_2); 02022 02023 //ROS_INFO("SYS: nodes = %d; tracks = %d", sys.nodes.size(), sys.tracks.size()); 02024 02025 //avgError = optimizeSystem(sys, 1e-4, configData.fullSystemIterations * 100); 02026 02027 //ROS_INFO("retrieving full system with image (%d) to start with", image_idx_1); 02028 02029 //retrieveFullSystem(sys, ACM, featureTrackVector, image_idx_1, image_idx_2); 02030 02031 02032 //for (unsigned int jjj = 0; jjj <= image_idx_2; jjj++) { 02033 02034 //if (ACM[jjj].rows != 0) { 02036 //} 02037 02038 //} 02039 02041 02042 //currentPoseIndex = image_idx_2; 02043 02044 //formedInitialStructure = true; 02045 02046 //ROS_INFO("Initial structure formed."); 02047 02048 //return formedInitialStructure; 02049 } 02050 02051 void slamNode::assignPose(geometry_msgs::PoseStamped& pPose, Mat& C) { 02052 pPose.header.seq = currentPoseIndex; 02053 pPose.header.stamp = ros::Time::now(); 02054 02055 Mat R, t; 02056 Quaterniond Q; 02057 decomposeTransform(C, R, t); 02058 matrixToQuaternion(R, Q); 02059 02060 // tried: 1,0,2; 1,2,0; 0,2,1; 2,0,1; 2,1,0; 0,1,2 02061 // x-corresponds to graph -x; y to graph -z; z to graph -y 02062 02063 pPose.pose.position.x = t.at<double>(2,0); //; 02064 pPose.pose.position.y = -t.at<double>(0,0); //t.at<double>(1,0); 02065 pPose.pose.position.z = -t.at<double>(1,0); //t.at<double>(2,0); 02066 02067 if (abs(pPose.pose.position.x) > MAX_RVIZ_DISPLACEMENT) { 02068 pPose.pose.position.x = 0.0; 02069 } 02070 02071 if (abs(pPose.pose.position.y) > MAX_RVIZ_DISPLACEMENT) { 02072 pPose.pose.position.y = 0.0; 02073 } 02074 02075 if (abs(pPose.pose.position.z) > MAX_RVIZ_DISPLACEMENT) { 02076 pPose.pose.position.z = 0.0; 02077 } 02078 02079 //printf("%s << QUAT = (%f, %f, %f, %f)", __FUNCTION__, Q.x(), Q.y(), Q.z(), Q.w()); 02080 02081 // tried x,y,z,w 02082 pPose.pose.orientation.x = Q.z(); 02083 pPose.pose.orientation.y = -Q.x(); 02084 pPose.pose.orientation.z = -Q.y(); 02085 pPose.pose.orientation.w = Q.w(); 02086 } 02087 02088 void slamNode::serverCallback(thermalvis::monoslamConfig &config, uint32_t level) { 02089 02090 configData.flowback = config.flowback; 02091 02092 configData.debugMode = config.debugMode; 02093 02094 configData.timeSpacing = config.timeSpacing; 02095 02096 configData.poseEstimateIterations = config.poseEstimateIterations; 02097 02098 configData.minStartupScore = config.minStartupScore; 02099 02100 configData.adjustmentFrames = config.adjustmentFrames; 02101 02102 configData.motionThreshold = config.motionThreshold; 02103 02104 configData.timeDebug = config.timeDebug; 02105 02106 configData.keyframeIterations = config.keyframeIterations; 02107 02108 configData.framesForTriangulation = config.framesForTriangulation; 02109 02110 configData.maxKeyframeSeparation = config.maxKeyframeSeparation; 02111 02112 configData.min3dPtsForPnP = config.min3dPtsForPnP; 02113 02114 configData.camerasPerSys = config.camerasPerSys; 02115 02116 configData.minTrackedFeatures = config.minTrackedFeatures; 02117 02118 configData.minGeometryScore = config.minGeometryScore; 02119 02120 configData.minKeyframeScore = config.minKeyframeScore; 02121 02122 configData.requiredTrackFrac = config.requiredTrackFrac; 02123 02124 configData.fullSystemIterations = config.fullSystemIterations; 02125 02126 configData.subsequenceIterations = config.subsequenceIterations; 02127 02128 configData.keyframeSpacing = config.keyframeSpacing; 02129 02130 configData.maxGuides = config.maxGuides; 02131 02132 configData.initialStructureIterations = config.initialStructureIterations; 02133 02134 //ROS_WARN("Switched keyframe evaluation to (%d)", configData.keyframeEvaluationMode ? 1 : 0); 02135 02136 } 02137 02138 slamNode::slamNode(ros::NodeHandle& nh, slamData startupData) { 02139 02140 configData = startupData; 02141 02142 scorecardParams = new double*[INITIALIZATION_SCORING_PARAMETERS]; 02143 02144 for (int iii = 0; iii < INITIALIZATION_SCORING_PARAMETERS; iii++) { 02145 scorecardParams[iii] = new double[3]; 02146 } 02147 02148 processScorecard(); 02149 02150 sprintf(nodeName, "%s", ros::this_node::getName().c_str()); 02151 02152 srand(time(NULL)); 02153 02154 evaluationCompleted = false; 02155 02156 //cam_sem = Semaphore("cameras"); 02157 //tracks_sem = Semaphore("tracks"); 02158 //keyframes_sem = Semaphore("keyframes"); 02159 02160 putativelyEstimatedFrames = 0; 02161 02162 firstIteration = true; 02163 02164 boost::mutex cam_mutex; 02165 boost::mutex tracks_mutex; 02166 boost::mutex keyframes_mutex; 02167 02168 char timeString[256]; 02169 02170 sprintf(timeString, "%010d.%09d", ros::Time::now().sec, ros::Time::now().nsec); 02171 //stringstream convert; 02172 //convert << ros::Time::now().sec << "." << ros::Time::now().nsec; 02173 02174 //configData.evaluationFile = configData.read_addr + "nodes/monoslam/log/" + convert.str() + ".txt"; 02175 configData.evaluationFile = configData.read_addr + "nodes/monoslam/log/" + timeString + "-" + ros::this_node::getName().substr(1,ros::this_node::getName().size()-1) + ".txt"; 02176 02177 if (configData.keyframeEvaluationMode) { 02178 ROS_INFO("evaluationFile = (%s)", configData.evaluationFile.c_str()); 02179 } 02180 02181 02182 decimation = DEFAULT_DRAWGRAPH_DECIMATION; 02183 bicolor = DEFAULT_DRAWGRAPH_BICOLOR; 02184 02185 display_sys.tracks.clear(); 02186 display_sys.nodes.clear(); 02187 02188 eye4 = Mat::eye(4, 4, CV_64FC1); 02189 02190 02191 repetitionNoted = false; 02192 02193 currentPoseIndex = -1; 02194 02195 isTracking = true; 02196 02197 baseConnectionNum = 0; 02198 02199 lastBasePose = -1; 02200 02201 latestFrame = -1; 02202 02203 path_pub = nh.advertise<visualization_msgs::Marker>( "path", 1 ); 02204 camera_pub = nh.advertise<visualization_msgs::Marker>( "cameras", 1 ); 02205 points_pub = nh.advertise<visualization_msgs::Marker>( "points", 1); 02206 02207 02208 02209 structureValid = false; 02210 structureFormed = false; 02211 02212 sys.verbose = 0; 02213 display_sys.verbose = 0; 02214 02215 02216 02217 ROS_INFO("Setting up node."); 02218 02219 infoProcessed = false; 02220 02221 //std::string topic_info = nh.resolveName(configData.stream + "camera_info"); 02222 02223 std::string topic_tracks = configData.stream + "tracks"; 02224 02225 ROS_INFO("Connecting to tracks topic. %s", topic_tracks.c_str()); 02226 tracks_sub = nh.subscribe<thermalvis::feature_tracks>(topic_tracks, 1, &slamNode::handle_tracks, this); 02227 02228 std::string topic_info = configData.stream + "camera_info"; 02229 02230 ROS_INFO("Connecting to camera_info. %s", topic_info.c_str()); 02231 02232 info_sub = nh.subscribe<sensor_msgs::CameraInfo>(topic_info, 1, &slamNode::handle_info, this); 02233 02234 02235 02236 ROS_INFO("Node setup."); 02237 02238 keyframeTestScores = cv::Mat::zeros(configData.maxInitializationFrames, configData.maxInitializationFrames, CV_64FC1); 02239 keyframeTestFlags = cv::Mat::zeros(configData.maxInitializationFrames, configData.maxInitializationFrames, CV_8UC1); 02240 02241 sprintf(pose_pub_name, "thermalvis%s/pose", nodeName); 02242 ROS_INFO("Configuring pose topic. %s", pose_pub_name); 02243 02244 currentPose.header.frame_id = "/pgraph"; //pose_pub_name; 02245 pose_pub = nh.advertise<geometry_msgs::PoseStamped>(pose_pub_name, 1); 02246 02247 timer = nh.createTimer(ros::Duration(0.01), &slamNode::main_loop, this); 02248 02249 //elapsedTime = timeElapsedMS(cycle_timer); 02250 02251 if (configData.logErrors) { 02252 time_t seconds; 02253 seconds = time (NULL); 02254 //sprintf(error_filename, "/home/steve/sfm/eval/%ld.txt", seconds); 02255 configData.errorFile = configData.read_addr + "nodes/monoslam/log/stability/" + timeString + "-" + ros::this_node::getName().substr(1,ros::this_node::getName().size()-1) + ".txt"; 02256 ROS_INFO("Current debug filename: %s", configData.errorFile.c_str()); 02257 error_file.open(configData.errorFile.c_str()); 02258 } 02259 02260 ROS_INFO("Establishing server callback..."); 02261 f = boost::bind (&slamNode::serverCallback, this, _1, _2); 02262 server.setCallback (f); 02263 02264 } 02265 02266 timeAnalyzer::timeAnalyzer() { 02267 02268 cycles = 0; 02269 average = 0.0; 02270 sigma = 0.0; 02271 02272 timeElapsedMS(cycle_timer, true); 02273 } 02274 02275 void timeAnalyzer::calcParameters() { 02276 if (cycles == 0) { 02277 return; 02278 } 02279 02280 average = 0.0; 02281 sigma = 0.0; 02282 02283 for (unsigned int iii = 0; iii < cycles; iii++) { 02284 average += vals[iii] / ((double) cycles); 02285 } 02286 02287 for (unsigned int iii = 0; iii < cycles; iii++) { 02288 sigma += pow(vals[iii] - average, 2.0) / ((double) cycles); 02289 } 02290 02291 sigma = pow(sigma, 0.5); 02292 02293 } 02294 02295 void timeAnalyzer::startRecording() { 02296 timeElapsedMS(cycle_timer, true); 02297 } 02298 02299 void timeAnalyzer::stopRecording() { 02300 02301 if (cycles < 1024) { 02302 vals[cycles] = timeElapsedMS(cycle_timer, true); 02303 cycles++; 02304 } else { 02305 ROS_ERROR("Too many cycles (%d) / (%d)", cycles, 1024); 02306 } 02307 02308 } 02309 02310