38 #include "../include/librealsense2/h/rs_types.h" 58 std::vector<std::shared_ptr<stream_profile_interface>>
list;
71 parent(parent), sensor(sensor)
85 std::shared_ptr<librealsense::context>
ctx;
90 std::shared_ptr<librealsense::device_hub>
hub;
95 std::shared_ptr<librealsense::pipeline::pipeline>
pipeline;
100 std::shared_ptr<librealsense::pipeline::config>
config;
105 std::shared_ptr<librealsense::pipeline::profile>
profile;
157 std::lock_guard<std::mutex>
lock(_callback_mutex);
159 if (_callback)_callback->on_notification(¬i);
194 auto dev =
hub->hub->wait_for_device();
195 return new rs2_device{
hub->hub->get_context(), std::make_shared<readonly_device_info>(
dev),
dev };
218 std::vector<rs2_device_info> results;
224 results.push_back(
d);
240 std::vector<rs2_device_info> results;
244 for (
unsigned int i = 0;
i <
dev->get_sensors_count();
i++)
247 results.push_back(
d);
263 return static_cast<int>(list->list.size());
271 return static_cast<int>(list->dev.device->get_sensors_count());
295 info_list->list[
index].info,
296 info_list->list[
index].info->create_device()
315 &list->dev.device->get_sensor(
index)
356 return list->list[
index]->get_c_wrapper();
363 return static_cast<int>(list->list.size());
381 *
intr = vid->get_intrinsics();
393 : _callback( callback ), _user_arg( user_arg ) {}
401 _callback(
status, _user_arg );
405 std::cerr <<
"Received an execption from profile intrinsics callback!" << std::endl;
412 throw std::runtime_error(
"calibration_change_callback::release() ?!?!?!" );
425 d2r->register_calibration_change_callback(
426 std::make_shared< calibration_change_callback >(
callback, user )
439 d2r->register_calibration_change_callback(
451 cal->trigger_device_calibration(
type );
492 *framerate =
mode->profile->get_framerate();
494 *
index =
mode->profile->get_stream_index();
525 auto sp =
mode->profile->clone();
526 sp->set_stream_type(
stream);
527 sp->set_stream_index(stream_idx);
540 auto sp =
mode->profile->clone();
541 sp->set_stream_type(
stream);
542 sp->set_stream_index(
index);
547 vid->set_intrinsics([
i]() {
return i; });
560 auto raw_data_buffer =
static_cast<uint8_t*
>(raw_data_to_send);
561 std::vector<uint8_t> buffer_to_send(raw_data_buffer, raw_data_buffer + size_of_raw_data_to_send);
570 return buffer->buffer.data();
577 return static_cast<int>(
buffer->buffer.size());
593 std::vector<std::shared_ptr<stream_profile_interface>> request;
594 request.push_back(std::dynamic_pointer_cast<stream_profile_interface>(
profile->profile->shared_from_this()));
595 sensor->sensor->open(request);
605 std::vector<std::shared_ptr<stream_profile_interface>> request;
608 request.push_back(std::dynamic_pointer_cast<stream_profile_interface>(
profiles[
i]->
profile->shared_from_this()));
610 sensor->sensor->open(request);
624 return options->options->get_option(
option).is_read_only();
632 return options->options->get_option(
option).query();
654 return options->options->get_option_name(
option);
661 return int(options->list.size());
668 return options->list[
i];
682 return options->options->supports_option(
option);
695 auto range = options->options->get_option(
option).get_range();
707 if (
dev->device->supports_info(
info))
709 return dev->device->get_info(
info).c_str();
720 return dev->device->supports_info(
info);
730 return sensor->sensor->get_info(
info).c_str();
895 for (
auto info : info_list->list)
927 auto dev_info = std::make_shared<librealsense::readonly_device_info>(dev.shared_from_this());
951 return vf->get_width();
959 return vf->get_height();
967 return vf->get_stride();
982 return vf->get_bpp();
1011 return options->options->get_option(
option).get_description();
1026 return options->options->get_option(
option).get_value_description(
value);
1047 if (!queue->queue.dequeue(&fh, timeout_ms))
1049 throw std::runtime_error(
"Frame did not arrive in time!");
1063 if (queue->queue.try_dequeue(&fh))
1080 if (!queue->queue.dequeue(&fh, timeout_ms))
1106 queue->queue.clear();
1152 *p_params_out =
cs->get_dsm_params();
1162 cs->override_dsm_params( *p_params );
1171 cs->reset_calibration();
1234 roi->get_roi_method().set({ min_x, min_y, max_x, max_y });
1247 auto rect = roi->get_roi_method().get();
1249 *min_x =
rect.min_x;
1250 *min_y =
rect.min_y;
1251 *max_x =
rect.max_x;
1252 *max_y =
rect.max_y;
1335 _on_log(
severity, &msg, _user_arg );
1339 std::cerr <<
"Received an execption from log callback!" << std::endl;
1346 throw std::runtime_error(
"on_log_callback::release() ?!?!?!" );
1398 switch (extension_type)
1465 switch (extension_type)
1485 switch (extension_type)
1508 switch (extension_type)
1524 auto dev_info =
ctx->ctx->add_device(file);
1525 return new rs2_device{
ctx->ctx, dev_info, dev_info->create_device(
false) };
1535 ctx->ctx->add_software_device(software_dev->get_info());
1543 ctx->ctx->remove_device(file);
1551 ctx->ctx->unload_tracking_module();
1560 return playback->get_file_name().c_str();
1609 playback->set_real_time(real_time == 0 ?
false :
true);
1617 return playback->is_real_time() ? 1 : 0;
1636 return playback->get_current_status();
1674 std::make_shared<record_device>(
device->
device, std::make_shared<ros_writer>(file, compression_enabled))
1711 auto recovered_profile = std::dynamic_pointer_cast<
stream_profile_interface>(new_stream->profile->shared_from_this());
1713 return (
rs2_frame*)
source->source->allocate_video_frame(recovered_profile,
1714 (
frame_interface*)original, new_bpp, new_width, new_height, new_stride, frame_type);
1725 auto recovered_profile = std::dynamic_pointer_cast<
stream_profile_interface>(new_stream->profile->shared_from_this());
1727 return (
rs2_frame*)
source->source->allocate_motion_frame(recovered_profile,
1738 auto recovered_profile = std::dynamic_pointer_cast<
stream_profile_interface>(new_stream->profile->shared_from_this());
1760 auto pipe = std::make_shared<pipeline::pipeline>(
ctx->ctx);
1770 pipe->pipeline->stop();
1778 auto f =
pipe->pipeline->wait_for_frames(timeout_ms);
1791 if (
pipe->pipeline->poll_for_frames(&fh))
1808 if (
pipe->pipeline->try_wait_for_frames(&fh, timeout_ms))
1876 { callback, [](rs2_frame_callback* p) { p->release(); } }) };
1892 auto dev =
profile->profile->get_device();
1893 auto dev_info = std::make_shared<librealsense::readonly_device_info>(
dev);
1916 return new rs2_config{ std::make_shared<pipeline::config>() };
1945 config->config->enable_all_stream();
1954 config->config->enable_device(serial);
1973 config->config->enable_device_from_file(file,
true);
1982 config->config->enable_record_to_file(file);
2003 config->config->disable_all_streams();
2019 return config->config->can_resolve(
pipe->pipeline) ? 1 : 0;
2025 auto block = std::make_shared<librealsense::processing_block>(
"Custom processing block");
2036 auto block = std::make_shared<librealsense::processing_block>(
"Custom processing block");
2038 block->set_processing_callback({
2053 if (block->options->supports_option(option_id))
return false;
2054 std::shared_ptr<option> opt = std::make_shared<float_option>(
option_range{
min, max, step, def });
2064 auto block = std::make_shared<librealsense::syncer_process_unit>();
2133 std::vector<frame_holder> holders(
count);
2150 return static_cast<int>(cf->get_embedded_frames_count());
2223 auto block = std::make_shared<librealsense::colorizer>();
2234 auto block = std::make_shared<librealsense::decimation_filter>();
2242 auto block = std::make_shared<librealsense::temporal_filter>();
2250 auto block = std::make_shared<librealsense::spatial_filter>();
2258 auto block = std::make_shared<librealsense::disparity_transform>(transform_to_disparity > 0);
2266 auto block = std::make_shared<librealsense::hole_filling_filter>();
2274 auto block = std::make_shared<librealsense::rates_printer>();
2282 auto block = std::make_shared<librealsense::zero_order>();
2290 auto block = std::make_shared<librealsense::depth_decompression_huffman>();
2298 auto block = std::make_shared<librealsense::hdr_merge>();
2306 auto block = std::make_shared<librealsense::sequence_id_filter>();
2316 return ds->get_depth_scale();
2325 return murs->get_max_usable_depth_range();
2334 return ds->get_stereo_baseline_mm();
2352 return df->get_distance(
x,
y);
2360 return df->get_units();
2368 return df->get_stereo_baseline();
2379 const float3 t = pf->get_translation();
2380 pose->translation = { t.
x, t.
y, t.
z };
2382 const float3 v = pf->get_velocity();
2383 pose->velocity = { v.
x, v.
y, v.
z };
2385 const float3 a = pf->get_acceleration();
2386 pose->acceleration = { a.
x, a.
y, a.
z };
2388 const float4 r = pf->get_rotation();
2389 pose->rotation = { r.
x, r.
y, r.
z, r.
w };
2391 const float3 av = pf->get_angular_velocity();
2392 pose->angular_velocity = { av.
x, av.
y, av.
z };
2394 const float3 aa = pf->get_angular_acceleration();
2395 pose->angular_acceleration = { aa.
x, aa.
y, aa.
z };
2397 pose->tracker_confidence = pf->get_tracker_confidence();
2398 pose->mapper_confidence = pf->get_mapper_confidence();
2409 throw std::runtime_error(
"wrong video frame format");
2411 std::shared_ptr<target_calculator_interface> target_calculator;
2413 target_calculator = std::make_shared<rect_gaussian_dots_target_calculator>(vf->get_width(), vf->get_height());
2415 throw std::runtime_error(
"unsupported calibration target type");
2417 if (!target_calculator->calculate(vf->get_frame_data(), target_dims, target_dims_size))
2418 throw std::runtime_error(
"Failed to find the four rectangle side sizes on the frame");
2430 auto dev = std::make_shared<software_device>();
2439 df->set_matcher_type(
m);
2455 if (df->supports_info(
info))
2470 &df->add_software_sensor(sensor_name));
2478 return bs->on_video_frame(
frame);
2486 return bs->on_motion_frame(
frame);
2494 return bs->on_pose_frame(
frame);
2502 return bs->on_notification(notif);
2510 return bs->set_metadata(
key,
value);
2518 return bs->add_video_stream(video_stream)->get_c_wrapper();
2526 return bs->add_video_stream(video_stream, is_default)->get_c_wrapper();
2528 HANDLE_EXCEPTIONS_AND_RETURN(0,
sensor, video_stream.type, video_stream.index, video_stream.fmt, video_stream.width, video_stream.height, video_stream.uid, is_default)
2534 return bs->add_motion_stream(motion_stream)->get_c_wrapper();
2542 return bs->add_motion_stream(motion_stream, is_default)->get_c_wrapper();
2550 return bs->add_pose_stream(pose_stream)->get_c_wrapper();
2558 return bs->add_pose_stream(pose_stream, is_default)->get_c_wrapper();
2566 return bs->add_read_only_option(
option,
val);
2574 return bs->update_read_only_option(
option,
val);
2594 sensor->parent.ctx.reset();
2595 sensor->parent.info.reset();
2596 sensor->parent.device.reset();
2635 loopback->enable_loopback(from_file);
2645 loopback->disable_loopback();
2654 return loopback->is_enabled() ? 1 : 0;
2664 tm2->connect_controller({ mac[0], mac[1], mac[2], mac[3], mac[4], mac[5] });
2673 tm2->disconnect_controller(
id);
2706 auto from_dev = from_sensor->parent.device;
2707 if (!from_dev) from_dev = from_sensor->sensor->get_device().shared_from_this();
2708 auto to_dev = to_sensor->parent.device;
2709 if (!to_dev) to_dev = to_sensor->sensor->get_device().shared_from_this();
2711 if (from_dev != to_dev)
2713 LOG_ERROR(
"Cannot set extrinsics of two different devices \n");
2738 tm2->reset_to_factory_calibration();
2743 throw std::runtime_error(
"this device does not supports reset to factory calibration");
2744 auto_calib->reset_to_factory_calibration();
2754 tm2->write_calibration();
2759 throw std::runtime_error(
"this device does not supports auto calibration");
2760 auto_calib->write_calibration();
2784 return static_cast<int>(list->list.size());
2799 if (block->block->supports_info(
info))
2801 return block->block->get_info(
info).c_str();
2811 return block->block->supports_info(
info);
2819 VALIDATE_RANGE(blob_size,1, std::numeric_limits<uint32_t>::max());
2823 std::vector<uint8_t> buffer_to_send(lmap_blob, lmap_blob + blob_size);
2824 return (
int)pose_snr->import_relocalization_map(buffer_to_send);
2833 std::vector<uint8_t> recv_buffer;
2834 if (pose_snr->export_relocalization_map(recv_buffer))
2848 return int(pose_snr->set_static_node(s_guid, { pos.x, pos.y, pos.z }, { orient.x, orient.y, orient.z, orient.w }));
2865 if ((ret = pose_snr->get_static_node(s_guid, t_pos, t_or)))
2887 return int(pose_snr->remove_static_node(s_guid));
2895 VALIDATE_RANGE(blob_size, 1, std::numeric_limits<uint32_t>::max());
2899 std::vector<uint8_t> buffer_to_send(odometry_blob, odometry_blob + blob_size);
2900 int ret = wo_snr->load_wheel_odometery_config(buffer_to_send);
2913 return wo_snr->send_wheel_odometry(
wo_sensor_id,
frame_num, { translational_velocity.x, translational_velocity.y, translational_velocity.z });
2926 fwu->update(fw_image, fw_image_size,
nullptr);
2938 if (fw_image_size <= 0)
2939 throw std::runtime_error(
"invlid firmware image size provided to rs2_update");
2944 fwu->update(fw_image, fw_image_size,
nullptr);
2949 fwu->update(fw_image, fw_image_size,
std::move(cb));
2960 throw std::runtime_error(
"This device does not supports update protocol!");
2962 std::vector<uint8_t>
res;
2965 res = fwud->backup_flash(
nullptr);
2979 throw std::runtime_error(
"This device does not supports update protocol!");
2981 std::vector<uint8_t>
res;
2984 res = fwud->backup_flash(
nullptr);
3004 throw std::runtime_error(
"This device does not supports update protocol!");
3009 fwud->update_flash(
buffer,
nullptr, update_mode);
3021 if (image_size <= 0)
3022 throw std::runtime_error(
"invlid firmware image size provided to rs2_update_firmware_unsigned");
3026 throw std::runtime_error(
"This device does not supports update protocol!");
3031 fwud->update_flash(
buffer,
nullptr, update_mode);
3047 throw std::runtime_error(
"this device does not supports fw update");
3048 fwud->enter_update_state();
3057 if (content_size > 0)
3062 std::vector<uint8_t>
buffer;
3064 std::string json((
char*)json_content, (
char*)json_content + content_size);
3065 if (progress_callback ==
nullptr)
3066 buffer = auto_calib->run_on_chip_calibration(timeout_ms,
json, health,
nullptr);
3079 if (content_size > 0)
3084 std::vector<uint8_t>
buffer;
3086 std::string json((
char*)json_content, (
char*)json_content + content_size);
3088 if (progress_callback ==
nullptr)
3089 buffer = auto_calib->run_on_chip_calibration(timeout_ms,
json, health,
nullptr);
3095 buffer = auto_calib->run_on_chip_calibration(timeout_ms,
json, health, cb);
3106 if(content_size > 0)
3111 std::vector<uint8_t>
buffer;
3112 std::string json((
char*)json_content, (
char*)json_content + content_size);
3113 if (progress_callback ==
nullptr)
3114 buffer = auto_calib->run_tare_calibration(timeout_ms, ground_truth_mm,
json,
nullptr);
3126 if (content_size > 0)
3131 std::vector<uint8_t>
buffer;
3132 std::string json((
char*)json_content, (
char*)json_content + content_size);
3134 if (progress_callback ==
nullptr)
3135 buffer = auto_calib->run_tare_calibration(timeout_ms, ground_truth_mm,
json,
nullptr);
3141 buffer = auto_calib->run_tare_calibration(timeout_ms, ground_truth_mm,
json, cb);
3152 auto buffer = auto_calib->get_calibration_table();
3165 auto_calib->set_calibration_table(
buffer);
3182 serializable->load_json(
std::string(static_cast<const char*>(json_content), content_size));
3202 bool result =
fw_logger->get_fw_log(binary_data);
3205 *(fw_log_msg->firmware_log_binary_data).
get() = binary_data;
3207 return result? 1 : 0;
3218 bool result =
fw_logger->get_flash_log(binary_data);
3221 *(fw_log_msg->firmware_log_binary_data).
get() = binary_data;
3223 return result ? 1 : 0;
3236 return msg->firmware_log_binary_data->logs_buffer.data();
3243 return (
int)msg->firmware_log_binary_data->logs_buffer.size();
3249 return msg->firmware_log_binary_data->get_severity();
3256 return msg->firmware_log_binary_data->get_timestamp();
3266 return (
fw_logger->init_parser(xml_content)) ? 1 : 0;
3288 bool parsing_result =
fw_logger->parse_log(fw_log_msg->firmware_log_binary_data.get(),
3289 parsed_msg->firmware_log_parsed.get());
3291 return parsing_result ? 1 : 0;
3300 return fw_logger->get_number_of_fw_logs();
3307 delete fw_log_parsed_msg;
3314 return fw_log_parsed_msg->firmware_log_parsed->get_message().c_str();
3321 return fw_log_parsed_msg->firmware_log_parsed->get_file_name().c_str();
3328 return fw_log_parsed_msg->firmware_log_parsed->get_thread_name().c_str();
3335 return fw_log_parsed_msg->firmware_log_parsed->get_severity();
3342 return fw_log_parsed_msg->firmware_log_parsed->get_line();
3349 return fw_log_parsed_msg->firmware_log_parsed->get_timestamp();
3356 return fw_log_parsed_msg->firmware_log_parsed->get_sequence_id();
3382 command_string.insert(command_string.begin(),
command,
command + size_of_command);
3390 const
char*
command,
unsigned int size_of_command,
3401 command_string.insert(command_string.begin(),
command,
command + size_of_command);
3403 std::vector<uint8_t> response_vec;
3404 response_vec.insert(response_vec.begin(), (
uint8_t*)response, (
uint8_t*)response + size_of_response);
void rs2_config_enable_stream(rs2_config *config, rs2_stream stream, int index, int width, int height, rs2_format format, int framerate, rs2_error **error) BEGIN_API_CALL
int rs2_playback_device_is_real_time(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
rs2_sensor(rs2_device parent, librealsense::sensor_interface *sensor)
void rs2_software_device_update_info(rs2_device *dev, rs2_camera_info info, const char *val, rs2_error **error) BEGIN_API_CALL
void rs2_delete_raw_data(const rs2_raw_data_buffer *buffer) BEGIN_API_CALL
int rs2_loopback_is_enabled(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
static const textual_icon lock
void rs2_set_motion_device_intrinsics(const rs2_sensor *sensor, const rs2_stream_profile *profile, const rs2_motion_device_intrinsic *intrinsics, rs2_error **error) BEGIN_API_CALL
rs2_time_t rs2_get_frame_timestamp(const rs2_frame *frame_ref, rs2_error **error) BEGIN_API_CALL
const void * rs2_get_frame_data(const rs2_frame *frame_ref, rs2_error **error) BEGIN_API_CALL
GLenum GLuint GLenum GLsizei const GLchar * message
rs2_options_list * rs2_get_options_list(const rs2_options *options, rs2_error **error) BEGIN_API_CALL
rs2_camera_info
Read-only strings that can be queried from the device. Not all information attributes are available o...
rs2_metadata_type rs2_get_frame_metadata(const rs2_frame *frame, rs2_frame_metadata_value frame_metadata, rs2_error **error) BEGIN_API_CALL
void rs2_trigger_device_calibration(rs2_device *dev, rs2_calibration_type type, rs2_error **error) BEGIN_API_CALL
rs2_log_callback_ptr _on_log
void rs2_config_enable_device_from_file_repeat_option(rs2_config *config, const char *file, int repeat_playback, rs2_error **error) BEGIN_API_CALL
void rs2_delete_frame_queue(rs2_frame_queue *queue) BEGIN_API_CALL
const char * rs2_log_severity_to_string(rs2_log_severity severity)
rs2_frame * rs2_allocate_synthetic_video_frame(rs2_source *source, const rs2_stream_profile *new_stream, rs2_frame *original, int new_bpp, int new_width, int new_height, int new_stride, rs2_extension frame_type, rs2_error **error) BEGIN_API_CALL
const char * rs2_extension_to_string(rs2_extension type)
void rs2_software_sensor_update_read_only_option(rs2_sensor *sensor, rs2_option option, float val, rs2_error **error) BEGIN_API_CALL
int rs2_get_stream_profiles_count(const rs2_stream_profile_list *list, rs2_error **error) BEGIN_API_CALL
rs2_processing_block * rs2_get_processing_block(const rs2_processing_block_list *list, int index, rs2_error **error) BEGIN_API_CALL
const rs2_raw_data_buffer * rs2_run_tare_calibration(rs2_device *device, float ground_truth_mm, const void *json_content, int content_size, rs2_update_progress_callback_ptr progress_callback, void *user, int timeout_ms, rs2_error **error) BEGIN_API_CALL
void rs2_set_option(const rs2_options *options, rs2_option option, float value, rs2_error **error) BEGIN_API_CALL
rs2_processing_block * rs2_create_spatial_filter_block(rs2_error **error) BEGIN_API_CALL
rs2_log_severity rs2_get_fw_log_parsed_severity(rs2_firmware_log_parsed_message *fw_log_parsed_msg, rs2_error **error) BEGIN_API_CALL
Gets RealSense firmware log parsed message severity.
rs2_processing_block * rs2_create_zero_order_invalidation_block(rs2_error **error) BEGIN_API_CALL
rs2_exception_type
Exception types are the different categories of errors that RealSense API might return.
rs2_processing_block * rs2_create_decimation_filter_block(rs2_error **error) BEGIN_API_CALL
::realsense_legacy_msgs::extrinsics_< std::allocator< void > > extrinsics
GLenum GLuint GLenum severity
const char * get_log_message_filename() const
const char * get_string(rs2_rs400_visual_preset value)
const char * rs2_notification_category_to_string(rs2_notification_category category)
const int unsigned_fw_size
rs2_calibration_change_callback_ptr _callback
typedef void(APIENTRY *GLDEBUGPROC)(GLenum source
void rs2_set_notifications_callback_cpp(const rs2_sensor *sensor, rs2_notifications_callback *callback, rs2_error **error) BEGIN_API_CALL
const char * rs2_ambient_light_to_string(rs2_ambient_light ambient)
GLuint const GLchar * name
float rs2_depth_frame_get_units(const rs2_frame *frame_ref, rs2_error **error) BEGIN_API_CALL
rs2_processing_block_list * rs2_get_recommended_processing_blocks(rs2_sensor *sensor, rs2_error **error) BEGIN_API_CALL
void rs2_delete_processing_block(rs2_processing_block *block) BEGIN_API_CALL
rs2_playback_status rs2_playback_device_get_current_status(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
void rs2_start_cpp(const rs2_sensor *sensor, rs2_frame_callback *callback, rs2_error **error) BEGIN_API_CALL
#define RS2_API_MAJOR_VERSION
float rs2_depth_stereo_frame_get_baseline(const rs2_frame *frame_ref, rs2_error **error) BEGIN_API_CALL
unsigned int rs2_get_fw_log_parsed_timestamp(rs2_firmware_log_parsed_message *fw_log_parsed_msg, rs2_error **error) BEGIN_API_CALL
Gets RealSense firmware log parsed message timestamp.
void rs2_context_add_software_device(rs2_context *ctx, rs2_device *dev, rs2_error **error) BEGIN_API_CALL
void rs2_extract_target_dimensions(const rs2_frame *frame_ref, rs2_calib_target_type calib_type, float *target_dims, unsigned int target_dims_size, rs2_error **error) BEGIN_API_CALL
rs2_time_t rs2_get_notification_timestamp(rs2_notification *notification, rs2_error **error) BEGIN_API_CALL
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls...
unsigned int rs2_get_fw_log_parsed_line(rs2_firmware_log_parsed_message *fw_log_parsed_msg, rs2_error **error) BEGIN_API_CALL
Gets RealSense firmware log parsed message relevant line (in the file that is returned by rs2_get_fw_...
std::shared_ptr< platform::time_service > get_time_service()
int rs2_supports_frame_metadata(const rs2_frame *frame, rs2_frame_metadata_value frame_metadata, rs2_error **error) BEGIN_API_CALL
void rs2_pose_frame_get_pose_data(const rs2_frame *frame, rs2_pose *pose, rs2_error **error) BEGIN_API_CALL
rs2_processing_block * rs2_create_temporal_filter_block(rs2_error **error) BEGIN_API_CALL
const char * get_full_log_message()
rs2_notification_category category
void rs2_delete_recommended_processing_blocks(rs2_processing_block_list *list) BEGIN_API_CALL
const char * rs2_get_option_value_description(const rs2_options *options, rs2_option option, float value, rs2_error **error) BEGIN_API_CALL
void(* rs2_frame_processor_callback_ptr)(rs2_frame *, rs2_source *, void *)
float2 * get_texture_coordinates()
std::shared_ptr< rs2_frame_callback > frame_callback_ptr
rs2_pipeline_profile * rs2_config_resolve(rs2_config *config, rs2_pipeline *pipe, rs2_error **error) BEGIN_API_CALL
std::shared_ptr< librealsense::pipeline::profile > profile
rs2_pixel * rs2_get_frame_texture_coordinates(const rs2_frame *frame, rs2_error **error) BEGIN_API_CALL
struct rs2_frame_queue rs2_frame_queue
void rs2_playback_device_stop(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
void rs2_software_device_create_matcher(rs2_device *dev, rs2_matchers m, rs2_error **error) BEGIN_API_CALL
rs2_distortion
Distortion model: defines how pixel coordinates should be mapped to sensor coordinates.
int rs2_is_sensor_extendable_to(const rs2_sensor *sensor, rs2_extension extension_type, rs2_error **error) BEGIN_API_CALL
const char * rs2_cah_trigger_to_string(rs2_cah_trigger mode)
int rs2_get_static_node(const rs2_sensor *sensor, const char *guid, rs2_vector *pos, rs2_quaternion *orient, rs2_error **error) BEGIN_API_CALL
void log_to_callback(rs2_log_severity min_severity, log_callback_ptr callback)
rs2_processing_block * rs2_create_units_transform(rs2_error **error) BEGIN_API_CALL
void rs2_set_devices_changed_callback(const rs2_context *context, rs2_devices_changed_callback_ptr callback, void *user, rs2_error **error) BEGIN_API_CALL
rs2_sr300_visual_preset
For SR300 devices: provides optimized settings (presets) for specific types of usage.
on_log_callback(rs2_log_callback_ptr on_log, void *user_arg)
std::shared_ptr< librealsense::fw_logs::fw_logs_binary_data > firmware_log_binary_data
a class to store JSON values
Video DSM (Digital Sync Module) parameters for calibration (same layout as in FW ac_depth_params) Thi...
std::vector< std::shared_ptr< device_info > > query_devices(int mask) const
int rs2_poll_for_frame(rs2_frame_queue *queue, rs2_frame **output_frame, rs2_error **error) BEGIN_API_CALL
void rs2_frame_add_ref(rs2_frame *frame, rs2_error **error) BEGIN_API_CALL
void rs2_delete_context(rs2_context *context) BEGIN_API_CALL
Frees the relevant context object.
int rs2_is_stream_profile_default(const rs2_stream_profile *profile, rs2_error **error) BEGIN_API_CALL
rs2_sensor_list * rs2_query_sensors(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
void rs2_delete_device(rs2_device *device) BEGIN_API_CALL
std::shared_ptr< librealsense::fw_logs::fw_log_data > firmware_log_parsed
void rs2_free_error(rs2_error *error)
void rs2_enable_rolling_log_file(unsigned max_size, rs2_error **error) BEGIN_API_CALL
std::shared_ptr< librealsense::pipeline::config > config
All the parameters required to define a video stream.
rs2_sensor * rs2_create_sensor(const rs2_sensor_list *list, int index, rs2_error **error) BEGIN_API_CALL
const char * rs2_exception_type_to_string(rs2_exception_type type)
void rs2_software_sensor_add_option(rs2_sensor *sensor, rs2_option option, float min, float max, float step, float def, int is_writable, rs2_error **error) BEGIN_API_CALL
All the parameters required to define a pose frame.
int rs2_set_static_node(const rs2_sensor *sensor, const char *guid, const rs2_vector pos, const rs2_quaternion orient, rs2_error **error) BEGIN_API_CALL
rs2_calib_target_type
Calibration target type.
rs2_timestamp_domain rs2_get_frame_timestamp_domain(const rs2_frame *frame_ref, rs2_error **error) BEGIN_API_CALL
std::function< void(frame_interface *)> on_frame
rs2_processing_block * rs2_create_huffman_depth_decompress_block(rs2_error **error) BEGIN_API_CALL
void rs2_reset_logger(rs2_error **error) BEGIN_API_CALL
void rs2_enqueue_frame(rs2_frame *frame, void *queue) BEGIN_API_CALL
void rs2_software_sensor_detach(rs2_sensor *sensor, rs2_error **error) BEGIN_API_CALL
#define VALIDATE_FIXED_SIZE(ARG, SIZE)
virtual std::vector< uint8_t > send_receive_raw_data(const std::vector< uint8_t > &input)=0
float rs2_get_max_usable_depth_range(rs2_sensor const *sensor, rs2_error **error) BEGIN_API_CALL
void rs2_update_firmware_cpp(const rs2_device *device, const void *fw_image, int fw_image_size, rs2_update_progress_callback *callback, rs2_error **error) BEGIN_API_CALL
const char * rs2_l500_visual_preset_to_string(rs2_l500_visual_preset preset)
void verify_version_compatibility(int api_version)
const char * rs2_get_fw_log_parsed_file_name(rs2_firmware_log_parsed_message *fw_log_parsed_msg, rs2_error **error) BEGIN_API_CALL
Gets RealSense firmware log parsed message file name.
rs2_context * rs2_create_mock_context(int api_version, const char *filename, const char *section, rs2_error **error) BEGIN_API_CALL
rs2_terminal_parser * rs2_create_terminal_parser(const char *xml_content, rs2_error **error) BEGIN_API_CALL
Creates RealSense terminal parser.
int rs2_supports_processing_block_info(const rs2_processing_block *block, rs2_camera_info info, rs2_error **error) BEGIN_API_CALL
const rs2_stream_profile * rs2_get_stream_profile(const rs2_stream_profile_list *list, int index, rs2_error **error) BEGIN_API_CALL
const char * rs2_sensor_mode_to_string(rs2_sensor_mode mode)
void rs2_log(rs2_log_severity severity, const char *message, rs2_error **error) BEGIN_API_CALL
GLsizei const GLchar *const * string
void export_to_ply(const std::string &fname, const frame_holder &texture)
3D coordinates with origin at topmost left corner of the lense, with positive Z pointing away from th...
rs2_processing_block * rs2_create_rates_printer_block(rs2_error **error) BEGIN_API_CALL
rs2_stream_profile * rs2_software_sensor_add_pose_stream_ex(rs2_sensor *sensor, rs2_pose_stream pose_stream, int is_default, rs2_error **error) BEGIN_API_CALL
void log_to_file(rs2_log_severity min_severity, const char *file_path)
rs2_device * rs2_create_record_device_ex(const rs2_device *device, const char *file, int compression_enabled, rs2_error **error) BEGIN_API_CALL
rs2_host_perf_mode
values for RS2_OPTION_HOST_PERFORMANCE option.
int rs2_get_recommended_processing_blocks_count(const rs2_processing_block_list *list, rs2_error **error) BEGIN_API_CALL
void rs2_delete_sensor(rs2_sensor *device) BEGIN_API_CALL
rs2_exception_type exception_type
void rs2_delete_options_list(rs2_options_list *list) BEGIN_API_CALL
const char * rs2_get_error_message(const rs2_error *error)
void rs2_set_region_of_interest(const rs2_sensor *sensor, int min_x, int min_y, int max_x, int max_y, rs2_error **error) BEGIN_API_CALL
sets the active region of interest to be used by auto-exposure algorithm
rs2_device * rs2_context_add_device(rs2_context *ctx, const char *file, rs2_error **error) BEGIN_API_CALL
const char * rs2_stream_to_string(rs2_stream stream)
std::shared_ptr< librealsense::terminal_parser > terminal_parser
void rs2_context_remove_device(rs2_context *ctx, const char *file, rs2_error **error) BEGIN_API_CALL
void rs2_get_extrinsics(const rs2_stream_profile *from, const rs2_stream_profile *to, rs2_extrinsics *extrin, rs2_error **error) BEGIN_API_CALL
void rs2_reset_sensor_calibration(rs2_sensor const *sensor, rs2_error **error) BEGIN_API_CALL
int rs2_embedded_frames_count(rs2_frame *composite, rs2_error **error) BEGIN_API_CALL
void rs2_software_sensor_on_video_frame(rs2_sensor *sensor, rs2_software_video_frame frame, rs2_error **error) BEGIN_API_CALL
rs2_cah_trigger
values for RS2_OPTION_TRIGGER_CAMERA_ACCURACY_HEALTH option.
rs2_pipeline_profile * rs2_pipeline_start_with_config_and_callback_cpp(rs2_pipeline *pipe, rs2_config *config, rs2_frame_callback *callback, rs2_error **error) BEGIN_API_CALL
int rs2_get_sensors_count(const rs2_sensor_list *list, rs2_error **error) BEGIN_API_CALL
void(* rs2_log_callback_ptr)(rs2_log_severity, rs2_log_message const *, void *arg)
struct rs2_sensor rs2_sensor
int rs2_pipeline_poll_for_frames(rs2_pipeline *pipe, rs2_frame **output_frame, rs2_error **error) BEGIN_API_CALL
GLenum GLenum GLsizei void * image
#define RS2_API_MINOR_VERSION
rs2_config * rs2_create_config(rs2_error **error) BEGIN_API_CALL
status
Defines return codes that SDK interfaces use. Negative values indicate errors, a zero value indicates...
void rs2_start_processing_queue(rs2_processing_block *block, rs2_frame_queue *queue, rs2_error **error) BEGIN_API_CALL
void rs2_override_dsm_params(const rs2_sensor *sensor, rs2_dsm_params const *p_params, rs2_error **error) BEGIN_API_CALL
rs2_firmware_log_parsed_message * rs2_create_fw_log_parsed_message(rs2_device *dev, rs2_error **error) BEGIN_API_CALL
Creates RealSense firmware log parsed message.
void rs2_log_to_callback_cpp(rs2_log_severity min_severity, rs2_log_callback *callback, rs2_error **error) BEGIN_API_CALL
void rs2_delete_fw_log_parsed_message(rs2_firmware_log_parsed_message *fw_log_parsed_msg) BEGIN_API_CALL
Deletes RealSense firmware log parsed message.
rs2_frame * rs2_allocate_points(rs2_source *source, const rs2_stream_profile *new_stream, rs2_frame *original, rs2_error **error) BEGIN_API_CALL
void register_option(rs2_option id, std::shared_ptr< option > option)
const char * rs2_get_raw_log_message(rs2_log_message const *msg, rs2_error **error) BEGIN_API_CALL
int rs2_pipeline_try_wait_for_frames(rs2_pipeline *pipe, rs2_frame **output_frame, unsigned int timeout_ms, rs2_error **error) BEGIN_API_CALL
const char * rs2_distortion_to_string(rs2_distortion distortion)
void(* rs2_update_progress_callback_ptr)(const float, void *)
std::shared_ptr< rs2_update_progress_callback > update_progress_callback_ptr
GLboolean GLboolean GLboolean GLboolean a
int rs2_get_frame_width(const rs2_frame *frame_ref, rs2_error **error) BEGIN_API_CALL
void rs2_update_firmware(const rs2_device *device, const void *fw_image, int fw_image_size, rs2_update_progress_callback_ptr callback, void *client_data, rs2_error **error) BEGIN_API_CALL
rs2_context * rs2_create_recording_context(int api_version, const char *filename, const char *section, rs2_recording_mode mode, rs2_error **error) BEGIN_API_CALL
rs2_processing_block * rs2_create_threshold(rs2_error **error) BEGIN_API_CALL
rs2_raw_data_buffer * rs2_terminal_parse_command(rs2_terminal_parser *terminal_parser, const char *command, unsigned int size_of_command, rs2_error **error) BEGIN_API_CALL
Parses terminal command via RealSense terminal parser.
#define RS2_API_PATCH_VERSION
rs2_processing_block * rs2_create_sequence_id_filter(rs2_error **error) BEGIN_API_CALL
void rs2_software_sensor_on_motion_frame(rs2_sensor *sensor, rs2_software_motion_frame frame, rs2_error **error) BEGIN_API_CALL
void rs2_load_json(rs2_device *dev, const void *json_content, unsigned content_size, rs2_error **error) BEGIN_API_CALL
const char * rs2_sr300_visual_preset_to_string(rs2_sr300_visual_preset preset)
def info(name, value, persistent=False)
rs2_notification_category rs2_get_notification_category(rs2_notification *notification, rs2_error **error) BEGIN_API_CALL
const char * rs2_get_device_info(const rs2_device *dev, rs2_camera_info info, rs2_error **error) BEGIN_API_CALL
Quaternion used to represent rotation.
std::shared_ptr< rs2_log_callback > log_callback_ptr
rs2_context * rs2_create_mock_context_versioned(int api_version, const char *filename, const char *section, const char *min_api_version, rs2_error **error) BEGIN_API_CALL
rs2_device_list * rs2_query_devices_ex(const rs2_context *context, int product_mask, rs2_error **error) BEGIN_API_CALL
const char * rs2_get_notification_serialized_data(rs2_notification *notification, rs2_error **error) BEGIN_API_CALL
rs2_exception_type rs2_get_librealsense_exception_type(const rs2_error *error)
rs2_processing_block * rs2_create_pointcloud(rs2_error **error) BEGIN_API_CALL
rs2_device * rs2_create_record_device(const rs2_device *device, const char *file, rs2_error **error) BEGIN_API_CALL
const rs2_raw_data_buffer * rs2_run_on_chip_calibration(rs2_device *device, const void *json_content, int content_size, float *health, rs2_update_progress_callback_ptr progress_callback, void *user, int timeout_ms, rs2_error **error) BEGIN_API_CALL
void rs2_hardware_reset(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
const rs2_stream_profile * rs2_get_frame_stream_profile(const rs2_frame *frame_ref, rs2_error **error) BEGIN_API_CALL
void rs2_log_to_console(rs2_log_severity min_severity, rs2_error **error) BEGIN_API_CALL
void register_extrinsics(const stream_interface &from, const stream_interface &to, std::weak_ptr< lazy< rs2_extrinsics >> extr)
void rs2_record_device_pause(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
rs2_stream_profile * rs2_software_sensor_add_motion_stream(rs2_sensor *sensor, rs2_motion_stream motion_stream, rs2_error **error) BEGIN_API_CALL
void rs2_process_frame(rs2_processing_block *block, rs2_frame *frame, rs2_error **error) BEGIN_API_CALL
static std::shared_ptr< pointcloud > create()
rs2_stream_profile * rs2_software_sensor_add_video_stream(rs2_sensor *sensor, rs2_video_stream video_stream, rs2_error **error) BEGIN_API_CALL
const char * rs2_get_fw_log_parsed_message(rs2_firmware_log_parsed_message *fw_log_parsed_msg, rs2_error **error) BEGIN_API_CALL
Gets RealSense firmware log parsed message.
const char * rs2_get_notification_description(rs2_notification *notification, rs2_error **error) BEGIN_API_CALL
const char * rs2_get_sensor_info(const rs2_sensor *sensor, rs2_camera_info info, rs2_error **error) BEGIN_API_CALL
rs2_pipeline_profile * rs2_pipeline_start(rs2_pipeline *pipe, rs2_error **error) BEGIN_API_CALL
void rs2_software_sensor_on_pose_frame(rs2_sensor *sensor, rs2_software_pose_frame frame, rs2_error **error) BEGIN_API_CALL
rs2_stream_profile * rs2_clone_video_stream_profile(const rs2_stream_profile *mode, rs2_stream stream, int index, rs2_format format, int width, int height, const rs2_intrinsics *intr, rs2_error **error) BEGIN_API_CALL
virtual std::shared_ptr< context > get_context() const =0
#define HANDLE_EXCEPTIONS_AND_RETURN(R,...)
void rs2_delete_terminal_parser(rs2_terminal_parser *terminal_parser) BEGIN_API_CALL
Deletes RealSense terminal parser.
void rs2_synthetic_frame_ready(rs2_source *source, rs2_frame *frame, rs2_error **error) BEGIN_API_CALL
librealsense::sensor_interface * sensor
void rs2_close(const rs2_sensor *sensor, rs2_error **error) BEGIN_API_CALL
unsigned rs2_get_log_message_line_number(rs2_log_message const *msg, rs2_error **error) BEGIN_API_CALL
#define VALIDATE_INTERFACE_NO_THROW(X, T)
int rs2_is_processing_block_extendable_to(const rs2_processing_block *f, rs2_extension extension_type, rs2_error **error) BEGIN_API_CALL
const char * rs2_option_to_string(rs2_option option)
const char * rs2_playback_status_to_string(rs2_playback_status status)
const char * rs2_get_log_message_filename(rs2_log_message const *msg, rs2_error **error) BEGIN_API_CALL
rs2_stream_profile * rs2_software_sensor_add_pose_stream(rs2_sensor *sensor, rs2_pose_stream pose_stream, rs2_error **error) BEGIN_API_CALL
rs2_processing_block * rs2_create_yuy_decoder(rs2_error **error) BEGIN_API_CALL
int rs2_get_options_list_size(const rs2_options_list *options, rs2_error **error) BEGIN_API_CALL
void rs2_playback_device_set_real_time(const rs2_device *device, int real_time, rs2_error **error) BEGIN_API_CALL
rs2_pipeline * rs2_create_pipeline(rs2_context *ctx, rs2_error **error) BEGIN_API_CALL
rs2_device * rs2_device_hub_wait_for_device(const rs2_device_hub *hub, rs2_error **error) BEGIN_API_CALL
void rs2_delete_pipeline(rs2_pipeline *pipe) BEGIN_API_CALL
std::shared_ptr< librealsense::device_hub > hub
void rs2_config_enable_device_from_file(rs2_config *config, const char *file, rs2_error **error) BEGIN_API_CALL
void rs2_enter_update_state(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
unsigned get_log_message_line_number() const
const unsigned char * rs2_fw_log_message_data(rs2_firmware_log_message *msg, rs2_error **error) BEGIN_API_CALL
Gets RealSense firmware log message data.
void frame_callback(rs2::device &dev, rs2::frame frame, void *user)
void rs2_set_calibration_table(const rs2_device *device, const void *calibration, int calibration_size, rs2_error **error) BEGIN_API_CALL
int rs2_parse_firmware_log(rs2_device *dev, rs2_firmware_log_message *fw_log_msg, rs2_firmware_log_parsed_message *parsed_msg, rs2_error **error) BEGIN_API_CALL
Gets RealSense firmware log parser.
All the parameters required to define a pose stream.
int rs2_get_frame_bits_per_pixel(const rs2_frame *frame_ref, rs2_error **error) BEGIN_API_CALL
int rs2_get_frame_height(const rs2_frame *frame_ref, rs2_error **error) BEGIN_API_CALL
rs2_matchers
Specifies types of different matchers.
const rs2_raw_data_buffer * rs2_get_calibration_table(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
rs2_pipeline_profile * rs2_pipeline_start_with_callback_cpp(rs2_pipeline *pipe, rs2_frame_callback *callback, rs2_error **error) BEGIN_API_CALL
#define NOARGS_HANDLE_EXCEPTIONS_AND_RETURN_VOID()
void rs2_software_sensor_add_read_only_option(rs2_sensor *sensor, rs2_option option, float val, rs2_error **error) BEGIN_API_CALL
std::shared_ptr< rs2_notifications_callback > notifications_callback_ptr
void rs2_get_video_stream_resolution(const rs2_stream_profile *from, int *width, int *height, rs2_error **error) BEGIN_API_CALL
void rs2_config_enable_record_to_file(rs2_config *config, const char *file, rs2_error **error) BEGIN_API_CALL
rs2_frame_queue * rs2_create_frame_queue(int capacity, rs2_error **error) BEGIN_API_CALL
rs2_stream_profile_list * rs2_pipeline_profile_get_streams(rs2_pipeline_profile *profile, rs2_error **error) BEGIN_API_CALL
rs2_stream get_stream_type() const override
const char * rs2_record_device_filename(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
GLint GLsizei GLsizei height
std::vector< std::shared_ptr< stream_profile_interface > > list
const char * rs2_get_full_log_message(rs2_log_message const *msg, rs2_error **error) BEGIN_API_CALL
rs2_stream_profile * rs2_clone_stream_profile(const rs2_stream_profile *mode, rs2_stream stream, int stream_idx, rs2_format fmt, rs2_error **error) BEGIN_API_CALL
int rs2_get_raw_data_size(const rs2_raw_data_buffer *buffer, rs2_error **error) BEGIN_API_CALL
GLint GLint GLsizei GLint GLenum format
void rs2_set_stream_profile_data(rs2_stream_profile *mode, rs2_stream stream, int index, rs2_format format, rs2_error **error) BEGIN_API_CALL
void(* rs2_devices_changed_callback_ptr)(rs2_device_list *, rs2_device_list *, void *)
int rs2_init_fw_log_parser(rs2_device *dev, const char *xml_content, rs2_error **error) BEGIN_API_CALL
Initializes RealSense firmware logs parser in device.
rs2_raw_data_buffer * rs2_serialize_json(rs2_device *dev, rs2_error **error) BEGIN_API_CALL
struct rs2_log_message rs2_log_message
unsigned long long int rs2_playback_get_position(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
void rs2_flush_queue(rs2_frame_queue *queue, rs2_error **error) BEGIN_API_CALL
rs2_processing_block * rs2_create_sync_processing_block(rs2_error **error) BEGIN_API_CALL
const char * rs2_format_to_string(rs2_format format)
void rs2_delete_stream_profile(rs2_stream_profile *p) BEGIN_API_CALL
void rs2_pipeline_stop(rs2_pipeline *pipe, rs2_error **error) BEGIN_API_CALL
void rs2_playback_device_resume(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
void rs2_delete_stream_profiles_list(rs2_stream_profile_list *list) BEGIN_API_CALL
void rs2_delete_device_hub(const rs2_device_hub *hub) BEGIN_API_CALL
Frees the relevant device hub object.
rs2_processing_block * rs2_create_hole_filling_filter_block(rs2_error **error) BEGIN_API_CALL
void rs2_override_extrinsics(const rs2_sensor *sensor, const rs2_extrinsics *extrinsics, rs2_error **error) BEGIN_API_CALL
Override extrinsics of a given sensor that supports calibrated_sensor.
int rs2_get_fw_log(rs2_device *dev, rs2_firmware_log_message *fw_log_msg, rs2_error **error) BEGIN_API_CALL
Gets RealSense firmware log.
int rs2_device_list_contains(const rs2_device_list *info_list, const rs2_device *device, rs2_error **error) BEGIN_API_CALL
single_consumer_frame_queue< librealsense::frame_holder > queue
void rs2_software_sensor_set_metadata(rs2_sensor *sensor, rs2_frame_metadata_value key, rs2_metadata_type value, rs2_error **error) BEGIN_API_CALL
All the parameters required to define a motion stream.
rs2_processing_block * rs2_create_processing_block(rs2_frame_processor_callback *proc, rs2_error **error) BEGIN_API_CALL
rs2_format
A stream's format identifies how binary data is encoded within a frame.
#define VALIDATE_LE(ARG, MAX)
int rs2_supports_device_info(const rs2_device *dev, rs2_camera_info info, rs2_error **error) BEGIN_API_CALL
int rs2_is_option_read_only(const rs2_options *options, rs2_option option, rs2_error **error) BEGIN_API_CALL
float rs2_get_depth_scale(rs2_sensor *sensor, rs2_error **error) BEGIN_API_CALL
rs2_device * rs2_create_software_device(rs2_error **error) BEGIN_API_CALL
int rs2_get_frame_points_count(const rs2_frame *frame, rs2_error **error) BEGIN_API_CALL
rs2_frame * rs2_extract_frame(rs2_frame *composite, int index, rs2_error **error) BEGIN_API_CALL
const rs2_raw_data_buffer * rs2_create_flash_backup(const rs2_device *device, rs2_update_progress_callback_ptr callback, void *client_data, rs2_error **error) BEGIN_API_CALL
rs2_pipeline_profile * rs2_pipeline_get_active_profile(rs2_pipeline *pipe, rs2_error **error) BEGIN_API_CALL
#define RS2_PRODUCT_LINE_ANY_INTEL
int rs2_load_wheel_odometry_config(const rs2_sensor *sensor, const unsigned char *odometry_blob, unsigned int blob_size, rs2_error **error) BEGIN_API_CALL
int rs2_config_can_resolve(rs2_config *config, rs2_pipeline *pipe, rs2_error **error) BEGIN_API_CALL
const char * rs2_frame_metadata_value_to_string(rs2_frame_metadata_value metadata)
void rs2_release_frame(rs2_frame *frame) BEGIN_API_CALL
void swap(nlohmann::json &j1, nlohmann::json &j2) noexcept(is_nothrow_move_constructible< nlohmann::json >::value andis_nothrow_move_assignable< nlohmann::json >::value)
exchanges the values of two JSON objects
void on_calibration_change(rs2_calibration_status status) noexceptoverride
const char * rs2_host_perf_mode_to_string(rs2_host_perf_mode mode)
rs2_stream
Streams are different types of data provided by RealSense devices.
void rs2_get_video_stream_intrinsics(const rs2_stream_profile *from, rs2_intrinsics *intr, rs2_error **error) BEGIN_API_CALL
void rs2_playback_seek(const rs2_device *device, long long int time, rs2_error **error) BEGIN_API_CALL
static environment & get_instance()
int rs2_try_wait_for_frame(rs2_frame_queue *queue, unsigned int timeout_ms, rs2_frame **output_frame, rs2_error **error) BEGIN_API_CALL
extrinsics_graph & get_extrinsics_graph()
int rs2_is_device_extendable_to(const rs2_device *dev, rs2_extension extension, rs2_error **error) BEGIN_API_CALL
std::chrono::duration< uint64_t, std::nano > nanoseconds
void rs2_connect_tm2_controller(const rs2_device *device, const unsigned char *mac, rs2_error **error) BEGIN_API_CALL
void rs2_software_device_register_info(rs2_device *dev, rs2_camera_info info, const char *val, rs2_error **error) BEGIN_API_CALL
#define VALIDATE_INTERFACE(X, T)
size_t get_vertex_count() const
rs2_device_list * rs2_query_devices(const rs2_context *context, rs2_error **error) BEGIN_API_CALL
int rs2_get_api_version(rs2_error **error) BEGIN_API_CALL
rs2_sensor_mode
For setting the camera_mode option.
#define VALIDATE_OPTION(OBJ, OPT_ID)
std::shared_ptr< librealsense::context > ctx
void rs2_update_firmware_unsigned(const rs2_device *device, const void *image, int image_size, rs2_update_progress_callback_ptr callback, void *client_data, int update_mode, rs2_error **error) BEGIN_API_CALL
rs2_device_hub * rs2_create_device_hub(const rs2_context *context, rs2_error **error) BEGIN_API_CALL
Creates RealSense device_hub .
rs2_processing_block * rs2_create_align(rs2_stream align_to, rs2_error **error) BEGIN_API_CALL
terminal_parser(const std::string &xml_content)
Cross-stream extrinsics: encodes the topology describing how the different devices are oriented...
int rs2_device_hub_is_device_connected(const rs2_device_hub *hub, const rs2_device *device, rs2_error **error) BEGIN_API_CALL
void rs2_register_calibration_change_callback_cpp(rs2_device *dev, rs2_calibration_change_callback *callback, rs2_error **error) BEGIN_API_CALL
void rs2_config_enable_all_stream(rs2_config *config, rs2_error **error) BEGIN_API_CALL
void rs2_delete_fw_log_message(rs2_firmware_log_message *msg) BEGIN_API_CALL
void rs2_config_disable_stream(rs2_config *config, rs2_stream stream, rs2_error **error) BEGIN_API_CALL
LOG_INFO("Log message using LOG_INFO()")
void rs2_record_device_resume(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
rs2_processing_block * rs2_create_hdr_merge_processing_block(rs2_error **error) BEGIN_API_CALL
void rs2_playback_device_set_status_changed_callback(const rs2_device *device, rs2_playback_status_changed_callback *callback, rs2_error **error) BEGIN_API_CALL
rs2_raw_data_buffer * rs2_terminal_parse_response(rs2_terminal_parser *terminal_parser, const char *command, unsigned int size_of_command, const void *response, unsigned int size_of_response, rs2_error **error) BEGIN_API_CALL
Parses terminal response via RealSense terminal parser.
#define NOARGS_HANDLE_EXCEPTIONS_AND_RETURN(R)
const rs2_raw_data_buffer * rs2_run_tare_calibration_cpp(rs2_device *device, float ground_truth_mm, const void *json_content, int content_size, rs2_update_progress_callback *progress_callback, int timeout_ms, rs2_error **error) BEGIN_API_CALL
void(* rs2_software_device_destruction_callback_ptr)(void *)
3D vector in Euclidean coordinate space
rs2_stream_profile_list * rs2_get_active_streams(rs2_sensor *sensor, rs2_error **error) BEGIN_API_CALL
const char * rs2_digital_gain_to_string(rs2_digital_gain gain)
calibration_change_callback(rs2_calibration_change_callback_ptr callback, void *user_arg)
rs2_processing_block * rs2_create_processing_block_fptr(rs2_frame_processor_callback_ptr proc, void *context, rs2_error **error) BEGIN_API_CALL
GLdouble GLdouble GLdouble q
void rs2_start_processing(rs2_processing_block *block, rs2_frame_callback *on_frame, rs2_error **error) BEGIN_API_CALL
void rs2_get_dsm_params(const rs2_sensor *sensor, rs2_dsm_params *p_params_out, rs2_error **error) BEGIN_API_CALL
void enable_rolling_log_file(unsigned max_size)
struct rs2_processing_block rs2_processing_block
All the parameters required to define a sensor notification.
void rs2_log_to_callback(rs2_log_severity min_severity, rs2_log_callback_ptr on_log, void *arg, rs2_error **error) BEGIN_API_CALL
int rs2_stream_profile_is(const rs2_stream_profile *f, rs2_extension extension_type, rs2_error **error) BEGIN_API_CALL
const char * rs2_get_option_name(const rs2_options *options, rs2_option option, rs2_error **error) BEGIN_API_CALL
int rs2_supports_sensor_info(const rs2_sensor *sensor, rs2_camera_info info, rs2_error **error) BEGIN_API_CALL
rs2_extension
Specifies advanced interfaces (capabilities) objects may implement.
void rs2_get_region_of_interest(const rs2_sensor *sensor, int *min_x, int *min_y, int *max_x, int *max_y, rs2_error **error) BEGIN_API_CALL
gets the active region of interest to be used by auto-exposure algorithm
rs2_notification_category
Category of the librealsense notification.
rs2_device * rs2_create_device(const rs2_device_list *info_list, int index, rs2_error **error) BEGIN_API_CALL
void rs2_delete_sensor_list(rs2_sensor_list *list) BEGIN_API_CALL
::realsense_legacy_msgs::metadata_< std::allocator< void > > metadata
const char * rs2_playback_device_get_file_path(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
void rs2_config_disable_indexed_stream(rs2_config *config, rs2_stream stream, int index, rs2_error **error) BEGIN_API_CALL
void(* rs2_notification_callback_ptr)(rs2_notification *, void *)
stream_profile to_profile(const stream_profile_interface *sp)
long long rs2_metadata_type
void rs2_open_multiple(rs2_sensor *sensor, const rs2_stream_profile **profiles, int count, rs2_error **error) BEGIN_API_CALL
const char * rs2_frame_metadata_to_string(rs2_frame_metadata_value metadata)
unsigned int rs2_fw_log_message_timestamp(rs2_firmware_log_message *msg, rs2_error **error) BEGIN_API_CALL
Gets RealSense firmware log message timestamp.
#define VALIDATE_RANGE(ARG, MIN, MAX)
const char * rs2_get_failed_function(const rs2_error *error)
unsigned int rs2_get_fw_log_parsed_sequence_id(rs2_firmware_log_parsed_message *fw_log_parsed_msg, rs2_error **error) BEGIN_API_CALL
Gets RealSense firmware log parsed message sequence id - cyclic number of FW log with [0...
void rs2_start_processing_fptr(rs2_processing_block *block, rs2_frame_callback_ptr on_frame, void *user, rs2_error **error) BEGIN_API_CALL
void rs2_write_calibration(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
const char * rs2_calibration_status_to_string(rs2_calibration_status status)
void rs2_playback_device_pause(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
std::shared_ptr< librealsense::align > create_align(rs2_stream align_to)
void rs2_set_devices_changed_callback_cpp(rs2_context *context, rs2_devices_changed_callback *callback, rs2_error **error) BEGIN_API_CALL
void rs2_start(const rs2_sensor *sensor, rs2_frame_callback_ptr on_frame, void *user, rs2_error **error) BEGIN_API_CALL
void rs2_register_calibration_change_callback(rs2_device *dev, rs2_calibration_change_callback_ptr callback, void *user, rs2_error **error) BEGIN_API_CALL
const rs2_raw_data_buffer * rs2_run_on_chip_calibration_cpp(rs2_device *device, const void *json_content, int content_size, float *health, rs2_update_progress_callback *progress_callback, int timeout_ms, rs2_error **error) BEGIN_API_CALL
rs2_error * rs2_create_error(const char *what, const char *name, const char *args, rs2_exception_type type) BEGIN_API_CALL
void rs2_get_motion_intrinsics(const rs2_stream_profile *mode, rs2_motion_device_intrinsic *intrinsics, rs2_error **error) BEGIN_API_CALL
All the parameters required to define a motion frame.
rs2_processing_block * rs2_create_colorizer(rs2_error **error) BEGIN_API_CALL
float rs2_depth_frame_get_distance(const rs2_frame *frame_ref, int x, int y, rs2_error **error) BEGIN_API_CALL
const char * rs2_get_fw_log_parsed_thread_name(rs2_firmware_log_parsed_message *fw_log_parsed_msg, rs2_error **error) BEGIN_API_CALL
Gets RealSense firmware log parsed message thread name.
struct rs2_device rs2_device
std::string serialized_data
rs2_processing_block * rs2_create_disparity_transform_block(unsigned char transform_to_disparity, rs2_error **error) BEGIN_API_CALL
rs2_sensor * rs2_get_frame_sensor(const rs2_frame *frame, rs2_error **error) BEGIN_API_CALL
int rs2_supports_option(const rs2_options *options, rs2_option option, rs2_error **error) BEGIN_API_CALL
void(* rs2_calibration_change_callback_ptr)(rs2_calibration_status, void *arg)
void rs2_delete_pipeline_profile(rs2_pipeline_profile *profile) BEGIN_API_CALL
typename::boost::move_detail::remove_reference< T >::type && move(T &&t) BOOST_NOEXCEPT
int rs2_is_frame_extendable_to(const rs2_frame *f, rs2_extension extension_type, rs2_error **error) BEGIN_API_CALL
void rs2_loopback_enable(const rs2_device *device, const char *from_file, rs2_error **error) BEGIN_API_CALL
const rs2_raw_data_buffer * rs2_send_and_receive_raw_data(rs2_device *device, void *raw_data_to_send, unsigned size_of_raw_data_to_send, rs2_error **error) BEGIN_API_CALL
rs2_ambient_light
DEPRECATED! - Use RS2_OPTION_DIGITAL_GAIN instead.
rs2_frame * rs2_wait_for_frame(rs2_frame_queue *queue, unsigned int timeout_ms, rs2_error **error) BEGIN_API_CALL
GLsizei GLsizei GLchar * source
void rs2_log_to_file(rs2_log_severity min_severity, const char *file_path, rs2_error **error) BEGIN_API_CALL
void rs2_context_unload_tracking_module(rs2_context *ctx, rs2_error **error) BEGIN_API_CALL
void rs2_software_device_set_destruction_callback_cpp(const rs2_device *dev, rs2_software_device_destruction_callback *callback, rs2_error **error) BEGIN_API_CALL
rs2_vertex * rs2_get_frame_vertices(const rs2_frame *frame, rs2_error **error) BEGIN_API_CALL
rs2_frame * rs2_allocate_synthetic_motion_frame(rs2_source *source, const rs2_stream_profile *new_stream, rs2_frame *original, rs2_extension frame_type, rs2_error **error) BEGIN_API_CALL
rs2_digital_gain
digital gain for RS2_OPTION_DIGITAL_GAIN option.
int rs2_get_frame_stride_in_bytes(const rs2_frame *frame_ref, rs2_error **error) BEGIN_API_CALL
rs2_context * rs2_create_context(int api_version, rs2_error **error) BEGIN_API_CALL
Creates RealSense context that is required for the rest of the API.
void rs2_software_sensor_on_notification(rs2_sensor *sensor, rs2_software_notification notif, rs2_error **error) BEGIN_API_CALL
void set_devices_changed_callback(devices_changed_callback_ptr callback)
void rs2_get_option_range(const rs2_options *options, rs2_option option, float *min, float *max, float *step, float *def, rs2_error **error) BEGIN_API_CALL
Motion device intrinsics: scale, bias, and variances.
void rs2_disconnect_tm2_controller(const rs2_device *device, int id, rs2_error **error) BEGIN_API_CALL
const char * rs2_extension_type_to_string(rs2_extension type)
float rs2_get_option(const rs2_options *options, rs2_option option, rs2_error **error) BEGIN_API_CALL
device(std::shared_ptr< context > ctx, const platform::backend_device_group group, bool device_changed_notifications=false)
std::shared_ptr< librealsense::context > ctx
int rs2_import_localization_map(const rs2_sensor *sensor, const unsigned char *lmap_blob, unsigned int blob_size, rs2_error **error) BEGIN_API_CALL
std::shared_ptr< rs2_devices_changed_callback > devices_changed_callback_ptr
int rs2_get_frame_data_size(const rs2_frame *frame_ref, rs2_error **error) BEGIN_API_CALL
void(* rs2_frame_callback_ptr)(rs2_frame *, void *)
rs2_pipeline_profile * rs2_pipeline_start_with_callback(rs2_pipeline *pipe, rs2_frame_callback_ptr on_frame, void *user, rs2_error **error) BEGIN_API_CALL
int rs2_send_wheel_odometry(const rs2_sensor *sensor, char wo_sensor_id, unsigned int frame_num, const rs2_vector translational_velocity, rs2_error **error) BEGIN_API_CALL
rs2_device * rs2_pipeline_profile_get_device(rs2_pipeline_profile *profile, rs2_error **error) BEGIN_API_CALL
void rs2_override_intrinsics(const rs2_sensor *sensor, const rs2_intrinsics *intrinsics, rs2_error **error) BEGIN_API_CALL
Override intrinsics of a given sensor that supports calibrated_sensor.
const char * rs2_calib_target_type_to_string(rs2_calib_target_type type)
const unsigned char * rs2_get_raw_data(const rs2_raw_data_buffer *buffer, rs2_error **error) BEGIN_API_CALL
const char * rs2_get_processing_block_info(const rs2_processing_block *block, rs2_camera_info info, rs2_error **error) BEGIN_API_CALL
rs2_stream_profile_list * rs2_get_debug_stream_profiles(rs2_sensor *sensor, rs2_error **error) BEGIN_API_CALL
unsigned long long rs2_get_frame_number(const rs2_frame *frame, rs2_error **error) BEGIN_API_CALL
All the parameters required to define a video frame.
void log_to_console(rs2_log_severity min_severity)
int rs2_remove_static_node(const rs2_sensor *sensor, const char *guid, rs2_error **error) BEGIN_API_CALL
void rs2_stop(const rs2_sensor *sensor, rs2_error **error) BEGIN_API_CALL
void rs2_update_firmware_unsigned_cpp(const rs2_device *device, const void *image, int image_size, rs2_update_progress_callback *callback, int update_mode, rs2_error **error) BEGIN_API_CALL
const char * rs2_camera_info_to_string(rs2_camera_info info)
const char * get_raw_log_message() const
rs2_pipeline_profile * rs2_pipeline_start_with_config(rs2_pipeline *pipe, rs2_config *config, rs2_error **error) BEGIN_API_CALL
rs2_sensor * rs2_software_device_add_sensor(rs2_device *dev, const char *sensor_name, rs2_error **error) BEGIN_API_CALL
const char * rs2_timestamp_domain_to_string(rs2_timestamp_domain info)
const char * rs2_calibration_type_to_string(rs2_calibration_type type)
void rs2_config_disable_all_streams(rs2_config *config, rs2_error **error) BEGIN_API_CALL
rs2_log_severity
Severity of the librealsense logger.
std::shared_ptr< rs2_software_device_destruction_callback > software_device_destruction_callback_ptr
platform::backend_device_group get_device_data() const override
rs2_log_severity severity
const rs2_raw_data_buffer * rs2_create_flash_backup_cpp(const rs2_device *device, rs2_update_progress_callback *callback, rs2_error **error) BEGIN_API_CALL
std::shared_ptr< librealsense::pipeline::pipeline > pipeline
void rs2_delete_config(rs2_config *config) BEGIN_API_CALL
void rs2_loopback_disable(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
rs2_frame * rs2_allocate_composite_frame(rs2_source *source, rs2_frame **frames, int count, rs2_error **error) BEGIN_API_CALL
const char * rs2_get_option_description(const rs2_options *options, rs2_option option, rs2_error **error) BEGIN_API_CALL
rs2_stream_profile_list * rs2_get_stream_profiles(rs2_sensor *sensor, rs2_error **error) BEGIN_API_CALL
const rs2_raw_data_buffer * rs2_export_localization_map(const rs2_sensor *sensor, rs2_error **error) BEGIN_API_CALL
void rs2_set_notifications_callback(const rs2_sensor *sensor, rs2_notification_callback_ptr on_notification, void *user, rs2_error **error) BEGIN_API_CALL
int rs2_fw_log_message_size(rs2_firmware_log_message *msg, rs2_error **error) BEGIN_API_CALL
Gets RealSense firmware log message size.
int rs2_get_device_count(const rs2_device_list *list, rs2_error **error) BEGIN_API_CALL
const char * rs2_get_failed_args(const rs2_error *error)
void rs2_delete_device_list(rs2_device_list *list) BEGIN_API_CALL
rs2_log_severity rs2_get_notification_severity(rs2_notification *notification, rs2_error **error) BEGIN_API_CALL
void rs2_reset_to_factory_calibration(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
rs2_frame * rs2_pipeline_wait_for_frames(rs2_pipeline *pipe, unsigned int timeout_ms, rs2_error **error) BEGIN_API_CALL
void rs2_set_extrinsics(const rs2_sensor *from_sensor, const rs2_stream_profile *from_profile, rs2_sensor *to_sensor, const rs2_stream_profile *to_profile, const rs2_extrinsics *extrinsics, rs2_error **error) BEGIN_API_CALL
int rs2_processing_block_register_simple_option(rs2_processing_block *block, rs2_option option_id, float min, float max, float step, float def, rs2_error **error) BEGIN_API_CALL
rs2_device * rs2_create_device_from_sensor(const rs2_sensor *sensor, rs2_error **error) BEGIN_API_CALL
const std::string & get_filename() const
unsigned long long int rs2_playback_get_duration(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
void rs2_keep_frame(rs2_frame *frame) BEGIN_API_CALL
void rs2_playback_device_set_playback_speed(const rs2_device *device, float speed, rs2_error **error) BEGIN_API_CALL
rs2_frame_metadata_value
Per-Frame-Metadata is the set of read-only properties that might be exposed for each individual frame...
rs2_stream_profile * rs2_software_sensor_add_video_stream_ex(rs2_sensor *sensor, rs2_video_stream video_stream, int is_default, rs2_error **error) BEGIN_API_CALL
void rs2_start_queue(const rs2_sensor *sensor, rs2_frame_queue *queue, rs2_error **error) BEGIN_API_CALL
rs2_pipeline_profile * rs2_pipeline_start_with_config_and_callback(rs2_pipeline *pipe, rs2_config *config, rs2_frame_callback_ptr on_frame, void *user, rs2_error **error) BEGIN_API_CALL
#define VALIDATE_NOT_NULL(ARG)
void rs2_software_device_set_destruction_callback(const rs2_device *dev, rs2_software_device_destruction_callback_ptr on_destruction, void *user, rs2_error **error) BEGIN_API_CALL
struct rs2_frame rs2_frame
int rs2_get_flash_log(rs2_device *dev, rs2_firmware_log_message *fw_log_msg, rs2_error **error) BEGIN_API_CALL
Gets RealSense flash log - this is a fw log that has been written in the device during the previous s...
void rs2_register_extrinsics(const rs2_stream_profile *from, const rs2_stream_profile *to, rs2_extrinsics extrin, rs2_error **error) BEGIN_API_CALL
rs2_log_severity rs2_fw_log_message_severity(const rs2_firmware_log_message *msg, rs2_error **error) BEGIN_API_CALL
Gets RealSense firmware log message severity.
void rs2_config_enable_device(rs2_config *config, const char *serial, rs2_error **error) BEGIN_API_CALL
void rs2_set_intrinsics(const rs2_sensor *sensor, const rs2_stream_profile *profile, const rs2_intrinsics *intrinsics, rs2_error **error) BEGIN_API_CALL
#define NOEXCEPT_RETURN(R,...)
rs2_stream_profile * rs2_software_sensor_add_motion_stream_ex(rs2_sensor *sensor, rs2_motion_stream motion_stream, int is_default, rs2_error **error) BEGIN_API_CALL
void rs2_get_stream_profile_data(const rs2_stream_profile *mode, rs2_stream *stream, rs2_format *format, int *index, int *unique_id, int *framerate, rs2_error **error) BEGIN_API_CALL
unsigned int rs2_get_number_of_fw_logs(rs2_device *dev, rs2_error **error) BEGIN_API_CALL
Returns number of fw logs already polled from device but not by user yet.
Pixel location within 2D image. (0,0) is the topmost, left corner. Positive X is right, positive Y is down.
rs2_firmware_log_message * rs2_create_fw_log_message(rs2_device *dev, rs2_error **error) BEGIN_API_CALL
Creates RealSense firmware log message.
#define VALIDATE_ENUM(ARG)
void rs2_open(rs2_sensor *sensor, const rs2_stream_profile *profile, rs2_error **error) BEGIN_API_CALL
void on_log(rs2_log_severity severity, rs2_log_message const &msg) noexceptoverride
void rs2_export_to_ply(const rs2_frame *frame, const char *fname, rs2_frame *texture, rs2_error **error) BEGIN_API_CALL
float rs2_get_stereo_baseline(rs2_sensor *sensor, rs2_error **error) BEGIN_API_CALL
rs2_option rs2_get_option_from_list(const rs2_options_list *options, int i, rs2_error **error) BEGIN_API_CALL
rs2_l500_visual_preset
For L500 devices: provides optimized settings (presets) for specific types of usage.
rs2_time_t rs2_get_time(rs2_error **error) BEGIN_API_CALL
rs2_timestamp_domain
Specifies the clock in relation to which the frame timestamp was measured.