mono_realsense_t265.cc 5.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173
  1. /**
  2. * This file is part of ORB-SLAM3
  3. *
  4. * Copyright (C) 2017-2021 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 <signal.h>
  19. #include <stdlib.h>
  20. #include <iostream>
  21. #include <algorithm>
  22. #include <fstream>
  23. #include <chrono>
  24. #include <ctime>
  25. #include <sstream>
  26. #include <opencv2/core/core.hpp>
  27. #include <librealsense2/rs.hpp>
  28. #include <System.h>
  29. using namespace std;
  30. bool b_continue_session;
  31. void exit_loop_handler(int s){
  32. cout << "Finishing session" << endl;
  33. b_continue_session = false;
  34. }
  35. int main(int argc, char **argv)
  36. {
  37. if(argc < 3 || argc > 4)
  38. {
  39. cerr << endl << "Usage: ./mono_realsense_t265 path_to_vocabulary path_to_settings (trajectory_file_name)" << endl;
  40. return 1;
  41. }
  42. string file_name;
  43. bool bFileName = false;
  44. if (argc == 4)
  45. {
  46. file_name = string(argv[argc-1]);
  47. bFileName = true;
  48. }
  49. struct sigaction sigIntHandler;
  50. sigIntHandler.sa_handler = exit_loop_handler;
  51. sigemptyset(&sigIntHandler.sa_mask);
  52. sigIntHandler.sa_flags = 0;
  53. sigaction(SIGINT, &sigIntHandler, NULL);
  54. b_continue_session = true;
  55. // Declare RealSense pipeline, encapsulating the actual device and sensors
  56. rs2::pipeline pipe;
  57. // Create a configuration for configuring the pipeline with a non default profile
  58. rs2::config cfg;
  59. // Enable the left camera
  60. cfg.enable_stream(RS2_STREAM_FISHEYE, 1, RS2_FORMAT_Y8);
  61. cfg.enable_stream(RS2_STREAM_FISHEYE, 2, RS2_FORMAT_Y8);
  62. rs2::pipeline_profile pipe_profile = pipe.start(cfg);
  63. cout.precision(17);
  64. /*cout << "Start processing sequence ..." << endl;
  65. cout << "Images in the sequence: " << nImages << endl;
  66. cout << "IMU data in the sequence: " << nImu << endl << endl;*/
  67. // Create SLAM system. It initializes all system threads and gets ready to process frames.
  68. ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::MONOCULAR, true);
  69. float imageScale = SLAM.GetImageScale();
  70. cv::Mat imCV;
  71. rs2::stream_profile fisheye_stream = pipe_profile.get_stream(RS2_STREAM_FISHEYE, 1);
  72. rs2_intrinsics intrinsics = fisheye_stream.as<rs2::video_stream_profile>().get_intrinsics();
  73. int width_img = intrinsics.width;
  74. int height_img = intrinsics.height;
  75. double t_resize = 0.f;
  76. double t_track = 0.f;
  77. while(b_continue_session)
  78. {
  79. //cv::Ptr<cv::CLAHE> clahe = cv::createCLAHE(3.0, cv::Size(8, 8));
  80. // Get the stream from the device
  81. rs2::frameset frame_set = pipe.wait_for_frames();
  82. double timestamp_ms = frame_set.get_timestamp(); //RS2_FRAME_METADATA_SENSOR_TIMESTAMP
  83. // cout << "timestamp: " << timestamp_ms << endl;
  84. if(rs2::video_frame image_frame = frame_set.first_or_default(RS2_STREAM_FISHEYE))
  85. {
  86. rs2::video_frame frame = frame_set.get_fisheye_frame(1); // Left image
  87. imCV = cv::Mat(cv::Size(width_img, height_img), CV_8UC1, (void*)(frame.get_data()), cv::Mat::AUTO_STEP);
  88. if(imageScale != 1.f)
  89. {
  90. #ifdef REGISTER_TIMES
  91. #ifdef COMPILEDWITHC14
  92. std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
  93. #else
  94. std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
  95. #endif
  96. #endif
  97. int width = imCV.cols * imageScale;
  98. int height = imCV.rows * imageScale;
  99. cv::resize(imCV, imCV, cv::Size(width, height));
  100. #ifdef REGISTER_TIMES
  101. #ifdef COMPILEDWITHC14
  102. std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
  103. #else
  104. std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
  105. #endif
  106. t_resize = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Resize - t_Start_Resize).count();
  107. SLAM.InsertResizeTime(t_resize);
  108. #endif
  109. }
  110. // clahe
  111. //clahe->apply(imLeft,imLeft);
  112. //clahe->apply(imRight,imRight);
  113. #ifdef REGISTER_TIMES
  114. #ifdef COMPILEDWITHC14
  115. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  116. #else
  117. std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
  118. #endif
  119. #endif
  120. // Pass the image to the SLAM system
  121. SLAM.TrackMonocular(imCV, timestamp_ms);
  122. #ifdef REGISTER_TIMES
  123. #ifdef COMPILEDWITHC14
  124. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  125. #else
  126. std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
  127. #endif
  128. t_track = t_resize + std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t2 - t1).count();
  129. SLAM.InsertTrackTime(t_track);
  130. #endif
  131. }
  132. }
  133. pipe.stop();
  134. // Stop all threads
  135. SLAM.Shutdown();
  136. return 0;
  137. }