stereo_inertial_realsense_t265.cc 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358
  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. #include <condition_variable>
  30. #include "ImuTypes.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. int main(int argc, char **argv)
  41. {
  42. if (argc < 3 || argc > 4) {
  43. cerr << endl
  44. << "Usage: ./stereo_inertial_realsense_t265 path_to_vocabulary path_to_settings (trajectory_file_name)"
  45. << endl;
  46. return 1;
  47. }
  48. string file_name;
  49. bool bFileName = false;
  50. if (argc == 5) {
  51. file_name = string(argv[argc - 1]);
  52. bFileName = true;
  53. }
  54. ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::IMU_STEREO, true, 0, file_name);
  55. float imageScale = SLAM.GetImageScale();
  56. struct sigaction sigIntHandler;
  57. sigIntHandler.sa_handler = exit_loop_handler;
  58. sigemptyset(&sigIntHandler.sa_mask);
  59. sigIntHandler.sa_flags = 0;
  60. sigaction(SIGINT, &sigIntHandler, NULL);
  61. b_continue_session = true;
  62. double offset = 0; // ms
  63. // Declare RealSense pipeline, encapsulating the actual device and sensors
  64. rs2::pipeline pipe;
  65. // Create a configuration for configuring the pipeline with a non default profile
  66. rs2::config cfg;
  67. // Enable both image streams (for some reason realsense does not allow to enable just one)
  68. cfg.enable_stream(RS2_STREAM_FISHEYE, 1, RS2_FORMAT_Y8,30);
  69. cfg.enable_stream(RS2_STREAM_FISHEYE, 2, RS2_FORMAT_Y8,30);
  70. // Add streams of gyro and accelerometer to configuration
  71. cfg.enable_stream(RS2_STREAM_ACCEL, RS2_FORMAT_MOTION_XYZ32F);
  72. cfg.enable_stream(RS2_STREAM_GYRO, RS2_FORMAT_MOTION_XYZ32F);
  73. std::mutex imu_mutex;
  74. std::condition_variable cond_image_rec;
  75. vector<double> v_accel_timestamp;
  76. vector<rs2_vector> v_accel_data;
  77. vector<double> v_gyro_timestamp;
  78. vector<rs2_vector> v_gyro_data;
  79. double prev_accel_timestamp = 0;
  80. rs2_vector prev_accel_data;
  81. double current_accel_timestamp = 0;
  82. rs2_vector current_accel_data;
  83. vector<double> v_accel_timestamp_sync;
  84. vector<rs2_vector> v_accel_data_sync;
  85. cv::Mat imCV,imCV_right;
  86. int width_img = 848, height_img = 800;
  87. double timestamp_image = -1.0;
  88. bool image_ready = false;
  89. int count_im_buffer = 0; // count dropped frames
  90. auto imu_callback = [&](const rs2::frame& frame){
  91. std::unique_lock<std::mutex> lock(imu_mutex);
  92. if(rs2::frameset fs = frame.as<rs2::frameset>()){
  93. count_im_buffer++;
  94. double new_timestamp_image = fs.get_timestamp()*1e-3;
  95. if(abs(timestamp_image-new_timestamp_image)<0.001){
  96. // cout << "Two frames with the same timeStamp!!!\n";
  97. count_im_buffer--;
  98. return;
  99. }
  100. rs2::video_frame color_frame = fs.get_fisheye_frame(1);
  101. rs2::video_frame color_frame_right = fs.get_fisheye_frame(2);
  102. imCV = cv::Mat(cv::Size(width_img, height_img), CV_8U, (void*)(color_frame.get_data()), cv::Mat::AUTO_STEP);
  103. imCV_right = cv::Mat(cv::Size(width_img, height_img), CV_8U, (void*)(color_frame_right.get_data()), cv::Mat::AUTO_STEP);
  104. timestamp_image = new_timestamp_image;
  105. double test = fs.get_timestamp()*1e-3;
  106. image_ready = true;
  107. while(v_gyro_timestamp.size() > v_accel_timestamp_sync.size()){
  108. int index = v_accel_timestamp_sync.size();
  109. double target_time = v_gyro_timestamp[index];
  110. rs2_vector interp_data = interpolateMeasure(target_time, current_accel_data, current_accel_timestamp, prev_accel_data, prev_accel_timestamp);
  111. v_accel_data_sync.push_back(interp_data);
  112. v_accel_timestamp_sync.push_back(target_time);
  113. }
  114. lock.unlock();
  115. cond_image_rec.notify_all();
  116. }
  117. else if (rs2::motion_frame m_frame = frame.as<rs2::motion_frame>()){
  118. if (m_frame.get_profile().stream_name() == "Gyro"){
  119. // It runs at 200Hz
  120. v_gyro_data.push_back(m_frame.get_motion_data());
  121. v_gyro_timestamp.push_back((m_frame.get_timestamp()+offset)*1e-3);
  122. }
  123. else if (m_frame.get_profile().stream_name() == "Accel"){
  124. // It runs at 60Hz
  125. prev_accel_timestamp = current_accel_timestamp;
  126. prev_accel_data = current_accel_data;
  127. current_accel_data = m_frame.get_motion_data();
  128. current_accel_timestamp = (m_frame.get_timestamp()+offset)*1e-3;
  129. while(v_gyro_timestamp.size() > v_accel_timestamp_sync.size())
  130. {
  131. int index = v_accel_timestamp_sync.size();
  132. double target_time = v_gyro_timestamp[index];
  133. rs2_vector interp_data = interpolateMeasure(target_time, current_accel_data, current_accel_timestamp,
  134. prev_accel_data, prev_accel_timestamp);
  135. v_accel_data_sync.push_back(interp_data);
  136. v_accel_timestamp_sync.push_back(target_time);
  137. }
  138. }
  139. }
  140. };
  141. rs2::pipeline_profile pipe_profile = pipe.start(cfg, imu_callback);
  142. rs2::stream_profile cam_stream = pipe_profile.get_stream(RS2_STREAM_FISHEYE, 1);
  143. rs2::stream_profile imu_stream = pipe_profile.get_stream(RS2_STREAM_GYRO);
  144. float* Rbc = cam_stream.get_extrinsics_to(imu_stream).rotation;
  145. float* tbc = cam_stream.get_extrinsics_to(imu_stream).translation;
  146. std::cout << "Tbc = " << std::endl;
  147. for(int i = 0; i<3; i++){
  148. for(int j = 0; j<3; j++)
  149. std::cout << Rbc[i*3 + j] << ", ";
  150. std::cout << tbc[i] << "\n";
  151. }
  152. // Create SLAM system. It initializes all system threads and gets ready to process frames.
  153. vector<ORB_SLAM3::IMU::Point> vImuMeas;
  154. double timestamp;
  155. cv::Mat im,imright;
  156. // Clear IMU vectors
  157. v_gyro_data.clear();
  158. v_gyro_timestamp.clear();
  159. v_accel_data_sync.clear();
  160. v_accel_timestamp_sync.clear();
  161. double t_resize = 0.f;
  162. double t_track = 0.f;
  163. cv::Mat im_left, im_right;
  164. while (!SLAM.isShutDown()){
  165. std::vector<rs2_vector> vGyro;
  166. std::vector<double> vGyro_times;
  167. std::vector<rs2_vector> vAccel;
  168. std::vector<double> vAccel_times;
  169. {
  170. std::unique_lock<std::mutex> lk(imu_mutex);
  171. while(!image_ready)
  172. cond_image_rec.wait(lk);
  173. if(count_im_buffer>1)
  174. cout << count_im_buffer -1 << " dropped frames\n";
  175. count_im_buffer = 0;
  176. while(v_gyro_timestamp.size() > v_accel_timestamp_sync.size()){
  177. int index = v_accel_timestamp_sync.size();
  178. double target_time = v_gyro_timestamp[index];
  179. rs2_vector interp_data = interpolateMeasure(target_time, current_accel_data, current_accel_timestamp, prev_accel_data, prev_accel_timestamp);
  180. v_accel_data_sync.push_back(interp_data);
  181. v_accel_timestamp_sync.push_back(target_time);
  182. }
  183. if(imageScale == 1.f)
  184. {
  185. im_left = imCV.clone();
  186. im_right = imCV_right.clone();
  187. }
  188. else
  189. {
  190. #ifdef REGISTER_TIMES
  191. #ifdef COMPILEDWITHC14
  192. std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
  193. #else
  194. std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
  195. #endif
  196. #endif
  197. int width = imCV.cols * imageScale;
  198. int height = imCV.rows * imageScale;
  199. cv::resize(imCV, im_left, cv::Size(width, height));
  200. cv::resize(imCV_right, im_right, cv::Size(width, height));
  201. #ifdef REGISTER_TIMES
  202. #ifdef COMPILEDWITHC14
  203. std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
  204. #else
  205. std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
  206. #endif
  207. t_resize = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Resize - t_Start_Resize).count();
  208. SLAM.InsertResizeTime(t_resize);
  209. #endif
  210. }
  211. // Copy the IMU data
  212. vGyro = v_gyro_data;
  213. vGyro_times = v_gyro_timestamp;
  214. vAccel = v_accel_data_sync;
  215. vAccel_times = v_accel_timestamp_sync;
  216. timestamp = timestamp_image;
  217. // Clear IMU vectors
  218. v_gyro_data.clear();
  219. v_gyro_timestamp.clear();
  220. v_accel_data_sync.clear();
  221. v_accel_timestamp_sync.clear();
  222. image_ready = false;
  223. }
  224. for(int i=0; i<vGyro.size(); ++i){
  225. ORB_SLAM3::IMU::Point lastPoint(vAccel[i].x, vAccel[i].y, vAccel[i].z,
  226. vGyro[i].x, vGyro[i].y, vGyro[i].z,
  227. vGyro_times[i]);
  228. vImuMeas.push_back(lastPoint);
  229. if(isnan(vAccel[i].x) || isnan(vAccel[i].y) || isnan(vAccel[i].z) ||
  230. isnan(vGyro[i].x) || isnan(vGyro[i].y) || isnan(vGyro[i].z) ||
  231. isnan(vGyro_times[i])){
  232. exit(-1);
  233. }
  234. }
  235. #ifdef REGISTER_TIMES
  236. #ifdef COMPILEDWITHC14
  237. std::chrono::steady_clock::time_point t_Start_Track = std::chrono::steady_clock::now();
  238. #else
  239. std::chrono::monotonic_clock::time_point t_Start_Track = std::chrono::monotonic_clock::now();
  240. #endif
  241. #endif
  242. // Pass the image to the SLAM system
  243. SLAM.TrackStereo(im_left, im_right, timestamp, vImuMeas);
  244. #ifdef REGISTER_TIMES
  245. #ifdef COMPILEDWITHC14
  246. std::chrono::steady_clock::time_point t_End_Track = std::chrono::steady_clock::now();
  247. #else
  248. std::chrono::monotonic_clock::time_point t_End_Track = std::chrono::monotonic_clock::now();
  249. #endif
  250. t_track = t_resize + std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Track - t_Start_Track).count();
  251. SLAM.InsertTrackTime(t_track);
  252. #endif
  253. // Clear the previous IMU measurements to load the new ones
  254. vImuMeas.clear();
  255. }
  256. SLAM.Shutdown();
  257. return 0;
  258. }
  259. rs2_vector interpolateMeasure(const double target_time,
  260. const rs2_vector current_data, const double current_time,
  261. const rs2_vector prev_data, const double prev_time){
  262. // If there are not previous information, the current data is propagated
  263. if(prev_time == 0){
  264. return current_data;
  265. }
  266. rs2_vector increment;
  267. rs2_vector value_interp;
  268. if(target_time > current_time) {
  269. value_interp = current_data;
  270. }
  271. else if(target_time > prev_time){
  272. increment.x = current_data.x - prev_data.x;
  273. increment.y = current_data.y - prev_data.y;
  274. increment.z = current_data.z - prev_data.z;
  275. double factor = (target_time - prev_time) / (current_time - prev_time);
  276. value_interp.x = prev_data.x + increment.x * factor;
  277. value_interp.y = prev_data.y + increment.y * factor;
  278. value_interp.z = prev_data.z + increment.z * factor;
  279. // zero interpolation
  280. value_interp = current_data;
  281. }
  282. else {
  283. value_interp = prev_data;
  284. }
  285. return value_interp;
  286. }