diff --git a/include/librealsense2/h/rs_record_playback.h b/include/librealsense2/h/rs_record_playback.h index cddec6da7db..a540e6d735c 100644 --- a/include/librealsense2/h/rs_record_playback.h +++ b/include/librealsense2/h/rs_record_playback.h @@ -24,6 +24,7 @@ typedef enum rs2_playback_status RS2_PLAYBACK_STATUS_STOPPED, /**< All sensors were stopped, or playback has ended (all data was read). This is the initial playback status*/ RS2_PLAYBACK_STATUS_COUNT } rs2_playback_status; + const char* rs2_playback_status_to_string(rs2_playback_status status); typedef void (*rs2_playback_status_changed_callback_ptr)(rs2_playback_status); @@ -37,6 +38,16 @@ typedef void (*rs2_playback_status_changed_callback_ptr)(rs2_playback_status); */ rs2_device* rs2_create_record_device(const rs2_device* device, const char* file, rs2_error** error); +/** +* Creates a recording device to record the given device and save it to the given file +* \param[in] device The device to record +* \param[in] file The desired path to which the recorder should save the data +* \param[in] compression_enabled Indicates if compression is enabled, 0 means false, otherwise true +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored +* \return A pointer to a device that records its data to file, or null in case of failure +*/ +rs2_device* rs2_create_record_device_ex(const rs2_device* device, const char* file, int compression_enabled, rs2_error** error); + /** * Pause the recording device without stopping the actual device from streaming. * Pausing will cause the device to stop writing new data to the file, in particular, frames and changes to extensions diff --git a/include/librealsense2/hpp/rs_record_playback.hpp b/include/librealsense2/hpp/rs_record_playback.hpp index 83520236866..3a4dd1620c5 100644 --- a/include/librealsense2/hpp/rs_record_playback.hpp +++ b/include/librealsense2/hpp/rs_record_playback.hpp @@ -219,6 +219,22 @@ namespace rs2 rs2::error::handle(e); } + /** + * Creates a recording device to record the given device and save it to the given file as rosbag format + * \param[in] file The desired path to which the recorder should save the data + * \param[in] device The device to record + * \param[in] compression_enabled Indicates if compression is enabled + */ + recorder(const std::string& file, rs2::device device, bool compression_enabled) + { + rs2_error* e = nullptr; + _dev = std::shared_ptr( + rs2_create_record_device_ex(device.get().get(), file.c_str(), compression_enabled, &e), + rs2_delete_device); + rs2::error::handle(e); + } + + /** * Pause the recording device without stopping the actual device from streaming. */ diff --git a/src/core/streaming.h b/src/core/streaming.h index 6dadd6a6ae5..af9bdec6b0d 100644 --- a/src/core/streaming.h +++ b/src/core/streaming.h @@ -213,6 +213,8 @@ namespace librealsense virtual std::vector get_profiles_tags() const = 0; virtual void tag_profiles(stream_profiles profiles) const = 0; + + virtual bool compress_while_record() const = 0; }; class depth_stereo_sensor; diff --git a/src/device.h b/src/device.h index a674c7b40f0..6807bb900da 100644 --- a/src/device.h +++ b/src/device.h @@ -74,6 +74,8 @@ namespace librealsense void tag_profiles(stream_profiles profiles) const override; + virtual bool compress_while_record() const override { return true; } + protected: int add_sensor(std::shared_ptr sensor_base); int assign_sensor(std::shared_ptr sensor_base, uint8_t idx); diff --git a/src/ds5/ds5-factory.cpp b/src/ds5/ds5-factory.cpp index dcdc56a01e0..2f0f15dba7d 100644 --- a/src/ds5/ds5-factory.cpp +++ b/src/ds5/ds5-factory.cpp @@ -437,6 +437,7 @@ namespace librealsense return tags; }; + bool compress_while_record() const override { return false; } }; diff --git a/src/media/playback/playback_device.h b/src/media/playback/playback_device.h index 0bb9c10bd71..5106cd48e28 100644 --- a/src/media/playback/playback_device.h +++ b/src/media/playback/playback_device.h @@ -54,6 +54,8 @@ namespace librealsense for(auto profile : profiles) profile->tag_profile(profile_tag::PROFILE_TAG_DEFAULT | profile_tag::PROFILE_TAG_SUPERSET); } + + bool compress_while_record() const override { return true; } private: void update_time_base(device_serializer::nanoseconds base_timestamp); diff --git a/src/media/record/record_device.h b/src/media/record/record_device.h index 6c8f11c3b35..532c21f7a9b 100644 --- a/src/media/record/record_device.h +++ b/src/media/record/record_device.h @@ -45,7 +45,7 @@ namespace librealsense std::vector get_profiles_tags() const override { return m_device->get_profiles_tags(); }; void tag_profiles(stream_profiles profiles) const override { m_device->tag_profiles(profiles); } - + bool compress_while_record() const override { return true; } private: template void write_device_extension_changes(const T& ext); template bool extend_to_aux(std::shared_ptr

p, void** ext); diff --git a/src/media/ros/ros_writer.h b/src/media/ros/ros_writer.h index c43b7db22b1..cc4a8614d5b 100644 --- a/src/media/ros/ros_writer.h +++ b/src/media/ros/ros_writer.h @@ -22,10 +22,14 @@ namespace librealsense class ros_writer: public writer { public: - explicit ros_writer(const std::string& file) : m_file_path(file) + explicit ros_writer(const std::string& file, bool compress_while_record) : m_file_path(file) { + LOG_INFO("Compression while record is set to " << (compress_while_record ? "ON" : "OFF")); m_bag.open(file, rosbag::BagMode::Write); - m_bag.setCompression(rosbag::CompressionType::LZ4); + if (compress_while_record) + { + m_bag.setCompression(rosbag::CompressionType::LZ4); + } write_file_version(); } diff --git a/src/pipeline.cpp b/src/pipeline.cpp index f6153c36cc7..28aac117131 100644 --- a/src/pipeline.cpp +++ b/src/pipeline.cpp @@ -640,7 +640,7 @@ namespace librealsense if (!dev) throw librealsense::invalid_value_exception("Failed to create a pipeline_profile, device is null"); - _dev = std::make_shared(dev, std::make_shared(to_file)); + _dev = std::make_shared(dev, std::make_shared(to_file, dev->compress_while_record())); } _multistream = config.resolve(_dev.get()); } diff --git a/src/realsense.def b/src/realsense.def index cf9827f4f3d..8f5587cc133 100644 --- a/src/realsense.def +++ b/src/realsense.def @@ -1,271 +1,272 @@ -LIBRARY - -EXPORTS - rs2_create_context - rs2_delete_context - rs2_create_recording_context - rs2_create_mock_context - rs2_create_mock_context_versioned - rs2_get_time - rs2_context_add_device - rs2_context_remove_device - - rs2_query_devices - rs2_query_devices_ex - rs2_get_device_count - rs2_delete_device_list - rs2_create_device - rs2_delete_device - - rs2_query_sensors - rs2_get_sensors_count - rs2_delete_sensor_list - rs2_create_sensor - rs2_delete_sensor - - rs2_get_extrinsics - rs2_register_extrinsics - rs2_get_motion_intrinsics - - rs2_get_stream_profiles - rs2_get_stream_profile - rs2_get_stream_profiles_count - rs2_delete_stream_profiles_list - - rs2_open - rs2_open_multiple - rs2_close - - rs2_start - rs2_start_queue - rs2_start_cpp - rs2_stop - rs2_hardware_reset - - rs2_set_notifications_callback - rs2_set_notifications_callback_cpp - rs2_get_notification_description - rs2_get_notification_timestamp - rs2_get_notification_severity - rs2_get_notification_category - rs2_get_notification_serialized_data - - rs2_get_frame_metadata - rs2_supports_frame_metadata - rs2_get_frame_timestamp - rs2_get_frame_timestamp_domain - rs2_get_frame_number - rs2_get_frame_data - rs2_get_frame_width - rs2_get_frame_height - rs2_get_frame_stride_in_bytes - rs2_get_frame_bits_per_pixel - rs2_get_frame_stream_profile - rs2_get_frame_vertices - rs2_get_frame_texture_coordinates - rs2_get_frame_points_count - rs2_release_frame - rs2_keep_frame - rs2_frame_add_ref - rs2_pose_frame_get_pose_data - - rs2_get_option - rs2_set_option - rs2_supports_option - rs2_get_option_range - rs2_get_option_description - rs2_get_option_value_description - rs2_is_option_read_only - - rs2_set_region_of_interest - rs2_get_region_of_interest - - rs2_send_and_receive_raw_data - rs2_get_raw_data_size - rs2_delete_raw_data - rs2_get_raw_data - - rs2_get_device_info - rs2_supports_device_info - rs2_get_sensor_info - rs2_supports_sensor_info - - rs2_create_frame_queue - rs2_delete_frame_queue - rs2_wait_for_frame - rs2_poll_for_frame - rs2_try_wait_for_frame - rs2_enqueue_frame - rs2_flush_queue - - rs2_get_failed_function - rs2_get_failed_args - rs2_get_error_message - rs2_free_error - rs2_get_librealsense_exception_type - rs2_exception_type_to_string - rs2_extension_type_to_string - rs2_extension_to_string - rs2_playback_status_to_string - rs2_log_severity_to_string - rs2_log - - rs2_stream_to_string - rs2_format_to_string - rs2_distortion_to_string - rs2_option_to_string - rs2_camera_info_to_string - rs2_frame_metadata_to_string - rs2_frame_metadata_value_to_string - rs2_timestamp_domain_to_string - rs2_sr300_visual_preset_to_string - rs2_notification_category_to_string - - rs2_log_to_console - rs2_log_to_file - - rs2_get_api_version - rs2_set_devices_changed_callback_cpp - rs2_set_devices_changed_callback - rs2_device_list_contains - rs2_create_device_from_sensor - rs2_get_depth_scale - - rs2_is_sensor_extendable_to - rs2_is_device_extendable_to - rs2_is_frame_extendable_to - rs2_stream_profile_is - - rs2_set_stream_profile_data - rs2_get_stream_profile_data - rs2_get_video_stream_resolution - rs2_get_video_stream_intrinsics - - rs2_is_stream_profile_default - - rs2_delete_stream_profile - rs2_clone_stream_profile - - rs2_allocate_synthetic_video_frame - rs2_allocate_points - rs2_allocate_composite_frame - rs2_synthetic_frame_ready - rs2_create_processing_block - rs2_create_processing_block_fptr - rs2_start_processing - rs2_start_processing_queue - rs2_start_processing_fptr - rs2_process_frame - rs2_delete_processing_block - rs2_create_sync_processing_block - rs2_create_pointcloud - rs2_create_colorizer - rs2_create_decimation_filter_block - rs2_create_temporal_filter_block - rs2_create_spatial_filter_block - rs2_create_hole_filling_filter_block - rs2_create_disparity_transform_block - rs2_embedded_frames_count - rs2_extract_frame - rs2_depth_frame_get_distance - rs2_depth_stereo_frame_get_baseline - - rs2_set_depth_control - rs2_get_depth_control - rs2_set_rsm - rs2_get_rsm - rs2_set_rau_support_vector_control - rs2_get_rau_support_vector_control - rs2_set_color_control - rs2_get_color_control - rs2_set_rau_thresholds_control - rs2_get_rau_thresholds_control - rs2_set_slo_color_thresholds_control - rs2_get_slo_color_thresholds_control - rs2_get_slo_penalty_control - rs2_set_slo_penalty_control - rs2_get_hdad - rs2_set_hdad - rs2_set_color_correction - rs2_get_color_correction - rs2_set_depth_table - rs2_get_depth_table - rs2_set_ae_control - rs2_get_ae_control - rs2_set_census - rs2_get_census - rs2_rs400_visual_preset_to_string - rs2_is_enabled - rs2_toggle_advanced_mode - rs2_load_json - rs2_serialize_json - - rs2_create_record_device - rs2_record_device_pause - rs2_record_device_resume - rs2_record_device_filename - - rs2_context_add_device - rs2_context_remove_device - - rs2_playback_device_get_file_path - rs2_playback_get_duration - rs2_playback_seek - rs2_playback_get_position - rs2_playback_device_resume - rs2_playback_device_pause - rs2_playback_device_set_real_time - rs2_playback_device_is_real_time - rs2_playback_device_set_status_changed_callback - rs2_playback_device_get_current_status - rs2_playback_device_set_playback_speed - rs2_playback_device_stop - - rs2_create_align - - rs2_create_pipeline - rs2_pipeline_stop - rs2_pipeline_wait_for_frames - rs2_pipeline_poll_for_frames - rs2_pipeline_try_wait_for_frames - rs2_delete_pipeline - rs2_pipeline_start - rs2_pipeline_start_with_config - rs2_pipeline_get_active_profile - rs2_pipeline_profile_get_device - rs2_pipeline_profile_get_streams - rs2_delete_pipeline_profile - rs2_create_config - rs2_delete_config - rs2_config_enable_stream - rs2_config_enable_all_stream - rs2_config_enable_device - rs2_config_enable_device_from_file - rs2_config_enable_device_from_file_repeat_option - rs2_config_enable_record_to_file - rs2_config_disable_stream - rs2_config_disable_indexed_stream - rs2_config_disable_all_streams - rs2_config_resolve - rs2_config_can_resolve - - rs2_create_device_hub - rs2_device_hub_is_device_connected - rs2_device_hub_wait_for_device - rs2_delete_device_hub - - rs2_export_to_ply - rs2_create_software_device - rs2_software_device_add_sensor - rs2_software_sensor_on_video_frame - rs2_software_device_create_matcher - rs2_software_sensor_add_video_stream - rs2_software_sensor_add_read_only_option - rs2_software_sensor_update_read_only_option - rs2_software_sensor_set_metadata - - rs2_loopback_enable - rs2_loopback_disable - rs2_loopback_is_enabled - rs2_connect_tm2_controller - rs2_disconnect_tm2_controller +LIBRARY + +EXPORTS + rs2_create_context + rs2_delete_context + rs2_create_recording_context + rs2_create_mock_context + rs2_create_mock_context_versioned + rs2_get_time + rs2_context_add_device + rs2_context_remove_device + + rs2_query_devices + rs2_query_devices_ex + rs2_get_device_count + rs2_delete_device_list + rs2_create_device + rs2_delete_device + + rs2_query_sensors + rs2_get_sensors_count + rs2_delete_sensor_list + rs2_create_sensor + rs2_delete_sensor + + rs2_get_extrinsics + rs2_register_extrinsics + rs2_get_motion_intrinsics + + rs2_get_stream_profiles + rs2_get_stream_profile + rs2_get_stream_profiles_count + rs2_delete_stream_profiles_list + + rs2_open + rs2_open_multiple + rs2_close + + rs2_start + rs2_start_queue + rs2_start_cpp + rs2_stop + rs2_hardware_reset + + rs2_set_notifications_callback + rs2_set_notifications_callback_cpp + rs2_get_notification_description + rs2_get_notification_timestamp + rs2_get_notification_severity + rs2_get_notification_category + rs2_get_notification_serialized_data + + rs2_get_frame_metadata + rs2_supports_frame_metadata + rs2_get_frame_timestamp + rs2_get_frame_timestamp_domain + rs2_get_frame_number + rs2_get_frame_data + rs2_get_frame_width + rs2_get_frame_height + rs2_get_frame_stride_in_bytes + rs2_get_frame_bits_per_pixel + rs2_get_frame_stream_profile + rs2_get_frame_vertices + rs2_get_frame_texture_coordinates + rs2_get_frame_points_count + rs2_release_frame + rs2_keep_frame + rs2_frame_add_ref + rs2_pose_frame_get_pose_data + + rs2_get_option + rs2_set_option + rs2_supports_option + rs2_get_option_range + rs2_get_option_description + rs2_get_option_value_description + rs2_is_option_read_only + + rs2_set_region_of_interest + rs2_get_region_of_interest + + rs2_send_and_receive_raw_data + rs2_get_raw_data_size + rs2_delete_raw_data + rs2_get_raw_data + + rs2_get_device_info + rs2_supports_device_info + rs2_get_sensor_info + rs2_supports_sensor_info + + rs2_create_frame_queue + rs2_delete_frame_queue + rs2_wait_for_frame + rs2_poll_for_frame + rs2_try_wait_for_frame + rs2_enqueue_frame + rs2_flush_queue + + rs2_get_failed_function + rs2_get_failed_args + rs2_get_error_message + rs2_free_error + rs2_get_librealsense_exception_type + rs2_exception_type_to_string + rs2_extension_type_to_string + rs2_extension_to_string + rs2_playback_status_to_string + rs2_log_severity_to_string + rs2_log + + rs2_stream_to_string + rs2_format_to_string + rs2_distortion_to_string + rs2_option_to_string + rs2_camera_info_to_string + rs2_frame_metadata_to_string + rs2_frame_metadata_value_to_string + rs2_timestamp_domain_to_string + rs2_sr300_visual_preset_to_string + rs2_notification_category_to_string + + rs2_log_to_console + rs2_log_to_file + + rs2_get_api_version + rs2_set_devices_changed_callback_cpp + rs2_set_devices_changed_callback + rs2_device_list_contains + rs2_create_device_from_sensor + rs2_get_depth_scale + + rs2_is_sensor_extendable_to + rs2_is_device_extendable_to + rs2_is_frame_extendable_to + rs2_stream_profile_is + + rs2_set_stream_profile_data + rs2_get_stream_profile_data + rs2_get_video_stream_resolution + rs2_get_video_stream_intrinsics + + rs2_is_stream_profile_default + + rs2_delete_stream_profile + rs2_clone_stream_profile + + rs2_allocate_synthetic_video_frame + rs2_allocate_points + rs2_allocate_composite_frame + rs2_synthetic_frame_ready + rs2_create_processing_block + rs2_create_processing_block_fptr + rs2_start_processing + rs2_start_processing_queue + rs2_start_processing_fptr + rs2_process_frame + rs2_delete_processing_block + rs2_create_sync_processing_block + rs2_create_pointcloud + rs2_create_colorizer + rs2_create_decimation_filter_block + rs2_create_temporal_filter_block + rs2_create_spatial_filter_block + rs2_create_hole_filling_filter_block + rs2_create_disparity_transform_block + rs2_embedded_frames_count + rs2_extract_frame + rs2_depth_frame_get_distance + rs2_depth_stereo_frame_get_baseline + + rs2_set_depth_control + rs2_get_depth_control + rs2_set_rsm + rs2_get_rsm + rs2_set_rau_support_vector_control + rs2_get_rau_support_vector_control + rs2_set_color_control + rs2_get_color_control + rs2_set_rau_thresholds_control + rs2_get_rau_thresholds_control + rs2_set_slo_color_thresholds_control + rs2_get_slo_color_thresholds_control + rs2_get_slo_penalty_control + rs2_set_slo_penalty_control + rs2_get_hdad + rs2_set_hdad + rs2_set_color_correction + rs2_get_color_correction + rs2_set_depth_table + rs2_get_depth_table + rs2_set_ae_control + rs2_get_ae_control + rs2_set_census + rs2_get_census + rs2_rs400_visual_preset_to_string + rs2_is_enabled + rs2_toggle_advanced_mode + rs2_load_json + rs2_serialize_json + + rs2_create_record_device + rs2_create_record_device_ex + rs2_record_device_pause + rs2_record_device_resume + rs2_record_device_filename + + rs2_context_add_device + rs2_context_remove_device + + rs2_playback_device_get_file_path + rs2_playback_get_duration + rs2_playback_seek + rs2_playback_get_position + rs2_playback_device_resume + rs2_playback_device_pause + rs2_playback_device_set_real_time + rs2_playback_device_is_real_time + rs2_playback_device_set_status_changed_callback + rs2_playback_device_get_current_status + rs2_playback_device_set_playback_speed + rs2_playback_device_stop + + rs2_create_align + + rs2_create_pipeline + rs2_pipeline_stop + rs2_pipeline_wait_for_frames + rs2_pipeline_poll_for_frames + rs2_pipeline_try_wait_for_frames + rs2_delete_pipeline + rs2_pipeline_start + rs2_pipeline_start_with_config + rs2_pipeline_get_active_profile + rs2_pipeline_profile_get_device + rs2_pipeline_profile_get_streams + rs2_delete_pipeline_profile + rs2_create_config + rs2_delete_config + rs2_config_enable_stream + rs2_config_enable_all_stream + rs2_config_enable_device + rs2_config_enable_device_from_file + rs2_config_enable_device_from_file_repeat_option + rs2_config_enable_record_to_file + rs2_config_disable_stream + rs2_config_disable_indexed_stream + rs2_config_disable_all_streams + rs2_config_resolve + rs2_config_can_resolve + + rs2_create_device_hub + rs2_device_hub_is_device_connected + rs2_device_hub_wait_for_device + rs2_delete_device_hub + + rs2_export_to_ply + rs2_create_software_device + rs2_software_device_add_sensor + rs2_software_sensor_on_video_frame + rs2_software_device_create_matcher + rs2_software_sensor_add_video_stream + rs2_software_sensor_add_read_only_option + rs2_software_sensor_update_read_only_option + rs2_software_sensor_set_metadata + + rs2_loopback_enable + rs2_loopback_disable + rs2_loopback_is_enabled + rs2_connect_tm2_controller + rs2_disconnect_tm2_controller diff --git a/src/rs.cpp b/src/rs.cpp index 398fbb937d1..6216b5c88cc 100644 --- a/src/rs.cpp +++ b/src/rs.cpp @@ -1295,6 +1295,16 @@ void rs2_playback_device_stop(const rs2_device* device, rs2_error** error) BEGIN HANDLE_EXCEPTIONS_AND_RETURN(, device) rs2_device* rs2_create_record_device(const rs2_device* device, const char* file, rs2_error** error) BEGIN_API_CALL +{ + VALIDATE_NOT_NULL(device); + VALIDATE_NOT_NULL(device->device); + VALIDATE_NOT_NULL(file); + + return rs2_create_record_device_ex(device, file, device->device->compress_while_record(), error); +} +HANDLE_EXCEPTIONS_AND_RETURN(nullptr, device, device->device, file) + +rs2_device* rs2_create_record_device_ex(const rs2_device* device, const char* file, int compression_enabled, rs2_error** error) BEGIN_API_CALL { VALIDATE_NOT_NULL(device); VALIDATE_NOT_NULL(file); @@ -1302,8 +1312,8 @@ rs2_device* rs2_create_record_device(const rs2_device* device, const char* file, return new rs2_device({ device->ctx, device->info, - std::make_shared(device->device, std::make_shared(file)) - }); + std::make_shared(device->device, std::make_shared(file, compression_enabled)) + }); } HANDLE_EXCEPTIONS_AND_RETURN(nullptr, device, file) diff --git a/src/tm2/tm-context.cpp b/src/tm2/tm-context.cpp index dfdb59935e1..d53043630fe 100644 --- a/src/tm2/tm-context.cpp +++ b/src/tm2/tm-context.cpp @@ -31,7 +31,7 @@ namespace librealsense [](perc::TrackingManager* ptr) { perc::TrackingManager::ReleaseInstance(ptr); }); if (_manager == nullptr) { - LOG_ERROR("Failed to create TrackingManager"); + LOG_DEBUG("Failed to create TrackingManager"); return; } _t = std::thread(&tm2_context::thread_proc, this); diff --git a/src/tm2/tm-device.h b/src/tm2/tm-device.h index 2afdcdbc819..e0195a4363a 100644 --- a/src/tm2/tm-device.h +++ b/src/tm2/tm-device.h @@ -33,6 +33,7 @@ namespace librealsense { return std::vector(); }; + bool compress_while_record() const override { return false; } private: static const char* tm2_device_name() {