123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286 |
- #include <signal.h>
- #include <stdlib.h>
- #include <iostream>
- #include <algorithm>
- #include <fstream>
- #include <chrono>
- #include <ctime>
- #include <sstream>
- #include <iomanip>
- #include <condition_variable>
- #include <opencv2/core/core.hpp>
- #include <opencv2/highgui.hpp>
- #include "opencv2/imgproc/imgproc.hpp"
- #include <librealsense2/rs.hpp>
- #include "librealsense2/rsutil.h"
- using namespace std;
- bool b_continue_session;
- const float reductionFactor = 0.5;
- const int colsRedIm = reductionFactor * 848;
- const int rowsRedIm = reductionFactor * 800;
- void exit_loop_handler(int s){
- cout << "Finishing session" << endl;
- b_continue_session = false;
- }
- static rs2_option get_sensor_option(const rs2::sensor& sensor)
- {
-
-
- std::cout << "Sensor supports the following options:\n" << std::endl;
-
-
- for (int i = 0; i < static_cast<int>(RS2_OPTION_COUNT); i++)
- {
- rs2_option option_type = static_cast<rs2_option>(i);
-
- std::cout << " " << i << ": " << option_type;
-
-
- if (sensor.supports(option_type))
- {
- std::cout << std::endl;
-
- const char* description = sensor.get_option_description(option_type);
- std::cout << " Description : " << description << std::endl;
-
- float current_value = sensor.get_option(option_type);
- std::cout << " Current Value : " << current_value << std::endl;
-
- }
- else
- {
- std::cout << " is not supported" << std::endl;
- }
- }
- uint32_t selected_sensor_option = 0;
- return static_cast<rs2_option>(selected_sensor_option);
- }
- int main(int argc, char **argv) {
- if (argc != 2) {
- cerr << endl
- << "Usage: ./recorder_realsense_D435i path_to_saving_folder"
- << endl;
- return 1;
- }
- string directory = string(argv[argc - 1]);
- struct sigaction sigIntHandler;
- sigIntHandler.sa_handler = exit_loop_handler;
- sigemptyset(&sigIntHandler.sa_mask);
- sigIntHandler.sa_flags = 0;
- sigaction(SIGINT, &sigIntHandler, NULL);
- b_continue_session = true;
- double offset = 0;
-
- rs2::pipeline pipe;
-
- rs2::config cfg;
- cfg.enable_stream(RS2_STREAM_FISHEYE, 1, RS2_FORMAT_Y8,30);
- cfg.enable_stream(RS2_STREAM_FISHEYE, 2, RS2_FORMAT_Y8,30);
- cfg.enable_stream(RS2_STREAM_ACCEL, RS2_FORMAT_MOTION_XYZ32F);
- cfg.enable_stream(RS2_STREAM_GYRO, RS2_FORMAT_MOTION_XYZ32F);
-
- std::mutex imu_mutex;
- std::condition_variable cond_image_rec;
- vector<double> v_gyro_timestamp;
- vector<rs2_vector> v_gyro_data;
- vector<double> v_acc_timestamp;
- vector<rs2_vector> v_acc_data;
- cv::Mat imCV_left, imCV_right;
- int width_img, height_img;
- double timestamp_image;
- bool image_ready = false;
- auto imu_callback = [&](const rs2::frame& frame)
- {
- std::unique_lock<std::mutex> lock(imu_mutex);
- if(rs2::frameset fs = frame.as<rs2::frameset>())
- {
- rs2::video_frame color_frame_left = fs.get_fisheye_frame(1);
- rs2::video_frame color_frame_right = fs.get_fisheye_frame(2);
- imCV_left = cv::Mat(cv::Size(width_img, height_img), CV_8U, (void*)(color_frame_left.get_data()), cv::Mat::AUTO_STEP);
- imCV_right = cv::Mat(cv::Size(width_img, height_img), CV_8U, (void*)(color_frame_right.get_data()), cv::Mat::AUTO_STEP);
- timestamp_image = fs.get_timestamp()*1e-3;
- image_ready = true;
- lock.unlock();
- cond_image_rec.notify_all();
- }
- else if (rs2::motion_frame m_frame = frame.as<rs2::motion_frame>())
- {
- if (m_frame.get_profile().stream_name() == "Gyro")
- {
-
- v_gyro_data.push_back(m_frame.get_motion_data());
- v_gyro_timestamp.push_back((m_frame.get_timestamp()+offset)*1e-3);
- }
- else if (m_frame.get_profile().stream_name() == "Accel")
- {
-
- v_acc_data.push_back(m_frame.get_motion_data());
- v_acc_timestamp.push_back((m_frame.get_timestamp()+offset)*1e-3);
- }
- }
- };
- rs2::pipeline_profile pipe_profile = pipe.start(cfg, imu_callback);
- rs2::stream_profile cam_stream_left = pipe_profile.get_stream(RS2_STREAM_FISHEYE, 1);
- rs2::stream_profile cam_stream_right = pipe_profile.get_stream(RS2_STREAM_FISHEYE, 2);
- rs2::stream_profile imu_stream = pipe_profile.get_stream(RS2_STREAM_GYRO);
- rs2_intrinsics intrinsics_cam = cam_stream_left.as<rs2::video_stream_profile>().get_intrinsics();
- width_img = intrinsics_cam.width;
- height_img = intrinsics_cam.height;
- cv::Mat imLeft, imRight;
- ofstream accFile, gyroFile, cam0TsFile, cam1TsFile;
- accFile.open (directory + "/IMU/acc.txt");
- gyroFile.open (directory + "/IMU/gyro.txt");
- cam0TsFile.open (directory + "/cam0/times.txt");
- cam1TsFile.open (directory + "/cam1/times.txt");
- cout << directory + "/IMU/acc.txt" << endl;
- if(!accFile.is_open() || ! gyroFile.is_open() || !cam0TsFile.is_open()){
- cerr << "FILES NOT OPENED" << endl;
- exit(-1);
- }
-
- v_gyro_data.clear();
- v_gyro_timestamp.clear();
- v_acc_data.clear();
- v_acc_timestamp.clear();
- cv::namedWindow("cam0",cv::WINDOW_AUTOSIZE);
- while (b_continue_session){
- std::vector<rs2_vector> vGyro;
- std::vector<double> vGyro_times;
- std::vector<rs2_vector> vAccel, vAccel_Sync;
- std::vector<double> vAccel_times;
- double imTs;
- {
- {
- std::unique_lock<std::mutex> lk(imu_mutex);
- if (!image_ready)
- cond_image_rec.wait(lk);
- }
- std::lock_guard<std::mutex> lk(imu_mutex);
-
- vGyro = v_gyro_data;
- vGyro_times = v_gyro_timestamp;
- vAccel = v_acc_data;
- vAccel_times = v_acc_timestamp;
- imTs = timestamp_image;
- if(reductionFactor == 1.0) {
- imLeft = imCV_left.clone();
- imRight = imCV_right.clone();
- } else {
- cv::resize(imCV_left, imLeft, cv::Size(colsRedIm,rowsRedIm));
- cv::resize(imCV_right, imRight, cv::Size(colsRedIm,rowsRedIm));
- }
-
- v_gyro_data.clear();
- v_gyro_timestamp.clear();
- v_acc_data.clear();
- v_acc_timestamp.clear();
- image_ready = false;
- }
- cv::imshow("cam0",imLeft);
- cv::imshow("cam1",imRight);
-
- long int imTsInt = (long int) (1e9*imTs);
- string imgRepoLeft = directory + "/cam0/" + to_string(imTsInt) + ".png";
- if(!imLeft.empty()) {
- cv::imwrite(imgRepoLeft, imLeft);
- cam0TsFile << imTsInt << endl;
- } else {
- cout << " left image empty!! \n";
- }
- string imgRepoRight = directory + "/cam1/" + to_string(imTsInt) + ".png";
- if(!imRight.empty()) {
- cv::imwrite(imgRepoRight, imRight);
- cam1TsFile << imTsInt << endl;
- } else {
- cout << "right image empty!! \n";
- }
-
-
- for(int i=0; i<vAccel.size(); ++i){
- accFile << std::setprecision(15) << vAccel_times[i] << "," << vAccel[i].x << "," << vAccel[i].y << "," << vAccel[i].z << endl;
- }
- for(int i=0; i<vGyro.size(); ++i){
- gyroFile << std::setprecision(15) << vGyro_times[i] << "," << vGyro[i].x << "," << vGyro[i].y << "," << vGyro[i].z << endl;
- }
- cv::waitKey(10);
- }
- accFile.close();
- gyroFile.close();
- cam0TsFile.close();
- cam1TsFile.close();
- cout << "System shutdown!\n";
- }
|