Skip to content

Commit

Permalink
Merge pull request IntelRealSense#3875 from schmidtp1/recorder
Browse files Browse the repository at this point in the history
added simple recorder
  • Loading branch information
dorodnic authored Jun 2, 2019
2 parents e8380a5 + 2b038a4 commit 25b8f34
Show file tree
Hide file tree
Showing 4 changed files with 179 additions and 0 deletions.
1 change: 1 addition & 0 deletions tools/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@ add_subdirectory(convert)
add_subdirectory(enumerate-devices)
add_subdirectory(fw-logger)
add_subdirectory(terminal)
add_subdirectory(recorder)

if(BUILD_GRAPHICAL_EXAMPLES)
include(${CMAKE_SOURCE_DIR}/CMake/opengl_config.cmake)
Expand Down
24 changes: 24 additions & 0 deletions tools/recorder/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
# License: Apache 2.0. See LICENSE file in root directory.
# Copyright(c) 2019 Intel Corporation. All Rights Reserved.
# minimum required cmake version: 3.1.0
cmake_minimum_required(VERSION 3.1.0)

project(RealsenseToolsRecorder)

add_executable(rs-record rs-record.cpp)
set_property(TARGET rs-record PROPERTY CXX_STANDARD 11)
target_link_libraries(rs-record ${DEPENDENCIES})
include_directories(rs-record ../../common ../../third-party/tclap/include)
set_target_properties (rs-record PROPERTIES
FOLDER "Tools"
)

install(
TARGETS

rs-record

RUNTIME DESTINATION
${CMAKE_INSTALL_BINDIR}
)

83 changes: 83 additions & 0 deletions tools/recorder/readme.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,83 @@
# rs-record Tool

## Overview

This tool is designed to collect raw sensor data to rosbag.

## Description
The tool records for a certain amount of time to a file as specified by the user.
The goal is to offer a command line recorder with low latency and zero frame drops.


## Command Line Parameters

|Flag |Description |Default|
|---|---|---|
|`-t X`|Stop recording after X seconds|10|
|`-f <filename>`|Save recording to <filename>|"test.bag"|

For example:
`rs-record -f ./test1.bag -t 60`
will collect the data for 60 seconds.
The data will be saved to `./test1.bag`.

# Recording file
The recorded rosbag can be replayed within librealsense as well as within ROS and inspected by common ROS tools such as `rosbag info` or `rqt_bag`.
One sample of the included data can be seen below:
```
path: test.bag
version: 2.0
duration: 10.0s
start: Dec 31 1969 16:00:00.00 (0.00)
end: Dec 31 1969 16:00:09.00 (10.00)
size: 392.2 MB
messages: 33420
compression: none [301/301 chunks]
types: diagnostic_msgs/KeyValue [cf57fdc6617a881a88c16e768132149c]
geometry_msgs/Accel [9f195f881246fdfa2798d1d3eebca84a]
geometry_msgs/Transform [ac9eff44abf714214112b05d54a3cf9b]
geometry_msgs/Twist [9f195f881246fdfa2798d1d3eebca84a]
realsense_msgs/ImuIntrinsic [aebdc2f8f9726f1c3ca823ab56e47429]
realsense_msgs/StreamInfo [311d7e24eac31bb87271d041bf70ff7d]
sensor_msgs/CameraInfo [c9a58c1b0b154e0e6da7578cb991d214]
sensor_msgs/Image [060021388200f6f0f447d0fcd9c64743]
sensor_msgs/Imu [6a62c6daae103f4ff57a132d6f95cec2]
std_msgs/Float32 [73fcbf46b49191e672908e50842a83d4]
std_msgs/String [992ce8a1687cec8c8bd883ec73ca41d1]
std_msgs/UInt32 [304a39449588c7f8ce2df6e8001c5fce]
topics: /device_0/info 5 msgs : diagnostic_msgs/KeyValue
/device_0/sensor_0/Accel_0/imu/data 640 msgs : sensor_msgs/Imu
/device_0/sensor_0/Accel_0/imu/metadata 2560 msgs : diagnostic_msgs/KeyValue
/device_0/sensor_0/Accel_0/imu_intrinsic 1 msg : realsense_msgs/ImuIntrinsic
/device_0/sensor_0/Accel_0/info 1 msg : realsense_msgs/StreamInfo
/device_0/sensor_0/Accel_0/tf/0 1 msg : geometry_msgs/Transform
/device_0/sensor_0/Fisheye_1/image/data 300 msgs : sensor_msgs/Image
/device_0/sensor_0/Fisheye_1/image/metadata 1200 msgs : diagnostic_msgs/KeyValue
/device_0/sensor_0/Fisheye_1/info 1 msg : realsense_msgs/StreamInfo
/device_0/sensor_0/Fisheye_1/info/camera_info 1 msg : sensor_msgs/CameraInfo
/device_0/sensor_0/Fisheye_1/tf/0 1 msg : geometry_msgs/Transform
/device_0/sensor_0/Fisheye_2/image/data 300 msgs : sensor_msgs/Image
/device_0/sensor_0/Fisheye_2/image/metadata 1200 msgs : diagnostic_msgs/KeyValue
/device_0/sensor_0/Fisheye_2/info 1 msg : realsense_msgs/StreamInfo
/device_0/sensor_0/Fisheye_2/info/camera_info 1 msg : sensor_msgs/CameraInfo
/device_0/sensor_0/Fisheye_2/tf/0 1 msg : geometry_msgs/Transform
/device_0/sensor_0/Gyro_0/imu/data 2006 msgs : sensor_msgs/Imu
/device_0/sensor_0/Gyro_0/imu/metadata 8024 msgs : diagnostic_msgs/KeyValue
/device_0/sensor_0/Gyro_0/imu_intrinsic 1 msg : realsense_msgs/ImuIntrinsic
/device_0/sensor_0/Gyro_0/info 1 msg : realsense_msgs/StreamInfo
/device_0/sensor_0/Gyro_0/tf/0 1 msg : geometry_msgs/Transform
/device_0/sensor_0/Pose_0/info 1 msg : realsense_msgs/StreamInfo
/device_0/sensor_0/Pose_0/pose/accel/data 1907 msgs : geometry_msgs/Accel
/device_0/sensor_0/Pose_0/pose/metadata 11442 msgs : diagnostic_msgs/KeyValue
/device_0/sensor_0/Pose_0/pose/transform/data 1907 msgs : geometry_msgs/Transform
/device_0/sensor_0/Pose_0/pose/twist/data 1907 msgs : geometry_msgs/Twist
/device_0/sensor_0/Pose_0/tf/0 1 msg : geometry_msgs/Transform
/device_0/sensor_0/info 1 msg : diagnostic_msgs/KeyValue
/device_0/sensor_0/option/Asic Temperature/description 1 msg : std_msgs/String
/device_0/sensor_0/option/Asic Temperature/value 1 msg : std_msgs/Float32
/device_0/sensor_0/option/Frames Queue Size/description 1 msg : std_msgs/String
/device_0/sensor_0/option/Frames Queue Size/value 1 msg : std_msgs/Float32
/device_0/sensor_0/option/Motion Module Temperature/description 1 msg : std_msgs/String
/device_0/sensor_0/option/Motion Module Temperature/value 1 msg : std_msgs/Float32
/file_version 1 msg : std_msgs/UInt32
```
71 changes: 71 additions & 0 deletions tools/recorder/rs-record.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
// License: Apache 2.0. See LICENSE file in root directory.
// Copyright(c) 2019 Intel Corporation. All Rights Reserved.

#include <librealsense2/rs.hpp>
#include <iostream>
#include <iomanip>
#include <thread>
#include <mutex>
#include <stdio.h>
#include <memory>
#include <functional>
#include <thread>
#include <string.h>
#include <chrono>
#include "tclap/CmdLine.h"

using namespace TCLAP;

int main(int argc, char * argv[]) try
{
// Parse command line arguments
CmdLine cmd("librealsense rs-record example tool", ' ');
ValueArg<int> time("t", "Time", "Amount of time to record (in seconds)", false, 10, "");
ValueArg<std::string> out_file("f", "FullFilePath", "the file where the data will be saved to", false, "test.bag", "");

cmd.add(time);
cmd.add(out_file);
cmd.parse(argc, argv);

rs2::pipeline pipe;
rs2::config cfg;
cfg.enable_record_to_file(out_file.getValue());

std::mutex m;
auto callback = [&](const rs2::frame& frame)
{
std::lock_guard<std::mutex> lock(m);
auto t = std::chrono::system_clock::now();
static auto tk = t;
static auto t0 = t;
if (t - tk >= std::chrono::seconds(1)) {
std::cout << "\r" << std::setprecision(3) << std::fixed
<< "Recording t = " << std::chrono::duration_cast<std::chrono::seconds>(t-t0).count() << "s" << std::flush;
tk = t;
}
};

rs2::pipeline_profile profiles = pipe.start(cfg, callback);

auto t = std::chrono::system_clock::now();
auto t0 = t;
while(t - t0 <= std::chrono::seconds(time.getValue())) {
std::this_thread::sleep_for(std::chrono::milliseconds(10));
t = std::chrono::system_clock::now();
}
std::cout << "\nFinished" << std::endl;

pipe.stop();

return EXIT_SUCCESS;
}
catch (const rs2::error & e)
{
std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() << "):\n " << e.what() << std::endl;
return EXIT_FAILURE;
}
catch (const std::exception& e)
{
std::cerr << e.what() << std::endl;
return EXIT_FAILURE;
}

0 comments on commit 25b8f34

Please sign in to comment.