rgbd_realsense_D435i.cc 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456
  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_stream find_stream_to_align(const std::vector<rs2::stream_profile>& streams);
  38. bool profile_changed(const std::vector<rs2::stream_profile>& current, const std::vector<rs2::stream_profile>& prev);
  39. void interpolateData(const std::vector<double> &vBase_times,
  40. std::vector<rs2_vector> &vInterp_data, std::vector<double> &vInterp_times,
  41. const rs2_vector &prev_data, const double &prev_time);
  42. rs2_vector interpolateMeasure(const double target_time,
  43. const rs2_vector current_data, const double current_time,
  44. const rs2_vector prev_data, const double prev_time);
  45. static rs2_option get_sensor_option(const rs2::sensor& sensor)
  46. {
  47. // Sensors usually have several options to control their properties
  48. // such as Exposure, Brightness etc.
  49. std::cout << "Sensor supports the following options:\n" << std::endl;
  50. // The following loop shows how to iterate over all available options
  51. // Starting from 0 until RS2_OPTION_COUNT (exclusive)
  52. for (int i = 0; i < static_cast<int>(RS2_OPTION_COUNT); i++)
  53. {
  54. rs2_option option_type = static_cast<rs2_option>(i);
  55. //SDK enum types can be streamed to get a string that represents them
  56. std::cout << " " << i << ": " << option_type;
  57. // To control an option, use the following api:
  58. // First, verify that the sensor actually supports this option
  59. if (sensor.supports(option_type))
  60. {
  61. std::cout << std::endl;
  62. // Get a human readable description of the option
  63. const char* description = sensor.get_option_description(option_type);
  64. std::cout << " Description : " << description << std::endl;
  65. // Get the current value of the option
  66. float current_value = sensor.get_option(option_type);
  67. std::cout << " Current Value : " << current_value << std::endl;
  68. //To change the value of an option, please follow the change_sensor_option() function
  69. }
  70. else
  71. {
  72. std::cout << " is not supported" << std::endl;
  73. }
  74. }
  75. uint32_t selected_sensor_option = 0;
  76. return static_cast<rs2_option>(selected_sensor_option);
  77. }
  78. int main(int argc, char **argv) {
  79. if (argc < 3 || argc > 4) {
  80. cerr << endl
  81. << "Usage: ./mono_inertial_realsense_D435i path_to_vocabulary path_to_settings (trajectory_file_name)"
  82. << endl;
  83. return 1;
  84. }
  85. string file_name;
  86. bool bFileName = false;
  87. if (argc == 4) {
  88. file_name = string(argv[argc - 1]);
  89. bFileName = true;
  90. }
  91. struct sigaction sigIntHandler;
  92. sigIntHandler.sa_handler = exit_loop_handler;
  93. sigemptyset(&sigIntHandler.sa_mask);
  94. sigIntHandler.sa_flags = 0;
  95. sigaction(SIGINT, &sigIntHandler, NULL);
  96. b_continue_session = true;
  97. double offset = 0; // ms
  98. rs2::context ctx;
  99. rs2::device_list devices = ctx.query_devices();
  100. rs2::device selected_device;
  101. if (devices.size() == 0)
  102. {
  103. std::cerr << "No device connected, please connect a RealSense device" << std::endl;
  104. return 0;
  105. }
  106. else
  107. selected_device = devices[0];
  108. std::vector<rs2::sensor> sensors = selected_device.query_sensors();
  109. int index = 0;
  110. // We can now iterate the sensors and print their names
  111. for (rs2::sensor sensor : sensors)
  112. if (sensor.supports(RS2_CAMERA_INFO_NAME)) {
  113. ++index;
  114. if (index == 1) {
  115. sensor.set_option(RS2_OPTION_ENABLE_AUTO_EXPOSURE, 1);
  116. sensor.set_option(RS2_OPTION_AUTO_EXPOSURE_LIMIT,50000);
  117. sensor.set_option(RS2_OPTION_EMITTER_ENABLED, 1); // emitter on for depth information
  118. }
  119. // std::cout << " " << index << " : " << sensor.get_info(RS2_CAMERA_INFO_NAME) << std::endl;
  120. get_sensor_option(sensor);
  121. if (index == 2){
  122. // RGB camera
  123. sensor.set_option(RS2_OPTION_EXPOSURE,80.f);
  124. }
  125. if (index == 3){
  126. sensor.set_option(RS2_OPTION_ENABLE_MOTION_CORRECTION,0);
  127. }
  128. }
  129. // Declare RealSense pipeline, encapsulating the actual device and sensors
  130. rs2::pipeline pipe;
  131. // Create a configuration for configuring the pipeline with a non default profile
  132. rs2::config cfg;
  133. // RGB stream
  134. cfg.enable_stream(RS2_STREAM_COLOR,640, 480, RS2_FORMAT_RGB8, 30);
  135. // Depth stream
  136. // cfg.enable_stream(RS2_STREAM_INFRARED, 1, 640, 480, RS2_FORMAT_Y8, 30);
  137. cfg.enable_stream(RS2_STREAM_DEPTH,640, 480, RS2_FORMAT_Z16, 30);
  138. // IMU stream
  139. cfg.enable_stream(RS2_STREAM_ACCEL, RS2_FORMAT_MOTION_XYZ32F); //, 250); // 63
  140. cfg.enable_stream(RS2_STREAM_GYRO, RS2_FORMAT_MOTION_XYZ32F); //, 400);
  141. // IMU callback
  142. std::mutex imu_mutex;
  143. std::condition_variable cond_image_rec;
  144. vector<double> v_accel_timestamp;
  145. vector<rs2_vector> v_accel_data;
  146. vector<double> v_gyro_timestamp;
  147. vector<rs2_vector> v_gyro_data;
  148. double prev_accel_timestamp = 0;
  149. rs2_vector prev_accel_data;
  150. double current_accel_timestamp = 0;
  151. rs2_vector current_accel_data;
  152. vector<double> v_accel_timestamp_sync;
  153. vector<rs2_vector> v_accel_data_sync;
  154. cv::Mat imCV, depthCV;
  155. int width_img, height_img;
  156. double timestamp_image = -1.0;
  157. bool image_ready = false;
  158. int count_im_buffer = 0; // count dropped frames
  159. // start and stop just to get necessary profile
  160. rs2::pipeline_profile pipe_profile = pipe.start(cfg);
  161. pipe.stop();
  162. // Align depth and RGB frames
  163. //Pipeline could choose a device that does not have a color stream
  164. //If there is no color stream, choose to align depth to another stream
  165. rs2_stream align_to = find_stream_to_align(pipe_profile.get_streams());
  166. // Create a rs2::align object.
  167. // rs2::align allows us to perform alignment of depth frames to others frames
  168. //The "align_to" is the stream type to which we plan to align depth frames.
  169. rs2::align align(align_to);
  170. rs2::frameset fsSLAM;
  171. auto imu_callback = [&](const rs2::frame& frame)
  172. {
  173. std::unique_lock<std::mutex> lock(imu_mutex);
  174. if(rs2::frameset fs = frame.as<rs2::frameset>())
  175. {
  176. count_im_buffer++;
  177. double new_timestamp_image = fs.get_timestamp()*1e-3;
  178. if(abs(timestamp_image-new_timestamp_image)<0.001){
  179. count_im_buffer--;
  180. return;
  181. }
  182. if (profile_changed(pipe.get_active_profile().get_streams(), pipe_profile.get_streams()))
  183. {
  184. //If the profile was changed, update the align object, and also get the new device's depth scale
  185. pipe_profile = pipe.get_active_profile();
  186. align_to = find_stream_to_align(pipe_profile.get_streams());
  187. align = rs2::align(align_to);
  188. }
  189. //Align depth and rgb takes long time, move it out of the interruption to avoid losing IMU measurements
  190. fsSLAM = fs;
  191. /*
  192. //Get processed aligned frame
  193. auto processed = align.process(fs);
  194. // Trying to get both other and aligned depth frames
  195. rs2::video_frame color_frame = processed.first(align_to);
  196. rs2::depth_frame depth_frame = processed.get_depth_frame();
  197. //If one of them is unavailable, continue iteration
  198. if (!depth_frame || !color_frame) {
  199. cout << "Not synchronized depth and image\n";
  200. return;
  201. }
  202. imCV = cv::Mat(cv::Size(width_img, height_img), CV_8UC3, (void*)(color_frame.get_data()), cv::Mat::AUTO_STEP);
  203. depthCV = cv::Mat(cv::Size(width_img, height_img), CV_16U, (void*)(depth_frame.get_data()), cv::Mat::AUTO_STEP);
  204. cv::Mat depthCV_8U;
  205. depthCV.convertTo(depthCV_8U,CV_8U,0.01);
  206. cv::imshow("depth image", depthCV_8U);*/
  207. timestamp_image = fs.get_timestamp()*1e-3;
  208. image_ready = true;
  209. while(v_gyro_timestamp.size() > v_accel_timestamp_sync.size())
  210. {
  211. int index = v_accel_timestamp_sync.size();
  212. double target_time = v_gyro_timestamp[index];
  213. v_accel_data_sync.push_back(current_accel_data);
  214. v_accel_timestamp_sync.push_back(target_time);
  215. }
  216. lock.unlock();
  217. cond_image_rec.notify_all();
  218. }
  219. };
  220. pipe_profile = pipe.start(cfg, imu_callback);
  221. rs2::stream_profile cam_stream = pipe_profile.get_stream(RS2_STREAM_COLOR);
  222. rs2_intrinsics intrinsics_cam = cam_stream.as<rs2::video_stream_profile>().get_intrinsics();
  223. width_img = intrinsics_cam.width;
  224. height_img = intrinsics_cam.height;
  225. std::cout << " fx = " << intrinsics_cam.fx << std::endl;
  226. std::cout << " fy = " << intrinsics_cam.fy << std::endl;
  227. std::cout << " cx = " << intrinsics_cam.ppx << std::endl;
  228. std::cout << " cy = " << intrinsics_cam.ppy << std::endl;
  229. std::cout << " height = " << intrinsics_cam.height << std::endl;
  230. std::cout << " width = " << intrinsics_cam.width << std::endl;
  231. std::cout << " Coeff = " << intrinsics_cam.coeffs[0] << ", " << intrinsics_cam.coeffs[1] << ", " <<
  232. intrinsics_cam.coeffs[2] << ", " << intrinsics_cam.coeffs[3] << ", " << intrinsics_cam.coeffs[4] << ", " << std::endl;
  233. std::cout << " Model = " << intrinsics_cam.model << std::endl;
  234. // Create SLAM system. It initializes all system threads and gets ready to process frames.
  235. ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::RGBD, true, 0, file_name);
  236. float imageScale = SLAM.GetImageScale();
  237. double timestamp;
  238. cv::Mat im, depth;
  239. double t_resize = 0.f;
  240. double t_track = 0.f;
  241. rs2::frameset fs;
  242. while (!SLAM.isShutDown())
  243. {
  244. {
  245. std::unique_lock<std::mutex> lk(imu_mutex);
  246. if(!image_ready)
  247. cond_image_rec.wait(lk);
  248. #ifdef COMPILEDWITHC14
  249. std::chrono::steady_clock::time_point time_Start_Process = std::chrono::steady_clock::now();
  250. #else
  251. std::chrono::monotonic_clock::time_point time_Start_Process = std::chrono::monotonic_clock::now();
  252. #endif
  253. fs = fsSLAM;
  254. if(count_im_buffer>1)
  255. cout << count_im_buffer -1 << " dropped frs\n";
  256. count_im_buffer = 0;
  257. timestamp = timestamp_image;
  258. im = imCV.clone();
  259. depth = depthCV.clone();
  260. image_ready = false;
  261. }
  262. // Perform alignment here
  263. auto processed = align.process(fs);
  264. // Trying to get both other and aligned depth frames
  265. rs2::video_frame color_frame = processed.first(align_to);
  266. rs2::depth_frame depth_frame = processed.get_depth_frame();
  267. im = cv::Mat(cv::Size(width_img, height_img), CV_8UC3, (void*)(color_frame.get_data()), cv::Mat::AUTO_STEP);
  268. depth = cv::Mat(cv::Size(width_img, height_img), CV_16U, (void*)(depth_frame.get_data()), cv::Mat::AUTO_STEP);
  269. /*cv::Mat depthCV_8U;
  270. depthCV.convertTo(depthCV_8U,CV_8U,0.01);
  271. cv::imshow("depth image", depthCV_8U);*/
  272. if(imageScale != 1.f)
  273. {
  274. #ifdef REGISTER_TIMES
  275. #ifdef COMPILEDWITHC14
  276. std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
  277. #else
  278. std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
  279. #endif
  280. #endif
  281. int width = im.cols * imageScale;
  282. int height = im.rows * imageScale;
  283. cv::resize(im, im, cv::Size(width, height));
  284. cv::resize(depth, depth, cv::Size(width, height));
  285. #ifdef REGISTER_TIMES
  286. #ifdef COMPILEDWITHC14
  287. std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
  288. #else
  289. std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
  290. #endif
  291. t_resize = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Resize - t_Start_Resize).count();
  292. SLAM.InsertResizeTime(t_resize);
  293. #endif
  294. }
  295. #ifdef REGISTER_TIMES
  296. #ifdef COMPILEDWITHC14
  297. std::chrono::steady_clock::time_point t_Start_Track = std::chrono::steady_clock::now();
  298. #else
  299. std::chrono::monotonic_clock::time_point t_Start_Track = std::chrono::monotonic_clock::now();
  300. #endif
  301. #endif
  302. // Pass the image to the SLAM system
  303. SLAM.TrackRGBD(im, depth, timestamp); //, vImuMeas); depthCV
  304. #ifdef REGISTER_TIMES
  305. #ifdef COMPILEDWITHC14
  306. std::chrono::steady_clock::time_point t_End_Track = std::chrono::steady_clock::now();
  307. #else
  308. std::chrono::monotonic_clock::time_point t_End_Track = std::chrono::monotonic_clock::now();
  309. #endif
  310. t_track = t_resize + std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Track - t_Start_Track).count();
  311. SLAM.InsertTrackTime(t_track);
  312. #endif
  313. }
  314. cout << "System shutdown!\n";
  315. }
  316. rs2_stream find_stream_to_align(const std::vector<rs2::stream_profile>& streams)
  317. {
  318. //Given a vector of streams, we try to find a depth stream and another stream to align depth with.
  319. //We prioritize color streams to make the view look better.
  320. //If color is not available, we take another stream that (other than depth)
  321. rs2_stream align_to = RS2_STREAM_ANY;
  322. bool depth_stream_found = false;
  323. bool color_stream_found = false;
  324. for (rs2::stream_profile sp : streams)
  325. {
  326. rs2_stream profile_stream = sp.stream_type();
  327. if (profile_stream != RS2_STREAM_DEPTH)
  328. {
  329. if (!color_stream_found) //Prefer color
  330. align_to = profile_stream;
  331. if (profile_stream == RS2_STREAM_COLOR)
  332. {
  333. color_stream_found = true;
  334. }
  335. }
  336. else
  337. {
  338. depth_stream_found = true;
  339. }
  340. }
  341. if(!depth_stream_found)
  342. throw std::runtime_error("No Depth stream available");
  343. if (align_to == RS2_STREAM_ANY)
  344. throw std::runtime_error("No stream found to align with Depth");
  345. return align_to;
  346. }
  347. bool profile_changed(const std::vector<rs2::stream_profile>& current, const std::vector<rs2::stream_profile>& prev)
  348. {
  349. for (auto&& sp : prev)
  350. {
  351. //If previous profile is in current (maybe just added another)
  352. auto itr = std::find_if(std::begin(current), std::end(current), [&sp](const rs2::stream_profile& current_sp) { return sp.unique_id() == current_sp.unique_id(); });
  353. if (itr == std::end(current)) //If it previous stream wasn't found in current
  354. {
  355. return true;
  356. }
  357. }
  358. return false;
  359. }