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