mono_inertial_realsense_t265.cc 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379
  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: ./mono_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 == 4) {
  51. file_name = string(argv[argc - 1]);
  52. bFileName = true;
  53. }
  54. ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::IMU_MONOCULAR, 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 strams (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, height_img; //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. timestamp_image = new_timestamp_image;
  104. // fs.get_timestamp()*1e-3;
  105. image_ready = true;
  106. while(v_gyro_timestamp.size() > v_accel_timestamp_sync.size()){
  107. int index = v_accel_timestamp_sync.size();
  108. double target_time = v_gyro_timestamp[index];
  109. rs2_vector interp_data = interpolateMeasure(target_time, current_accel_data, current_accel_timestamp, prev_accel_data, prev_accel_timestamp);
  110. v_accel_data_sync.push_back(interp_data);
  111. v_accel_timestamp_sync.push_back(target_time);
  112. }
  113. lock.unlock();
  114. cond_image_rec.notify_all();
  115. }
  116. else if (rs2::motion_frame m_frame = frame.as<rs2::motion_frame>()){
  117. if (m_frame.get_profile().stream_name() == "Gyro"){
  118. // It runs at 200Hz
  119. v_gyro_data.push_back(m_frame.get_motion_data());
  120. v_gyro_timestamp.push_back((m_frame.get_timestamp()+offset)*1e-3);
  121. }
  122. else if (m_frame.get_profile().stream_name() == "Accel"){
  123. // It runs at 60Hz
  124. prev_accel_timestamp = current_accel_timestamp;
  125. prev_accel_data = current_accel_data;
  126. current_accel_data = m_frame.get_motion_data();
  127. current_accel_timestamp = (m_frame.get_timestamp()+offset)*1e-3;
  128. while(v_gyro_timestamp.size() > v_accel_timestamp_sync.size())
  129. {
  130. int index = v_accel_timestamp_sync.size();
  131. double target_time = v_gyro_timestamp[index];
  132. rs2_vector interp_data = interpolateMeasure(target_time, current_accel_data, current_accel_timestamp,
  133. prev_accel_data, prev_accel_timestamp);
  134. v_accel_data_sync.push_back(interp_data);
  135. v_accel_timestamp_sync.push_back(target_time);
  136. }
  137. }
  138. }
  139. };
  140. rs2::pipeline_profile pipe_profile = pipe.start(cfg, imu_callback);
  141. rs2::stream_profile cam_stream = pipe_profile.get_stream(RS2_STREAM_FISHEYE, 1);
  142. rs2::stream_profile imu_stream = pipe_profile.get_stream(RS2_STREAM_GYRO);
  143. float* Rbc = cam_stream.get_extrinsics_to(imu_stream).rotation;
  144. float* tbc = cam_stream.get_extrinsics_to(imu_stream).translation;
  145. std::cout << "Tbc = " << std::endl;
  146. for(int i = 0; i<3; i++){
  147. for(int j = 0; j<3; j++)
  148. std::cout << Rbc[i*3 + j] << ", ";
  149. std::cout << tbc[i] << "\n";
  150. }
  151. rs2_intrinsics intrinsics_cam = cam_stream.as<rs2::video_stream_profile>().get_intrinsics();
  152. width_img = intrinsics_cam.width;
  153. height_img = intrinsics_cam.height;
  154. std::cout << " fx = " << intrinsics_cam.fx << std::endl;
  155. std::cout << " fy = " << intrinsics_cam.fy << std::endl;
  156. std::cout << " cx = " << intrinsics_cam.ppx << std::endl;
  157. std::cout << " cy = " << intrinsics_cam.ppy << std::endl;
  158. std::cout << " height = " << intrinsics_cam.height << std::endl;
  159. std::cout << " width = " << intrinsics_cam.width << std::endl;
  160. std::cout << " Coeff = " << intrinsics_cam.coeffs[0] << ", " << intrinsics_cam.coeffs[1] << ", " <<
  161. intrinsics_cam.coeffs[2] << ", " << intrinsics_cam.coeffs[3] << ", " << intrinsics_cam.coeffs[4] << ", " << std::endl;
  162. std::cout << " Model = " << intrinsics_cam.model << std::endl;
  163. // Create SLAM system. It initializes all system threads and gets ready to process frames.
  164. vector<ORB_SLAM3::IMU::Point> vImuMeas;
  165. double timestamp;
  166. cv::Mat im;
  167. // Clear IMU vectors
  168. v_gyro_data.clear();
  169. v_gyro_timestamp.clear();
  170. v_accel_data_sync.clear();
  171. v_accel_timestamp_sync.clear();
  172. double t_resize = 0.f;
  173. double t_track = 0.f;
  174. std::chrono::steady_clock::time_point time_Start_Process;
  175. while (!SLAM.isShutDown()){
  176. std::vector<rs2_vector> vGyro;
  177. std::vector<double> vGyro_times;
  178. std::vector<rs2_vector> vAccel;
  179. std::vector<double> vAccel_times;
  180. {
  181. std::unique_lock<std::mutex> lk(imu_mutex);
  182. while(!image_ready)
  183. cond_image_rec.wait(lk);
  184. #ifdef COMPILEDWITHC14
  185. std::chrono::steady_clock::time_point time_Start_Process = std::chrono::steady_clock::now();
  186. #else
  187. std::chrono::monotonic_clock::time_point time_Start_Process = std::chrono::monotonic_clock::now();
  188. #endif
  189. if(count_im_buffer>1)
  190. cout << count_im_buffer -1 << " dropped frs\n";
  191. count_im_buffer = 0;
  192. while(v_gyro_timestamp.size() > v_accel_timestamp_sync.size()){
  193. int index = v_accel_timestamp_sync.size();
  194. double target_time = v_gyro_timestamp[index];
  195. rs2_vector interp_data = interpolateMeasure(target_time, current_accel_data, current_accel_timestamp, prev_accel_data, prev_accel_timestamp);
  196. v_accel_data_sync.push_back(interp_data);
  197. v_accel_timestamp_sync.push_back(target_time);
  198. }
  199. if(imageScale == 1.f)
  200. {
  201. im = imCV.clone();
  202. }
  203. else
  204. {
  205. #ifdef REGISTER_TIMES
  206. #ifdef COMPILEDWITHC14
  207. std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
  208. #else
  209. std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
  210. #endif
  211. #endif
  212. int width = imCV.cols * imageScale;
  213. int height = imCV.rows * imageScale;
  214. cv::resize(imCV, im, cv::Size(width, height));
  215. #ifdef REGISTER_TIMES
  216. #ifdef COMPILEDWITHC14
  217. std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
  218. #else
  219. std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
  220. #endif
  221. t_resize = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Resize - t_Start_Resize).count();
  222. SLAM.InsertResizeTime(t_resize);
  223. #endif
  224. }
  225. // Copy the IMU data
  226. vGyro = v_gyro_data;
  227. vGyro_times = v_gyro_timestamp;
  228. vAccel = v_accel_data_sync;
  229. vAccel_times = v_accel_timestamp_sync;
  230. timestamp = timestamp_image;
  231. // Clear IMU vectors
  232. v_gyro_data.clear();
  233. v_gyro_timestamp.clear();
  234. v_accel_data_sync.clear();
  235. v_accel_timestamp_sync.clear();
  236. image_ready = false;
  237. }
  238. for(int i=0; i<vGyro.size(); ++i){
  239. ORB_SLAM3::IMU::Point lastPoint(vAccel[i].x, vAccel[i].y, vAccel[i].z,
  240. vGyro[i].x, vGyro[i].y, vGyro[i].z,
  241. vGyro_times[i]);
  242. vImuMeas.push_back(lastPoint);
  243. if(isnan(vAccel[i].x) || isnan(vAccel[i].y) || isnan(vAccel[i].z) ||
  244. isnan(vGyro[i].x) || isnan(vGyro[i].y) || isnan(vGyro[i].z) ||
  245. isnan(vGyro_times[i])){
  246. //cerr << "NAN AT MAIN" << endl;
  247. exit(-1);
  248. }
  249. }
  250. #ifdef COMPILEDWITHC14
  251. std::chrono::steady_clock::time_point t_Start_Track = std::chrono::steady_clock::now();
  252. #else
  253. std::chrono::monotonic_clock::time_point t_Start_Track = std::chrono::monotonic_clock::now();
  254. #endif
  255. // Pass the image to the SLAM system
  256. SLAM.TrackMonocular(im, timestamp, vImuMeas);
  257. #ifdef COMPILEDWITHC14
  258. std::chrono::steady_clock::time_point t_End_Track = std::chrono::steady_clock::now();
  259. #else
  260. std::chrono::monotonic_clock::time_point t_End_Track = std::chrono::monotonic_clock::now();
  261. #endif
  262. #ifdef REGISTER_TIMES
  263. t_track = t_resize + std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Track - t_Start_Track).count();
  264. SLAM.InsertTrackTime(t_track);
  265. #endif
  266. double timeProcess = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_Start_Track - time_Start_Process).count();
  267. double timeSLAM = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Track - t_Start_Track).count();
  268. // cout << "Time process: " << timeProcess << endl;
  269. // cout << "Time SLAM: " << timeSLAM << endl;
  270. // Clear the previous IMU measurements to load the new ones
  271. vImuMeas.clear();
  272. }
  273. SLAM.Shutdown();
  274. return 0;
  275. }
  276. rs2_vector interpolateMeasure(const double target_time,
  277. const rs2_vector current_data, const double current_time,
  278. const rs2_vector prev_data, const double prev_time){
  279. // If there are not previous information, the current data is propagated
  280. if(prev_time == 0){
  281. return current_data;
  282. }
  283. rs2_vector increment;
  284. rs2_vector value_interp;
  285. if(target_time > current_time) {
  286. value_interp = current_data;
  287. }
  288. else if(target_time > prev_time){
  289. increment.x = current_data.x - prev_data.x;
  290. increment.y = current_data.y - prev_data.y;
  291. increment.z = current_data.z - prev_data.z;
  292. double factor = (target_time - prev_time) / (current_time - prev_time);
  293. value_interp.x = prev_data.x + increment.x * factor;
  294. value_interp.y = prev_data.y + increment.y * factor;
  295. value_interp.z = prev_data.z + increment.z * factor;
  296. // zero interpolation
  297. value_interp = current_data;
  298. }
  299. else {
  300. value_interp = prev_data;
  301. }
  302. return value_interp;
  303. }