System.cc 34 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069
  1. /**
  2. * This file is part of ORB-SLAM3
  3. *
  4. * Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  5. * Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  6. *
  7. * ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public
  8. * License as published by the Free Software Foundation, either version 3 of the License, or
  9. * (at your option) any later version.
  10. *
  11. * ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even
  12. * the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  13. * GNU General Public License for more details.
  14. *
  15. * You should have received a copy of the GNU General Public License along with ORB-SLAM3.
  16. * If not, see <http://www.gnu.org/licenses/>.
  17. */
  18. #include "System.h"
  19. #include "Converter.h"
  20. #include <thread>
  21. #include <pangolin/pangolin.h>
  22. #include <iomanip>
  23. #include <openssl/md5.h>
  24. #include <boost/serialization/base_object.hpp>
  25. #include <boost/serialization/string.hpp>
  26. #include <boost/archive/text_iarchive.hpp>
  27. #include <boost/archive/text_oarchive.hpp>
  28. #include <boost/archive/binary_iarchive.hpp>
  29. #include <boost/archive/binary_oarchive.hpp>
  30. #include <boost/archive/xml_iarchive.hpp>
  31. #include <boost/archive/xml_oarchive.hpp>
  32. namespace ORB_SLAM3
  33. {
  34. Verbose::eLevel Verbose::th = Verbose::VERBOSITY_NORMAL;
  35. System::System(const string &strVocFile, const string &strSettingsFile, const eSensor sensor,
  36. const bool bUseViewer, const int initFr, const string &strSequence, const string &strLoadingFile):
  37. mSensor(sensor), mpViewer(static_cast<Viewer*>(NULL)), mbReset(false), mbResetActiveMap(false),
  38. mbActivateLocalizationMode(false), mbDeactivateLocalizationMode(false)
  39. {
  40. // Output welcome message
  41. cout << endl <<
  42. "ORB-SLAM3 Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza." << endl <<
  43. "ORB-SLAM2 Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza." << endl <<
  44. "This program comes with ABSOLUTELY NO WARRANTY;" << endl <<
  45. "This is free software, and you are welcome to redistribute it" << endl <<
  46. "under certain conditions. See LICENSE.txt." << endl << endl;
  47. cout << "Input sensor was set to: ";
  48. if(mSensor==MONOCULAR)
  49. cout << "Monocular" << endl;
  50. else if(mSensor==STEREO)
  51. cout << "Stereo" << endl;
  52. else if(mSensor==RGBD)
  53. cout << "RGB-D" << endl;
  54. else if(mSensor==IMU_MONOCULAR)
  55. cout << "Monocular-Inertial" << endl;
  56. else if(mSensor==IMU_STEREO)
  57. cout << "Stereo-Inertial" << endl;
  58. //Check settings file
  59. cv::FileStorage fsSettings(strSettingsFile.c_str(), cv::FileStorage::READ);
  60. if(!fsSettings.isOpened())
  61. {
  62. cerr << "Failed to open settings file at: " << strSettingsFile << endl;
  63. exit(-1);
  64. }
  65. bool loadedAtlas = false;
  66. //----
  67. //Load ORB Vocabulary
  68. cout << endl << "Loading ORB Vocabulary. This could take a while..." << endl;
  69. mpVocabulary = new ORBVocabulary();
  70. bool bVocLoad = mpVocabulary->loadFromTextFile(strVocFile);
  71. if(!bVocLoad)
  72. {
  73. cerr << "Wrong path to vocabulary. " << endl;
  74. cerr << "Falied to open at: " << strVocFile << endl;
  75. exit(-1);
  76. }
  77. cout << "Vocabulary loaded!" << endl << endl;
  78. //Create KeyFrame Database
  79. mpKeyFrameDatabase = new KeyFrameDatabase(*mpVocabulary);
  80. //Create the Atlas
  81. //mpMap = new Map();
  82. mpAtlas = new Atlas(0);
  83. //----
  84. /*if(strLoadingFile.empty())
  85. {
  86. //Load ORB Vocabulary
  87. cout << endl << "Loading ORB Vocabulary. This could take a while..." << endl;
  88. mpVocabulary = new ORBVocabulary();
  89. bool bVocLoad = mpVocabulary->loadFromTextFile(strVocFile);
  90. if(!bVocLoad)
  91. {
  92. cerr << "Wrong path to vocabulary. " << endl;
  93. cerr << "Falied to open at: " << strVocFile << endl;
  94. exit(-1);
  95. }
  96. cout << "Vocabulary loaded!" << endl << endl;
  97. //Create KeyFrame Database
  98. mpKeyFrameDatabase = new KeyFrameDatabase(*mpVocabulary);
  99. //Create the Atlas
  100. //mpMap = new Map();
  101. mpAtlas = new Atlas(0);
  102. }
  103. else
  104. {
  105. //Load ORB Vocabulary
  106. cout << endl << "Loading ORB Vocabulary. This could take a while..." << endl;
  107. mpVocabulary = new ORBVocabulary();
  108. bool bVocLoad = mpVocabulary->loadFromTextFile(strVocFile);
  109. if(!bVocLoad)
  110. {
  111. cerr << "Wrong path to vocabulary. " << endl;
  112. cerr << "Falied to open at: " << strVocFile << endl;
  113. exit(-1);
  114. }
  115. cout << "Vocabulary loaded!" << endl << endl;
  116. cout << "Load File" << endl;
  117. // Load the file with an earlier session
  118. //clock_t start = clock();
  119. bool isRead = LoadAtlas(strLoadingFile,BINARY_FILE);
  120. if(!isRead)
  121. {
  122. cout << "Error to load the file, please try with other session file or vocabulary file" << endl;
  123. exit(-1);
  124. }
  125. mpKeyFrameDatabase = new KeyFrameDatabase(*mpVocabulary);
  126. mpAtlas->SetKeyFrameDababase(mpKeyFrameDatabase);
  127. mpAtlas->SetORBVocabulary(mpVocabulary);
  128. mpAtlas->PostLoad();
  129. //cout << "KF in DB: " << mpKeyFrameDatabase->mnNumKFs << "; words: " << mpKeyFrameDatabase->mnNumWords << endl;
  130. loadedAtlas = true;
  131. mpAtlas->CreateNewMap();
  132. //clock_t timeElapsed = clock() - start;
  133. //unsigned msElapsed = timeElapsed / (CLOCKS_PER_SEC / 1000);
  134. //cout << "Binary file read in " << msElapsed << " ms" << endl;
  135. //usleep(10*1000*1000);
  136. }*/
  137. if (mSensor==IMU_STEREO || mSensor==IMU_MONOCULAR)
  138. mpAtlas->SetInertialSensor();
  139. //Create Drawers. These are used by the Viewer
  140. mpFrameDrawer = new FrameDrawer(mpAtlas);
  141. mpMapDrawer = new MapDrawer(mpAtlas, strSettingsFile);
  142. //Initialize the Tracking thread
  143. //(it will live in the main thread of execution, the one that called this constructor)
  144. cout << "Seq. Name: " << strSequence << endl;
  145. mpTracker = new Tracking(this, mpVocabulary, mpFrameDrawer, mpMapDrawer,
  146. mpAtlas, mpKeyFrameDatabase, strSettingsFile, mSensor, strSequence);
  147. //Initialize the Local Mapping thread and launch
  148. mpLocalMapper = new LocalMapping(this, mpAtlas, mSensor==MONOCULAR || mSensor==IMU_MONOCULAR, mSensor==IMU_MONOCULAR || mSensor==IMU_STEREO, strSequence);
  149. mptLocalMapping = new thread(&ORB_SLAM3::LocalMapping::Run,mpLocalMapper);
  150. mpLocalMapper->mInitFr = initFr;
  151. mpLocalMapper->mThFarPoints = fsSettings["thFarPoints"];
  152. if(mpLocalMapper->mThFarPoints!=0)
  153. {
  154. cout << "Discard points further than " << mpLocalMapper->mThFarPoints << " m from current camera" << endl;
  155. mpLocalMapper->mbFarPoints = true;
  156. }
  157. else
  158. mpLocalMapper->mbFarPoints = false;
  159. //Initialize the Loop Closing thread and launch
  160. // mSensor!=MONOCULAR && mSensor!=IMU_MONOCULAR
  161. mpLoopCloser = new LoopClosing(mpAtlas, mpKeyFrameDatabase, mpVocabulary, mSensor!=MONOCULAR); // mSensor!=MONOCULAR);
  162. mptLoopClosing = new thread(&ORB_SLAM3::LoopClosing::Run, mpLoopCloser);
  163. //Initialize the Viewer thread and launch
  164. if(bUseViewer)
  165. {
  166. mpViewer = new Viewer(this, mpFrameDrawer,mpMapDrawer,mpTracker,strSettingsFile);
  167. mptViewer = new thread(&Viewer::Run, mpViewer);
  168. mpTracker->SetViewer(mpViewer);
  169. mpLoopCloser->mpViewer = mpViewer;
  170. mpViewer->both = mpFrameDrawer->both;
  171. }
  172. //Set pointers between threads
  173. mpTracker->SetLocalMapper(mpLocalMapper);
  174. mpTracker->SetLoopClosing(mpLoopCloser);
  175. mpLocalMapper->SetTracker(mpTracker);
  176. mpLocalMapper->SetLoopCloser(mpLoopCloser);
  177. mpLoopCloser->SetTracker(mpTracker);
  178. mpLoopCloser->SetLocalMapper(mpLocalMapper);
  179. // Fix verbosity
  180. Verbose::SetTh(Verbose::VERBOSITY_QUIET);
  181. }
  182. cv::Mat System::TrackStereo(const cv::Mat &imLeft, const cv::Mat &imRight, const double &timestamp, const vector<IMU::Point>& vImuMeas, string filename)
  183. {
  184. if(mSensor!=STEREO && mSensor!=IMU_STEREO)
  185. {
  186. cerr << "ERROR: you called TrackStereo but input sensor was not set to Stereo nor Stereo-Inertial." << endl;
  187. exit(-1);
  188. }
  189. // Check mode change
  190. {
  191. unique_lock<mutex> lock(mMutexMode);
  192. if(mbActivateLocalizationMode)
  193. {
  194. mpLocalMapper->RequestStop();
  195. // Wait until Local Mapping has effectively stopped
  196. while(!mpLocalMapper->isStopped())
  197. {
  198. usleep(1000);
  199. }
  200. mpTracker->InformOnlyTracking(true);
  201. mbActivateLocalizationMode = false;
  202. }
  203. if(mbDeactivateLocalizationMode)
  204. {
  205. mpTracker->InformOnlyTracking(false);
  206. mpLocalMapper->Release();
  207. mbDeactivateLocalizationMode = false;
  208. }
  209. }
  210. // Check reset
  211. {
  212. unique_lock<mutex> lock(mMutexReset);
  213. if(mbReset)
  214. {
  215. mpTracker->Reset();
  216. cout << "Reset stereo..." << endl;
  217. mbReset = false;
  218. mbResetActiveMap = false;
  219. }
  220. else if(mbResetActiveMap)
  221. {
  222. mpTracker->ResetActiveMap();
  223. mbResetActiveMap = false;
  224. }
  225. }
  226. if (mSensor == System::IMU_STEREO)
  227. for(size_t i_imu = 0; i_imu < vImuMeas.size(); i_imu++)
  228. mpTracker->GrabImuData(vImuMeas[i_imu]);
  229. // std::cout << "start GrabImageStereo" << std::endl;
  230. cv::Mat Tcw = mpTracker->GrabImageStereo(imLeft,imRight,timestamp,filename);
  231. // std::cout << "out grabber" << std::endl;
  232. unique_lock<mutex> lock2(mMutexState);
  233. mTrackingState = mpTracker->mState;
  234. mTrackedMapPoints = mpTracker->mCurrentFrame.mvpMapPoints;
  235. mTrackedKeyPointsUn = mpTracker->mCurrentFrame.mvKeysUn;
  236. return Tcw;
  237. }
  238. cv::Mat System::TrackRGBD(const cv::Mat &im, const cv::Mat &depthmap, const double &timestamp, string filename)
  239. {
  240. if(mSensor!=RGBD)
  241. {
  242. cerr << "ERROR: you called TrackRGBD but input sensor was not set to RGBD." << endl;
  243. exit(-1);
  244. }
  245. // Check mode change
  246. {
  247. unique_lock<mutex> lock(mMutexMode);
  248. if(mbActivateLocalizationMode)
  249. {
  250. mpLocalMapper->RequestStop();
  251. // Wait until Local Mapping has effectively stopped
  252. while(!mpLocalMapper->isStopped())
  253. {
  254. usleep(1000);
  255. }
  256. mpTracker->InformOnlyTracking(true);
  257. mbActivateLocalizationMode = false;
  258. }
  259. if(mbDeactivateLocalizationMode)
  260. {
  261. mpTracker->InformOnlyTracking(false);
  262. mpLocalMapper->Release();
  263. mbDeactivateLocalizationMode = false;
  264. }
  265. }
  266. // Check reset
  267. {
  268. unique_lock<mutex> lock(mMutexReset);
  269. if(mbReset)
  270. {
  271. mpTracker->Reset();
  272. mbReset = false;
  273. mbResetActiveMap = false;
  274. }
  275. else if(mbResetActiveMap)
  276. {
  277. mpTracker->ResetActiveMap();
  278. mbResetActiveMap = false;
  279. }
  280. }
  281. cv::Mat Tcw = mpTracker->GrabImageRGBD(im,depthmap,timestamp,filename);
  282. unique_lock<mutex> lock2(mMutexState);
  283. mTrackingState = mpTracker->mState;
  284. mTrackedMapPoints = mpTracker->mCurrentFrame.mvpMapPoints;
  285. mTrackedKeyPointsUn = mpTracker->mCurrentFrame.mvKeysUn;
  286. return Tcw;
  287. }
  288. cv::Mat System::TrackMonocular(const cv::Mat &im, const double &timestamp, const vector<IMU::Point>& vImuMeas, string filename)
  289. {
  290. if(mSensor!=MONOCULAR && mSensor!=IMU_MONOCULAR)
  291. {
  292. cerr << "ERROR: you called TrackMonocular but input sensor was not set to Monocular nor Monocular-Inertial." << endl;
  293. exit(-1);
  294. }
  295. // Check mode change
  296. {
  297. unique_lock<mutex> lock(mMutexMode);
  298. if(mbActivateLocalizationMode)
  299. {
  300. mpLocalMapper->RequestStop();
  301. // Wait until Local Mapping has effectively stopped
  302. while(!mpLocalMapper->isStopped())
  303. {
  304. usleep(1000);
  305. }
  306. mpTracker->InformOnlyTracking(true);
  307. mbActivateLocalizationMode = false;
  308. }
  309. if(mbDeactivateLocalizationMode)
  310. {
  311. mpTracker->InformOnlyTracking(false);
  312. mpLocalMapper->Release();
  313. mbDeactivateLocalizationMode = false;
  314. }
  315. }
  316. // Check reset
  317. {
  318. unique_lock<mutex> lock(mMutexReset);
  319. if(mbReset)
  320. {
  321. mpTracker->Reset();
  322. mbReset = false;
  323. mbResetActiveMap = false;
  324. }
  325. else if(mbResetActiveMap)
  326. {
  327. cout << "SYSTEM-> Reseting active map in monocular case" << endl;
  328. mpTracker->ResetActiveMap();
  329. mbResetActiveMap = false;
  330. }
  331. }
  332. if (mSensor == System::IMU_MONOCULAR)
  333. for(size_t i_imu = 0; i_imu < vImuMeas.size(); i_imu++)
  334. mpTracker->GrabImuData(vImuMeas[i_imu]);
  335. cv::Mat Tcw = mpTracker->GrabImageMonocular(im,timestamp,filename);
  336. unique_lock<mutex> lock2(mMutexState);
  337. mTrackingState = mpTracker->mState;
  338. mTrackedMapPoints = mpTracker->mCurrentFrame.mvpMapPoints;
  339. mTrackedKeyPointsUn = mpTracker->mCurrentFrame.mvKeysUn;
  340. return Tcw;
  341. }
  342. void System::ActivateLocalizationMode()
  343. {
  344. unique_lock<mutex> lock(mMutexMode);
  345. mbActivateLocalizationMode = true;
  346. }
  347. void System::DeactivateLocalizationMode()
  348. {
  349. unique_lock<mutex> lock(mMutexMode);
  350. mbDeactivateLocalizationMode = true;
  351. }
  352. bool System::MapChanged()
  353. {
  354. static int n=0;
  355. int curn = mpAtlas->GetLastBigChangeIdx();
  356. if(n<curn)
  357. {
  358. n=curn;
  359. return true;
  360. }
  361. else
  362. return false;
  363. }
  364. void System::Reset()
  365. {
  366. unique_lock<mutex> lock(mMutexReset);
  367. mbReset = true;
  368. }
  369. void System::ResetActiveMap()
  370. {
  371. unique_lock<mutex> lock(mMutexReset);
  372. mbResetActiveMap = true;
  373. }
  374. void System::Shutdown()
  375. {
  376. mpLocalMapper->RequestFinish();
  377. mpLoopCloser->RequestFinish();
  378. if(mpViewer)
  379. {
  380. mpViewer->RequestFinish();
  381. while(!mpViewer->isFinished())
  382. usleep(5000);
  383. }
  384. // Wait until all thread have effectively stopped
  385. while(!mpLocalMapper->isFinished() || !mpLoopCloser->isFinished() || mpLoopCloser->isRunningGBA())
  386. {
  387. if(!mpLocalMapper->isFinished())
  388. cout << "mpLocalMapper is not finished" << endl;
  389. if(!mpLoopCloser->isFinished())
  390. cout << "mpLoopCloser is not finished" << endl;
  391. if(mpLoopCloser->isRunningGBA()){
  392. cout << "mpLoopCloser is running GBA" << endl;
  393. cout << "break anyway..." << endl;
  394. break;
  395. }
  396. usleep(5000);
  397. }
  398. if(mpViewer)
  399. pangolin::BindToContext("ORB-SLAM2: Map Viewer");
  400. }
  401. void System::SaveTrajectoryTUM(const string &filename)
  402. {
  403. cout << endl << "Saving camera trajectory to " << filename << " ..." << endl;
  404. if(mSensor==MONOCULAR)
  405. {
  406. cerr << "ERROR: SaveTrajectoryTUM cannot be used for monocular." << endl;
  407. return;
  408. }
  409. vector<KeyFrame*> vpKFs = mpAtlas->GetAllKeyFrames();
  410. sort(vpKFs.begin(),vpKFs.end(),KeyFrame::lId);
  411. // Transform all keyframes so that the first keyframe is at the origin.
  412. // After a loop closure the first keyframe might not be at the origin.
  413. cv::Mat Two = vpKFs[0]->GetPoseInverse();
  414. ofstream f;
  415. f.open(filename.c_str());
  416. f << fixed;
  417. // Frame pose is stored relative to its reference keyframe (which is optimized by BA and pose graph).
  418. // We need to get first the keyframe pose and then concatenate the relative transformation.
  419. // Frames not localized (tracking failure) are not saved.
  420. // For each frame we have a reference keyframe (lRit), the timestamp (lT) and a flag
  421. // which is true when tracking failed (lbL).
  422. list<ORB_SLAM3::KeyFrame*>::iterator lRit = mpTracker->mlpReferences.begin();
  423. list<double>::iterator lT = mpTracker->mlFrameTimes.begin();
  424. list<bool>::iterator lbL = mpTracker->mlbLost.begin();
  425. for(list<cv::Mat>::iterator lit=mpTracker->mlRelativeFramePoses.begin(),
  426. lend=mpTracker->mlRelativeFramePoses.end();lit!=lend;lit++, lRit++, lT++, lbL++)
  427. {
  428. if(*lbL)
  429. continue;
  430. KeyFrame* pKF = *lRit;
  431. cv::Mat Trw = cv::Mat::eye(4,4,CV_32F);
  432. // If the reference keyframe was culled, traverse the spanning tree to get a suitable keyframe.
  433. while(pKF->isBad())
  434. {
  435. Trw = Trw*pKF->mTcp;
  436. pKF = pKF->GetParent();
  437. }
  438. Trw = Trw*pKF->GetPose()*Two;
  439. cv::Mat Tcw = (*lit)*Trw;
  440. cv::Mat Rwc = Tcw.rowRange(0,3).colRange(0,3).t();
  441. cv::Mat twc = -Rwc*Tcw.rowRange(0,3).col(3);
  442. vector<float> q = Converter::toQuaternion(Rwc);
  443. f << setprecision(6) << *lT << " " << setprecision(9) << twc.at<float>(0) << " " << twc.at<float>(1) << " " << twc.at<float>(2) << " " << q[0] << " " << q[1] << " " << q[2] << " " << q[3] << endl;
  444. }
  445. f.close();
  446. // cout << endl << "trajectory saved!" << endl;
  447. }
  448. void System::SaveKeyFrameTrajectoryTUM(const string &filename)
  449. {
  450. cout << endl << "Saving keyframe trajectory to " << filename << " ..." << endl;
  451. vector<KeyFrame*> vpKFs = mpAtlas->GetAllKeyFrames();
  452. sort(vpKFs.begin(),vpKFs.end(),KeyFrame::lId);
  453. // Transform all keyframes so that the first keyframe is at the origin.
  454. // After a loop closure the first keyframe might not be at the origin.
  455. ofstream f;
  456. f.open(filename.c_str());
  457. f << fixed;
  458. for(size_t i=0; i<vpKFs.size(); i++)
  459. {
  460. KeyFrame* pKF = vpKFs[i];
  461. // pKF->SetPose(pKF->GetPose()*Two);
  462. if(pKF->isBad())
  463. continue;
  464. cv::Mat R = pKF->GetRotation().t();
  465. vector<float> q = Converter::toQuaternion(R);
  466. cv::Mat t = pKF->GetCameraCenter();
  467. f << setprecision(6) << pKF->mTimeStamp << setprecision(7) << " " << t.at<float>(0) << " " << t.at<float>(1) << " " << t.at<float>(2)
  468. << " " << q[0] << " " << q[1] << " " << q[2] << " " << q[3] << endl;
  469. }
  470. f.close();
  471. }
  472. void System::SaveTrajectoryEuRoC(const string &filename)
  473. {
  474. cout << endl << "Saving trajectory to " << filename << " ..." << endl;
  475. /*if(mSensor==MONOCULAR)
  476. {
  477. cerr << "ERROR: SaveTrajectoryEuRoC cannot be used for monocular." << endl;
  478. return;
  479. }*/
  480. vector<Map*> vpMaps = mpAtlas->GetAllMaps();
  481. Map* pBiggerMap;
  482. int numMaxKFs = 0;
  483. for(Map* pMap :vpMaps)
  484. {
  485. if(pMap->GetAllKeyFrames().size() > numMaxKFs)
  486. {
  487. numMaxKFs = pMap->GetAllKeyFrames().size();
  488. pBiggerMap = pMap;
  489. }
  490. }
  491. vector<KeyFrame*> vpKFs = pBiggerMap->GetAllKeyFrames();
  492. sort(vpKFs.begin(),vpKFs.end(),KeyFrame::lId);
  493. // Transform all keyframes so that the first keyframe is at the origin.
  494. // After a loop closure the first keyframe might not be at the origin.
  495. cv::Mat Twb; // Can be word to cam0 or world to b dependingo on IMU or not.
  496. if (mSensor==IMU_MONOCULAR || mSensor==IMU_STEREO)
  497. Twb = vpKFs[0]->GetImuPose();
  498. else
  499. Twb = vpKFs[0]->GetPoseInverse();
  500. ofstream f;
  501. f.open(filename.c_str());
  502. // cout << "file open" << endl;
  503. f << fixed;
  504. // Frame pose is stored relative to its reference keyframe (which is optimized by BA and pose graph).
  505. // We need to get first the keyframe pose and then concatenate the relative transformation.
  506. // Frames not localized (tracking failure) are not saved.
  507. // For each frame we have a reference keyframe (lRit), the timestamp (lT) and a flag
  508. // which is true when tracking failed (lbL).
  509. list<ORB_SLAM3::KeyFrame*>::iterator lRit = mpTracker->mlpReferences.begin();
  510. list<double>::iterator lT = mpTracker->mlFrameTimes.begin();
  511. list<bool>::iterator lbL = mpTracker->mlbLost.begin();
  512. //cout << "size mlpReferences: " << mpTracker->mlpReferences.size() << endl;
  513. //cout << "size mlRelativeFramePoses: " << mpTracker->mlRelativeFramePoses.size() << endl;
  514. //cout << "size mpTracker->mlFrameTimes: " << mpTracker->mlFrameTimes.size() << endl;
  515. //cout << "size mpTracker->mlbLost: " << mpTracker->mlbLost.size() << endl;
  516. for(list<cv::Mat>::iterator lit=mpTracker->mlRelativeFramePoses.begin(),
  517. lend=mpTracker->mlRelativeFramePoses.end();lit!=lend;lit++, lRit++, lT++, lbL++)
  518. {
  519. //cout << "1" << endl;
  520. if(*lbL)
  521. continue;
  522. KeyFrame* pKF = *lRit;
  523. //cout << "KF: " << pKF->mnId << endl;
  524. cv::Mat Trw = cv::Mat::eye(4,4,CV_32F);
  525. /*cout << "2" << endl;
  526. cout << "KF id: " << pKF->mnId << endl;*/
  527. // If the reference keyframe was culled, traverse the spanning tree to get a suitable keyframe.
  528. if (!pKF)
  529. continue;
  530. //cout << "2.5" << endl;
  531. while(pKF->isBad())
  532. {
  533. //cout << " 2.bad" << endl;
  534. Trw = Trw*pKF->mTcp;
  535. pKF = pKF->GetParent();
  536. //cout << "--Parent KF: " << pKF->mnId << endl;
  537. }
  538. if(!pKF || pKF->GetMap() != pBiggerMap)
  539. {
  540. //cout << "--Parent KF is from another map" << endl;
  541. /*if(pKF)
  542. cout << "--Parent KF " << pKF->mnId << " is from another map " << pKF->GetMap()->GetId() << endl;*/
  543. continue;
  544. }
  545. //cout << "3" << endl;
  546. Trw = Trw*pKF->GetPose()*Twb; // Tcp*Tpw*Twb0=Tcb0 where b0 is the new world reference
  547. // cout << "4" << endl;
  548. if (mSensor == IMU_MONOCULAR || mSensor == IMU_STEREO)
  549. {
  550. cv::Mat Tbw = pKF->mImuCalib.Tbc*(*lit)*Trw;
  551. cv::Mat Rwb = Tbw.rowRange(0,3).colRange(0,3).t();
  552. cv::Mat twb = -Rwb*Tbw.rowRange(0,3).col(3);
  553. vector<float> q = Converter::toQuaternion(Rwb);
  554. f << setprecision(6) << 1e9*(*lT) << " " << setprecision(9) << twb.at<float>(0) << " " << twb.at<float>(1) << " " << twb.at<float>(2) << " " << q[0] << " " << q[1] << " " << q[2] << " " << q[3] << endl;
  555. }
  556. else
  557. {
  558. cv::Mat Tcw = (*lit)*Trw;
  559. cv::Mat Rwc = Tcw.rowRange(0,3).colRange(0,3).t();
  560. cv::Mat twc = -Rwc*Tcw.rowRange(0,3).col(3);
  561. vector<float> q = Converter::toQuaternion(Rwc);
  562. f << setprecision(6) << 1e9*(*lT) << " " << setprecision(9) << twc.at<float>(0) << " " << twc.at<float>(1) << " " << twc.at<float>(2) << " " << q[0] << " " << q[1] << " " << q[2] << " " << q[3] << endl;
  563. }
  564. // cout << "5" << endl;
  565. }
  566. //cout << "end saving trajectory" << endl;
  567. f.close();
  568. cout << endl << "End of saving trajectory to " << filename << " ..." << endl;
  569. }
  570. void System::SaveKeyFrameTrajectoryEuRoC(const string &filename)
  571. {
  572. cout << endl << "Saving keyframe trajectory to " << filename << " ..." << endl;
  573. vector<Map*> vpMaps = mpAtlas->GetAllMaps();
  574. Map* pBiggerMap;
  575. int numMaxKFs = 0;
  576. for(Map* pMap :vpMaps)
  577. {
  578. if(pMap->GetAllKeyFrames().size() > numMaxKFs)
  579. {
  580. numMaxKFs = pMap->GetAllKeyFrames().size();
  581. pBiggerMap = pMap;
  582. }
  583. }
  584. vector<KeyFrame*> vpKFs = pBiggerMap->GetAllKeyFrames();
  585. sort(vpKFs.begin(),vpKFs.end(),KeyFrame::lId);
  586. // Transform all keyframes so that the first keyframe is at the origin.
  587. // After a loop closure the first keyframe might not be at the origin.
  588. ofstream f;
  589. f.open(filename.c_str());
  590. f << fixed;
  591. for(size_t i=0; i<vpKFs.size(); i++)
  592. {
  593. KeyFrame* pKF = vpKFs[i];
  594. // pKF->SetPose(pKF->GetPose()*Two);
  595. if(pKF->isBad())
  596. continue;
  597. if (mSensor == IMU_MONOCULAR || mSensor == IMU_STEREO)
  598. {
  599. cv::Mat R = pKF->GetImuRotation().t();
  600. vector<float> q = Converter::toQuaternion(R);
  601. cv::Mat twb = pKF->GetImuPosition();
  602. f << setprecision(6) << 1e9*pKF->mTimeStamp << " " << setprecision(9) << twb.at<float>(0) << " " << twb.at<float>(1) << " " << twb.at<float>(2) << " " << q[0] << " " << q[1] << " " << q[2] << " " << q[3] << endl;
  603. }
  604. else
  605. {
  606. cv::Mat R = pKF->GetRotation();
  607. vector<float> q = Converter::toQuaternion(R);
  608. cv::Mat t = pKF->GetCameraCenter();
  609. f << setprecision(6) << 1e9*pKF->mTimeStamp << " " << setprecision(9) << t.at<float>(0) << " " << t.at<float>(1) << " " << t.at<float>(2) << " " << q[0] << " " << q[1] << " " << q[2] << " " << q[3] << endl;
  610. }
  611. }
  612. f.close();
  613. }
  614. void System::SaveTrajectoryKITTI(const string &filename)
  615. {
  616. cout << endl << "Saving camera trajectory to " << filename << " ..." << endl;
  617. if(mSensor==MONOCULAR)
  618. {
  619. cerr << "ERROR: SaveTrajectoryKITTI cannot be used for monocular." << endl;
  620. return;
  621. }
  622. vector<KeyFrame*> vpKFs = mpAtlas->GetAllKeyFrames();
  623. sort(vpKFs.begin(),vpKFs.end(),KeyFrame::lId);
  624. // Transform all keyframes so that the first keyframe is at the origin.
  625. // After a loop closure the first keyframe might not be at the origin.
  626. cv::Mat Two = vpKFs[0]->GetPoseInverse();
  627. ofstream f;
  628. f.open(filename.c_str());
  629. f << fixed;
  630. // Frame pose is stored relative to its reference keyframe (which is optimized by BA and pose graph).
  631. // We need to get first the keyframe pose and then concatenate the relative transformation.
  632. // Frames not localized (tracking failure) are not saved.
  633. // For each frame we have a reference keyframe (lRit), the timestamp (lT) and a flag
  634. // which is true when tracking failed (lbL).
  635. list<ORB_SLAM3::KeyFrame*>::iterator lRit = mpTracker->mlpReferences.begin();
  636. list<double>::iterator lT = mpTracker->mlFrameTimes.begin();
  637. for(list<cv::Mat>::iterator lit=mpTracker->mlRelativeFramePoses.begin(), lend=mpTracker->mlRelativeFramePoses.end();lit!=lend;lit++, lRit++, lT++)
  638. {
  639. ORB_SLAM3::KeyFrame* pKF = *lRit;
  640. cv::Mat Trw = cv::Mat::eye(4,4,CV_32F);
  641. while(pKF->isBad())
  642. {
  643. Trw = Trw*pKF->mTcp;
  644. pKF = pKF->GetParent();
  645. }
  646. Trw = Trw*pKF->GetPose()*Two;
  647. cv::Mat Tcw = (*lit)*Trw;
  648. cv::Mat Rwc = Tcw.rowRange(0,3).colRange(0,3).t();
  649. cv::Mat twc = -Rwc*Tcw.rowRange(0,3).col(3);
  650. f << setprecision(9) << Rwc.at<float>(0,0) << " " << Rwc.at<float>(0,1) << " " << Rwc.at<float>(0,2) << " " << twc.at<float>(0) << " " <<
  651. Rwc.at<float>(1,0) << " " << Rwc.at<float>(1,1) << " " << Rwc.at<float>(1,2) << " " << twc.at<float>(1) << " " <<
  652. Rwc.at<float>(2,0) << " " << Rwc.at<float>(2,1) << " " << Rwc.at<float>(2,2) << " " << twc.at<float>(2) << endl;
  653. }
  654. f.close();
  655. }
  656. void System::SaveDebugData(const int &initIdx)
  657. {
  658. // 0. Save initialization trajectory
  659. SaveTrajectoryEuRoC("init_FrameTrajectoy_" +to_string(mpLocalMapper->mInitSect)+ "_" + to_string(initIdx)+".txt");
  660. // 1. Save scale
  661. ofstream f;
  662. f.open("init_Scale_" + to_string(mpLocalMapper->mInitSect) + ".txt", ios_base::app);
  663. f << fixed;
  664. f << mpLocalMapper->mScale << endl;
  665. f.close();
  666. // 2. Save gravity direction
  667. f.open("init_GDir_" +to_string(mpLocalMapper->mInitSect)+ ".txt", ios_base::app);
  668. f << fixed;
  669. f << mpLocalMapper->mRwg(0,0) << "," << mpLocalMapper->mRwg(0,1) << "," << mpLocalMapper->mRwg(0,2) << endl;
  670. f << mpLocalMapper->mRwg(1,0) << "," << mpLocalMapper->mRwg(1,1) << "," << mpLocalMapper->mRwg(1,2) << endl;
  671. f << mpLocalMapper->mRwg(2,0) << "," << mpLocalMapper->mRwg(2,1) << "," << mpLocalMapper->mRwg(2,2) << endl;
  672. f.close();
  673. // 3. Save computational cost
  674. f.open("init_CompCost_" +to_string(mpLocalMapper->mInitSect)+ ".txt", ios_base::app);
  675. f << fixed;
  676. f << mpLocalMapper->mCostTime << endl;
  677. f.close();
  678. // 4. Save biases
  679. f.open("init_Biases_" +to_string(mpLocalMapper->mInitSect)+ ".txt", ios_base::app);
  680. f << fixed;
  681. f << mpLocalMapper->mbg(0) << "," << mpLocalMapper->mbg(1) << "," << mpLocalMapper->mbg(2) << endl;
  682. f << mpLocalMapper->mba(0) << "," << mpLocalMapper->mba(1) << "," << mpLocalMapper->mba(2) << endl;
  683. f.close();
  684. // 5. Save covariance matrix
  685. f.open("init_CovMatrix_" +to_string(mpLocalMapper->mInitSect)+ "_" +to_string(initIdx)+".txt", ios_base::app);
  686. f << fixed;
  687. for(int i=0; i<mpLocalMapper->mcovInertial.rows(); i++)
  688. {
  689. for(int j=0; j<mpLocalMapper->mcovInertial.cols(); j++)
  690. {
  691. if(j!=0)
  692. f << ",";
  693. f << setprecision(15) << mpLocalMapper->mcovInertial(i,j);
  694. }
  695. f << endl;
  696. }
  697. f.close();
  698. // 6. Save initialization time
  699. f.open("init_Time_" +to_string(mpLocalMapper->mInitSect)+ ".txt", ios_base::app);
  700. f << fixed;
  701. f << mpLocalMapper->mInitTime << endl;
  702. f.close();
  703. }
  704. int System::GetTrackingState()
  705. {
  706. unique_lock<mutex> lock(mMutexState);
  707. return mTrackingState;
  708. }
  709. vector<MapPoint*> System::GetTrackedMapPoints()
  710. {
  711. unique_lock<mutex> lock(mMutexState);
  712. return mTrackedMapPoints;
  713. }
  714. vector<cv::KeyPoint> System::GetTrackedKeyPointsUn()
  715. {
  716. unique_lock<mutex> lock(mMutexState);
  717. return mTrackedKeyPointsUn;
  718. }
  719. double System::GetTimeFromIMUInit()
  720. {
  721. double aux = mpLocalMapper->GetCurrKFTime()-mpLocalMapper->mFirstTs;
  722. if ((aux>0.) && mpAtlas->isImuInitialized())
  723. return mpLocalMapper->GetCurrKFTime()-mpLocalMapper->mFirstTs;
  724. else
  725. return 0.f;
  726. }
  727. bool System::isLost()
  728. {
  729. if (!mpAtlas->isImuInitialized())
  730. return false;
  731. else
  732. {
  733. if ((mpTracker->mState==Tracking::LOST)) //||(mpTracker->mState==Tracking::RECENTLY_LOST))
  734. return true;
  735. else
  736. return false;
  737. }
  738. }
  739. bool System::isFinished()
  740. {
  741. return (GetTimeFromIMUInit()>0.1);
  742. }
  743. void System::ChangeDataset()
  744. {
  745. if(mpAtlas->GetCurrentMap()->KeyFramesInMap() < 12)
  746. {
  747. mpTracker->ResetActiveMap();
  748. }
  749. else
  750. {
  751. mpTracker->CreateMapInAtlas();
  752. }
  753. mpTracker->NewDataset();
  754. }
  755. /*void System::SaveAtlas(int type){
  756. cout << endl << "Enter the name of the file if you want to save the current Atlas session. To exit press ENTER: ";
  757. string saveFileName;
  758. getline(cin,saveFileName);
  759. if(!saveFileName.empty())
  760. {
  761. //clock_t start = clock();
  762. // Save the current session
  763. mpAtlas->PreSave();
  764. mpKeyFrameDatabase->PreSave();
  765. string pathSaveFileName = "./";
  766. pathSaveFileName = pathSaveFileName.append(saveFileName);
  767. pathSaveFileName = pathSaveFileName.append(".osa");
  768. string strVocabularyChecksum = CalculateCheckSum(mStrVocabularyFilePath,TEXT_FILE);
  769. std::size_t found = mStrVocabularyFilePath.find_last_of("/\\");
  770. string strVocabularyName = mStrVocabularyFilePath.substr(found+1);
  771. if(type == TEXT_FILE) // File text
  772. {
  773. cout << "Starting to write the save text file " << endl;
  774. std::remove(pathSaveFileName.c_str());
  775. std::ofstream ofs(pathSaveFileName, std::ios::binary);
  776. boost::archive::text_oarchive oa(ofs);
  777. oa << strVocabularyName;
  778. oa << strVocabularyChecksum;
  779. oa << mpAtlas;
  780. oa << mpKeyFrameDatabase;
  781. cout << "End to write the save text file" << endl;
  782. }
  783. else if(type == BINARY_FILE) // File binary
  784. {
  785. cout << "Starting to write the save binary file" << endl;
  786. std::remove(pathSaveFileName.c_str());
  787. std::ofstream ofs(pathSaveFileName, std::ios::binary);
  788. boost::archive::binary_oarchive oa(ofs);
  789. oa << strVocabularyName;
  790. oa << strVocabularyChecksum;
  791. oa << mpAtlas;
  792. oa << mpKeyFrameDatabase;
  793. cout << "End to write save binary file" << endl;
  794. }
  795. //clock_t timeElapsed = clock() - start;
  796. //unsigned msElapsed = timeElapsed / (CLOCKS_PER_SEC / 1000);
  797. //cout << "Binary file saved in " << msElapsed << " ms" << endl;
  798. }
  799. }
  800. bool System::LoadAtlas(string filename, int type)
  801. {
  802. string strFileVoc, strVocChecksum;
  803. bool isRead = false;
  804. if(type == TEXT_FILE) // File text
  805. {
  806. cout << "Starting to read the save text file " << endl;
  807. std::ifstream ifs(filename, std::ios::binary);
  808. if(!ifs.good())
  809. {
  810. cout << "Load file not found" << endl;
  811. return false;
  812. }
  813. boost::archive::text_iarchive ia(ifs);
  814. ia >> strFileVoc;
  815. ia >> strVocChecksum;
  816. ia >> mpAtlas;
  817. //ia >> mpKeyFrameDatabase;
  818. cout << "End to load the save text file " << endl;
  819. isRead = true;
  820. }
  821. else if(type == BINARY_FILE) // File binary
  822. {
  823. cout << "Starting to read the save binary file" << endl;
  824. std::ifstream ifs(filename, std::ios::binary);
  825. if(!ifs.good())
  826. {
  827. cout << "Load file not found" << endl;
  828. return false;
  829. }
  830. boost::archive::binary_iarchive ia(ifs);
  831. ia >> strFileVoc;
  832. ia >> strVocChecksum;
  833. ia >> mpAtlas;
  834. //ia >> mpKeyFrameDatabase;
  835. cout << "End to load the save binary file" << endl;
  836. isRead = true;
  837. }
  838. if(isRead)
  839. {
  840. //Check if the vocabulary is the same
  841. string strInputVocabularyChecksum = CalculateCheckSum(mStrVocabularyFilePath,TEXT_FILE);
  842. if(strInputVocabularyChecksum.compare(strVocChecksum) != 0)
  843. {
  844. cout << "The vocabulary load isn't the same which the load session was created " << endl;
  845. cout << "-Vocabulary name: " << strFileVoc << endl;
  846. return false; // Both are differents
  847. }
  848. return true;
  849. }
  850. return false;
  851. }
  852. string System::CalculateCheckSum(string filename, int type)
  853. {
  854. string checksum = "";
  855. unsigned char c[MD5_DIGEST_LENGTH];
  856. std::ios_base::openmode flags = std::ios::in;
  857. if(type == BINARY_FILE) // Binary file
  858. flags = std::ios::in | std::ios::binary;
  859. ifstream f(filename.c_str(), flags);
  860. if ( !f.is_open() )
  861. {
  862. cout << "[E] Unable to open the in file " << filename << " for Md5 hash." << endl;
  863. return checksum;
  864. }
  865. MD5_CTX md5Context;
  866. char buffer[1024];
  867. MD5_Init (&md5Context);
  868. while ( int count = f.readsome(buffer, sizeof(buffer)))
  869. {
  870. MD5_Update(&md5Context, buffer, count);
  871. }
  872. f.close();
  873. MD5_Final(c, &md5Context );
  874. for(int i = 0; i < MD5_DIGEST_LENGTH; i++)
  875. {
  876. char aux[10];
  877. sprintf(aux,"%02x", c[i]);
  878. checksum = checksum + aux;
  879. }
  880. return checksum;
  881. }*/
  882. } //namespace ORB_SLAM