mono_inertial_realsense_D435i.cc 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452
  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. void interpolateData(const std::vector<double> &vBase_times,
  38. std::vector<rs2_vector> &vInterp_data, std::vector<double> &vInterp_times,
  39. const rs2_vector &prev_data, const double &prev_time);
  40. rs2_vector interpolateMeasure(const double target_time,
  41. const rs2_vector current_data, const double current_time,
  42. const rs2_vector prev_data, const double prev_time);
  43. static rs2_option get_sensor_option(const rs2::sensor& sensor)
  44. {
  45. // Sensors usually have several options to control their properties
  46. // such as Exposure, Brightness etc.
  47. std::cout << "Sensor supports the following options:\n" << std::endl;
  48. // The following loop shows how to iterate over all available options
  49. // Starting from 0 until RS2_OPTION_COUNT (exclusive)
  50. for (int i = 0; i < static_cast<int>(RS2_OPTION_COUNT); i++)
  51. {
  52. rs2_option option_type = static_cast<rs2_option>(i);
  53. //SDK enum types can be streamed to get a string that represents them
  54. std::cout << " " << i << ": " << option_type;
  55. // To control an option, use the following api:
  56. // First, verify that the sensor actually supports this option
  57. if (sensor.supports(option_type))
  58. {
  59. std::cout << std::endl;
  60. // Get a human readable description of the option
  61. const char* description = sensor.get_option_description(option_type);
  62. std::cout << " Description : " << description << std::endl;
  63. // Get the current value of the option
  64. float current_value = sensor.get_option(option_type);
  65. std::cout << " Current Value : " << current_value << std::endl;
  66. //To change the value of an option, please follow the change_sensor_option() function
  67. }
  68. else
  69. {
  70. std::cout << " is not supported" << std::endl;
  71. }
  72. }
  73. uint32_t selected_sensor_option = 0;
  74. return static_cast<rs2_option>(selected_sensor_option);
  75. }
  76. int main(int argc, char **argv) {
  77. if (argc < 3 || argc > 4) {
  78. cerr << endl
  79. << "Usage: ./mono_inertial_realsense_D435i path_to_vocabulary path_to_settings (trajectory_file_name)"
  80. << endl;
  81. return 1;
  82. }
  83. string file_name;
  84. if (argc == 4) {
  85. file_name = string(argv[argc - 1]);
  86. }
  87. struct sigaction sigIntHandler;
  88. sigIntHandler.sa_handler = exit_loop_handler;
  89. sigemptyset(&sigIntHandler.sa_mask);
  90. sigIntHandler.sa_flags = 0;
  91. sigaction(SIGINT, &sigIntHandler, NULL);
  92. b_continue_session = true;
  93. double offset = 0; // ms
  94. rs2::context ctx;
  95. rs2::device_list devices = ctx.query_devices();
  96. rs2::device selected_device;
  97. if (devices.size() == 0)
  98. {
  99. std::cerr << "No device connected, please connect a RealSense device" << std::endl;
  100. return 0;
  101. }
  102. else
  103. selected_device = devices[0];
  104. std::vector<rs2::sensor> sensors = selected_device.query_sensors();
  105. int index = 0;
  106. // We can now iterate the sensors and print their names
  107. for (rs2::sensor sensor : sensors)
  108. if (sensor.supports(RS2_CAMERA_INFO_NAME)) {
  109. ++index;
  110. if (index == 1) {
  111. sensor.set_option(RS2_OPTION_ENABLE_AUTO_EXPOSURE, 1);
  112. sensor.set_option(RS2_OPTION_AUTO_EXPOSURE_LIMIT,5000);
  113. sensor.set_option(RS2_OPTION_EMITTER_ENABLED, 0); // switch off emitter
  114. }
  115. // std::cout << " " << index << " : " << sensor.get_info(RS2_CAMERA_INFO_NAME) << std::endl;
  116. get_sensor_option(sensor);
  117. if (index == 2){
  118. // RGB camera (not used here...)
  119. sensor.set_option(RS2_OPTION_EXPOSURE,100.f);
  120. }
  121. if (index == 3){
  122. sensor.set_option(RS2_OPTION_ENABLE_MOTION_CORRECTION,0);
  123. }
  124. }
  125. // Declare RealSense pipeline, encapsulating the actual device and sensors
  126. rs2::pipeline pipe;
  127. // Create a configuration for configuring the pipeline with a non default profile
  128. rs2::config cfg;
  129. cfg.enable_stream(RS2_STREAM_INFRARED, 1, 640, 480, RS2_FORMAT_Y8, 30);
  130. cfg.enable_stream(RS2_STREAM_ACCEL, RS2_FORMAT_MOTION_XYZ32F);
  131. cfg.enable_stream(RS2_STREAM_GYRO, RS2_FORMAT_MOTION_XYZ32F);
  132. // IMU callback
  133. std::mutex imu_mutex;
  134. std::condition_variable cond_image_rec;
  135. vector<double> v_accel_timestamp;
  136. vector<rs2_vector> v_accel_data;
  137. vector<double> v_gyro_timestamp;
  138. vector<rs2_vector> v_gyro_data;
  139. double prev_accel_timestamp = 0;
  140. rs2_vector prev_accel_data;
  141. double current_accel_timestamp = 0;
  142. rs2_vector current_accel_data;
  143. vector<double> v_accel_timestamp_sync;
  144. vector<rs2_vector> v_accel_data_sync;
  145. cv::Mat imCV;
  146. int width_img, height_img;
  147. double timestamp_image = -1.0;
  148. bool image_ready = false;
  149. int count_im_buffer = 0; // count dropped frames
  150. auto imu_callback = [&](const rs2::frame& frame)
  151. {
  152. std::unique_lock<std::mutex> lock(imu_mutex);
  153. if(rs2::frameset fs = frame.as<rs2::frameset>())
  154. {
  155. count_im_buffer++;
  156. double new_timestamp_image = fs.get_timestamp()*1e-3;
  157. if(abs(timestamp_image-new_timestamp_image)<0.001){
  158. // cout << "Two frames with the same timeStamp!!!\n";
  159. count_im_buffer--;
  160. return;
  161. }
  162. rs2::video_frame color_frame = fs.get_infrared_frame();
  163. imCV = cv::Mat(cv::Size(width_img, height_img), CV_8U, (void*)(color_frame.get_data()), cv::Mat::AUTO_STEP);
  164. timestamp_image = fs.get_timestamp()*1e-3;
  165. image_ready = true;
  166. while(v_gyro_timestamp.size() > v_accel_timestamp_sync.size())
  167. {
  168. int index = v_accel_timestamp_sync.size();
  169. double target_time = v_gyro_timestamp[index];
  170. v_accel_data_sync.push_back(current_accel_data);
  171. v_accel_timestamp_sync.push_back(target_time);
  172. }
  173. lock.unlock();
  174. cond_image_rec.notify_all();
  175. }
  176. else if (rs2::motion_frame m_frame = frame.as<rs2::motion_frame>())
  177. {
  178. if (m_frame.get_profile().stream_name() == "Gyro")
  179. {
  180. // It runs at 200Hz
  181. v_gyro_data.push_back(m_frame.get_motion_data());
  182. v_gyro_timestamp.push_back((m_frame.get_timestamp()+offset)*1e-3);
  183. //rs2_vector gyro_sample = m_frame.get_motion_data();
  184. //std::cout << "Gyro:" << gyro_sample.x << ", " << gyro_sample.y << ", " << gyro_sample.z << std::endl;
  185. }
  186. else if (m_frame.get_profile().stream_name() == "Accel")
  187. {
  188. // It runs at 60Hz
  189. prev_accel_timestamp = current_accel_timestamp;
  190. prev_accel_data = current_accel_data;
  191. current_accel_data = m_frame.get_motion_data();
  192. current_accel_timestamp = (m_frame.get_timestamp()+offset)*1e-3;
  193. while(v_gyro_timestamp.size() > v_accel_timestamp_sync.size())
  194. {
  195. int index = v_accel_timestamp_sync.size();
  196. double target_time = v_gyro_timestamp[index];
  197. rs2_vector interp_data = interpolateMeasure(target_time, current_accel_data, current_accel_timestamp,
  198. prev_accel_data, prev_accel_timestamp);
  199. v_accel_data_sync.push_back(interp_data);
  200. v_accel_timestamp_sync.push_back(target_time);
  201. }
  202. // std::cout << "Accel:" << current_accel_data.x << ", " << current_accel_data.y << ", " << current_accel_data.z << std::endl;
  203. }
  204. }
  205. };
  206. rs2::pipeline_profile pipe_profile = pipe.start(cfg, imu_callback);
  207. vector<ORB_SLAM3::IMU::Point> vImuMeas;
  208. rs2::stream_profile cam_stream = pipe_profile.get_stream(RS2_STREAM_INFRARED, 1);
  209. rs2::stream_profile imu_stream = pipe_profile.get_stream(RS2_STREAM_GYRO);
  210. float* Rbc = cam_stream.get_extrinsics_to(imu_stream).rotation;
  211. float* tbc = cam_stream.get_extrinsics_to(imu_stream).translation;
  212. std::cout << "Tbc = " << std::endl;
  213. for(int i = 0; i<3; i++){
  214. for(int j = 0; j<3; j++)
  215. std::cout << Rbc[i*3 + j] << ", ";
  216. std::cout << tbc[i] << "\n";
  217. }
  218. rs2_intrinsics intrinsics_cam = cam_stream.as<rs2::video_stream_profile>().get_intrinsics();
  219. width_img = intrinsics_cam.width;
  220. height_img = intrinsics_cam.height;
  221. std::cout << " fx = " << intrinsics_cam.fx << std::endl;
  222. std::cout << " fy = " << intrinsics_cam.fy << std::endl;
  223. std::cout << " cx = " << intrinsics_cam.ppx << std::endl;
  224. std::cout << " cy = " << intrinsics_cam.ppy << std::endl;
  225. std::cout << " height = " << intrinsics_cam.height << std::endl;
  226. std::cout << " width = " << intrinsics_cam.width << std::endl;
  227. std::cout << " Coeff = " << intrinsics_cam.coeffs[0] << ", " << intrinsics_cam.coeffs[1] << ", " <<
  228. intrinsics_cam.coeffs[2] << ", " << intrinsics_cam.coeffs[3] << ", " << intrinsics_cam.coeffs[4] << ", " << std::endl;
  229. std::cout << " Model = " << intrinsics_cam.model << std::endl;
  230. // Create SLAM system. It initializes all system threads and gets ready to process frames.
  231. ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::IMU_MONOCULAR, true, 0, file_name);
  232. float imageScale = SLAM.GetImageScale();
  233. double timestamp;
  234. cv::Mat im;
  235. // Clear IMU vectors
  236. v_gyro_data.clear();
  237. v_gyro_timestamp.clear();
  238. v_accel_data_sync.clear();
  239. v_accel_timestamp_sync.clear();
  240. double t_resize = 0.f;
  241. double t_track = 0.f;
  242. while (!SLAM.isShutDown())
  243. {
  244. std::vector<rs2_vector> vGyro;
  245. std::vector<double> vGyro_times;
  246. std::vector<rs2_vector> vAccel;
  247. std::vector<double> vAccel_times;
  248. {
  249. std::unique_lock<std::mutex> lk(imu_mutex);
  250. if(!image_ready)
  251. cond_image_rec.wait(lk);
  252. #ifdef COMPILEDWITHC14
  253. std::chrono::steady_clock::time_point time_Start_Process = std::chrono::steady_clock::now();
  254. #else
  255. std::chrono::monotonic_clock::time_point time_Start_Process = std::chrono::monotonic_clock::now();
  256. #endif
  257. if(count_im_buffer>1)
  258. cout << count_im_buffer -1 << " dropped frs\n";
  259. count_im_buffer = 0;
  260. while(v_gyro_timestamp.size() > v_accel_timestamp_sync.size())
  261. {
  262. int index = v_accel_timestamp_sync.size();
  263. double target_time = v_gyro_timestamp[index];
  264. rs2_vector interp_data = interpolateMeasure(target_time, current_accel_data, current_accel_timestamp, prev_accel_data, prev_accel_timestamp);
  265. v_accel_data_sync.push_back(interp_data);
  266. // v_accel_data_sync.push_back(current_accel_data); // 0 interpolation
  267. v_accel_timestamp_sync.push_back(target_time);
  268. }
  269. // Copy the IMU data
  270. vGyro = v_gyro_data;
  271. vGyro_times = v_gyro_timestamp;
  272. vAccel = v_accel_data_sync;
  273. vAccel_times = v_accel_timestamp_sync;
  274. timestamp = timestamp_image;
  275. im = imCV.clone();
  276. // Clear IMU vectors
  277. v_gyro_data.clear();
  278. v_gyro_timestamp.clear();
  279. v_accel_data_sync.clear();
  280. v_accel_timestamp_sync.clear();
  281. image_ready = false;
  282. }
  283. for(int i=0; i<vGyro.size(); ++i)
  284. {
  285. ORB_SLAM3::IMU::Point lastPoint(vAccel[i].x, vAccel[i].y, vAccel[i].z,
  286. vGyro[i].x, vGyro[i].y, vGyro[i].z,
  287. vGyro_times[i]);
  288. vImuMeas.push_back(lastPoint);
  289. }
  290. if(imageScale != 1.f)
  291. {
  292. #ifdef REGISTER_TIMES
  293. #ifdef COMPILEDWITHC14
  294. std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
  295. #else
  296. std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
  297. #endif
  298. #endif
  299. int width = im.cols * imageScale;
  300. int height = im.rows * imageScale;
  301. cv::resize(im, im, cv::Size(width, height));
  302. #ifdef REGISTER_TIMES
  303. #ifdef COMPILEDWITHC14
  304. std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
  305. #else
  306. std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
  307. #endif
  308. t_resize = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Resize - t_Start_Resize).count();
  309. SLAM.InsertResizeTime(t_resize);
  310. #endif
  311. }
  312. #ifdef REGISTER_TIMES
  313. #ifdef COMPILEDWITHC14
  314. std::chrono::steady_clock::time_point t_Start_Track = std::chrono::steady_clock::now();
  315. #else
  316. std::chrono::monotonic_clock::time_point t_Start_Track = std::chrono::monotonic_clock::now();
  317. #endif
  318. #endif
  319. // Pass the image to the SLAM system
  320. SLAM.TrackMonocular(im, timestamp, vImuMeas);
  321. #ifdef REGISTER_TIMES
  322. #ifdef COMPILEDWITHC14
  323. std::chrono::steady_clock::time_point t_End_Track = std::chrono::steady_clock::now();
  324. #else
  325. std::chrono::monotonic_clock::time_point t_End_Track = std::chrono::monotonic_clock::now();
  326. #endif
  327. t_track = t_resize + std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Track - t_Start_Track).count();
  328. SLAM.InsertTrackTime(t_track);
  329. #endif
  330. // Clear the previous IMU measurements to load the new ones
  331. vImuMeas.clear();
  332. }
  333. cout << "System shutdown!\n";
  334. }
  335. rs2_vector interpolateMeasure(const double target_time,
  336. const rs2_vector current_data, const double current_time,
  337. const rs2_vector prev_data, const double prev_time)
  338. {
  339. // If there are not previous information, the current data is propagated
  340. if(prev_time == 0)
  341. {
  342. return current_data;
  343. }
  344. rs2_vector increment;
  345. rs2_vector value_interp;
  346. if(target_time > current_time) {
  347. value_interp = current_data;
  348. }
  349. else if(target_time > prev_time)
  350. {
  351. increment.x = current_data.x - prev_data.x;
  352. increment.y = current_data.y - prev_data.y;
  353. increment.z = current_data.z - prev_data.z;
  354. double factor = (target_time - prev_time) / (current_time - prev_time);
  355. value_interp.x = prev_data.x + increment.x * factor;
  356. value_interp.y = prev_data.y + increment.y * factor;
  357. value_interp.z = prev_data.z + increment.z * factor;
  358. // zero interpolation
  359. value_interp = current_data;
  360. }
  361. else {
  362. value_interp = prev_data;
  363. }
  364. return value_interp;
  365. }