13 std::shared_ptr<librealsense::device_serializer::writer> serializer):
14 m_write_thread([](){
return std::make_shared<dispatcher>(std::numeric_limits<unsigned int>::max());}),
23 if (serializer ==
nullptr)
30 (*m_write_thread)->start();
37 std::vector<std::shared_ptr<librealsense::record_sensor>> record_sensors;
38 for (
size_t sensor_index = 0; sensor_index < device->get_sensors_count(); sensor_index++)
40 auto& live_sensor = device->get_sensor(sensor_index);
41 auto recording_sensor = std::make_shared<librealsense::record_sensor>(*
this, live_sensor);
43 auto on_error = [recording_sensor](
const std::string&
s) {recording_sensor->stop_with_error(
s); };
48 recording_sensor->init();
49 record_sensors.emplace_back(recording_sensor);
51 return record_sensors;
61 s->disable_recording();
63 if ((*m_write_thread)->flush() ==
false)
65 LOG_ERROR(
"Error - timeout waiting for flush, possible deadlock detected");
67 (*m_write_thread)->stop();
91 LOG_DEBUG(
"Created device snapshot with " << device_extensions_md.get_snapshots().size() <<
" snapshots");
93 std::vector<device_serializer::sensor_snapshot> sensors_snapshot;
94 for (
size_t j = 0;
j <
m_device->get_sensors_count(); ++
j)
98 sensors_snapshot.emplace_back(static_cast<uint32_t>(
j), sensor_extensions_snapshots);
99 LOG_DEBUG(
"Created sensor " <<
j <<
" snapshot with " << device_extensions_md.get_snapshots().size() <<
" snapshots");
102 m_ros_writer->write_device_description({ device_extensions_md, sensors_snapshot, {} });
110 return std::chrono::nanoseconds::zero();
131 LOG_WARNING(
"Recorder reached maximum cache size, frame dropped");
132 on_error(
"Recorder reached maximum cache size, frame dropped");
139 auto frame_holder_ptr = std::make_shared<frame_holder>();
152 catch (
const std::exception&
e)
154 LOG_ERROR(
"Failed to write header. " << e.what());
155 on_error(
to_string() <<
"Failed to write header. " << e.what());
162 auto stream_type = frame_holder_ptr->frame->get_stream()->get_stream_type();
163 auto stream_index =
static_cast<uint32_t>(frame_holder_ptr->frame->get_stream()->get_stream_index());
167 catch(std::exception&
e)
169 on_error(
to_string() <<
"Failed to write frame. " << e.what());
181 return m_device->supports_info(info);
193 template <
typename T,
typename Ext>
200 std::shared_ptr<Ext>
p;
203 api->create_snapshot(p);
205 if (snapshot !=
nullptr)
215 catch (
const std::exception&
e)
266 template <
typename T>
269 std::shared_ptr<T> snapshot;
270 ext.create_snapshot(snapshot);
271 auto ext_snapshot = As<extension_snapshot>(snapshot);
285 catch (
const std::exception&
e)
294 std::shared_ptr<extension_snapshot> snapshot,
305 catch (
const std::exception&
e)
322 catch (
const std::exception&
e)
330 template <rs2_extension E,
typename P>
334 auto ptr = As<EXT_TYPE>(
p);
358 switch (extension_type)
390 (*m_write_thread)->flush();
420 return m_device->create_matcher(frame);
440 return m_device->get_extrinsics(stream);
std::shared_ptr< device_serializer::writer > m_ros_writer
rs2_camera_info
Read-only strings that can be queried from the device. Not all information attributes are available o...
const char * get_string(rs2_rs400_visual_preset value)
std::shared_ptr< T > As(std::shared_ptr< P > ptr)
sensor_interface & get_sensor(size_t i) override
device_serializer::snapshot_collection get_extensions_snapshots(T *extendable)
void write_data(size_t sensor_index, frame_holder f, std::function< void(std::string const &)> on_error)
std::chrono::high_resolution_clock::time_point m_capture_time_base
std::shared_ptr< device_interface > m_device
void hardware_reset() override
GLsizei const GLchar *const * string
virtual std::shared_ptr< matcher > create_matcher(const frame_holder &frame) const override
platform::backend_device_group get_device_data() const override
int m_on_notification_token
void try_add_snapshot(T *extendable, device_serializer::snapshot_collection &snapshots)
virtual void enable_recording(std::function< void(const T &)> recording_function)=0
std::chrono::nanoseconds get_capture_time() const
def info(name, value, persistent=False)
std::once_flag m_first_frame_flag
bool extend_to(rs2_extension extension_type, void **ext) override
bool is_valid() const override
std::shared_ptr< context > get_context() const override
bool extend_to_aux(std::shared_ptr< P > p, void **ext)
size_t get_sensors_count() const override
std::once_flag m_first_call_flag
void write_sensor_extension_snapshot(size_t sensor_index, rs2_extension ext, std::shared_ptr< extension_snapshot > snapshot, std::function< void(std::string const &)> on_error)
void initialize_recording()
unsigned __int64 uint64_t
bool supports_info(rs2_camera_info info) const override
int m_on_extension_change_token
GLuint GLuint64EXT * capture_time
std::vector< std::shared_ptr< record_sensor > > create_record_sensors(std::shared_ptr< device_interface > m_device)
std::chrono::duration< uint64_t, std::nano > nanoseconds
LOG_INFO("Log message using LOG_INFO()")
rs2_extension
Specifies advanced interfaces (capabilities) objects may implement.
record_device(std::shared_ptr< device_interface > device, std::shared_ptr< device_serializer::writer > serializer)
std::chrono::high_resolution_clock::duration m_record_pause_time
void write_notification(size_t sensor_index, const notification &n)
typename::boost::move_detail::remove_reference< T >::type && move(T &&t) BOOST_NOEXCEPT
std::vector< std::shared_ptr< record_sensor > > m_sensors
uint64_t m_cached_data_size
std::pair< uint32_t, rs2_extrinsics > get_extrinsics(const stream_interface &stream) const override
std::chrono::high_resolution_clock::time_point m_time_of_pause
virtual unsigned long long get_frame_number() const =0
void stop_gracefully(to_string error_msg)
const std::string & get_filename() const
void write_device_extension_changes(const T &ext)
std::string to_string(T value)
const std::string & get_info(rs2_camera_info info) const override
static const uint64_t MAX_CACHED_DATA_SIZE