stereo_realsense_D435i.cc 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324
  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 <condition_variable>
  27. #include <opencv2/core/core.hpp>
  28. #include <librealsense2/rs.hpp>
  29. #include "librealsense2/rsutil.h"
  30. #include <System.h>
  31. using namespace std;
  32. bool b_continue_session;
  33. void exit_loop_handler(int s){
  34. cout << "Finishing session" << endl;
  35. b_continue_session = false;
  36. }
  37. rs2_vector interpolateMeasure(const double target_time,
  38. const rs2_vector current_data, const double current_time,
  39. const rs2_vector prev_data, const double prev_time);
  40. static rs2_option get_sensor_option(const rs2::sensor& sensor)
  41. {
  42. // Sensors usually have several options to control their properties
  43. // such as Exposure, Brightness etc.
  44. std::cout << "Sensor supports the following options:\n" << std::endl;
  45. // The following loop shows how to iterate over all available options
  46. // Starting from 0 until RS2_OPTION_COUNT (exclusive)
  47. for (int i = 0; i < static_cast<int>(RS2_OPTION_COUNT); i++)
  48. {
  49. rs2_option option_type = static_cast<rs2_option>(i);
  50. //SDK enum types can be streamed to get a string that represents them
  51. std::cout << " " << i << ": " << option_type;
  52. // To control an option, use the following api:
  53. // First, verify that the sensor actually supports this option
  54. if (sensor.supports(option_type))
  55. {
  56. std::cout << std::endl;
  57. // Get a human readable description of the option
  58. const char* description = sensor.get_option_description(option_type);
  59. std::cout << " Description : " << description << std::endl;
  60. // Get the current value of the option
  61. float current_value = sensor.get_option(option_type);
  62. std::cout << " Current Value : " << current_value << std::endl;
  63. //To change the value of an option, please follow the change_sensor_option() function
  64. }
  65. else
  66. {
  67. std::cout << " is not supported" << std::endl;
  68. }
  69. }
  70. uint32_t selected_sensor_option = 0;
  71. return static_cast<rs2_option>(selected_sensor_option);
  72. }
  73. int main(int argc, char **argv) {
  74. if (argc < 3 || argc > 4) {
  75. cerr << endl
  76. << "Usage: ./stereo_realsense_D435i path_to_vocabulary path_to_settings (trajectory_file_name)"
  77. << endl;
  78. return 1;
  79. }
  80. string file_name;
  81. if (argc == 4) {
  82. file_name = string(argv[argc - 1]);
  83. }
  84. struct sigaction sigIntHandler;
  85. sigIntHandler.sa_handler = exit_loop_handler;
  86. sigemptyset(&sigIntHandler.sa_mask);
  87. sigIntHandler.sa_flags = 0;
  88. sigaction(SIGINT, &sigIntHandler, NULL);
  89. b_continue_session = true;
  90. double offset = 0; // ms
  91. rs2::context ctx;
  92. rs2::device_list devices = ctx.query_devices();
  93. rs2::device selected_device;
  94. if (devices.size() == 0)
  95. {
  96. std::cerr << "No device connected, please connect a RealSense device" << std::endl;
  97. return 0;
  98. }
  99. else
  100. selected_device = devices[0];
  101. std::vector<rs2::sensor> sensors = selected_device.query_sensors();
  102. int index = 0;
  103. // We can now iterate the sensors and print their names
  104. for (rs2::sensor sensor : sensors)
  105. if (sensor.supports(RS2_CAMERA_INFO_NAME)) {
  106. ++index;
  107. if (index == 1) {
  108. sensor.set_option(RS2_OPTION_ENABLE_AUTO_EXPOSURE, 1);
  109. sensor.set_option(RS2_OPTION_AUTO_EXPOSURE_LIMIT,5000);
  110. sensor.set_option(RS2_OPTION_EMITTER_ENABLED, 0); // switch off emitter
  111. }
  112. // std::cout << " " << index << " : " << sensor.get_info(RS2_CAMERA_INFO_NAME) << std::endl;
  113. get_sensor_option(sensor);
  114. if (index == 2){
  115. // RGB camera (not used here...)
  116. sensor.set_option(RS2_OPTION_EXPOSURE,100.f);
  117. }
  118. }
  119. // Declare RealSense pipeline, encapsulating the actual device and sensors
  120. rs2::pipeline pipe;
  121. // Create a configuration for configuring the pipeline with a non default profile
  122. rs2::config cfg;
  123. cfg.enable_stream(RS2_STREAM_INFRARED, 1, 640, 480, RS2_FORMAT_Y8, 30);
  124. cfg.enable_stream(RS2_STREAM_INFRARED, 2, 640, 480, RS2_FORMAT_Y8, 30);
  125. // IMU callback
  126. std::mutex imu_mutex;
  127. std::condition_variable cond_image_rec;
  128. cv::Mat imCV, imRightCV;
  129. int width_img, height_img;
  130. double timestamp_image = -1.0;
  131. bool image_ready = false;
  132. int count_im_buffer = 0; // count dropped frames
  133. auto imu_callback = [&](const rs2::frame& frame)
  134. {
  135. std::unique_lock<std::mutex> lock(imu_mutex);
  136. if(rs2::frameset fs = frame.as<rs2::frameset>())
  137. {
  138. count_im_buffer++;
  139. double new_timestamp_image = fs.get_timestamp()*1e-3;
  140. if(abs(timestamp_image-new_timestamp_image)<0.001){
  141. // cout << "Two frames with the same timeStamp!!!\n";
  142. count_im_buffer--;
  143. return;
  144. }
  145. rs2::video_frame ir_frameL = fs.get_infrared_frame(1);
  146. rs2::video_frame ir_frameR = fs.get_infrared_frame(2);
  147. imCV = cv::Mat(cv::Size(width_img, height_img), CV_8U, (void*)(ir_frameL.get_data()), cv::Mat::AUTO_STEP);
  148. imRightCV = cv::Mat(cv::Size(width_img, height_img), CV_8U, (void*)(ir_frameR.get_data()), cv::Mat::AUTO_STEP);
  149. timestamp_image = fs.get_timestamp()*1e-3;
  150. image_ready = true;
  151. lock.unlock();
  152. cond_image_rec.notify_all();
  153. }
  154. };
  155. rs2::pipeline_profile pipe_profile = pipe.start(cfg, imu_callback);
  156. rs2::stream_profile cam_left = pipe_profile.get_stream(RS2_STREAM_INFRARED, 1);
  157. rs2::stream_profile cam_right = pipe_profile.get_stream(RS2_STREAM_INFRARED, 2);
  158. float* Rlr = cam_right.get_extrinsics_to(cam_left).rotation;
  159. float* tlr = cam_right.get_extrinsics_to(cam_left).translation;
  160. std::cout << "Tlr = " << std::endl;
  161. for(int i = 0; i<3; i++){
  162. for(int j = 0; j<3; j++)
  163. std::cout << Rlr[i*3 + j] << ", ";
  164. std::cout << tlr[i] << "\n";
  165. }
  166. rs2_intrinsics intrinsics_left = cam_left.as<rs2::video_stream_profile>().get_intrinsics();
  167. width_img = intrinsics_left.width;
  168. height_img = intrinsics_left.height;
  169. cout << "Left camera: \n";
  170. std::cout << " fx = " << intrinsics_left.fx << std::endl;
  171. std::cout << " fy = " << intrinsics_left.fy << std::endl;
  172. std::cout << " cx = " << intrinsics_left.ppx << std::endl;
  173. std::cout << " cy = " << intrinsics_left.ppy << std::endl;
  174. std::cout << " height = " << intrinsics_left.height << std::endl;
  175. std::cout << " width = " << intrinsics_left.width << std::endl;
  176. std::cout << " Coeff = " << intrinsics_left.coeffs[0] << ", " << intrinsics_left.coeffs[1] << ", " <<
  177. intrinsics_left.coeffs[2] << ", " << intrinsics_left.coeffs[3] << ", " << intrinsics_left.coeffs[4] << ", " << std::endl;
  178. std::cout << " Model = " << intrinsics_left.model << std::endl;
  179. rs2_intrinsics intrinsics_right = cam_right.as<rs2::video_stream_profile>().get_intrinsics();
  180. width_img = intrinsics_right.width;
  181. height_img = intrinsics_right.height;
  182. cout << "Right camera: \n";
  183. std::cout << " fx = " << intrinsics_right.fx << std::endl;
  184. std::cout << " fy = " << intrinsics_right.fy << std::endl;
  185. std::cout << " cx = " << intrinsics_right.ppx << std::endl;
  186. std::cout << " cy = " << intrinsics_right.ppy << std::endl;
  187. std::cout << " height = " << intrinsics_right.height << std::endl;
  188. std::cout << " width = " << intrinsics_right.width << std::endl;
  189. std::cout << " Coeff = " << intrinsics_right.coeffs[0] << ", " << intrinsics_right.coeffs[1] << ", " <<
  190. intrinsics_right.coeffs[2] << ", " << intrinsics_right.coeffs[3] << ", " << intrinsics_right.coeffs[4] << ", " << std::endl;
  191. std::cout << " Model = " << intrinsics_right.model << std::endl;
  192. // Create SLAM system. It initializes all system threads and gets ready to process frames.
  193. ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::STEREO, true, 0, file_name);
  194. float imageScale = SLAM.GetImageScale();
  195. double timestamp;
  196. cv::Mat im, imRight;
  197. double t_resize = 0.f;
  198. double t_track = 0.f;
  199. while (!SLAM.isShutDown())
  200. {
  201. std::vector<rs2_vector> vGyro;
  202. std::vector<double> vGyro_times;
  203. std::vector<rs2_vector> vAccel;
  204. std::vector<double> vAccel_times;
  205. {
  206. std::unique_lock<std::mutex> lk(imu_mutex);
  207. if(!image_ready)
  208. cond_image_rec.wait(lk);
  209. #ifdef COMPILEDWITHC14
  210. std::chrono::steady_clock::time_point time_Start_Process = std::chrono::steady_clock::now();
  211. #else
  212. std::chrono::monotonic_clock::time_point time_Start_Process = std::chrono::monotonic_clock::now();
  213. #endif
  214. if(count_im_buffer>1)
  215. cout << count_im_buffer -1 << " dropped frs\n";
  216. count_im_buffer = 0;
  217. timestamp = timestamp_image;
  218. im = imCV.clone();
  219. imRight = imRightCV.clone();
  220. image_ready = false;
  221. }
  222. if(imageScale != 1.f)
  223. {
  224. #ifdef REGISTER_TIMES
  225. #ifdef COMPILEDWITHC14
  226. std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
  227. #else
  228. std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
  229. #endif
  230. #endif
  231. int width = im.cols * imageScale;
  232. int height = im.rows * imageScale;
  233. cv::resize(im, im, cv::Size(width, height));
  234. cv::resize(imRight, imRight, cv::Size(width, height));
  235. #ifdef REGISTER_TIMES
  236. #ifdef COMPILEDWITHC14
  237. std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
  238. #else
  239. std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
  240. #endif
  241. t_resize = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Resize - t_Start_Resize).count();
  242. SLAM.InsertResizeTime(t_resize);
  243. #endif
  244. }
  245. #ifdef REGISTER_TIMES
  246. #ifdef COMPILEDWITHC14
  247. std::chrono::steady_clock::time_point t_Start_Track = std::chrono::steady_clock::now();
  248. #else
  249. std::chrono::monotonic_clock::time_point t_Start_Track = std::chrono::monotonic_clock::now();
  250. #endif
  251. #endif
  252. // Stereo images are already rectified.
  253. SLAM.TrackStereo(im, imRight, timestamp);
  254. #ifdef REGISTER_TIMES
  255. #ifdef COMPILEDWITHC14
  256. std::chrono::steady_clock::time_point t_End_Track = std::chrono::steady_clock::now();
  257. #else
  258. std::chrono::monotonic_clock::time_point t_End_Track = std::chrono::monotonic_clock::now();
  259. #endif
  260. t_track = t_resize + std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Track - t_Start_Track).count();
  261. SLAM.InsertTrackTime(t_track);
  262. #endif
  263. }
  264. cout << "System shutdown!\n";
  265. }