recorder_realsense_D435i.cc 9.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286
  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 <iomanip>
  27. #include <condition_variable>
  28. #include <opencv2/core/core.hpp>
  29. #include <opencv2/highgui.hpp>
  30. #include <librealsense2/rs.hpp>
  31. #include "librealsense2/rsutil.h"
  32. using namespace std;
  33. bool b_continue_session;
  34. void exit_loop_handler(int s){
  35. cout << "Finishing session" << endl;
  36. b_continue_session = false;
  37. }
  38. static rs2_option get_sensor_option(const rs2::sensor& sensor)
  39. {
  40. // Sensors usually have several options to control their properties
  41. // such as Exposure, Brightness etc.
  42. std::cout << "Sensor supports the following options:\n" << std::endl;
  43. // The following loop shows how to iterate over all available options
  44. // Starting from 0 until RS2_OPTION_COUNT (exclusive)
  45. for (int i = 0; i < static_cast<int>(RS2_OPTION_COUNT); i++)
  46. {
  47. rs2_option option_type = static_cast<rs2_option>(i);
  48. //SDK enum types can be streamed to get a string that represents them
  49. std::cout << " " << i << ": " << option_type;
  50. // To control an option, use the following api:
  51. // First, verify that the sensor actually supports this option
  52. if (sensor.supports(option_type))
  53. {
  54. std::cout << std::endl;
  55. // Get a human readable description of the option
  56. const char* description = sensor.get_option_description(option_type);
  57. std::cout << " Description : " << description << std::endl;
  58. // Get the current value of the option
  59. float current_value = sensor.get_option(option_type);
  60. std::cout << " Current Value : " << current_value << std::endl;
  61. //To change the value of an option, please follow the change_sensor_option() function
  62. }
  63. else
  64. {
  65. std::cout << " is not supported" << std::endl;
  66. }
  67. }
  68. uint32_t selected_sensor_option = 0;
  69. return static_cast<rs2_option>(selected_sensor_option);
  70. }
  71. int main(int argc, char **argv) {
  72. if (argc != 2) {
  73. cerr << endl
  74. << "Usage: ./recorder_realsense_D435i path_to_saving_folder"
  75. << endl;
  76. return 1;
  77. }
  78. string directory = string(argv[argc - 1]);
  79. struct sigaction sigIntHandler;
  80. sigIntHandler.sa_handler = exit_loop_handler;
  81. sigemptyset(&sigIntHandler.sa_mask);
  82. sigIntHandler.sa_flags = 0;
  83. sigaction(SIGINT, &sigIntHandler, NULL);
  84. b_continue_session = true;
  85. double offset = 0; // ms
  86. rs2::context ctx;
  87. rs2::device_list devices = ctx.query_devices();
  88. rs2::device selected_device;
  89. if (devices.size() == 0)
  90. {
  91. std::cerr << "No device connected, please connect a RealSense device" << std::endl;
  92. return 0;
  93. }
  94. else
  95. selected_device = devices[0];
  96. std::vector<rs2::sensor> sensors = selected_device.query_sensors();
  97. int index = 0;
  98. // We can now iterate the sensors and print their names
  99. for (rs2::sensor sensor : sensors)
  100. if (sensor.supports(RS2_CAMERA_INFO_NAME)) {
  101. ++index;
  102. if (index == 1) {
  103. sensor.set_option(RS2_OPTION_ENABLE_AUTO_EXPOSURE, 1);
  104. sensor.set_option(RS2_OPTION_AUTO_EXPOSURE_LIMIT,5000);
  105. sensor.set_option(RS2_OPTION_EMITTER_ENABLED, 0);
  106. }
  107. // std::cout << " " << index << " : " << sensor.get_info(RS2_CAMERA_INFO_NAME) << std::endl;
  108. get_sensor_option(sensor);
  109. if (index == 2){
  110. // RGB camera
  111. sensor.set_option(RS2_OPTION_EXPOSURE,100.f);
  112. }
  113. if (index == 3){
  114. sensor.set_option(RS2_OPTION_ENABLE_MOTION_CORRECTION,0);
  115. }
  116. }
  117. // Declare RealSense pipeline, encapsulating the actual device and sensors
  118. rs2::pipeline pipe;
  119. // Create a configuration for configuring the pipeline with a non default profile
  120. rs2::config cfg;
  121. cfg.enable_stream(RS2_STREAM_INFRARED, 1, 640, 480, RS2_FORMAT_Y8, 30);
  122. cfg.enable_stream(RS2_STREAM_ACCEL, RS2_FORMAT_MOTION_XYZ32F); //, 250); // 63
  123. cfg.enable_stream(RS2_STREAM_GYRO, RS2_FORMAT_MOTION_XYZ32F); //, 400);
  124. // IMU callback
  125. std::mutex imu_mutex;
  126. std::condition_variable cond_image_rec;
  127. vector<double> v_gyro_timestamp;
  128. vector<rs2_vector> v_gyro_data;
  129. vector<double> v_acc_timestamp;
  130. vector<rs2_vector> v_acc_data;
  131. cv::Mat imCV;
  132. int width_img, height_img;
  133. double timestamp_image;
  134. bool image_ready = false;
  135. auto imu_callback = [&](const rs2::frame& frame)
  136. {
  137. std::unique_lock<std::mutex> lock(imu_mutex);
  138. if(rs2::frameset fs = frame.as<rs2::frameset>())
  139. {
  140. rs2::video_frame color_frame = fs.get_infrared_frame();
  141. imCV = cv::Mat(cv::Size(width_img, height_img), CV_8U, (void*)(color_frame.get_data()), cv::Mat::AUTO_STEP);
  142. timestamp_image = fs.get_timestamp()*1e-3;
  143. image_ready = true;
  144. lock.unlock();
  145. cond_image_rec.notify_all();
  146. }
  147. else if (rs2::motion_frame m_frame = frame.as<rs2::motion_frame>())
  148. {
  149. if (m_frame.get_profile().stream_name() == "Gyro")
  150. {
  151. // It runs at 200Hz
  152. v_gyro_data.push_back(m_frame.get_motion_data());
  153. v_gyro_timestamp.push_back((m_frame.get_timestamp()+offset)*1e-3);
  154. }
  155. else if (m_frame.get_profile().stream_name() == "Accel")
  156. {
  157. // It runs at 60Hz
  158. v_acc_data.push_back(m_frame.get_motion_data());
  159. v_acc_timestamp.push_back((m_frame.get_timestamp()+offset)*1e-3);
  160. }
  161. }
  162. };
  163. rs2::pipeline_profile pipe_profile = pipe.start(cfg, imu_callback);
  164. rs2::stream_profile cam_stream = pipe_profile.get_stream(RS2_STREAM_INFRARED, 1);
  165. rs2::stream_profile imu_stream = pipe_profile.get_stream(RS2_STREAM_GYRO);
  166. rs2_intrinsics intrinsics_cam = cam_stream.as<rs2::video_stream_profile>().get_intrinsics();
  167. width_img = intrinsics_cam.width;
  168. height_img = intrinsics_cam.height;
  169. cv::Mat im;
  170. ofstream accFile, gyroFile, cam0TsFile;
  171. accFile.open (directory + "/IMU/acc.txt");
  172. gyroFile.open (directory + "/IMU/gyro.txt");
  173. cam0TsFile.open (directory + "/cam0/times.txt");
  174. // Clear IMU vectors
  175. v_gyro_data.clear();
  176. v_gyro_timestamp.clear();
  177. v_acc_data.clear();
  178. v_acc_timestamp.clear();
  179. cv::namedWindow("cam0",cv::WINDOW_AUTOSIZE);
  180. while (b_continue_session){
  181. std::vector<rs2_vector> vGyro;
  182. std::vector<double> vGyro_times;
  183. std::vector<rs2_vector> vAccel, vAccel_Sync;
  184. std::vector<double> vAccel_times;
  185. double imTs;
  186. {
  187. {
  188. std::unique_lock<std::mutex> lk(imu_mutex);
  189. if (!image_ready) // wait until image read from the other thread
  190. cond_image_rec.wait(lk);
  191. }
  192. std::lock_guard<std::mutex> lk(imu_mutex);
  193. // Copy the IMU data to local single thread variables
  194. vGyro = v_gyro_data;
  195. vGyro_times = v_gyro_timestamp;
  196. vAccel = v_acc_data;
  197. vAccel_times = v_acc_timestamp;
  198. imTs = timestamp_image;
  199. im = imCV.clone();
  200. // Clear IMU vectors
  201. v_gyro_data.clear();
  202. v_gyro_timestamp.clear();
  203. v_acc_data.clear();
  204. v_acc_timestamp.clear();
  205. image_ready = false;
  206. }
  207. cv::imshow("cam0",im);
  208. // save image and IMU data
  209. long int imTsInt = (long int) (1e9*imTs);
  210. string imgRepo = directory + "/cam0/" + to_string(imTsInt) + ".png";
  211. if(!im.empty()) {
  212. cv::imwrite(imgRepo, im);
  213. cam0TsFile << imTsInt << endl;
  214. } else {
  215. cout << "image empty!! \n";
  216. }
  217. //assert(vAccel.size() == vAccel_times.size());
  218. //assert(vGyro.size() == vGyro_times.size());
  219. for(int i=0; i<vAccel.size(); ++i){
  220. accFile << std::setprecision(15) << vAccel_times[i] << "," << vAccel[i].x << "," << vAccel[i].y << "," << vAccel[i].z << endl;
  221. }
  222. for(int i=0; i<vGyro.size(); ++i){
  223. gyroFile << std::setprecision(15) << vGyro_times[i] << "," << vGyro[i].x << "," << vGyro[i].y << "," << vGyro[i].z << endl;
  224. }
  225. cv::waitKey(10);
  226. }
  227. accFile.close();
  228. gyroFile.close();
  229. cam0TsFile.close();
  230. cout << "System shutdown!\n";
  231. }