PTAMWrapper.cpp
Go to the documentation of this file.
00001 
00023 #include "PTAMWrapper.h"
00024 #include <cvd/gl_helpers.h>
00025 #include <gvars3/instances.h>
00026 #include "PTAM/ATANCamera.h"
00027 #include "PTAM/MapMaker.h"
00028 #include "PTAM/Tracker.h"
00029 #include "PTAM/Map.h"
00030 #include "PTAM/MapPoint.h"
00031 #include "../HelperFunctions.h"
00032 #include "Predictor.h"
00033 #include "DroneKalmanFilter.h"
00034 #include <cv_bridge/cv_bridge.h>
00035 #include <sensor_msgs/image_encodings.h>
00036 #include "GLWindow2.h"
00037 #include "EstimationNode.h"
00038 #include <iostream>
00039 #include <fstream>
00040 #include <string>
00041 
00042 pthread_mutex_t PTAMWrapper::navInfoQueueCS = PTHREAD_MUTEX_INITIALIZER;
00043 pthread_mutex_t PTAMWrapper::shallowMapCS = PTHREAD_MUTEX_INITIALIZER;
00044 
00045 pthread_mutex_t PTAMWrapper::logScalePairs_CS = PTHREAD_MUTEX_INITIALIZER;
00046 
00047 PTAMWrapper::PTAMWrapper(DroneKalmanFilter* f, EstimationNode* nde)
00048 {
00049         filter = f;
00050         node = nde;
00051 
00052         mpMap = 0; 
00053         mpMapMaker = 0; 
00054         mpTracker = 0; 
00055         predConvert = 0;
00056         predIMUOnlyForScale = 0;
00057         mpCamera = 0;
00058         newImageAvailable = false;
00059         
00060         mapPointsTransformed = std::vector<tvec3>();
00061         keyFramesTransformed = std::vector<tse3>();
00062 
00063         
00064         predConvert = new Predictor();
00065         predIMUOnlyForScale = new Predictor();
00066         imuOnlyPred = new Predictor();
00067 
00068         drawUI = UI_PRES;
00069         frameWidth = frameHeight = 0;
00070 
00071         minKFDist = 0;
00072         minKFWiggleDist = 0;
00073         minKFTimeDist = 0;
00074 
00075         maxKF = 60;
00076 
00077         logfileScalePairs = 0;
00078 }
00079 
00080 void PTAMWrapper::ResetInternal()
00081 {
00082         mimFrameBW.resize(CVD::ImageRef(frameWidth, frameHeight));
00083         mimFrameBW_workingCopy.resize(CVD::ImageRef(frameWidth, frameHeight));
00084 
00085 
00086         if(mpMapMaker != 0) delete mpMapMaker;
00087         if(mpMap != 0) delete mpMap;
00088         if(mpTracker != 0) delete mpTracker;
00089         if(mpCamera != 0) delete mpCamera;
00090 
00091 
00092         // read camera calibration (yes, its done here)
00093         std::string file = node->calibFile;
00094         while(node->arDroneVersion == 0)
00095         {
00096                 std::cout << "Waiting for first navdata to determine drone version!" << std::endl;
00097                 usleep(250000);
00098         }
00099         if(file.size()==0)
00100         {
00101                 if(node->arDroneVersion == 1)
00102                         file = node->packagePath + "/camcalib/ardrone1_default.txt";
00103                 else if(node->arDroneVersion == 2)
00104                         file = node->packagePath + "/camcalib/ardrone2_default.txt";
00105         }
00106 
00107         std::ifstream fleH (file.c_str());
00108         TooN::Vector<5> camPar;
00109         fleH >> camPar[0] >> camPar[1] >> camPar[2] >> camPar[3] >> camPar[4];
00110         fleH.close();
00111         std::cout<< "Set Camera Paramerer to: " << camPar[0] << " " << camPar[1] << " " << camPar[2] << " " << camPar[3] << " " << camPar[4] << std::endl;
00112 
00113 
00114 
00115         mpMap = new Map;
00116         mpCamera = new ATANCamera(camPar);
00117         mpMapMaker = new MapMaker(*mpMap, *mpCamera);
00118         mpTracker = new Tracker(CVD::ImageRef(frameWidth, frameHeight), *mpCamera, *mpMap, *mpMapMaker);
00119 
00120         setPTAMPars(minKFTimeDist, minKFWiggleDist, minKFDist);
00121 
00122         predConvert->setPosRPY(0,0,0,0,0,0);
00123         predIMUOnlyForScale->setPosRPY(0,0,0,0,0,0);
00124 
00125         resetPTAMRequested = false;
00126         forceKF = false;
00127         isGoodCount = 0;
00128         lastAnimSentClock = 0;
00129         lockNextFrame = false;
00130         PTAMInitializedClock = 0;
00131         lastPTAMMessage = "";
00132 
00133         flushMapKeypoints = false;
00134 
00135         node->publishCommand("u l PTAM has been reset.");
00136 }
00137 
00138 void PTAMWrapper::setPTAMPars(double minKFTimeDist, double minKFWiggleDist, double minKFDist)
00139 {
00140         if(mpMapMaker != 0)
00141                 mpMapMaker->minKFDist = minKFDist;
00142         if(mpMapMaker != 0)
00143                 mpMapMaker->minKFWiggleDist = minKFWiggleDist;
00144         if(mpTracker != 0)
00145                 mpTracker->minKFTimeDist = minKFTimeDist;
00146 
00147         this->minKFDist = minKFDist;
00148         this->minKFWiggleDist = minKFWiggleDist;
00149         this->minKFTimeDist = minKFTimeDist;
00150 }
00151 
00152 PTAMWrapper::~PTAMWrapper(void)
00153 {
00154         if(mpCamera != 0) delete mpCamera;
00155         if(mpMap != 0) delete mpMap;
00156         if(mpMapMaker != 0) delete mpMapMaker;
00157         if(mpTracker != 0) delete mpTracker;
00158         if(predConvert != 0) delete predConvert;
00159         if(predIMUOnlyForScale != 0) delete predIMUOnlyForScale;
00160         if(imuOnlyPred != 0) delete imuOnlyPred;
00161 
00162 }
00163 
00164 
00165 void PTAMWrapper::startSystem()
00166 {
00167         keepRunning = true;
00168         changeSizeNextRender = false;
00169         start();
00170 }
00171 
00172 void PTAMWrapper::stopSystem()
00173 {
00174         keepRunning = false;
00175         new_frame_signal.notify_all();
00176         join();
00177 }
00178 
00179 
00180 void PTAMWrapper::run()
00181 {
00182         std::cout << "Waiting for Video" << std::endl;
00183 
00184         // wait for firsst image
00185         while(!newImageAvailable)
00186                 usleep(100000); // sleep 100ms
00187         newImageAvailable = false;
00188         while(!newImageAvailable)
00189                 usleep(100000); // sleep 100ms
00190 
00191         // read image height and width
00192         frameWidth = mimFrameBW.size().x;
00193         frameHeight = mimFrameBW.size().y;
00194 
00195         ResetInternal();
00196 
00197 
00198         snprintf(charBuf,200,"Video resolution: %d x %d",frameWidth,frameHeight);
00199         ROS_INFO(charBuf);
00200         node->publishCommand(std::string("u l ")+charBuf);
00201 
00202         // create window
00203     myGLWindow = new GLWindow2(CVD::ImageRef(frameWidth,frameHeight), "PTAM Drone Camera Feed", this);
00204         myGLWindow->set_title("PTAM Drone Camera Feed");
00205 
00206         changeSizeNextRender = true;
00207         if(frameWidth < 640)
00208                 desiredWindowSize = CVD::ImageRef(frameWidth*2,frameHeight*2);
00209         else
00210                 desiredWindowSize = CVD::ImageRef(frameWidth,frameHeight);
00211 
00212 
00213         boost::unique_lock<boost::mutex> lock(new_frame_signal_mutex);
00214 
00215         while(keepRunning)
00216         {
00217                 if(newImageAvailable)
00218                 {
00219                         newImageAvailable = false;
00220 
00221                         // copy to working copy
00222                         mimFrameBW_workingCopy.copy_from(mimFrameBW);
00223                         mimFrameTime_workingCopy = mimFrameTime;
00224                         mimFrameSEQ_workingCopy = mimFrameSEQ;
00225                         mimFrameTimeRos_workingCopy = mimFrameTimeRos;
00226 
00227                         // release lock and do the work-intensive stuff.....
00228                         lock.unlock();
00229 
00230                         HandleFrame();
00231 
00232 
00233                         if(changeSizeNextRender)
00234                         {
00235                                 myGLWindow->set_size(desiredWindowSize);
00236                                 changeSizeNextRender = false;
00237                         }
00238 
00239                         // get lock again
00240                         lock.lock();
00241                 }
00242                 else
00243                         new_frame_signal.wait(lock);
00244         }
00245 
00246         lock.unlock();
00247         delete myGLWindow;
00248 }
00249 
00250 // called every time a new frame is available.
00251 // needs to be able to 
00252 // - (finally) roll forward filter
00253 // - query it's state 
00254 // - add a PTAM observation to filter.
00255 void PTAMWrapper::HandleFrame()
00256 {
00257         //printf("tracking Frame at ms=%d (from %d)\n",getMS(ros::Time::now()),mimFrameTime-filter->delayVideo);
00258 
00259 
00260         // prep data
00261         msg = "";
00262         ros::Time startedFunc = ros::Time::now();
00263 
00264         // reset?
00265         if(resetPTAMRequested)
00266                 ResetInternal();
00267 
00268 
00269         // make filter thread-safe.
00270         // --------------------------- ROLL FORWARD TIL FRAME. This is ONLY done here. ---------------------------
00271         pthread_mutex_lock( &filter->filter_CS );
00272         //filter->predictUpTo(mimFrameTime,true, true);
00273         TooN::Vector<10> filterPosePrePTAM = filter->getPoseAtAsVec(mimFrameTime_workingCopy-filter->delayVideo,true);
00274         pthread_mutex_unlock( &filter->filter_CS );
00275 
00276         // ------------------------ do PTAM -------------------------
00277         myGLWindow->SetupViewport();
00278         myGLWindow->SetupVideoOrtho();
00279         myGLWindow->SetupVideoRasterPosAndZoom();
00280 
00281 
00282 
00283         // 1. transform with filter
00284         TooN::Vector<6> PTAMPoseGuess = filter->backTransformPTAMObservation(filterPosePrePTAM.slice<0,6>());
00285         // 2. convert to se3
00286         predConvert->setPosRPY(PTAMPoseGuess[0], PTAMPoseGuess[1], PTAMPoseGuess[2], PTAMPoseGuess[3], PTAMPoseGuess[4], PTAMPoseGuess[5]);
00287         // 3. multiply with rotation matrix     
00288         TooN::SE3<> PTAMPoseGuessSE3 = predConvert->droneToFrontNT * predConvert->globaltoDrone;
00289 
00290 
00291         // set
00292         mpTracker->setPredictedCamFromW(PTAMPoseGuessSE3);
00293         //mpTracker->setLastFrameLost((isGoodCount < -10), (videoFrameID%2 != 0));
00294         mpTracker->setLastFrameLost((isGoodCount < -20), (mimFrameSEQ_workingCopy%3 == 0));
00295 
00296         // track
00297         ros::Time startedPTAM = ros::Time::now();
00298         mpTracker->TrackFrame(mimFrameBW_workingCopy, true);
00299         TooN::SE3<> PTAMResultSE3 = mpTracker->GetCurrentPose();
00300         lastPTAMMessage = msg = mpTracker->GetMessageForUser();
00301         ros::Duration timePTAM= ros::Time::now() - startedPTAM;
00302 
00303         TooN::Vector<6> PTAMResultSE3TwistOrg = PTAMResultSE3.ln();
00304 
00305         node->publishTf(mpTracker->GetCurrentPose(),mimFrameTimeRos_workingCopy, mimFrameSEQ_workingCopy,"cam_front");
00306 
00307 
00308         // 1. multiply from left by frontToDroneNT.
00309         // 2. convert to xyz,rpy
00310         predConvert->setPosSE3_globalToDrone(predConvert->frontToDroneNT * PTAMResultSE3);
00311         TooN::Vector<6> PTAMResult = TooN::makeVector(predConvert->x, predConvert->y, predConvert->z, predConvert->roll, predConvert->pitch, predConvert->yaw);
00312 
00313         // 3. transform with filter
00314         TooN::Vector<6> PTAMResultTransformed = filter->transformPTAMObservation(PTAMResult);
00315 
00316 
00317 
00318 
00319         // init failed?
00320         if(mpTracker->lastStepResult == mpTracker->I_FAILED)
00321         {
00322                 ROS_INFO("initializing PTAM failed, resetting!");
00323                 resetPTAMRequested = true;
00324         }
00325         if(mpTracker->lastStepResult == mpTracker->I_SECOND)
00326         {
00327                 PTAMInitializedClock = getMS();
00328                 filter->setCurrentScales(TooN::makeVector(mpMapMaker->initialScaleFactor*1.2,mpMapMaker->initialScaleFactor*1.2,mpMapMaker->initialScaleFactor*1.2));
00329                 mpMapMaker->currentScaleFactor = filter->getCurrentScales()[0];
00330                 ROS_INFO("PTAM initialized!");
00331                 ROS_INFO("initial scale: %f\n",mpMapMaker->initialScaleFactor*1.2);
00332                 node->publishCommand("u l PTAM initialized (took second KF)");
00333                 framesIncludedForScaleXYZ = -1;
00334                 lockNextFrame = true;
00335                 imuOnlyPred->resetPos();
00336         }
00337         if(mpTracker->lastStepResult == mpTracker->I_FIRST)
00338         {
00339                 node->publishCommand("u l PTAM initialization started (took first KF)");
00340         }
00341 
00342 
00343 
00344 
00345 
00346 
00347         // --------------------------- assess result ------------------------------
00348         bool isGood = true;
00349         bool isVeryGood = true;
00350         // calculate absolute differences.
00351         TooN::Vector<6> diffs = PTAMResultTransformed - filterPosePrePTAM.slice<0,6>();
00352         for(int i=0;1<1;i++) diffs[i] = abs(diffs[i]);
00353 
00354 
00355         if(filter->getNumGoodPTAMObservations() < 10 && mpMap->IsGood())
00356         {
00357                 isGood = true;
00358                 isVeryGood = false;
00359         }
00360         else if(mpTracker->lastStepResult == mpTracker->I_FIRST ||
00361                 mpTracker->lastStepResult == mpTracker->I_SECOND || 
00362                 mpTracker->lastStepResult == mpTracker->I_FAILED ||
00363                 mpTracker->lastStepResult == mpTracker->T_LOST ||
00364                 mpTracker->lastStepResult == mpTracker->NOT_TRACKING ||
00365                 mpTracker->lastStepResult == mpTracker->INITIALIZING)
00366                 isGood = isVeryGood = false;
00367         else
00368         {
00369                 // some chewy heuristic when to add and when not to.
00370                 bool dodgy = mpTracker->lastStepResult == mpTracker->T_DODGY ||
00371                         mpTracker->lastStepResult == mpTracker->T_RECOVERED_DODGY;
00372 
00373                 // if yaw difference too big: something certainly is wrong.
00374                 // maximum difference is 5 + 2*(number of seconds since PTAM observation).
00375                 double maxYawDiff = 10.0 + (getMS()-lastGoodYawClock)*0.002;
00376                 if(maxYawDiff > 20) maxYawDiff = 1000;
00377                 if(false && diffs[5] > maxYawDiff) 
00378                         isGood = false;
00379 
00380                 if(diffs[5] < 10) 
00381                         lastGoodYawClock = getMS();
00382 
00383                 if(diffs[5] > 4.0) 
00384                         isVeryGood = false;
00385 
00386                 // if rp difference too big: something certainly is wrong.
00387                 if(diffs[3] > 20 || diffs[4] > 20)
00388                         isGood = false;
00389 
00390                 if(diffs[3] > 3 || diffs[4] > 3 || dodgy)
00391                         isVeryGood = false;
00392         }
00393 
00394         if(isGood)
00395         {
00396                 if(isGoodCount < 0) isGoodCount = 0;
00397                 isGoodCount++;
00398         }
00399         else
00400         {
00401                 if(isGoodCount > 0) isGoodCount = 0;
00402                 isGoodCount--;
00403                 
00404                 if(mpTracker->lastStepResult == mpTracker->T_RECOVERED_DODGY)
00405                         isGoodCount = std::max(isGoodCount,-2);
00406                 if(mpTracker->lastStepResult == mpTracker->T_RECOVERED_GOOD)
00407                         isGoodCount = std::max(isGoodCount,-5);
00408 
00409         }
00410 
00411         TooN::Vector<10> filterPosePostPTAM;
00412         // --------------------------- scale estimation & update filter (REDONE) -----------------------------
00413         // interval length is always between 1s and 2s, to enshure approx. same variances.
00414         // if interval contained height inconsistency, z-distances are simply both set to zero, which does not generate a bias.
00415         // otherwise distances are scaled such that height is weighted more.
00416         // if isGood>=3 && framesIncludedForScale < 0                   ===> START INTERVAL
00417         // if 18 <= framesIncludedForScale <= 36 AND isGood>=3  ===> ADD INTERVAL, START INTERVAL
00418         // if framesIncludedForScale > 36                                               ===> set framesIncludedForScale=-1 
00419 
00420         // include!
00421 
00422         // TODO: make shure filter is handled properly with permanent roll-forwards.
00423         pthread_mutex_lock( &filter->filter_CS );
00424         if(filter->usePTAM && isGoodCount >= 3)
00425         {
00426                 filter->addPTAMObservation(PTAMResult,mimFrameTime_workingCopy-filter->delayVideo);
00427         }
00428         else
00429                 filter->addFakePTAMObservation(mimFrameTime_workingCopy-filter->delayVideo);
00430 
00431         filterPosePostPTAM = filter->getCurrentPoseSpeedAsVec();
00432         pthread_mutex_unlock( &filter->filter_CS );
00433 
00434         TooN::Vector<6> filterPosePostPTAMBackTransformed = filter->backTransformPTAMObservation(filterPosePostPTAM.slice<0,6>());
00435 
00436 
00437         // if interval is started: add one step.
00438         int includedTime = mimFrameTime_workingCopy - ptamPositionForScaleTakenTimestamp;
00439         if(framesIncludedForScaleXYZ >= 0) framesIncludedForScaleXYZ++;
00440 
00441         // if interval is overdue: reset & dont add
00442         if(includedTime > 3000) 
00443         {
00444                 framesIncludedForScaleXYZ = -1;
00445         }
00446 
00447         if(isGoodCount >= 3)
00448         {
00449                 // filter stuff
00450                 lastScaleEKFtimestamp = mimFrameTime_workingCopy;
00451 
00452                 if(includedTime >= 2000 && framesIncludedForScaleXYZ > 1)       // ADD! (if too many, was resetted before...)
00453                 {
00454                         TooN::Vector<3> diffPTAM = filterPosePostPTAMBackTransformed.slice<0,3>() - PTAMPositionForScale;
00455                         bool zCorrupted, allCorrupted;
00456                         float pressureStart = 0, pressureEnd = 0;
00457                         TooN::Vector<3> diffIMU = evalNavQue(ptamPositionForScaleTakenTimestamp - filter->delayVideo + filter->delayXYZ,mimFrameTime_workingCopy - filter->delayVideo + filter->delayXYZ,&zCorrupted, &allCorrupted, &pressureStart, &pressureEnd);
00458 
00459                         pthread_mutex_lock(&logScalePairs_CS);
00460                         if(logfileScalePairs != 0)
00461                                 (*logfileScalePairs) <<
00462                                                 pressureStart << " " <<
00463                                                 pressureEnd << " " <<
00464                                                 diffIMU[2] << " " <<
00465                                                 diffPTAM[2] << std::endl;
00466                         pthread_mutex_unlock(&logScalePairs_CS);
00467 
00468 
00469                         if(!allCorrupted)
00470                         {
00471                                 // filtering: z more weight, but only if not corrupted.
00472                                 double xyFactor = 0.05;
00473                                 double zFactor = zCorrupted ? 0 : 3;
00474                         
00475                                 diffPTAM.slice<0,2>() *= xyFactor; diffPTAM[2] *= zFactor;
00476                                 diffIMU.slice<0,2>() *= xyFactor; diffIMU[2] *= zFactor;
00477 
00478                                 filter->updateScaleXYZ(diffPTAM, diffIMU, PTAMResult.slice<0,3>());
00479                                 mpMapMaker->currentScaleFactor = filter->getCurrentScales()[0];
00480                         }
00481                         framesIncludedForScaleXYZ = -1; // causing reset afterwards
00482                 }
00483 
00484                 if(framesIncludedForScaleXYZ == -1)     // RESET!
00485                 {
00486                         framesIncludedForScaleXYZ = 0;
00487                         PTAMPositionForScale = filterPosePostPTAMBackTransformed.slice<0,3>();
00488                         //predIMUOnlyForScale->resetPos();      // also resetting z corrupted flag etc. (NOT REquired as reset is done in eval)
00489                         ptamPositionForScaleTakenTimestamp = mimFrameTime_workingCopy;
00490                 }
00491         }
00492         
00493 
00494         if(lockNextFrame && isGood)
00495         {
00496                 filter->scalingFixpoint = PTAMResult.slice<0,3>();
00497                 lockNextFrame = false;  
00498                 //filter->useScalingFixpoint = true;
00499 
00500                 snprintf(charBuf,500,"locking scale fixpoint to %.3f %.3f %.3f",PTAMResultTransformed[0], PTAMResultTransformed[1], PTAMResultTransformed[2]);
00501                 ROS_INFO(charBuf);
00502                 node->publishCommand(std::string("u l ")+charBuf);
00503         }
00504 
00505 
00506         // ----------------------------- Take KF? -----------------------------------
00507         if(!mapLocked && isVeryGood && (forceKF || mpMap->vpKeyFrames.size() < maxKF || maxKF <= 1))
00508         {
00509                 mpTracker->TakeKF(forceKF);
00510                 forceKF = false;
00511         }
00512 
00513         // ---------------- save PTAM status for KI --------------------------------
00514         if(mpTracker->lastStepResult == mpTracker->NOT_TRACKING)
00515                 PTAMStatus = PTAM_IDLE;
00516         else if(mpTracker->lastStepResult == mpTracker->I_FIRST ||
00517                 mpTracker->lastStepResult == mpTracker->I_SECOND ||
00518                 mpTracker->lastStepResult == mpTracker->T_TOOK_KF)
00519                 PTAMStatus = PTAM_TOOKKF;
00520         else if(mpTracker->lastStepResult == mpTracker->INITIALIZING)
00521                 PTAMStatus = PTAM_INITIALIZING;
00522         else if(isVeryGood)
00523                 PTAMStatus = PTAM_BEST;
00524         else if(isGood)
00525                 PTAMStatus = PTAM_GOOD;
00526         else if(mpTracker->lastStepResult == mpTracker->T_DODGY ||
00527                 mpTracker->lastStepResult == mpTracker->T_GOOD)
00528                 PTAMStatus = PTAM_FALSEPOSITIVE;
00529         else
00530                 PTAMStatus = PTAM_LOST;
00531 
00532          
00533         // ----------------------------- update shallow map --------------------------
00534         if(!mapLocked && rand()%5==0)
00535         {
00536                 pthread_mutex_lock(&shallowMapCS);
00537                 mapPointsTransformed.clear();
00538                 keyFramesTransformed.clear();
00539                 for(unsigned int i=0;i<mpMap->vpKeyFrames.size();i++)
00540                 {
00541                         predConvert->setPosSE3_globalToDrone(predConvert->frontToDroneNT * mpMap->vpKeyFrames[i]->se3CfromW);
00542                         TooN::Vector<6> CamPos = TooN::makeVector(predConvert->x, predConvert->y, predConvert->z, predConvert->roll, predConvert->pitch, predConvert->yaw);
00543                         CamPos = filter->transformPTAMObservation(CamPos);
00544                         predConvert->setPosRPY(CamPos[0], CamPos[1], CamPos[2], CamPos[3], CamPos[4], CamPos[5]);
00545                         keyFramesTransformed.push_back(predConvert->droneToGlobal);
00546                 }
00547                 TooN::Vector<3> PTAMScales = filter->getCurrentScales();
00548                 TooN::Vector<3> PTAMOffsets = filter->getCurrentOffsets().slice<0,3>();
00549                 for(unsigned int i=0;i<mpMap->vpPoints.size();i++)
00550                 {
00551                         TooN::Vector<3> pos = (mpMap->vpPoints)[i]->v3WorldPos;
00552                         pos[0] *= PTAMScales[0];
00553                         pos[1] *= PTAMScales[1];
00554                         pos[2] *= PTAMScales[2];
00555                         pos += PTAMOffsets;
00556                         mapPointsTransformed.push_back(pos);
00557                 }
00558 
00559                 // flush map keypoints
00560                 if(flushMapKeypoints)
00561                 {
00562                         std::ofstream* fle = new std::ofstream();
00563                         fle->open("pointcloud.txt");
00564 
00565                         for(unsigned int i=0;i<mapPointsTransformed.size();i++)
00566                         {
00567                                 (*fle) << mapPointsTransformed[i][0] << " "
00568                                            << mapPointsTransformed[i][1] << " "
00569                                            << mapPointsTransformed[i][2] << std::endl;
00570                         }
00571 
00572                         fle->flush();
00573                         fle->close();
00574 
00575                         printf("FLUSHED %d KEYPOINTS to file pointcloud.txt\n\n",mapPointsTransformed.size());
00576 
00577                         flushMapKeypoints = false;
00578                 }
00579 
00580 
00581                 pthread_mutex_unlock(&shallowMapCS);
00582 
00583         }
00584 
00585 
00586 
00587         // ---------------------- output and render! ---------------------------
00588         ros::Duration timeALL = ros::Time::now() - startedFunc;
00589         if(isVeryGood) snprintf(charBuf,1000,"\nQuality: best            ");
00590         else if(isGood) snprintf(charBuf,1000,"\nQuality: good           ");
00591         else snprintf(charBuf,1000,"\nQuality: lost                       ");
00592         
00593         snprintf(charBuf+20,800, "scale: %.3f (acc: %.3f)                            ",filter->getCurrentScales()[0],(double)filter->getScaleAccuracy());
00594         snprintf(charBuf+50,800, "PTAM time: %i ms                            ",(int)(1000*timeALL.toSec()));
00595         snprintf(charBuf+68,800, "(%i ms total)  ",(int)(1000*timeALL.toSec()));
00596         if(mapLocked) snprintf(charBuf+83,800, "m.l. ");
00597         else snprintf(charBuf+83,800, "     ");
00598         if(filter->allSyncLocked) snprintf(charBuf+88,800, "s.l. ");
00599         else snprintf(charBuf+88,800, "     ");
00600 
00601 
00602         msg += charBuf;
00603 
00604         if(mpMap->IsGood())
00605         {
00606                 if(drawUI == UI_DEBUG)
00607                 {
00608                         snprintf(charBuf,1000,"\nPTAM Diffs:              ");
00609                         snprintf(charBuf+13,800, "x: %.3f                          ",diffs[0]);
00610                         snprintf(charBuf+23,800, "y: %.3f                          ",diffs[1]);
00611                         snprintf(charBuf+33,800, "z: %.3f                          ",diffs[2]);
00612                         snprintf(charBuf+43,800, "r: %.2f                          ",diffs[3]);
00613                         snprintf(charBuf+53,800, "p: %.2f                          ",diffs[4]);
00614                         snprintf(charBuf+63,800, "y: %.2f",diffs[5]);
00615                         msg += charBuf;
00616 
00617 
00618                         snprintf(charBuf,1000,"\nPTAM Pose:              ");
00619                         snprintf(charBuf+13,800, "x: %.3f                          ",PTAMResultTransformed[0]);
00620                         snprintf(charBuf+23,800, "y: %.3f                          ",PTAMResultTransformed[1]);
00621                         snprintf(charBuf+33,800, "z: %.3f                          ",PTAMResultTransformed[2]);
00622                         snprintf(charBuf+43,800, "r: %.2f                          ",PTAMResultTransformed[3]);
00623                         snprintf(charBuf+53,800, "p: %.2f                          ",PTAMResultTransformed[4]);
00624                         snprintf(charBuf+63,800, "y: %.2f",PTAMResultTransformed[5]);
00625                         msg += charBuf;
00626 
00627 
00628                         snprintf(charBuf,1000,"\nPTAM WiggleDist:              ");
00629                         snprintf(charBuf+18,800, "%.3f                          ",mpMapMaker->lastWiggleDist);
00630                         snprintf(charBuf+24,800, "MetricDist: %.3f",mpMapMaker->lastMetricDist);
00631                         msg += charBuf;
00632                 }
00633         }
00634 
00635         if(drawUI != UI_NONE)
00636         {
00637                 // render grid
00638                 predConvert->setPosRPY(filterPosePostPTAM[0], filterPosePostPTAM[1], filterPosePostPTAM[2], filterPosePostPTAM[3], filterPosePostPTAM[4], filterPosePostPTAM[5]);
00639 
00640                 //renderGrid(predConvert->droneToFrontNT * predConvert->globaltoDrone);
00641                 //renderGrid(PTAMResultSE3);
00642 
00643 
00644                 // draw HUD
00645                 //if(mod->getControlSystem()->isControlling())
00646                 {
00647                         myGLWindow->SetupViewport();
00648                         myGLWindow->SetupVideoOrtho();
00649                         myGLWindow->SetupVideoRasterPosAndZoom();
00650 
00651                         //glDisable(GL_LINE_SMOOTH);
00652                         glLineWidth(2);
00653                         glBegin(GL_LINES);
00654                         glColor3f(0,0,1);
00655 
00656                         glVertex2f(0,frameHeight/2);
00657                         glVertex2f(frameWidth,frameHeight/2);
00658 
00659                         glVertex2f(frameWidth/2,0);
00660                         glVertex2f(frameWidth/2,frameHeight);
00661 
00662                         // 1m lines
00663                         glVertex2f(0.25*frameWidth,0.48*frameHeight);
00664                         glVertex2f(0.25*frameWidth,0.52*frameHeight);
00665                         glVertex2f(0.75*frameWidth,0.48*frameHeight);
00666                         glVertex2f(0.75*frameWidth,0.52*frameHeight);
00667                         glVertex2f(0.48*frameWidth,0.25*frameHeight);
00668                         glVertex2f(0.52*frameWidth,0.25*frameHeight);
00669                         glVertex2f(0.48*frameWidth,0.75*frameHeight);
00670                         glVertex2f(0.52*frameWidth,0.75*frameHeight);
00671 
00672                         glEnd();
00673                 }
00674 
00675 
00676                 myGLWindow->DrawCaption(msg);
00677         }
00678 
00679         lastPTAMResultRaw = PTAMResultSE3; 
00680         // ------------------------ LOG --------------------------------------
00681         // log!
00682         if(node->logfilePTAM != NULL)
00683         {
00684                 TooN::Vector<3> scales = filter->getCurrentScalesForLog();
00685                 TooN::Vector<3> sums = TooN::makeVector(0,0,0);
00686                 TooN::Vector<6> offsets = filter->getCurrentOffsets();
00687                 pthread_mutex_lock(&(node->logPTAM_CS));
00688                 // log:
00689                 // - filterPosePrePTAM estimated for videoFrameTimestamp-delayVideo.
00690                 // - PTAMResulttransformed estimated for videoFrameTimestamp-delayVideo. (using imu only for last step)
00691                 // - predictedPoseSpeed estimated for lastNfoTimestamp+filter->delayControl     (actually predicting)
00692                 // - predictedPoseSpeedATLASTNFO estimated for lastNfoTimestamp (using imu only)
00693                 if(node->logfilePTAM != NULL)
00694                         (*(node->logfilePTAM)) << (isGood ? (isVeryGood ? 2 : 1) : 0) << " " <<
00695                                 (mimFrameTime_workingCopy-filter->delayVideo) << " " << filterPosePrePTAM[0] << " " << filterPosePrePTAM[1] << " " << filterPosePrePTAM[2] << " " << filterPosePrePTAM[3] << " " << filterPosePrePTAM[4] << " " << filterPosePrePTAM[5] << " " << filterPosePrePTAM[6] << " " << filterPosePrePTAM[7] << " " << filterPosePrePTAM[8] << " " << filterPosePrePTAM[9] << " " <<
00696                                 filterPosePostPTAM[0] << " " << filterPosePostPTAM[1] << " " << filterPosePostPTAM[2] << " " << filterPosePostPTAM[3] << " " << filterPosePostPTAM[4] << " " << filterPosePostPTAM[5] << " " << filterPosePostPTAM[6] << " " << filterPosePostPTAM[7] << " " << filterPosePostPTAM[8] << " " << filterPosePostPTAM[9] << " " << 
00697                                 PTAMResultTransformed[0] << " " << PTAMResultTransformed[1] << " " << PTAMResultTransformed[2] << " " << PTAMResultTransformed[3] << " " << PTAMResultTransformed[4] << " " << PTAMResultTransformed[5] << " " << 
00698                                 scales[0] << " " << scales[1] << " " << scales[2] << " " << 
00699                                 offsets[0] << " " << offsets[1] << " " << offsets[2] << " " << offsets[3] << " " << offsets[4] << " " << offsets[5] << " " <<
00700                                 sums[0] << " " << sums[1] << " " << sums[2] << " " << 
00701                                 PTAMResult[0] << " " << PTAMResult[1] << " " << PTAMResult[2] << " " << PTAMResult[3] << " " << PTAMResult[4] << " " << PTAMResult[5] << " " <<
00702                                 PTAMResultSE3TwistOrg[0] << " " << PTAMResultSE3TwistOrg[1] << " " << PTAMResultSE3TwistOrg[2] << " " << PTAMResultSE3TwistOrg[3] << " " << PTAMResultSE3TwistOrg[4] << " " << PTAMResultSE3TwistOrg[5] << " " <<
00703                                 videoFramePing << " " << mimFrameTimeRos_workingCopy << " " << mimFrameSEQ_workingCopy << std::endl;
00704 
00705                 pthread_mutex_unlock(&(node->logPTAM_CS));
00706         }
00707 
00708         myGLWindow->swap_buffers();
00709         myGLWindow->HandlePendingEvents();
00710 
00711 }
00712 
00713 
00714 // Draw the reference grid to give the user an idea of wether tracking is OK or not.
00715 void PTAMWrapper::renderGrid(TooN::SE3<> camFromWorld)
00716 {
00717         myGLWindow->SetupViewport();
00718         myGLWindow->SetupVideoOrtho();
00719         myGLWindow->SetupVideoRasterPosAndZoom();
00720 
00721         camFromWorld.get_translation() *= 1;
00722 
00723         // The colour of the ref grid shows if the coarse stage of tracking was used
00724         // (it's turned off when the camera is sitting still to reduce jitter.)
00725         glColor4f(0,0,0,0.6);
00726   
00727         // The grid is projected manually, i.e. GL receives projected 2D coords to draw.
00728         int nHalfCells = 5;
00729         int nTot = nHalfCells * 2 + 1;
00730         CVD::Image<Vector<2> >  imVertices(CVD::ImageRef(nTot,nTot));
00731         for(int i=0; i<nTot; i++)
00732                 for(int j=0; j<nTot; j++)
00733                 {
00734                         Vector<3> v3;
00735                         v3[0] = (i - nHalfCells) * 1;
00736                         v3[1] = (j - nHalfCells) * 1;
00737                         v3[2] = 0.0;
00738                         Vector<3> v3Cam = camFromWorld * v3;
00739                         //v3Cam[2] *= 100;
00740                         if(v3Cam[2] < 0.001)
00741                                 v3Cam = TooN::makeVector(100000*v3Cam[0],100000*v3Cam[1],0.0001);
00742 
00743                         imVertices[i][j] = mpCamera->Project(TooN::project(v3Cam))*0.5;
00744                 }
00745 
00746         glEnable(GL_LINE_SMOOTH);
00747         glEnable(GL_BLEND);
00748         glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
00749         glLineWidth(2);
00750         for(int i=0; i<nTot; i++)
00751         {
00752                 glBegin(GL_LINE_STRIP);
00753                 for(int j=0; j<nTot; j++)
00754                 CVD::glVertex(imVertices[i][j]);
00755                 glEnd();
00756       
00757                 glBegin(GL_LINE_STRIP);
00758                 for(int j=0; j<nTot; j++)
00759                 CVD::glVertex(imVertices[j][i]);
00760                 glEnd();
00761         };
00762   
00763   glLineWidth(1);
00764   glColor3f(1,0,0);
00765 
00766 
00767 
00768 }
00769 
00770 TooN::Vector<3> PTAMWrapper::evalNavQue(unsigned int from, unsigned int to, bool* zCorrupted, bool* allCorrupted, float* out_start_pressure, float* out_end_pressure)
00771 {
00772         predIMUOnlyForScale->resetPos();
00773 
00774         int firstAdded = 0, lastAdded = 0;
00775         pthread_mutex_lock(&navInfoQueueCS);
00776         int skipped=0;
00777         int used = 0;
00778         int firstZ = 0;
00779 
00780         float sum_first=0, num_first=0, sum_last=0, num_last=0;
00781         int pressureAverageRange = 100;
00782 
00783 
00784         for(std::deque<ardrone_autonomy::Navdata>::iterator cur = navInfoQueue.begin();
00785                         cur != navInfoQueue.end();
00786                         )
00787         {
00788                 int curStampMs = getMS(cur->header.stamp);
00789 
00790                 if(curStampMs < (int)from-pressureAverageRange)
00791                         cur = navInfoQueue.erase(cur);
00792                 else
00793                 {
00794                         if(curStampMs >= (int)from-pressureAverageRange && curStampMs <= (int)from+pressureAverageRange)
00795                         {
00796                                 sum_first += cur->pressure;
00797                                 num_first++;
00798                         }
00799 
00800                         if(curStampMs >= (int)to-pressureAverageRange && curStampMs <= (int)to+pressureAverageRange)
00801                         {
00802                                 sum_last += cur->pressure;
00803                                 num_last++;
00804                         }
00805                         cur++;
00806                 }
00807         }
00808 
00809         for(std::deque<ardrone_autonomy::Navdata>::iterator cur = navInfoQueue.begin();
00810                         cur != navInfoQueue.end();
00811                         cur++
00812                         )
00813         {
00814                 int frontStamp = getMS(cur->header.stamp);
00815                 if(frontStamp < from)           // packages before: delete
00816                 {
00817                         //navInfoQueue.pop_front();
00818                         skipped++;
00819                 }
00820                 else if(frontStamp >= from && frontStamp <= to)
00821                 {
00822                         if(firstAdded == 0) 
00823                         {
00824                                 firstAdded = frontStamp;
00825                                 firstZ = cur->altd;
00826                                 predIMUOnlyForScale->z = firstZ*0.001;  // avoid height check initially!
00827                         }
00828                         lastAdded = frontStamp;
00829                         // add
00830                         predIMUOnlyForScale->predictOneStep(&(*cur));
00831                         // pop
00832                         //navInfoQueue.pop_front();
00833                         used++;
00834                 }
00835                 else
00836                         break;
00837 
00838         }
00839         //printf("QueEval: before: %i; skipped: %i, used: %i, left: %i\n", totSize, skipped, used, navInfoQueue.size());
00840         predIMUOnlyForScale->z -= firstZ*0.001; // make height to height-diff
00841 
00842         *zCorrupted = predIMUOnlyForScale->zCorrupted;
00843         *allCorrupted = abs(firstAdded - (int)from) + abs(lastAdded - (int)to) > 80;
00844         pthread_mutex_unlock(&navInfoQueueCS);
00845 
00846         if(*allCorrupted)
00847                 printf("scalePackage corrupted (imu data gap for %ims)\n",abs(firstAdded - (int)from) + abs(lastAdded - (int)to));
00848         else if(*zCorrupted)
00849                 printf("scalePackage z corrupted (jump in meters: %.3f)!\n",predIMUOnlyForScale->zCorruptedJump);
00850 
00851         printf("first: %f (%f); last: %f (%f)=> diff: %f (z alt diff: %f)\n",
00852                         sum_first/num_first,
00853                         num_first,
00854                         sum_last/num_last,
00855                         num_last,
00856                         sum_last/num_last - sum_first/num_first,
00857                         predIMUOnlyForScale->z
00858         );
00859 
00860 
00861         *out_end_pressure = sum_last/num_last;
00862         *out_start_pressure = sum_first/num_first;
00863 
00864         return TooN::makeVector(predIMUOnlyForScale->x,predIMUOnlyForScale->y,predIMUOnlyForScale->z);
00865 }
00866 
00867 void PTAMWrapper::newNavdata(ardrone_autonomy::Navdata* nav)
00868 {
00869         lastNavinfoReceived = *nav;
00870 
00871         if(getMS(lastNavinfoReceived.header.stamp) > 2000000)
00872         {
00873                 printf("PTAMSystem: ignoring navdata package with timestamp %f\n", lastNavinfoReceived.tm);
00874                 return;
00875         }
00876         if(lastNavinfoReceived.header.seq > 2000000 || lastNavinfoReceived.header.seq < 0)
00877         {
00878                 printf("PTAMSystem: ignoring navdata package with ID %i\n", lastNavinfoReceived.header.seq);
00879                 return;
00880         }
00881 
00882         // correct yaw with filter-yaw (!):
00883         lastNavinfoReceived.rotZ = filter->getCurrentPose()[5];
00884 
00885         pthread_mutex_lock( &navInfoQueueCS );
00886         navInfoQueue.push_back(lastNavinfoReceived);
00887 
00888         if(navInfoQueue.size() > 1000)  // respective 5s
00889         {
00890                 navInfoQueue.pop_front();
00891                 if(!navQueueOverflown)
00892                         printf("NavQue Overflow detected!\n");
00893                 navQueueOverflown = true;
00894         }
00895         pthread_mutex_unlock( &navInfoQueueCS );
00896 
00897         //filter->setPing(nav->pingNav, nav->pingVid);
00898 
00899         imuOnlyPred->yaw = filter->getCurrentPose()[5];
00900         imuOnlyPred->predictOneStep(&lastNavinfoReceived);
00901 }
00902 
00903 void PTAMWrapper::newImage(sensor_msgs::ImageConstPtr img)
00904 {
00905 
00906         // convert to CVImage
00907         cv_bridge::CvImagePtr cv_ptr = cv_bridge::toCvCopy(img, sensor_msgs::image_encodings::MONO8);
00908 
00909 
00910         boost::unique_lock<boost::mutex> lock(new_frame_signal_mutex);
00911 
00912         // copy to internal image, convert to bw, set flag.
00913         if(ros::Time::now() - img->header.stamp > ros::Duration(30.0))
00914                 mimFrameTimeRos = (ros::Time::now()-ros::Duration(0.001));
00915         else
00916                 mimFrameTimeRos = (img->header.stamp);
00917 
00918         mimFrameTime = getMS(mimFrameTimeRos);
00919 
00920         //mimFrameTime = getMS(img->header.stamp);
00921         mimFrameSEQ = img->header.seq;
00922 
00923         // copy to mimFrame.
00924         // TODO: make this threadsafe (save pointer only and copy in HandleFrame)
00925         if(mimFrameBW.size().x != img->width || mimFrameBW.size().y != img->height)
00926                 mimFrameBW.resize(CVD::ImageRef(img->width, img->height));
00927 
00928         memcpy(mimFrameBW.data(),cv_ptr->image.data,img->width * img->height);
00929         newImageAvailable = true;
00930 
00931         lock.unlock();
00932         new_frame_signal.notify_all();
00933 }
00934 
00935 
00936 
00937 void PTAMWrapper::on_key_down(int key)
00938 {
00939         if(key == 114) // r
00940         {
00941                 node->publishCommand("p reset");
00942         }
00943         if(key == 117) // u
00944         {
00945                 node->publishCommand("p toggleUI");
00946         }
00947         if(key == 32) // Space
00948         {
00949                 node->publishCommand("p space");
00950         }
00951         if(key == 107) // k
00952         {
00953                 node->publishCommand("p keyframe");
00954         }
00955         if(key == 108) // l
00956         {
00957                 node->publishCommand("toggleLog");
00958         }
00959         if(key == 115) // s
00960         {
00961                 pthread_mutex_lock(&logScalePairs_CS);
00962                 if(logfileScalePairs == 0)
00963                 {
00964                         logfileScalePairs = new std::ofstream();
00965                         logfileScalePairs->open ("logScalePairs.txt");
00966                         printf("\nSTART logging scale pairs\n\n");
00967                 }
00968                 else
00969                 {
00970                         logfileScalePairs->flush();
00971                         logfileScalePairs->close();
00972                         delete logfileScalePairs;
00973                         logfileScalePairs = NULL;
00974                         printf("\nEND logging scale pairs\n\n");
00975                 }
00976                 pthread_mutex_unlock(&logScalePairs_CS);
00977         }
00978 
00979         if(key == 109) // m
00980         {
00981                 node->publishCommand("p toggleLockMap");
00982         }
00983 
00984         if(key == 110) // n
00985         {
00986 
00987                 node->publishCommand("p toggleLockSync");
00988         }
00989 
00990         if(key == 116) // t
00991         {
00992 
00993                 flushMapKeypoints = true;
00994         }
00995 
00996 }
00997 
00998 
00999 // reached by typing "df p COMMAND" into console
01000 bool PTAMWrapper::handleCommand(std::string s)
01001 {
01002         if(s.length() == 5 && s.substr(0,5) == "space")
01003         {
01004                 mpTracker->pressSpacebar();
01005         }
01006 
01007         // ptam reset: resets only PTAM, keeps filter state.
01008         if(s.length() == 5 && s.substr(0,5) == "reset")
01009         {
01010                 //filter->clearPTAM();
01011                 Reset();
01012 
01013         }
01014 
01015         if(s.length() == 8 && s.substr(0,8) == "keyframe")
01016         {
01017                 forceKF = true;
01018         }
01019 
01020         if(s.length() == 8 && s.substr(0,8) == "toggleUI")
01021         {
01022                 if(drawUI == UI_NONE) drawUI = UI_DEBUG;
01023                 else if(drawUI == UI_DEBUG) drawUI = UI_PRES;
01024                 else if(drawUI == UI_PRES) drawUI = UI_NONE;
01025                 else drawUI = UI_PRES;
01026         }
01027 
01028         if(s.length() == 11 && s.substr(0,11) == "lockScaleFP")
01029         {
01030                 lockNextFrame = true;
01031         }
01032 
01033         if(s.length() == 13 && s.substr(0,13) == "toggleLockMap")
01034         {
01035                 mapLocked = !mapLocked;
01036 
01037 
01038                 if(mapLocked)
01039                 {
01040                         node->publishCommand("u l PTAM map locked.");
01041                         printf("\n\nMAP LOCKED!\n\n\n");
01042                 }
01043                 else
01044                 {
01045                         printf("\n\nMAP UNLOCKED!\n\n\n");
01046                         node->publishCommand("u l PTAM map UNlocked.");
01047                 }
01048         }
01049 
01050         if(s.length() == 14 && s.substr(0,14) == "toggleLockSync")
01051         {
01052                 filter->allSyncLocked = !filter->allSyncLocked;
01053 
01054 
01055                 if(filter->allSyncLocked)
01056                 {
01057                         printf("\n\nSYNC LOCKED!\n\n\n");
01058                         node->publishCommand("u l PTAM sync locked.");
01059                 }
01060                 else
01061                 {
01062                         printf("\n\nSYNC UNLOCKED!\n\n\n");
01063                         node->publishCommand("u l PTAM sync UNlocked.");
01064                 }
01065         }
01066 
01067         return true;
01068 }
01069 
01070 void PTAMWrapper::on_mouse_down(CVD::ImageRef where, int state, int button)
01071 {
01072         double x = 4*(where.x/(double)this->myGLWindow->size().x - 0.5);
01073         double y = -4*(where.y/(double)this->myGLWindow->size().y - 0.5);
01074         char bf[100];
01075 
01076 
01077         node->publishCommand("c clearCommands");
01078         node->publishCommand("c lockScaleFP");
01079 
01080         if(button == 1)
01081                 snprintf(bf,100,"c moveByRel %.3f %.3f 0 0",x,y);
01082         else
01083                 snprintf(bf,100,"c moveByRel 0 0 %.3f %.3f",y,x*45);
01084 
01085         node->publishCommand(bf);
01086 }


tum_ardrone
Author(s):
autogenerated on Sat Jun 8 2019 20:27:23