rs.cpp
Go to the documentation of this file.
1 // License: Apache 2.0 See LICENSE file in root directory.
2 // Copyright(c) 2015 Intel Corporation. All Rights Reserved.
3 
4 #include <functional> // For function
5 
6 #include "api.h"
7 #include "log.h"
8 #include "context.h"
9 #include "device.h"
10 #include "algo.h"
11 #include "core/debug.h"
12 #include "core/motion.h"
13 #include "core/extension.h"
15 #include <media/ros/ros_writer.h>
16 #include <media/ros/ros_reader.h>
17 #include "core/advanced_mode.h"
18 #include "source.h"
19 #include "core/processing.h"
20 #include "proc/synthetic-stream.h"
22 #include "proc/colorizer.h"
23 #include "proc/pointcloud.h"
24 #include "proc/threshold.h"
25 #include "proc/units-transform.h"
28 #include "proc/decimation-filter.h"
29 #include "proc/spatial-filter.h"
30 #include "proc/zero-order.h"
33 #include "proc/rates-printer.h"
34 #include "proc/hdr-merge.h"
37 #include "stream.h"
38 #include "../include/librealsense2/h/rs_types.h"
39 #include "pipeline/pipeline.h"
40 #include "environment.h"
41 #include "proc/temporal-filter.h"
42 #include "proc/depth-decompress.h"
43 #include "software-device.h"
45 #include "auto-calibrated-device.h"
46 #include "terminal-parser.h"
47 #include "firmware_logger_device.h"
48 #include "device-calibration.h"
49 #include "calibrated-sensor.h"
51 // API implementation //
53 
54 using namespace librealsense;
55 
57 {
58  std::vector<std::shared_ptr<stream_profile_interface>> list;
59 };
60 
62 {
64 };
65 
66 struct rs2_sensor : public rs2_options
67 {
71  parent(parent), sensor(sensor)
72  {}
73 
76 
77  rs2_sensor& operator=(const rs2_sensor&) = delete;
78  rs2_sensor(const rs2_sensor&) = delete;
79 };
80 
81 
83 {
84  ~rs2_context() { ctx->stop(); }
85  std::shared_ptr<librealsense::context> ctx;
86 };
87 
89 {
90  std::shared_ptr<librealsense::device_hub> hub;
91 };
92 
94 {
95  std::shared_ptr<librealsense::pipeline::pipeline> pipeline;
96 };
97 
98 struct rs2_config
99 {
100  std::shared_ptr<librealsense::pipeline::config> config;
101 };
102 
104 {
105  std::shared_ptr<librealsense::pipeline::profile> profile;
106 };
107 
109 {
110  explicit rs2_frame_queue(int cap)
111  : queue(cap)
112  {
113  }
114 
116 };
117 
119 {
121 };
122 
124 {
125  std::shared_ptr<librealsense::terminal_parser> terminal_parser;
126 };
127 
129 {
130  std::shared_ptr<librealsense::fw_logs::fw_logs_binary_data> firmware_log_binary_data;
131 };
132 
134 {
135  std::shared_ptr<librealsense::fw_logs::fw_log_data> firmware_log_parsed;
136 };
137 
138 
139 struct rs2_error
140 {
142  std::string function;
145 };
146 
147 rs2_error *rs2_create_error(const char* what, const char* name, const char* args, rs2_exception_type type) BEGIN_API_CALL
148 {
149  return new rs2_error{ what, name, args, type };
150 }
151 NOEXCEPT_RETURN(nullptr, what, name, args, type)
152 
153 void notifications_processor::raise_notification(const notification n)
154 {
155  _dispatcher.invoke([this, n](dispatcher::cancellable_timer ct)
156  {
157  std::lock_guard<std::mutex> lock(_callback_mutex);
158  rs2_notification noti(&n);
159  if (_callback)_callback->on_notification(&noti);
160  });
161 }
162 
164 {
165  verify_version_compatibility(api_version);
166 
167  return new rs2_context{ std::make_shared<librealsense::context>(librealsense::backend_type::standard) };
168 }
169 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, api_version)
170 
172 {
174  delete context;
175 }
177 
179 {
180  return new rs2_device_hub{ std::make_shared<librealsense::device_hub>(context->ctx) };
181 }
183 
185 {
187  delete hub;
188 }
190 
192 {
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 };
196 }
198 
200 {
203  auto res = hub->hub->is_connected(*device->device);
204  return res ? 1 : 0;
205 }
207 
209 {
211 }
213 
215 {
217 
218  std::vector<rs2_device_info> results;
219  for (auto&& dev_info : context->ctx->query_devices(product_mask))
220  {
221  try
222  {
223  rs2_device_info d{ context->ctx, dev_info };
224  results.push_back(d);
225  }
226  catch (...)
227  {
228  LOG_WARNING("Could not open device!");
229  }
230  }
231 
232  return new rs2_device_list{ context->ctx, results };
233 }
234 HANDLE_EXCEPTIONS_AND_RETURN(0, context, product_mask)
235 
237 {
239 
240  std::vector<rs2_device_info> results;
241  try
242  {
243  auto dev = device->device;
244  for (unsigned int i = 0; i < dev->get_sensors_count(); i++)
245  {
246  rs2_device_info d{ device->ctx, device->info };
247  results.push_back(d);
248  }
249  }
250  catch (...)
251  {
252  LOG_WARNING("Could not open device!");
253  }
254 
255  return new rs2_sensor_list{ *device };
256 }
258 
260 {
261  if (list == nullptr)
262  return 0;
263  return static_cast<int>(list->list.size());
264 }
266 
268 {
269  if (list == nullptr)
270  return 0;
271  return static_cast<int>(list->dev.device->get_sensors_count());
272 }
274 
276 {
277  VALIDATE_NOT_NULL(list);
278  delete list;
279 }
280 NOEXCEPT_RETURN(, list)
281 
283 {
284  VALIDATE_NOT_NULL(list);
285  delete list;
286 }
287 NOEXCEPT_RETURN(, list)
288 
290 {
291  VALIDATE_NOT_NULL(info_list);
292  VALIDATE_RANGE(index, 0, (int)info_list->list.size() - 1);
293 
294  return new rs2_device{ info_list->ctx,
295  info_list->list[index].info,
296  info_list->list[index].info->create_device()
297  };
298 }
299 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, info_list, index)
300 
302 {
304  delete device;
305 }
307 
309 {
310  VALIDATE_NOT_NULL(list);
311  VALIDATE_RANGE(index, 0, (int)list->dev.device->get_sensors_count() - 1);
312 
313  return new rs2_sensor{
314  list->dev,
315  &list->dev.device->get_sensor(index)
316  };
317 }
318 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, list, index)
319 
321 {
323  delete device;
324 }
326 
328 {
330  return new rs2_stream_profile_list{ sensor->sensor->get_stream_profiles() };
331 }
333 
336 {
338  auto debug_streaming
340  return new rs2_stream_profile_list{ debug_streaming->get_debug_stream_profiles() };
341 }
343 
345 {
347  return new rs2_stream_profile_list{ sensor->sensor->get_active_streams() };
348 }
350 
352 {
353  VALIDATE_NOT_NULL(list);
354  VALIDATE_RANGE(index, 0, (int)list->list.size() - 1);
355 
356  return list->list[index]->get_c_wrapper();
357 }
358 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, list, index)
359 
361 {
362  VALIDATE_NOT_NULL(list);
363  return static_cast<int>(list->list.size());
364 }
366 
368 {
369  VALIDATE_NOT_NULL(list);
370  delete list;
371 }
372 NOEXCEPT_RETURN(, list)
373 
375 {
376  VALIDATE_NOT_NULL(from);
378 
380 
381  *intr = vid->get_intrinsics();
382 }
384 
385 // librealsense wrapper around a C function
387 {
389  void* _user_arg;
390 
391 public:
393  : _callback( callback ), _user_arg( user_arg ) {}
394 
396  {
397  if( _callback )
398  {
399  try
400  {
401  _callback( status, _user_arg );
402  }
403  catch( ... )
404  {
405  std::cerr << "Received an execption from profile intrinsics callback!" << std::endl;
406  }
407  }
408  }
409  void release() override
410  {
411  // Shouldn't get called...
412  throw std::runtime_error( "calibration_change_callback::release() ?!?!?!" );
413  delete this;
414  }
415 };
416 
418 {
421 
423 
424  // Wrap the C function with a callback interface that will get deleted when done
425  d2r->register_calibration_change_callback(
426  std::make_shared< calibration_change_callback >( callback, user )
427  );
428 }
430 
432 {
435 
437 
438  // Wrap the C++ callback interface with a shared_ptr that we set to release() it (rather than delete it)
439  d2r->register_calibration_change_callback(
440  { callback, []( rs2_calibration_change_callback* p ) { p->release(); } }
441  );
442 }
444 
446 {
448 
450 
451  cal->trigger_device_calibration( type );
452 }
454 
456 {
459 
461  *intrinsics = motion->get_intrinsics();
462 }
464 
465 
467 {
468  VALIDATE_NOT_NULL(from);
469 
471 
472  if (width) *width = vid->get_width();
473  if (height) *height = vid->get_height();
474 }
476 
478 {
480  return profile->profile->get_tag() & profile_tag::PROFILE_TAG_DEFAULT ? 1 : 0;
481 }
483 
485 {
491 
492  *framerate = mode->profile->get_framerate();
493  *format = mode->profile->get_format();
494  *index = mode->profile->get_stream_index();
495  *stream = mode->profile->get_stream_type();
496  *unique_id = mode->profile->get_unique_id();
497 }
499 
501 {
505 
506  mode->profile->set_format(format);
507  mode->profile->set_stream_type(stream);
508  mode->profile->set_stream_index(index);
509 }
511 
513 {
515  delete p;
516 }
518 
520 {
524 
525  auto sp = mode->profile->clone();
526  sp->set_stream_type(stream);
527  sp->set_stream_index(stream_idx);
528  sp->set_format(fmt);
529  return new rs2_stream_profile{ sp.get(), sp };
530 }
531 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, mode, stream, stream_idx, fmt)
532 
534 {
539 
540  auto sp = mode->profile->clone();
541  sp->set_stream_type(stream);
542  sp->set_stream_index(index);
543  sp->set_format(format);
544 
545  auto vid = std::dynamic_pointer_cast<video_stream_profile_interface>(sp);
546  auto i = *intr;
547  vid->set_intrinsics([i]() { return i; });
548  vid->set_dims(width, height);
549 
550  return new rs2_stream_profile{ sp.get(), sp };
551 }
553 
554 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
555 {
557 
559 
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);
562  auto ret_data = debug_interface->send_receive_raw_data(buffer_to_send);
563  return new rs2_raw_data_buffer{ ret_data };
564 }
566 
568 {
570  return buffer->buffer.data();
571 }
573 
575 {
577  return static_cast<int>(buffer->buffer.size());
578 }
580 
582 {
584  delete buffer;
585 }
587 
589 {
592 
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);
596 }
598 
601 {
604 
605  std::vector<std::shared_ptr<stream_profile_interface>> request;
606  for (auto i = 0; i < count; i++)
607  {
608  request.push_back(std::dynamic_pointer_cast<stream_profile_interface>(profiles[i]->profile->shared_from_this()));
609  }
610  sensor->sensor->open(request);
611 }
613 
615 {
617  sensor->sensor->close();
618 }
620 
622 {
623  VALIDATE_NOT_NULL(options);
624  return options->options->get_option(option).is_read_only();
625 }
627 
629 {
630  VALIDATE_NOT_NULL(options);
631  VALIDATE_OPTION(options, option);
632  return options->options->get_option(option).query();
633 }
635 
637 {
638  VALIDATE_NOT_NULL(options);
639  VALIDATE_OPTION(options, option);
640  options->options->get_option(option).set(value);
641 }
643 
645 {
646  VALIDATE_NOT_NULL(options);
647  return new rs2_options_list{ options->options->get_supported_options() };
648 }
649 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, options)
650 
652 {
653  VALIDATE_NOT_NULL(options);
654  return options->options->get_option_name(option);
655 }
656 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, option, options)
657 
659 {
660  VALIDATE_NOT_NULL(options);
661  return int(options->list.size());
662 }
664 
666 {
667  VALIDATE_NOT_NULL(options);
668  return options->list[i];
669 }
671 
673 {
674  VALIDATE_NOT_NULL(list);
675  delete list;
676 }
677 NOEXCEPT_RETURN(, list)
678 
680 {
681  VALIDATE_NOT_NULL(options);
682  return options->options->supports_option(option);
683 }
685 
687  float* min, float* max, float* step, float* def, rs2_error** error) BEGIN_API_CALL
688 {
689  VALIDATE_NOT_NULL(options);
690  VALIDATE_OPTION(options, option);
692  VALIDATE_NOT_NULL(max);
693  VALIDATE_NOT_NULL(step);
694  VALIDATE_NOT_NULL(def);
695  auto range = options->options->get_option(option).get_range();
696  *min = range.min;
697  *max = range.max;
698  *def = range.def;
699  *step = range.step;
700 }
701 HANDLE_EXCEPTIONS_AND_RETURN(, options, option, min, max, step, def)
702 
704 {
707  if (dev->device->supports_info(info))
708  {
709  return dev->device->get_info(info).c_str();
710  }
711  throw librealsense::invalid_value_exception(librealsense::to_string() << "info " << rs2_camera_info_to_string(info) << " not supported by the device!");
712 }
714 
716 {
718  VALIDATE_NOT_NULL(dev->device);
720  return dev->device->supports_info(info);
721 }
723 
725 {
728  if (sensor->sensor->supports_info(info))
729  {
730  return sensor->sensor->get_info(info).c_str();
731  }
732  throw librealsense::invalid_value_exception(librealsense::to_string() << "info " << rs2_camera_info_to_string(info) << " not supported by the sensor!");
733 }
735 
737 {
740  return sensor->sensor->supports_info(info);
741 }
743 
745 {
750  sensor->sensor->start(move(callback));
751 }
753 
755 {
757  VALIDATE_NOT_NULL(queue);
760  sensor->sensor->start(move(callback));
761 }
763 
765 {
767  VALIDATE_NOT_NULL(on_notification);
769  new librealsense::notifications_callback(on_notification, user),
770  [](rs2_notifications_callback* p) { delete p; });
771  sensor->sensor->register_notifications_callback(std::move(callback));
772 }
773 HANDLE_EXCEPTIONS_AND_RETURN(, sensor, on_notification, user)
774 
776 {
779  VALIDATE_NOT_NULL(on_destruction);
781  new librealsense::software_device_destruction_callback(on_destruction, user),
782  [](rs2_software_device_destruction_callback* p) { delete p; });
783  swdev->register_destruction_callback(std::move(callback));
784 }
785 HANDLE_EXCEPTIONS_AND_RETURN(, dev, on_destruction, user)
786 
788 {
793  [](rs2_devices_changed_callback* p) { delete p; });
795 }
797 
799 {
802  sensor->sensor->start({ callback, [](rs2_frame_callback* p) { p->release(); } });
803 }
805 
807 {
810  sensor->sensor->register_notifications_callback({ callback, [](rs2_notifications_callback* p) { p->release(); } });
811 }
813 
815 {
819  swdev->register_destruction_callback({ callback, [](rs2_software_device_destruction_callback* p) { p->release(); } });
820 }
822 
824 {
828 }
830 
832 {
834  sensor->sensor->stop();
835 }
837 
839 {
842  return ((frame_interface*)frame)->supports_frame_metadata(frame_metadata);
843 }
845 
847 {
850  return ((frame_interface*)frame)->get_frame_metadata(frame_metadata);
851 }
853 
855 {
857  return notification->_notification->description.c_str();
858 }
860 
862 {
864  return notification->_notification->timestamp;
865 }
867 
869 {
871  return (rs2_log_severity)notification->_notification->severity;
872 }
874 
876 {
878  return (rs2_notification_category)notification->_notification->category;
879 }
881 
883 {
885  return notification->_notification->serialized_data.c_str();
886 }
888 
889 
891 {
892  VALIDATE_NOT_NULL(info_list);
894 
895  for (auto info : info_list->list)
896  {
897  // TODO: This is incapable of detecting playback devices
898  // Need to extend, if playback, compare filename or something
899  if (device->info && device->info->get_device_data() == info.info->get_device_data())
900  {
901  return 1;
902  }
903  }
904  return 0;
905 }
906 HANDLE_EXCEPTIONS_AND_RETURN(false, info_list, device)
907 
909 {
910  VALIDATE_NOT_NULL(frame_ref);
911  return ((frame_interface*)frame_ref)->get_frame_timestamp();
912 }
913 HANDLE_EXCEPTIONS_AND_RETURN(0, frame_ref)
914 
916 {
917  VALIDATE_NOT_NULL(frame_ref);
918  return ((frame_interface*)frame_ref)->get_frame_timestamp_domain();
919 }
921 
923 {
925  std::shared_ptr<librealsense::sensor_interface> sensor( ((frame_interface*)frame)->get_sensor() );
926  device_interface& dev = sensor->get_device();
927  auto dev_info = std::make_shared<librealsense::readonly_device_info>(dev.shared_from_this());
928  rs2_device dev2{ dev.get_context(), dev_info, dev.shared_from_this() };
929  return new rs2_sensor(dev2, sensor.get());
930 }
932 
934 {
935  VALIDATE_NOT_NULL(frame_ref);
936  return ((frame_interface*)frame_ref)->get_frame_data_size();
937 }
938 HANDLE_EXCEPTIONS_AND_RETURN(0, frame_ref)
939 
941 {
942  VALIDATE_NOT_NULL(frame_ref);
943  return ((frame_interface*)frame_ref)->get_frame_data();
944 }
945 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, frame_ref)
946 
948 {
949  VALIDATE_NOT_NULL(frame_ref);
951  return vf->get_width();
952 }
953 HANDLE_EXCEPTIONS_AND_RETURN(0, frame_ref)
954 
956 {
957  VALIDATE_NOT_NULL(frame_ref);
959  return vf->get_height();
960 }
961 HANDLE_EXCEPTIONS_AND_RETURN(0, frame_ref)
962 
964 {
965  VALIDATE_NOT_NULL(frame_ref);
967  return vf->get_stride();
968 }
969 HANDLE_EXCEPTIONS_AND_RETURN(0, frame_ref)
970 
972 {
973  VALIDATE_NOT_NULL(frame_ref);
974  return ((frame_interface*)frame_ref)->get_stream()->get_c_wrapper();
975 }
976 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, frame_ref)
977 
979 {
980  VALIDATE_NOT_NULL(frame_ref);
982  return vf->get_bpp();
983 }
984 HANDLE_EXCEPTIONS_AND_RETURN(0, frame_ref)
985 
987 {
989  return ((frame_interface*)frame)->get_frame_number();
990 }
992 
994 {
996  ((frame_interface*)frame)->release();
997 }
999 
1001 {
1003  ((frame_interface*)frame)->keep();
1004 }
1006 
1008 {
1009  VALIDATE_NOT_NULL(options);
1010  VALIDATE_OPTION(options, option);
1011  return options->options->get_option(option).get_description();
1012 }
1013 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, options, option)
1014 
1016 {
1018  ((frame_interface*)frame)->acquire();
1019 }
1021 
1023 {
1024  VALIDATE_NOT_NULL(options);
1025  VALIDATE_OPTION(options, option);
1026  return options->options->get_option(option).get_value_description(value);
1027 }
1028 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, options, option, value)
1029 
1031 {
1032  return new rs2_frame_queue(capacity);
1033 }
1034 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, capacity)
1035 
1037 {
1038  VALIDATE_NOT_NULL(queue);
1039  delete queue;
1040 }
1041 NOEXCEPT_RETURN(, queue)
1042 
1044 {
1045  VALIDATE_NOT_NULL(queue);
1047  if (!queue->queue.dequeue(&fh, timeout_ms))
1048  {
1049  throw std::runtime_error("Frame did not arrive in time!");
1050  }
1051 
1052  frame_interface* result = nullptr;
1053  std::swap(result, fh.frame);
1054  return (rs2_frame*)result;
1055 }
1056 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, queue)
1057 
1059 {
1060  VALIDATE_NOT_NULL(queue);
1061  VALIDATE_NOT_NULL(output_frame);
1063  if (queue->queue.try_dequeue(&fh))
1064  {
1065  frame_interface* result = nullptr;
1066  std::swap(result, fh.frame);
1067  *output_frame = (rs2_frame*)result;
1068  return true;
1069  }
1070 
1071  return false;
1072 }
1073 HANDLE_EXCEPTIONS_AND_RETURN(0, queue, output_frame)
1074 
1075 int rs2_try_wait_for_frame(rs2_frame_queue* queue, unsigned int timeout_ms, rs2_frame** output_frame, rs2_error** error) BEGIN_API_CALL
1076 {
1077  VALIDATE_NOT_NULL(queue);
1078  VALIDATE_NOT_NULL(output_frame);
1080  if (!queue->queue.dequeue(&fh, timeout_ms))
1081  {
1082  return false;
1083  }
1084 
1085  frame_interface* result = nullptr;
1086  std::swap(result, fh.frame);
1087  *output_frame = (rs2_frame*)result;
1088  return true;
1089 }
1090 HANDLE_EXCEPTIONS_AND_RETURN(0, queue, output_frame)
1091 
1093 {
1095  VALIDATE_NOT_NULL(queue);
1096  auto q = reinterpret_cast<rs2_frame_queue*>(queue);
1098  fh.frame = (frame_interface*)frame;
1099  q->queue.enqueue(std::move(fh));
1100 }
1101 NOEXCEPT_RETURN(, frame, queue)
1102 
1104 {
1105  VALIDATE_NOT_NULL(queue);
1106  queue->queue.clear();
1107 }
1109 
1111  const rs2_stream_profile* to,
1113 {
1114  VALIDATE_NOT_NULL(from);
1115  VALIDATE_NOT_NULL(to);
1116  VALIDATE_NOT_NULL(extrin);
1117 
1118  if (!environment::get_instance().get_extrinsics_graph().try_fetch_extrinsics(*from->profile, *to->profile, extrin))
1119  {
1120  throw not_implemented_exception("Requested extrinsics are not available!");
1121  }
1122 }
1123 HANDLE_EXCEPTIONS_AND_RETURN(, from, to, extrin)
1124 
1126  const rs2_stream_profile* to,
1128 {
1129  VALIDATE_NOT_NULL(from);
1130  VALIDATE_NOT_NULL(to);
1131 
1132  environment::get_instance().get_extrinsics_graph().register_extrinsics(*from->profile, *to->profile, extrin);
1133 }
1134 HANDLE_EXCEPTIONS_AND_RETURN(, from, to, extrin)
1135 
1137 {
1140 
1142  ois->override_extrinsics( *extrinsics );
1143 }
1145 
1147 {
1149  VALIDATE_NOT_NULL( p_params_out );
1150 
1152  *p_params_out = cs->get_dsm_params();
1153 }
1154 HANDLE_EXCEPTIONS_AND_RETURN( , sensor, p_params_out )
1155 
1157 {
1159  VALIDATE_NOT_NULL( p_params );
1160 
1162  cs->override_dsm_params( *p_params );
1163 }
1164 HANDLE_EXCEPTIONS_AND_RETURN( , sensor, p_params )
1165 
1167 {
1169 
1171  cs->reset_calibration();
1172 }
1174 
1175 
1177 {
1179  device->device->hardware_reset();
1180 }
1182 
1183 // Verify and provide API version encoded as integer value
1185 {
1186  // Each component type is within [0-99] range
1190  return RS2_API_VERSION;
1191 }
1193 
1195 {
1198  verify_version_compatibility(api_version);
1199 
1200  return new rs2_context{ std::make_shared<librealsense::context>(librealsense::backend_type::record, filename, section, mode) };
1201 }
1202 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, api_version, filename, section, mode)
1203 
1204 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
1205 {
1208  verify_version_compatibility(api_version);
1209 
1210  return new rs2_context{ std::make_shared<librealsense::context>(librealsense::backend_type::playback, filename, section, RS2_RECORDING_MODE_COUNT, std::string(min_api_version)) };
1211 }
1212 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, api_version, filename, section)
1213 
1214 rs2_context* rs2_create_mock_context(int api_version, const char* filename, const char* section, rs2_error** error) BEGIN_API_CALL
1215 {
1218  verify_version_compatibility(api_version);
1219 
1220  return new rs2_context{ std::make_shared<librealsense::context>(librealsense::backend_type::playback, filename, section, RS2_RECORDING_MODE_COUNT) };
1221 }
1222 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, api_version, filename, section)
1223 
1224 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
1225 {
1227 
1228  VALIDATE_LE(min_x, max_x);
1229  VALIDATE_LE(min_y, max_y);
1230  VALIDATE_LE(0, min_x);
1231  VALIDATE_LE(0, min_y);
1232 
1234  roi->get_roi_method().set({ min_x, min_y, max_x, max_y });
1235 }
1236 HANDLE_EXCEPTIONS_AND_RETURN(, sensor, min_x, min_y, max_x, max_y)
1237 
1238 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
1239 {
1241  VALIDATE_NOT_NULL(min_x);
1242  VALIDATE_NOT_NULL(min_y);
1243  VALIDATE_NOT_NULL(max_x);
1244  VALIDATE_NOT_NULL(max_y);
1245 
1247  auto rect = roi->get_roi_method().get();
1248 
1249  *min_x = rect.min_x;
1250  *min_y = rect.min_y;
1251  *max_x = rect.max_x;
1252  *max_y = rect.max_y;
1253 }
1254 HANDLE_EXCEPTIONS_AND_RETURN(, sensor, min_x, min_y, max_x, max_y)
1255 
1257 const char* rs2_get_failed_function(const rs2_error* error) { return error ? error->function.c_str() : nullptr; }
1258 const char* rs2_get_failed_args(const rs2_error* error) { return error ? error->args.c_str() : nullptr; }
1259 const char* rs2_get_error_message(const rs2_error* error) { return error ? error->message.c_str() : nullptr; }
1261 
1280 const char* rs2_ambient_light_to_string( rs2_ambient_light ambient ) { return get_string(ambient); }
1281 const char* rs2_digital_gain_to_string(rs2_digital_gain gain) { return get_string(gain); }
1286 
1288 {
1289  librealsense::log_to_console(min_severity);
1290 }
1291 HANDLE_EXCEPTIONS_AND_RETURN(, min_severity)
1292 
1294 {
1295  librealsense::log_to_file(min_severity, file_path);
1296 }
1297 HANDLE_EXCEPTIONS_AND_RETURN(, min_severity, file_path)
1298 
1300 {
1301  // Wrap the C++ callback interface with a shared_ptr that we set to release() it (rather than delete it)
1302  librealsense::log_to_callback( min_severity,
1303  { callback, []( rs2_log_callback * p ) { p->release(); } }
1304  );
1305 }
1306 HANDLE_EXCEPTIONS_AND_RETURN( , min_severity, callback )
1307 
1309 {
1311 }
1313 
1315 {
1317 }
1318 HANDLE_EXCEPTIONS_AND_RETURN(, max_size)
1319 
1320 // librealsense wrapper around a C function
1322 {
1324  void* _user_arg;
1325 
1326 public:
1327  on_log_callback( rs2_log_callback_ptr on_log, void * user_arg ) : _on_log( on_log ), _user_arg( user_arg ) {}
1328 
1329  void on_log( rs2_log_severity severity, rs2_log_message const& msg ) noexcept override
1330  {
1331  if( _on_log )
1332  {
1333  try
1334  {
1335  _on_log( severity, &msg, _user_arg );
1336  }
1337  catch( ... )
1338  {
1339  std::cerr << "Received an execption from log callback!" << std::endl;
1340  }
1341  }
1342  }
1343  void release() override
1344  {
1345  // Shouldn't get called...
1346  throw std::runtime_error( "on_log_callback::release() ?!?!?!" );
1347  delete this;
1348  }
1349 };
1350 
1352 {
1353  // Wrap the C function with a callback interface that will get deleted when done
1354  librealsense::log_to_callback( min_severity,
1356  );
1357 }
1358 HANDLE_EXCEPTIONS_AND_RETURN( , min_severity, on_log, arg )
1359 
1360 
1362 {
1363  VALIDATE_NOT_NULL( msg );
1364  log_message const& wrapper = *(log_message const*) (msg);
1365  return wrapper.get_log_message_line_number();
1366 }
1368 
1370 {
1371  VALIDATE_NOT_NULL( msg );
1372  log_message const& wrapper = *(log_message const*) (msg);
1373  return wrapper.get_log_message_filename();
1374 }
1375 HANDLE_EXCEPTIONS_AND_RETURN( nullptr, msg )
1376 
1378 {
1379  VALIDATE_NOT_NULL( msg );
1380  log_message const & wrapper = *( log_message const * )( msg );
1381  return wrapper.get_raw_log_message();
1382 }
1383 HANDLE_EXCEPTIONS_AND_RETURN( nullptr, msg )
1384 
1386 {
1387  VALIDATE_NOT_NULL( msg );
1388  log_message & wrapper = *( log_message * )( msg );
1389  return wrapper.get_full_log_message();
1390 }
1391 HANDLE_EXCEPTIONS_AND_RETURN( nullptr, msg )
1392 
1393 
1395 {
1397  VALIDATE_ENUM(extension_type);
1398  switch (extension_type)
1399  {
1417 
1418 
1419  default:
1420  return false;
1421  }
1422 }
1423 HANDLE_EXCEPTIONS_AND_RETURN(0, sensor, extension_type)
1424 
1426 {
1427  VALIDATE_NOT_NULL(dev);
1428  VALIDATE_ENUM(extension);
1429  switch (extension)
1430  {
1431  case RS2_EXTENSION_DEBUG : return VALIDATE_INTERFACE_NO_THROW(dev->device, librealsense::debug_interface) != nullptr;
1432  case RS2_EXTENSION_INFO : return VALIDATE_INTERFACE_NO_THROW(dev->device, librealsense::info_interface) != nullptr;
1442  case RS2_EXTENSION_RECORD : return VALIDATE_INTERFACE_NO_THROW(dev->device, librealsense::record_device) != nullptr;
1444  case RS2_EXTENSION_TM2 : return VALIDATE_INTERFACE_NO_THROW(dev->device, librealsense::tm2_extensions) != nullptr;
1445  case RS2_EXTENSION_UPDATABLE : return VALIDATE_INTERFACE_NO_THROW(dev->device, librealsense::updatable) != nullptr;
1453 
1454  default:
1455  return false;
1456  }
1457 }
1458 HANDLE_EXCEPTIONS_AND_RETURN(0, dev, extension)
1459 
1460 
1462 {
1464  VALIDATE_ENUM(extension_type);
1465  switch (extension_type)
1466  {
1474 
1475  default:
1476  return false;
1477  }
1478 }
1479 HANDLE_EXCEPTIONS_AND_RETURN(0, f, extension_type)
1480 
1482 {
1484  VALIDATE_ENUM(extension_type);
1485  switch (extension_type)
1486  {
1497 
1498  default:
1499  return false;
1500  }
1501 }
1502 HANDLE_EXCEPTIONS_AND_RETURN(0, f, extension_type)
1503 
1505 {
1507  VALIDATE_ENUM(extension_type);
1508  switch (extension_type)
1509  {
1513  default:
1514  return false;
1515  }
1516 }
1517 HANDLE_EXCEPTIONS_AND_RETURN(0, f, extension_type)
1518 
1520 {
1522  VALIDATE_NOT_NULL(file);
1523 
1524  auto dev_info = ctx->ctx->add_device(file);
1525  return new rs2_device{ ctx->ctx, dev_info, dev_info->create_device(false) };
1526 }
1527 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, ctx, file)
1528 
1530 {
1532  VALIDATE_NOT_NULL(dev);
1533  auto software_dev = VALIDATE_INTERFACE(dev->device, librealsense::software_device);
1534 
1535  ctx->ctx->add_software_device(software_dev->get_info());
1536 }
1538 
1540 {
1542  VALIDATE_NOT_NULL(file);
1543  ctx->ctx->remove_device(file);
1544 }
1546 
1548 {
1549 #if WITH_TRACKING
1551  ctx->ctx->unload_tracking_module();
1552 #endif
1553 }
1555 
1557 {
1560  return playback->get_file_name().c_str();
1561 }
1563 
1565 {
1568  return playback->get_duration();
1569 }
1571 
1573 {
1575  VALIDATE_LE(0, time);
1577  playback->seek_to_time(std::chrono::nanoseconds(time));
1578 }
1580 
1582 {
1585  return playback->get_position();
1586 }
1588 
1590 {
1593  playback->resume();
1594 }
1596 
1598 {
1601  return playback->pause();
1602 }
1604 
1606 {
1609  playback->set_real_time(real_time == 0 ? false : true);
1610 }
1612 
1614 {
1617  return playback->is_real_time() ? 1 : 0;
1618 }
1620 
1622 {
1626  auto cb = std::shared_ptr<rs2_playback_status_changed_callback>(callback, [](rs2_playback_status_changed_callback* p) { if (p) p->release(); });
1627  playback->playback_status_changed += [cb](rs2_playback_status status) { cb->on_playback_status_changed(status); };
1628 }
1630 
1631 
1633 {
1636  return playback->get_current_status();
1637 }
1639 
1641 {
1644  playback->set_frame_rate(speed);
1645 }
1647 
1649 {
1652  return playback->stop();
1653 }
1655 
1657 {
1660  VALIDATE_NOT_NULL(file);
1661 
1662  return rs2_create_record_device_ex(device, file, device->device->compress_while_record(), error);
1663 }
1665 
1666 rs2_device* rs2_create_record_device_ex(const rs2_device* device, const char* file, int compression_enabled, rs2_error** error) BEGIN_API_CALL
1667 {
1669  VALIDATE_NOT_NULL(file);
1670 
1671  return new rs2_device({
1672  device->ctx,
1673  device->info,
1674  std::make_shared<record_device>(device->device, std::make_shared<ros_writer>(file, compression_enabled))
1675  });
1676 }
1677 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, device, file)
1678 
1680 {
1684 }
1686 
1688 {
1692 }
1694 
1696 {
1699  return record_device->get_filename().c_str();
1700 }
1702 
1703 
1705  int new_bpp, int new_width, int new_height, int new_stride, rs2_extension frame_type, rs2_error** error) BEGIN_API_CALL
1706 {
1708  VALIDATE_NOT_NULL(original);
1709  VALIDATE_NOT_NULL(new_stream);
1710 
1711  auto recovered_profile = std::dynamic_pointer_cast<stream_profile_interface>(new_stream->profile->shared_from_this());
1712 
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);
1715 }
1716 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, source, new_stream, original, new_bpp, new_width, new_height, new_stride, frame_type)
1717 
1720 {
1722  VALIDATE_NOT_NULL(original);
1723  VALIDATE_NOT_NULL(new_stream);
1724 
1725  auto recovered_profile = std::dynamic_pointer_cast<stream_profile_interface>(new_stream->profile->shared_from_this());
1726 
1727  return (rs2_frame*)source->source->allocate_motion_frame(recovered_profile,
1728  (frame_interface*)original, frame_type);
1729 }
1730 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, source, new_stream, original, frame_type)
1731 
1733 {
1735  VALIDATE_NOT_NULL(original);
1736  VALIDATE_NOT_NULL(new_stream);
1737 
1738  auto recovered_profile = std::dynamic_pointer_cast<stream_profile_interface>(new_stream->profile->shared_from_this());
1739 
1740  return (rs2_frame*)source->source->allocate_points(recovered_profile,
1741  (frame_interface*)original);
1742 }
1743 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, source, new_stream, original)
1744 
1746 {
1748 
1751 
1752  source->source->frame_ready(std::move(holder));
1753 }
1755 
1757 {
1759 
1760  auto pipe = std::make_shared<pipeline::pipeline>(ctx->ctx);
1761 
1762  return new rs2_pipeline{ pipe };
1763 }
1765 
1767 {
1769 
1770  pipe->pipeline->stop();
1771 }
1773 
1775 {
1777 
1778  auto f = pipe->pipeline->wait_for_frames(timeout_ms);
1779  auto frame = f.frame;
1780  f.frame = nullptr;
1781  return (rs2_frame*)(frame);
1782 }
1784 
1786 {
1788  VALIDATE_NOT_NULL(output_frame);
1789 
1791  if (pipe->pipeline->poll_for_frames(&fh))
1792  {
1793  frame_interface* result = nullptr;
1794  std::swap(result, fh.frame);
1795  *output_frame = (rs2_frame*)result;
1796  return true;
1797  }
1798  return false;
1799 }
1800 HANDLE_EXCEPTIONS_AND_RETURN(0, pipe, output_frame)
1801 
1803 {
1805  VALIDATE_NOT_NULL(output_frame);
1806 
1808  if (pipe->pipeline->try_wait_for_frames(&fh, timeout_ms))
1809  {
1810  frame_interface* result = nullptr;
1811  std::swap(result, fh.frame);
1812  *output_frame = (rs2_frame*)result;
1813  return true;
1814  }
1815  return false;
1816 }
1817 HANDLE_EXCEPTIONS_AND_RETURN(0, pipe, output_frame)
1818 
1820 {
1822 
1823  delete pipe;
1824 }
1826 
1828 {
1830  return new rs2_pipeline_profile{ pipe->pipeline->start(std::make_shared<pipeline::config>()) };
1831 }
1833 
1835 {
1838  return new rs2_pipeline_profile{ pipe->pipeline->start(config->config) };
1839 }
1841 
1843 {
1846  return new rs2_pipeline_profile{ pipe->pipeline->start(std::make_shared<pipeline::config>(), move(callback)) };
1847 }
1849 
1851 {
1855  return new rs2_pipeline_profile{ pipe->pipeline->start(config->config, callback) };
1856 }
1858 
1860 {
1863 
1864  return new rs2_pipeline_profile{ pipe->pipeline->start(std::make_shared<pipeline::config>(),
1865  { callback, [](rs2_frame_callback* p) { p->release(); } }) };
1866 }
1868 
1870 {
1874 
1875  return new rs2_pipeline_profile{ pipe->pipeline->start(config->config,
1876  { callback, [](rs2_frame_callback* p) { p->release(); } }) };
1877 }
1879 
1881 {
1883 
1884  return new rs2_pipeline_profile{ pipe->pipeline->get_active_profile() };
1885 }
1887 
1889 {
1891 
1892  auto dev = profile->profile->get_device();
1893  auto dev_info = std::make_shared<librealsense::readonly_device_info>(dev);
1894  return new rs2_device{ dev->get_context(), dev_info , dev };
1895 }
1897 
1899 {
1901  return new rs2_stream_profile_list{ profile->profile->get_active_streams() };
1902 }
1904 
1906 {
1908 
1909  delete profile;
1910 }
1912 
1913 //config
1915 {
1916  return new rs2_config{ std::make_shared<pipeline::config>() };
1917 }
1918 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, 0)
1919 
1921 {
1923 
1924  delete config;
1925 }
1927 
1930  int index,
1931  int width,
1932  int height,
1934  int framerate,
1936 {
1938  config->config->enable_stream(stream, index, width, height, format, framerate);
1939 }
1941 
1943 {
1945  config->config->enable_all_stream();
1946 }
1948 
1950 {
1952  VALIDATE_NOT_NULL(serial);
1953 
1954  config->config->enable_device(serial);
1955 
1956 }
1958 
1960 {
1962  VALIDATE_NOT_NULL(file);
1963 
1964  config->config->enable_device_from_file(file, repeat_playback);
1965 }
1967 
1969 {
1971  VALIDATE_NOT_NULL(file);
1972 
1973  config->config->enable_device_from_file(file, true);
1974 }
1976 
1978 {
1980  VALIDATE_NOT_NULL(file);
1981 
1982  config->config->enable_record_to_file(file);
1983 }
1985 
1987 {
1989  config->config->disable_stream(stream);
1990 }
1992 
1994 {
1996  config->config->disable_stream(stream, index);
1997 }
1999 
2001 {
2003  config->config->disable_all_streams();
2004 }
2006 
2008 {
2011  return new rs2_pipeline_profile{ config->config->resolve(pipe->pipeline) };
2012 }
2014 
2016 {
2019  return config->config->can_resolve(pipe->pipeline) ? 1 : 0;
2020 }
2022 
2024 {
2025  auto block = std::make_shared<librealsense::processing_block>("Custom processing block");
2026  block->set_processing_callback({ proc, [](rs2_frame_processor_callback* p) { p->release(); } });
2027 
2028  return new rs2_processing_block{ block };
2029 }
2030 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, proc)
2031 
2033 {
2034  VALIDATE_NOT_NULL(proc);
2035 
2036  auto block = std::make_shared<librealsense::processing_block>("Custom processing block");
2037 
2038  block->set_processing_callback({
2040  [](rs2_frame_processor_callback* p) { } });
2041 
2042  return new rs2_processing_block{ block };
2043 }
2044 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, proc, context)
2045 
2046 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
2047 {
2048  VALIDATE_NOT_NULL(block);
2049  VALIDATE_LE(min, max);
2050  VALIDATE_RANGE(def, min, max);
2051  VALIDATE_LE(0, step);
2052 
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 });
2055  // TODO: am I supposed to use the extensions API here?
2056  auto options = dynamic_cast<options_container*>(block->options);
2057  options->register_option(option_id, opt);
2058  return true;
2059 }
2060 HANDLE_EXCEPTIONS_AND_RETURN(false, block, option_id, min, max, step, def)
2061 
2063 {
2064  auto block = std::make_shared<librealsense::syncer_process_unit>();
2065 
2066  return new rs2_processing_block{ block };
2067 }
2069 
2071 {
2072  VALIDATE_NOT_NULL(block);
2073 
2074  block->block->set_output_callback({ on_frame, [](rs2_frame_callback* p) { p->release(); } });
2075 }
2077 
2079 {
2080  VALIDATE_NOT_NULL(block);
2082 
2083  block->block->set_output_callback({ new frame_callback(on_frame, user), [](rs2_frame_callback* p) { } });
2084 }
2085 HANDLE_EXCEPTIONS_AND_RETURN(, block, on_frame, user)
2086 
2088 {
2089  VALIDATE_NOT_NULL(block);
2090  VALIDATE_NOT_NULL(queue);
2093  block->block->set_output_callback(move(callback));
2094 }
2095 HANDLE_EXCEPTIONS_AND_RETURN(, block, queue)
2096 
2098 {
2099  VALIDATE_NOT_NULL(block);
2101 
2102  block->block->invoke(frame_holder((frame_interface*)frame));
2103 }
2105 
2107 {
2108  VALIDATE_NOT_NULL(block);
2109 
2110  delete block;
2111 }
2112 NOEXCEPT_RETURN(, block)
2113 
2115 {
2116  VALIDATE_NOT_NULL(composite);
2117 
2119 
2120  VALIDATE_RANGE(index, 0, (int)cf->get_embedded_frames_count() - 1);
2121  auto res = cf->get_frame(index);
2122  res->acquire();
2123  return (rs2_frame*)res;
2124 }
2125 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, composite)
2126 
2128 {
2131  VALIDATE_RANGE(count, 1, 128);
2132 
2133  std::vector<frame_holder> holders(count);
2134  for (int i = 0; i < count; i++)
2135  {
2136  holders[i] = std::move(frame_holder((frame_interface*)frames[i]));
2137  }
2138  auto res = source->source->allocate_composite_frame(std::move(holders));
2139 
2140  return (rs2_frame*)res;
2141 }
2143 
2145 {
2146  VALIDATE_NOT_NULL(composite)
2147 
2149 
2150  return static_cast<int>(cf->get_embedded_frames_count());
2151 }
2152 HANDLE_EXCEPTIONS_AND_RETURN(0, composite)
2153 
2155 {
2158  return (rs2_vertex*)points->get_vertices();
2159 }
2161 
2163 {
2168 }
2170 
2172 {
2176 }
2178 
2180 {
2183  return static_cast<int>(points->get_vertex_count());
2184 }
2186 
2188 {
2189  return new rs2_processing_block { pointcloud::create() };
2190 }
2192 
2194 {
2195  return new rs2_processing_block { std::make_shared<yuy2_converter>(RS2_FORMAT_RGB8) };
2196 }
2198 
2200 {
2201  return new rs2_processing_block { std::make_shared<threshold>() };
2202 }
2204 
2206 {
2207  return new rs2_processing_block { std::make_shared<units_transform>() };
2208 }
2210 
2212 {
2214 
2215  auto block = create_align(align_to);
2216 
2217  return new rs2_processing_block{ block };
2218 }
2220 
2222 {
2223  auto block = std::make_shared<librealsense::colorizer>();
2224 
2225  auto res = new rs2_processing_block{ block };
2226 
2227  return res;
2228 }
2230 
2231 
2233 {
2234  auto block = std::make_shared<librealsense::decimation_filter>();
2235 
2236  return new rs2_processing_block{ block };
2237 }
2239 
2241 {
2242  auto block = std::make_shared<librealsense::temporal_filter>();
2243 
2244  return new rs2_processing_block{ block };
2245 }
2247 
2249 {
2250  auto block = std::make_shared<librealsense::spatial_filter>();
2251 
2252  return new rs2_processing_block{ block };
2253 }
2255 
2257 {
2258  auto block = std::make_shared<librealsense::disparity_transform>(transform_to_disparity > 0);
2259 
2260  return new rs2_processing_block{ block };
2261 }
2262 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, transform_to_disparity)
2263 
2265 {
2266  auto block = std::make_shared<librealsense::hole_filling_filter>();
2267 
2268  return new rs2_processing_block{ block };
2269 }
2271 
2273 {
2274  auto block = std::make_shared<librealsense::rates_printer>();
2275 
2276  return new rs2_processing_block{ block };
2277 }
2279 
2281 {
2282  auto block = std::make_shared<librealsense::zero_order>();
2283 
2284  return new rs2_processing_block{ block };
2285 }
2287 
2289 {
2290  auto block = std::make_shared<librealsense::depth_decompression_huffman>();
2291 
2292  return new rs2_processing_block{ block };
2293 }
2295 
2297 {
2298  auto block = std::make_shared<librealsense::hdr_merge>();
2299 
2300  return new rs2_processing_block{ block };
2301 }
2303 
2305 {
2306  auto block = std::make_shared<librealsense::sequence_id_filter>();
2307 
2308  return new rs2_processing_block{ block };
2309 }
2311 
2313 {
2316  return ds->get_depth_scale();
2317 }
2319 
2321 {
2323 
2325  return murs->get_max_usable_depth_range();
2326 }
2327 
2329 
2331 {
2334  return ds->get_stereo_baseline_mm();
2335 }
2337 
2339 {
2341  VALIDATE_NOT_NULL(sensor->parent.device);
2342  return new rs2_device(sensor->parent);
2343 }
2345 
2347 {
2348  VALIDATE_NOT_NULL(frame_ref);
2350  VALIDATE_RANGE(x, 0, df->get_width() - 1);
2351  VALIDATE_RANGE(y, 0, df->get_height() - 1);
2352  return df->get_distance(x, y);
2353 }
2354 HANDLE_EXCEPTIONS_AND_RETURN(0, frame_ref, x, y)
2355 
2357 {
2358  VALIDATE_NOT_NULL( frame_ref );
2359  auto df = VALIDATE_INTERFACE((( frame_interface * ) frame_ref ), librealsense::depth_frame );
2360  return df->get_units();
2361 }
2362 HANDLE_EXCEPTIONS_AND_RETURN( 0, frame_ref )
2363 
2365 {
2366  VALIDATE_NOT_NULL(frame_ref);
2368  return df->get_stereo_baseline();
2369 }
2370 HANDLE_EXCEPTIONS_AND_RETURN(0, frame_ref)
2371 
2373 {
2376 
2378 
2379  const float3 t = pf->get_translation();
2380  pose->translation = { t.x, t.y, t.z };
2381 
2382  const float3 v = pf->get_velocity();
2383  pose->velocity = { v.x, v.y, v.z };
2384 
2385  const float3 a = pf->get_acceleration();
2386  pose->acceleration = { a.x, a.y, a.z };
2387 
2388  const float4 r = pf->get_rotation();
2389  pose->rotation = { r.x, r.y, r.z, r.w };
2390 
2391  const float3 av = pf->get_angular_velocity();
2392  pose->angular_velocity = { av.x, av.y, av.z };
2393 
2394  const float3 aa = pf->get_angular_acceleration();
2395  pose->angular_acceleration = { aa.x, aa.y, aa.z };
2396 
2397  pose->tracker_confidence = pf->get_tracker_confidence();
2398  pose->mapper_confidence = pf->get_mapper_confidence();
2399 }
2401 
2402 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
2403 {
2404  VALIDATE_NOT_NULL(frame_ref);
2405  VALIDATE_NOT_NULL(target_dims_size);
2406 
2408  if (vf->get_stream()->get_format() != RS2_FORMAT_Y8)
2409  throw std::runtime_error("wrong video frame format");
2410 
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());
2414  else
2415  throw std::runtime_error("unsupported calibration target type");
2416 
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");
2419 }
2420 HANDLE_EXCEPTIONS_AND_RETURN(, frame_ref, calib_type, target_dims, target_dims_size)
2421 
2423 {
2424  return environment::get_instance().get_time_service()->get_time();
2425 }
2427 
2429 {
2430  auto dev = std::make_shared<software_device>();
2431  return new rs2_device{ dev->get_context(), std::make_shared<readonly_device_info>(dev), dev };
2432 }
2434 
2436 {
2437  VALIDATE_NOT_NULL(dev);
2438  auto df = VALIDATE_INTERFACE(dev->device, librealsense::software_device);
2439  df->set_matcher_type(m);
2440 }
2442 
2444 {
2445  VALIDATE_NOT_NULL(dev);
2446  auto df = VALIDATE_INTERFACE(dev->device, librealsense::software_device);
2447  df->register_info(info, val);
2448 }
2450 
2452 {
2453  VALIDATE_NOT_NULL(dev);
2454  auto df = VALIDATE_INTERFACE(dev->device, librealsense::software_device);
2455  if (df->supports_info(info))
2456  {
2457  df->update_info(info, val);
2458  }
2459  else throw librealsense::invalid_value_exception(librealsense::to_string() << "info " << rs2_camera_info_to_string(info) << " not supported by the device!");
2460 }
2462 
2464 {
2465  VALIDATE_NOT_NULL(dev);
2466  auto df = VALIDATE_INTERFACE(dev->device, librealsense::software_device);
2467 
2468  return new rs2_sensor(
2469  *dev,
2470  &df->add_software_sensor(sensor_name));
2471 }
2472 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, dev, sensor_name)
2473 
2475 {
2478  return bs->on_video_frame(frame);
2479 }
2481 
2483 {
2486  return bs->on_motion_frame(frame);
2487 }
2489 
2491 {
2494  return bs->on_pose_frame(frame);
2495 }
2497 
2499 {
2502  return bs->on_notification(notif);
2503 }
2504 HANDLE_EXCEPTIONS_AND_RETURN(, sensor, notif.category, notif.type, notif.severity, notif.description, notif.serialized_data)
2505 
2507 {
2510  return bs->set_metadata(key, value);
2511 }
2513 
2515 {
2518  return bs->add_video_stream(video_stream)->get_c_wrapper();
2519 }
2520 HANDLE_EXCEPTIONS_AND_RETURN(0,sensor, video_stream.type, video_stream.index, video_stream.fmt, video_stream.width, video_stream.height, video_stream.uid)
2521 
2523 {
2526  return bs->add_video_stream(video_stream, is_default)->get_c_wrapper();
2527 }
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)
2529 
2531 {
2534  return bs->add_motion_stream(motion_stream)->get_c_wrapper();
2535 }
2536 HANDLE_EXCEPTIONS_AND_RETURN(0, sensor, motion_stream.type, motion_stream.index, motion_stream.fmt, motion_stream.uid)
2537 
2539 {
2542  return bs->add_motion_stream(motion_stream, is_default)->get_c_wrapper();
2543 }
2544 HANDLE_EXCEPTIONS_AND_RETURN(0, sensor, motion_stream.type, motion_stream.index, motion_stream.fmt, motion_stream.uid, is_default)
2545 
2547 {
2550  return bs->add_pose_stream(pose_stream)->get_c_wrapper();
2551 }
2552 HANDLE_EXCEPTIONS_AND_RETURN(0, sensor, pose_stream.type, pose_stream.index, pose_stream.fmt, pose_stream.uid)
2553 
2555 {
2558  return bs->add_pose_stream(pose_stream, is_default)->get_c_wrapper();
2559 }
2560 HANDLE_EXCEPTIONS_AND_RETURN(0, sensor, pose_stream.type, pose_stream.index, pose_stream.fmt, pose_stream.uid, is_default)
2561 
2563 {
2566  return bs->add_read_only_option(option, val);
2567 }
2569 
2571 {
2574  return bs->update_read_only_option(option, val);
2575 }
2577 
2578 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
2579 {
2580  VALIDATE_LE(min, max);
2581  VALIDATE_RANGE(def, min, max);
2582  VALIDATE_LE(0, step);
2585  return bs->add_option(option, option_range{ min, max, step, def }, bool(is_writable));
2586 }
2587 HANDLE_EXCEPTIONS_AND_RETURN(, sensor, option, min, max, step, def, is_writable)
2588 
2590 {
2593  // Are the first two necessary?
2594  sensor->parent.ctx.reset();
2595  sensor->parent.info.reset();
2596  sensor->parent.device.reset();
2597 }
2599 
2601 {
2604  switch (severity)
2605  {
2607  LOG_DEBUG(message);
2608  break;
2609  case RS2_LOG_SEVERITY_INFO:
2610  LOG_INFO(message);
2611  break;
2612  case RS2_LOG_SEVERITY_WARN:
2614  break;
2616  LOG_ERROR(message);
2617  break;
2619  LOG_FATAL(message);
2620  break;
2621  case RS2_LOG_SEVERITY_NONE:
2622  break;
2623  default:
2624  LOG_INFO(message);
2625  }
2626 }
2628 
2630 {
2632  VALIDATE_NOT_NULL(from_file);
2633 
2635  loopback->enable_loopback(from_file);
2636 
2637 }
2639 
2641 {
2643 
2645  loopback->disable_loopback();
2646 }
2648 
2650 {
2652 
2654  return loopback->is_enabled() ? 1 : 0;
2655 }
2657 
2659 {
2661  VALIDATE_NOT_NULL(mac);
2662 
2664  tm2->connect_controller({ mac[0], mac[1], mac[2], mac[3], mac[4], mac[5] });
2665 }
2667 
2669 {
2671 
2673  tm2->disconnect_controller(id);
2674 }
2676 
2678 {
2682 
2684  tm2->set_intrinsics(*profile->profile, *intrinsics);
2685 }
2687 
2689 {
2692 
2694  ois->override_intrinsics( *intrinsics );
2695 }
2697 
2699 {
2700  VALIDATE_NOT_NULL(from_sensor);
2701  VALIDATE_NOT_NULL(from_profile);
2702  VALIDATE_NOT_NULL(to_sensor);
2705 
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();
2710 
2711  if (from_dev != to_dev)
2712  {
2713  LOG_ERROR("Cannot set extrinsics of two different devices \n");
2714  return;
2715  }
2716 
2717  auto tm2 = VALIDATE_INTERFACE(from_sensor->sensor, librealsense::tm2_sensor_interface);
2718  tm2->set_extrinsics(*from_profile->profile, *to_profile->profile, *extrinsics);
2719 }
2720 HANDLE_EXCEPTIONS_AND_RETURN(, from_sensor, from_profile, to_sensor, to_profile, extrinsics)
2721 
2723 {
2727 
2729  tm2->set_motion_device_intrinsics(*profile->profile, *intrinsics);
2730 }
2732 
2734 {
2736  auto tm2 = dynamic_cast<tm2_sensor_interface*>(&device->device->get_sensor(0));
2737  if (tm2)
2738  tm2->reset_to_factory_calibration();
2739  else
2740  {
2741  auto auto_calib = std::dynamic_pointer_cast<auto_calibrated_interface>(device->device);
2742  if (!auto_calib)
2743  throw std::runtime_error("this device does not supports reset to factory calibration");
2744  auto_calib->reset_to_factory_calibration();
2745  }
2746 }
2748 
2750 {
2752  auto tm2 = dynamic_cast<tm2_sensor_interface*>(&device->device->get_sensor(0));
2753  if (tm2)
2754  tm2->write_calibration();
2755  else
2756  {
2757  auto auto_calib = std::dynamic_pointer_cast<auto_calibrated_interface>(device->device);
2758  if (!auto_calib)
2759  throw std::runtime_error("this device does not supports auto calibration");
2760  auto_calib->write_calibration();
2761  }
2762 }
2764 
2766 {
2768  return new rs2_processing_block_list{ sensor->sensor->get_recommended_processing_blocks() };
2769 }
2771 
2773 {
2774  VALIDATE_NOT_NULL(list);
2775  VALIDATE_RANGE(index, 0, (int)list->list.size() - 1);
2776 
2777  return new rs2_processing_block(list->list[index]);
2778 }
2779 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, list, index)
2780 
2782 {
2783  VALIDATE_NOT_NULL(list);
2784  return static_cast<int>(list->list.size());
2785 }
2787 
2789 {
2790  VALIDATE_NOT_NULL(list);
2791  delete list;
2792 }
2793 NOEXCEPT_RETURN(, list)
2794 
2796 {
2797  VALIDATE_NOT_NULL(block);
2799  if (block->block->supports_info(info))
2800  {
2801  return block->block->get_info(info).c_str();
2802  }
2803  throw librealsense::invalid_value_exception(librealsense::to_string() << "Info " << rs2_camera_info_to_string(info) << " not supported by processing block!");
2804 }
2805 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, block, info)
2806 
2808 {
2809  VALIDATE_NOT_NULL(block);
2811  return block->block->supports_info(info);
2812 }
2813 HANDLE_EXCEPTIONS_AND_RETURN(false, block, info)
2814 
2815 int rs2_import_localization_map(const rs2_sensor* sensor, const unsigned char* lmap_blob, unsigned int blob_size, rs2_error** error) BEGIN_API_CALL
2816 {
2818  VALIDATE_NOT_NULL(lmap_blob);
2819  VALIDATE_RANGE(blob_size,1, std::numeric_limits<uint32_t>::max()); // Set by FW
2820 
2822 
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);
2825 }
2826 HANDLE_EXCEPTIONS_AND_RETURN(0, sensor, lmap_blob, blob_size)
2827 
2829 {
2831 
2833  std::vector<uint8_t> recv_buffer;
2834  if (pose_snr->export_relocalization_map(recv_buffer))
2835  return new rs2_raw_data_buffer{ recv_buffer };
2836  return (rs2_raw_data_buffer*)nullptr;
2837 }
2839 
2840 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
2841 {
2843  VALIDATE_NOT_NULL(guid);
2845  std::string s_guid(guid);
2846  VALIDATE_RANGE(s_guid.size(), 1, 127); // T2xx spec
2847 
2848  return int(pose_snr->set_static_node(s_guid, { pos.x, pos.y, pos.z }, { orient.x, orient.y, orient.z, orient.w }));
2849 }
2850 HANDLE_EXCEPTIONS_AND_RETURN(0, sensor, guid, pos, orient)
2851 
2853 {
2855  VALIDATE_NOT_NULL(guid);
2857  VALIDATE_NOT_NULL(orient);
2859  std::string s_guid(guid);
2860  VALIDATE_RANGE(s_guid.size(), 1, 127); // T2xx spec
2861 
2862  float3 t_pos{};
2863  float4 t_or {};
2864  int ret = 0;
2865  if ((ret = pose_snr->get_static_node(s_guid, t_pos, t_or)))
2866  {
2867  pos->x = t_pos.x;
2868  pos->y = t_pos.y;
2869  pos->z = t_pos.z;
2870  orient->x = t_or.x;
2871  orient->y = t_or.y;
2872  orient->z = t_or.z;
2873  orient->w = t_or.w;
2874  }
2875  return ret;
2876 }
2877 HANDLE_EXCEPTIONS_AND_RETURN(0, sensor, guid, pos, orient)
2878 
2880 {
2882  VALIDATE_NOT_NULL(guid);
2884  std::string s_guid(guid);
2885  VALIDATE_RANGE(s_guid.size(), 1, 127); // T2xx spec
2886 
2887  return int(pose_snr->remove_static_node(s_guid));
2888 }
2890 
2891 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
2892 {
2894  VALIDATE_NOT_NULL(odometry_blob);
2895  VALIDATE_RANGE(blob_size, 1, std::numeric_limits<uint32_t>::max());
2896 
2898 
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);
2901  if (!ret)
2902  throw librealsense::wrong_api_call_sequence_exception(librealsense::to_string() << "Load wheel odometry config failed, file size " << blob_size);
2903  return ret;
2904 }
2905 HANDLE_EXCEPTIONS_AND_RETURN(0, sensor, odometry_blob, blob_size)
2906 
2908  const rs2_vector translational_velocity, rs2_error** error) BEGIN_API_CALL
2909 {
2912 
2913  return wo_snr->send_wheel_odometry(wo_sensor_id, frame_num, { translational_velocity.x, translational_velocity.y, translational_velocity.z });
2914 }
2915 HANDLE_EXCEPTIONS_AND_RETURN(0, sensor, wo_sensor_id, frame_num, translational_velocity)
2916 
2918 {
2920  VALIDATE_NOT_NULL(fw_image);
2921  VALIDATE_FIXED_SIZE(fw_image_size, signed_fw_size); // check if the given FW size matches the expected FW size
2922 
2924 
2925  if (callback == NULL)
2926  fwu->update(fw_image, fw_image_size, nullptr);
2927  else
2928  fwu->update(fw_image, fw_image_size, { callback, [](rs2_update_progress_callback* p) { p->release(); } });
2929 }
2931 
2932 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
2933 {
2935  VALIDATE_NOT_NULL(fw_image);
2936  VALIDATE_FIXED_SIZE(fw_image_size, signed_fw_size); // check if the given FW size matches the expected FW size
2937 
2938  if (fw_image_size <= 0)
2939  throw std::runtime_error("invlid firmware image size provided to rs2_update");
2940 
2942 
2943  if(callback == NULL)
2944  fwu->update(fw_image, fw_image_size, nullptr);
2945  else
2946  {
2948  [](update_progress_callback* p) { delete p; });
2949  fwu->update(fw_image, fw_image_size, std::move(cb));
2950  }
2951 }
2953 
2955 {
2957 
2958  auto fwud = std::dynamic_pointer_cast<updatable>(device->device);
2959  if (!fwud)
2960  throw std::runtime_error("This device does not supports update protocol!");
2961 
2962  std::vector<uint8_t> res;
2963 
2964  if (callback == NULL)
2965  res = fwud->backup_flash(nullptr);
2966  else
2967  res = fwud->backup_flash({ callback, [](rs2_update_progress_callback* p) { p->release(); } });
2968 
2969  return new rs2_raw_data_buffer{ res };
2970 }
2972 
2974 {
2976 
2977  auto fwud = std::dynamic_pointer_cast<updatable>(device->device);
2978  if (!fwud)
2979  throw std::runtime_error("This device does not supports update protocol!");
2980 
2981  std::vector<uint8_t> res;
2982 
2983  if (callback == NULL)
2984  res = fwud->backup_flash(nullptr);
2985  else
2986  {
2988  [](update_progress_callback* p) { delete p; });
2989  res = fwud->backup_flash(std::move(cb));
2990  }
2991 
2992  return new rs2_raw_data_buffer{ res };
2993 }
2995 
2997 {
3000  VALIDATE_FIXED_SIZE(image_size, unsigned_fw_size); // check if the given FW size matches the expected FW size
3001 
3002  auto fwud = std::dynamic_pointer_cast<updatable>(device->device);
3003  if (!fwud)
3004  throw std::runtime_error("This device does not supports update protocol!");
3005 
3006  std::vector<uint8_t> buffer((uint8_t*)image, (uint8_t*)image + image_size);
3007 
3008  if (callback == NULL)
3009  fwud->update_flash(buffer, nullptr, update_mode);
3010  else
3011  fwud->update_flash(buffer, { callback, [](rs2_update_progress_callback* p) { p->release(); } }, update_mode);
3012 }
3014 
3015 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
3016 {
3019  VALIDATE_FIXED_SIZE(image_size, unsigned_fw_size); // check if the given FW size matches the expected FW size
3020 
3021  if (image_size <= 0)
3022  throw std::runtime_error("invlid firmware image size provided to rs2_update_firmware_unsigned");
3023 
3024  auto fwud = std::dynamic_pointer_cast<updatable>(device->device);
3025  if (!fwud)
3026  throw std::runtime_error("This device does not supports update protocol!");
3027 
3028  std::vector<uint8_t> buffer((uint8_t*)image, (uint8_t*)image + image_size);
3029 
3030  if (callback == NULL)
3031  fwud->update_flash(buffer, nullptr, update_mode);
3032  else
3033  {
3035  [](update_progress_callback* p) { delete p; });
3036  fwud->update_flash(buffer, std::move(cb), update_mode);
3037  }
3038 }
3040 
3042 {
3044 
3045  auto fwud = std::dynamic_pointer_cast<updatable>(device->device);
3046  if (!fwud)
3047  throw std::runtime_error("this device does not supports fw update");
3048  fwud->enter_update_state();
3049 }
3051 
3052 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
3053 {
3055  VALIDATE_NOT_NULL(health);
3056 
3057  if (content_size > 0)
3058  VALIDATE_NOT_NULL(json_content);
3059 
3061 
3062  std::vector<uint8_t> buffer;
3063 
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);
3067  else
3068  buffer = auto_calib->run_on_chip_calibration(timeout_ms, json, health, { progress_callback, [](rs2_update_progress_callback* p) { p->release(); } });
3069 
3070  return new rs2_raw_data_buffer { buffer };
3071 }
3073 
3074 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
3075 {
3077  VALIDATE_NOT_NULL(health);
3078 
3079  if (content_size > 0)
3080  VALIDATE_NOT_NULL(json_content);
3081 
3083 
3084  std::vector<uint8_t> buffer;
3085 
3086  std::string json((char*)json_content, (char*)json_content + content_size);
3087 
3088  if (progress_callback == nullptr)
3089  buffer = auto_calib->run_on_chip_calibration(timeout_ms, json, health, nullptr);
3090  else
3091  {
3093  [](update_progress_callback* p) { delete p; });
3094 
3095  buffer = auto_calib->run_on_chip_calibration(timeout_ms, json, health, cb);
3096  }
3097 
3098  return new rs2_raw_data_buffer{ buffer };
3099 }
3101 
3102 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
3103 {
3105 
3106  if(content_size > 0)
3107  VALIDATE_NOT_NULL(json_content);
3108 
3110 
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);
3115  else
3116  buffer = auto_calib->run_tare_calibration(timeout_ms, ground_truth_mm, json, { progress_callback, [](rs2_update_progress_callback* p) { p->release(); } });
3117 
3118  return new rs2_raw_data_buffer{ buffer };
3119 }
3121 
3122 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
3123 {
3125 
3126  if (content_size > 0)
3127  VALIDATE_NOT_NULL(json_content);
3128 
3130 
3131  std::vector<uint8_t> buffer;
3132  std::string json((char*)json_content, (char*)json_content + content_size);
3133 
3134  if (progress_callback == nullptr)
3135  buffer = auto_calib->run_tare_calibration(timeout_ms, ground_truth_mm, json, nullptr);
3136  else
3137  {
3139  [](update_progress_callback* p) { delete p; });
3140 
3141  buffer = auto_calib->run_tare_calibration(timeout_ms, ground_truth_mm, json, cb);
3142  }
3143  return new rs2_raw_data_buffer{ buffer };
3144 }
3146 
3148 {
3150 
3152  auto buffer = auto_calib->get_calibration_table();
3153  return new rs2_raw_data_buffer{ buffer };
3154 }
3156 
3157 void rs2_set_calibration_table(const rs2_device* device, const void* calibration, int calibration_size, rs2_error** error) BEGIN_API_CALL
3158 {
3160  VALIDATE_NOT_NULL(calibration);
3161 
3163 
3164  std::vector<uint8_t> buffer((uint8_t*)calibration, (uint8_t*)calibration + calibration_size);
3165  auto_calib->set_calibration_table(buffer);
3166 }
3167 HANDLE_EXCEPTIONS_AND_RETURN(,calibration, device)
3168 
3170 {
3171  VALIDATE_NOT_NULL(dev);
3172  auto serializable = VALIDATE_INTERFACE(dev->device, librealsense::serializable_interface);
3173  return new rs2_raw_data_buffer{ serializable->serialize_json() };
3174 }
3175 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, dev)
3176 
3177 void rs2_load_json(rs2_device* dev, const void* json_content, unsigned content_size, rs2_error** error) BEGIN_API_CALL
3178 {
3179  VALIDATE_NOT_NULL(dev);
3180  VALIDATE_NOT_NULL(json_content);
3181  auto serializable = VALIDATE_INTERFACE(dev->device, librealsense::serializable_interface);
3182  serializable->load_json(std::string(static_cast<const char*>(json_content), content_size));
3183 }
3184 HANDLE_EXCEPTIONS_AND_RETURN(, dev, json_content, content_size)
3185 
3187 {
3188  VALIDATE_NOT_NULL(dev);
3190 
3191  return new rs2_firmware_log_message{ std::make_shared <librealsense::fw_logs::fw_logs_binary_data>() };
3192 }
3193 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, dev)
3194 
3196 {
3197  VALIDATE_NOT_NULL(dev);
3198  VALIDATE_NOT_NULL(fw_log_msg);
3200 
3201  fw_logs::fw_logs_binary_data binary_data;
3202  bool result = fw_logger->get_fw_log(binary_data);
3203  if (result)
3204  {
3205  *(fw_log_msg->firmware_log_binary_data).get() = binary_data;
3206  }
3207  return result? 1 : 0;
3208 }
3209 HANDLE_EXCEPTIONS_AND_RETURN(0, dev, fw_log_msg)
3210 
3212 {
3213  VALIDATE_NOT_NULL(dev);
3214  VALIDATE_NOT_NULL(fw_log_msg);
3216 
3217  fw_logs::fw_logs_binary_data binary_data;
3218  bool result = fw_logger->get_flash_log(binary_data);
3219  if (result)
3220  {
3221  *(fw_log_msg->firmware_log_binary_data).get() = binary_data;
3222  }
3223  return result ? 1 : 0;
3224 }
3225 HANDLE_EXCEPTIONS_AND_RETURN(0, dev, fw_log_msg)
3227 {
3228  VALIDATE_NOT_NULL(msg);
3229  delete msg;
3230 }
3231 NOEXCEPT_RETURN(, msg)
3232 
3234 {
3235  VALIDATE_NOT_NULL(msg);
3236  return msg->firmware_log_binary_data->logs_buffer.data();
3237 }
3238 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, msg)
3239 
3241 {
3242  VALIDATE_NOT_NULL(msg);
3243  return (int)msg->firmware_log_binary_data->logs_buffer.size();
3244 }
3246 
3248 {
3249  return msg->firmware_log_binary_data->get_severity();
3250 }
3252 
3254 {
3255  VALIDATE_NOT_NULL(msg);
3256  return msg->firmware_log_binary_data->get_timestamp();
3257 }
3259 
3261 {
3262  VALIDATE_NOT_NULL(xml_content);
3263 
3265 
3266  return (fw_logger->init_parser(xml_content)) ? 1 : 0;
3267 }
3268 HANDLE_EXCEPTIONS_AND_RETURN(0, xml_content)
3269 
3271 {
3272  VALIDATE_NOT_NULL(dev);
3273 
3275 
3276  return new rs2_firmware_log_parsed_message{ std::make_shared <librealsense::fw_logs::fw_log_data>() };
3277 }
3279 
3281 {
3282  VALIDATE_NOT_NULL(dev);
3283  VALIDATE_NOT_NULL(fw_log_msg);
3284  VALIDATE_NOT_NULL(parsed_msg);
3285 
3287 
3288  bool parsing_result = fw_logger->parse_log(fw_log_msg->firmware_log_binary_data.get(),
3289  parsed_msg->firmware_log_parsed.get());
3290 
3291  return parsing_result ? 1 : 0;
3292 }
3293 HANDLE_EXCEPTIONS_AND_RETURN(0, dev, fw_log_msg)
3294 
3296 {
3297  VALIDATE_NOT_NULL(dev);
3298 
3300  return fw_logger->get_number_of_fw_logs();
3301 }
3303 
3305 {
3306  VALIDATE_NOT_NULL(fw_log_parsed_msg);
3307  delete fw_log_parsed_msg;
3308 }
3309 NOEXCEPT_RETURN(, fw_log_parsed_msg)
3310 
3312 {
3313  VALIDATE_NOT_NULL(fw_log_parsed_msg);
3314  return fw_log_parsed_msg->firmware_log_parsed->get_message().c_str();
3315 }
3316 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, fw_log_parsed_msg)
3317 
3319 {
3320  VALIDATE_NOT_NULL(fw_log_parsed_msg);
3321  return fw_log_parsed_msg->firmware_log_parsed->get_file_name().c_str();
3322 }
3323 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, fw_log_parsed_msg)
3324 
3326 {
3327  VALIDATE_NOT_NULL(fw_log_parsed_msg);
3328  return fw_log_parsed_msg->firmware_log_parsed->get_thread_name().c_str();
3329 }
3330 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, fw_log_parsed_msg)
3331 
3333 {
3334  VALIDATE_NOT_NULL(fw_log_parsed_msg);
3335  return fw_log_parsed_msg->firmware_log_parsed->get_severity();
3336 }
3338 
3340 {
3341  VALIDATE_NOT_NULL(fw_log_parsed_msg);
3342  return fw_log_parsed_msg->firmware_log_parsed->get_line();
3343 }
3344 HANDLE_EXCEPTIONS_AND_RETURN(0, fw_log_parsed_msg)
3345 
3347 {
3348  VALIDATE_NOT_NULL(fw_log_parsed_msg);
3349  return fw_log_parsed_msg->firmware_log_parsed->get_timestamp();
3350 }
3351 HANDLE_EXCEPTIONS_AND_RETURN(0, fw_log_parsed_msg)
3352 
3354 {
3355  VALIDATE_NOT_NULL(fw_log_parsed_msg);
3356  return fw_log_parsed_msg->firmware_log_parsed->get_sequence_id();
3357 }
3358 HANDLE_EXCEPTIONS_AND_RETURN(0, fw_log_parsed_msg)
3359 
3361 {
3362  VALIDATE_NOT_NULL(xml_content);
3363  return new rs2_terminal_parser{ std::make_shared<librealsense::terminal_parser>(std::string(xml_content)) };
3364 }
3365 HANDLE_EXCEPTIONS_AND_RETURN(nullptr, xml_content)
3366 
3368 {
3370  delete terminal_parser;
3371 }
3373 
3375  const char* command, unsigned int size_of_command, rs2_error** error) BEGIN_API_CALL
3376 {
3379  VALIDATE_LE(size_of_command, 1000);//bufer shall be less than 1000 bytes or similar
3380 
3381  std::string command_string;
3382  command_string.insert(command_string.begin(), command, command + size_of_command);
3383 
3384  auto result = terminal_parser->terminal_parser->parse_command(command_string);
3385  return new rs2_raw_data_buffer{ result };
3386 }
3388 
3390  const char* command, unsigned int size_of_command,
3391  const void* response, unsigned int size_of_response, rs2_error** error) BEGIN_API_CALL
3392 {
3395  VALIDATE_NOT_NULL(response);
3396  VALIDATE_LE(size_of_command, 1000); //bufer shall be less than 1000 bytes or similar
3397  VALIDATE_LE(size_of_response, 5000);//bufer shall be less than 5000 bytes or similar
3398 
3399 
3400  std::string command_string;
3401  command_string.insert(command_string.begin(), command, command + size_of_command);
3402 
3403  std::vector<uint8_t> response_vec;
3404  response_vec.insert(response_vec.begin(), (uint8_t*)response, (uint8_t*)response + size_of_response);
3405 
3406  auto result = terminal_parser->terminal_parser->parse_response(command_string, response_vec);
3407  return new rs2_raw_data_buffer{ result };
3408 }
3410 
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
Definition: rs.cpp:1928
int rs2_playback_device_is_real_time(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1613
rs2_sensor(rs2_device parent, librealsense::sensor_interface *sensor)
Definition: rs.cpp:68
void rs2_software_device_update_info(rs2_device *dev, rs2_camera_info info, const char *val, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2451
void rs2_delete_raw_data(const rs2_raw_data_buffer *buffer) BEGIN_API_CALL
Definition: rs.cpp:581
int rs2_loopback_is_enabled(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2649
static const textual_icon lock
Definition: model-views.h:218
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
Definition: rs.cpp:2722
rs2_time_t rs2_get_frame_timestamp(const rs2_frame *frame_ref, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:908
const void * rs2_get_frame_data(const rs2_frame *frame_ref, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:940
GLenum GLuint GLenum GLsizei const GLchar * message
rs2_options_list * rs2_get_options_list(const rs2_options *options, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:644
rs2_camera_info
Read-only strings that can be queried from the device. Not all information attributes are available o...
Definition: rs_sensor.h:22
rs2_metadata_type rs2_get_frame_metadata(const rs2_frame *frame, rs2_frame_metadata_value frame_metadata, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:846
void rs2_trigger_device_calibration(rs2_device *dev, rs2_calibration_type type, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:445
rs2_log_callback_ptr _on_log
Definition: rs.cpp:1323
void rs2_config_enable_device_from_file_repeat_option(rs2_config *config, const char *file, int repeat_playback, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1959
void rs2_delete_frame_queue(rs2_frame_queue *queue) BEGIN_API_CALL
Definition: rs.cpp:1036
const char * rs2_log_severity_to_string(rs2_log_severity severity)
Definition: rs.cpp:1271
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
Definition: rs.cpp:1704
const char * rs2_extension_to_string(rs2_extension type)
Definition: rs.cpp:1276
void rs2_software_sensor_update_read_only_option(rs2_sensor *sensor, rs2_option option, float val, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2570
~rs2_context()
Definition: rs.cpp:84
void reset_logger()
Definition: log.cpp:59
int rs2_get_stream_profiles_count(const rs2_stream_profile_list *list, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:360
GLint y
rs2_processing_block * rs2_get_processing_block(const rs2_processing_block_list *list, int index, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2772
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
Definition: rs.cpp:3122
#define RS2_API_VERSION
Definition: rs.h:41
void rs2_set_option(const rs2_options *options, rs2_option option, float value, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:636
rs2_processing_block * rs2_create_spatial_filter_block(rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2248
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.
Definition: rs.cpp:3332
rs2_processing_block * rs2_create_zero_order_invalidation_block(rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2280
rs2_exception_type
Exception types are the different categories of errors that RealSense API might return.
Definition: rs_types.h:30
rs2_processing_block * rs2_create_decimation_filter_block(rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2232
::realsense_legacy_msgs::extrinsics_< std::allocator< void > > extrinsics
Definition: extrinsics.h:59
GLenum GLuint GLenum severity
const char * get_log_message_filename() const
Definition: log.h:308
const char * get_string(rs2_rs400_visual_preset value)
const char * rs2_notification_category_to_string(rs2_notification_category category)
Definition: rs.cpp:1268
const int unsigned_fw_size
Definition: rs_internal.h:26
rs2_calibration_change_callback_ptr _callback
Definition: rs.cpp:388
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
Definition: rs.cpp:806
const char * rs2_ambient_light_to_string(rs2_ambient_light ambient)
Definition: rs.cpp:1280
GLuint const GLchar * name
float rs2_depth_frame_get_units(const rs2_frame *frame_ref, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2356
rs2_processing_block_list * rs2_get_recommended_processing_blocks(rs2_sensor *sensor, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2765
rs2_calibration_type
Definition: rs_device.h:344
void rs2_delete_processing_block(rs2_processing_block *block) BEGIN_API_CALL
Definition: rs.cpp:2106
rs2_playback_status rs2_playback_device_get_current_status(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1632
void rs2_start_cpp(const rs2_sensor *sensor, rs2_frame_callback *callback, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:798
#define RS2_API_MAJOR_VERSION
Definition: rs.h:25
#define LOG_FATAL(...)
Definition: src/types.h:243
float rs2_depth_stereo_frame_get_baseline(const rs2_frame *frame_ref, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2364
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.
Definition: rs.cpp:3346
void rs2_context_add_software_device(rs2_context *ctx, rs2_device *dev, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1529
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
Definition: rs.cpp:2402
rs2_time_t rs2_get_notification_timestamp(rs2_notification *notification, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:861
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls...
Definition: rs_option.h:22
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_...
Definition: rs.cpp:3339
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
Definition: rs.cpp:838
void rs2_pose_frame_get_pose_data(const rs2_frame *frame, rs2_pose *pose, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2372
rs2_processing_block * rs2_create_temporal_filter_block(rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2240
const char * get_full_log_message()
Definition: log.h:316
rs2_notification_category category
Definition: src/types.h:1107
void rs2_delete_recommended_processing_blocks(rs2_processing_block_list *list) BEGIN_API_CALL
Definition: rs.cpp:2788
const char * rs2_get_option_value_description(const rs2_options *options, rs2_option option, float value, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1022
void(* rs2_frame_processor_callback_ptr)(rs2_frame *, rs2_source *, void *)
Definition: rs_types.h:297
float2 * get_texture_coordinates()
Definition: archive.cpp:149
std::shared_ptr< rs2_frame_callback > frame_callback_ptr
Definition: src/types.h:1071
rs2_pipeline_profile * rs2_config_resolve(rs2_config *config, rs2_pipeline *pipe, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2007
std::shared_ptr< librealsense::pipeline::profile > profile
Definition: rs.cpp:105
rs2_pixel * rs2_get_frame_texture_coordinates(const rs2_frame *frame, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2171
struct rs2_frame_queue rs2_frame_queue
Definition: rs_types.h:262
GLfloat GLfloat p
Definition: glext.h:12687
const GLfloat * m
Definition: glext.h:6814
const int signed_fw_size
Definition: rs_internal.h:25
void rs2_playback_device_stop(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1648
void rs2_software_device_create_matcher(rs2_device *dev, rs2_matchers m, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2435
rs2_distortion
Distortion model: defines how pixel coordinates should be mapped to sensor coordinates.
Definition: rs_types.h:45
int rs2_is_sensor_extendable_to(const rs2_sensor *sensor, rs2_extension extension_type, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1394
const char * rs2_cah_trigger_to_string(rs2_cah_trigger mode)
Definition: rs.cpp:1282
int rs2_get_static_node(const rs2_sensor *sensor, const char *guid, rs2_vector *pos, rs2_quaternion *orient, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2852
void log_to_callback(rs2_log_severity min_severity, log_callback_ptr callback)
Definition: log.cpp:54
rs2_processing_block * rs2_create_units_transform(rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2205
rs2_recording_mode
Definition: rs_internal.h:32
void rs2_set_devices_changed_callback(const rs2_context *context, rs2_devices_changed_callback_ptr callback, void *user, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:787
rs2_sr300_visual_preset
For SR300 devices: provides optimized settings (presets) for specific types of usage.
Definition: rs_option.h:119
#define LOG_WARNING(...)
Definition: src/types.h:241
on_log_callback(rs2_log_callback_ptr on_log, void *user_arg)
Definition: rs.cpp:1327
std::shared_ptr< librealsense::fw_logs::fw_logs_binary_data > firmware_log_binary_data
Definition: rs.cpp:130
a class to store JSON values
Definition: json.hpp:221
Video DSM (Digital Sync Module) parameters for calibration (same layout as in FW ac_depth_params) Thi...
Definition: rs_types.h:74
std::vector< std::shared_ptr< device_info > > query_devices(int mask) const
Definition: context.cpp:320
int rs2_poll_for_frame(rs2_frame_queue *queue, rs2_frame **output_frame, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1058
void rs2_frame_add_ref(rs2_frame *frame, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1015
GLfloat value
void rs2_delete_context(rs2_context *context) BEGIN_API_CALL
Frees the relevant context object.
Definition: rs.cpp:171
int rs2_is_stream_profile_default(const rs2_stream_profile *profile, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:477
rs2_sensor_list * rs2_query_sensors(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:236
void rs2_delete_device(rs2_device *device) BEGIN_API_CALL
Definition: rs.cpp:301
std::shared_ptr< librealsense::fw_logs::fw_log_data > firmware_log_parsed
Definition: rs.cpp:135
void rs2_free_error(rs2_error *error)
Definition: rs.cpp:1256
void rs2_enable_rolling_log_file(unsigned max_size, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1314
std::shared_ptr< librealsense::pipeline::config > config
Definition: rs.cpp:100
All the parameters required to define a video stream.
Definition: rs_internal.h:41
rs2_sensor * rs2_create_sensor(const rs2_sensor_list *list, int index, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:308
const char * rs2_exception_type_to_string(rs2_exception_type type)
Definition: rs.cpp:1272
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
Definition: rs.cpp:2578
All the parameters required to define a pose frame.
Definition: rs_internal.h:100
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
Definition: rs.cpp:2840
rs2_calib_target_type
Calibration target type.
Definition: rs_frame.h:74
rs2_timestamp_domain rs2_get_frame_timestamp_domain(const rs2_frame *frame_ref, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:915
std::function< void(frame_interface *)> on_frame
Definition: streaming.h:164
rs2_processing_block * rs2_create_huffman_depth_decompress_block(rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2288
void rs2_reset_logger(rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1308
void rs2_enqueue_frame(rs2_frame *frame, void *queue) BEGIN_API_CALL
Definition: rs.cpp:1092
void rs2_software_sensor_detach(rs2_sensor *sensor, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2589
#define VALIDATE_FIXED_SIZE(ARG, SIZE)
Definition: api.h:405
virtual std::vector< uint8_t > send_receive_raw_data(const std::vector< uint8_t > &input)=0
std::string args
Definition: rs.cpp:143
float rs2_get_max_usable_depth_range(rs2_sensor const *sensor, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2320
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
Definition: rs.cpp:2917
const char * rs2_l500_visual_preset_to_string(rs2_l500_visual_preset preset)
Definition: rs.cpp:1278
void verify_version_compatibility(int api_version)
Definition: api.h:463
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.
Definition: rs.cpp:3318
rs2_context * rs2_create_mock_context(int api_version, const char *filename, const char *section, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1214
rs2_terminal_parser * rs2_create_terminal_parser(const char *xml_content, rs2_error **error) BEGIN_API_CALL
Creates RealSense terminal parser.
Definition: rs.cpp:3360
int rs2_supports_processing_block_info(const rs2_processing_block *block, rs2_camera_info info, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2807
const rs2_stream_profile * rs2_get_stream_profile(const rs2_stream_profile_list *list, int index, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:351
const char * rs2_sensor_mode_to_string(rs2_sensor_mode mode)
Definition: rs.cpp:1279
void rs2_log(rs2_log_severity severity, const char *message, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2600
GLsizei const GLchar *const * string
void export_to_ply(const std::string &fname, const frame_holder &texture)
Definition: archive.cpp:48
3D coordinates with origin at topmost left corner of the lense, with positive Z pointing away from th...
Definition: rs_types.h:117
d
Definition: rmse.py:171
rs2_processing_block * rs2_create_rates_printer_block(rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2272
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
Definition: rs.cpp:2554
void log_to_file(rs2_log_severity min_severity, const char *file_path)
Definition: log.cpp:49
rs2_device * rs2_create_record_device_ex(const rs2_device *device, const char *file, int compression_enabled, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1666
rs2_host_perf_mode
values for RS2_OPTION_HOST_PERFORMANCE option.
Definition: rs_option.h:202
int rs2_get_recommended_processing_blocks_count(const rs2_processing_block_list *list, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2781
void rs2_delete_sensor(rs2_sensor *device) BEGIN_API_CALL
Definition: rs.cpp:320
rs2_exception_type exception_type
Definition: rs.cpp:144
void rs2_delete_options_list(rs2_options_list *list) BEGIN_API_CALL
Definition: rs.cpp:672
const char * rs2_get_error_message(const rs2_error *error)
Definition: rs.cpp:1259
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
Definition: rs.cpp:1224
Definition: arg_fwd.hpp:23
GLdouble n
Definition: glext.h:1966
rs2_device * rs2_context_add_device(rs2_context *ctx, const char *file, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1519
unsigned char uint8_t
Definition: stdint.h:78
const char * rs2_stream_to_string(rs2_stream stream)
Definition: rs.cpp:1262
std::shared_ptr< librealsense::terminal_parser > terminal_parser
Definition: rs.cpp:125
void rs2_context_remove_device(rs2_context *ctx, const char *file, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1539
void rs2_get_extrinsics(const rs2_stream_profile *from, const rs2_stream_profile *to, rs2_extrinsics *extrin, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1110
GLenum GLfloat * buffer
void rs2_reset_sensor_calibration(rs2_sensor const *sensor, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1166
int rs2_embedded_frames_count(rs2_frame *composite, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2144
void rs2_software_sensor_on_video_frame(rs2_sensor *sensor, rs2_software_video_frame frame, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2474
rs2_cah_trigger
values for RS2_OPTION_TRIGGER_CAMERA_ACCURACY_HEALTH option.
Definition: rs_option.h:192
The texture class.
Definition: example.hpp:402
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
Definition: rs.cpp:1869
int rs2_get_sensors_count(const rs2_sensor_list *list, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:267
void(* rs2_log_callback_ptr)(rs2_log_severity, rs2_log_message const *, void *arg)
Definition: rs_types.h:292
struct rs2_sensor rs2_sensor
Definition: rs_types.h:282
int rs2_pipeline_poll_for_frames(rs2_pipeline *pipe, rs2_frame **output_frame, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1785
GLenum GLenum GLsizei void * image
#define RS2_API_MINOR_VERSION
Definition: rs.h:26
rs2_config * rs2_create_config(rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1914
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
Definition: rs.cpp:2087
void rs2_override_dsm_params(const rs2_sensor *sensor, rs2_dsm_params const *p_params, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1156
GLuint index
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.
Definition: rs.cpp:3270
void rs2_log_to_callback_cpp(rs2_log_severity min_severity, rs2_log_callback *callback, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1299
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.
Definition: rs.cpp:3304
rs2_frame * rs2_allocate_points(rs2_source *source, const rs2_stream_profile *new_stream, rs2_frame *original, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1732
void register_option(rs2_option id, std::shared_ptr< option > option)
Definition: options.h:86
virtual void release()=0
const char * rs2_get_raw_log_message(rs2_log_message const *msg, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1377
int rs2_pipeline_try_wait_for_frames(rs2_pipeline *pipe, rs2_frame **output_frame, unsigned int timeout_ms, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1802
const char * rs2_distortion_to_string(rs2_distortion distortion)
Definition: rs.cpp:1264
void(* rs2_update_progress_callback_ptr)(const float, void *)
Definition: rs_types.h:298
std::shared_ptr< rs2_update_progress_callback > update_progress_callback_ptr
Definition: src/types.h:1077
GLdouble t
GLenum cap
Definition: glext.h:8882
GLboolean GLboolean GLboolean GLboolean a
int rs2_get_frame_width(const rs2_frame *frame_ref, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:947
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
Definition: rs.cpp:2932
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
Definition: rs.cpp:1194
rs2_processing_block * rs2_create_threshold(rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2199
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.
Definition: rs.cpp:3374
#define RS2_API_PATCH_VERSION
Definition: rs.h:27
rs2_processing_block * rs2_create_sequence_id_filter(rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2304
void rs2_software_sensor_on_motion_frame(rs2_sensor *sensor, rs2_software_motion_frame frame, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2482
GLuint GLfloat * val
GLuint64 key
Definition: glext.h:8966
void rs2_load_json(rs2_device *dev, const void *json_content, unsigned content_size, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:3177
const char * rs2_sr300_visual_preset_to_string(rs2_sr300_visual_preset preset)
Definition: rs.cpp:1270
def info(name, value, persistent=False)
Definition: test.py:301
void * _user_arg
Definition: rs.cpp:1324
rs2_notification_category rs2_get_notification_category(rs2_notification *notification, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:875
const char * rs2_get_device_info(const rs2_device *dev, rs2_camera_info info, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:703
Quaternion used to represent rotation.
Definition: rs_types.h:135
std::shared_ptr< rs2_log_callback > log_callback_ptr
Definition: src/types.h:202
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
Definition: rs.cpp:1204
rs2_device_list * rs2_query_devices_ex(const rs2_context *context, int product_mask, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:214
const char * rs2_get_notification_serialized_data(rs2_notification *notification, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:882
rs2_exception_type rs2_get_librealsense_exception_type(const rs2_error *error)
Definition: rs.cpp:1260
rs2_processing_block * rs2_create_pointcloud(rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2187
rs2_device * rs2_create_record_device(const rs2_device *device, const char *file, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1656
GLdouble f
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
Definition: rs.cpp:3074
void rs2_hardware_reset(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1176
const rs2_stream_profile * rs2_get_frame_stream_profile(const rs2_frame *frame_ref, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:971
void rs2_log_to_console(rs2_log_severity min_severity, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1287
void register_extrinsics(const stream_interface &from, const stream_interface &to, std::weak_ptr< lazy< rs2_extrinsics >> extr)
Definition: environment.cpp:28
GLenum mode
void rs2_record_device_pause(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1679
rs2_stream_profile * rs2_software_sensor_add_motion_stream(rs2_sensor *sensor, rs2_motion_stream motion_stream, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2530
void rs2_process_frame(rs2_processing_block *block, rs2_frame *frame, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2097
static std::shared_ptr< pointcloud > create()
Definition: pointcloud.cpp:392
rs2_stream_profile * rs2_software_sensor_add_video_stream(rs2_sensor *sensor, rs2_video_stream video_stream, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2514
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.
Definition: rs.cpp:3311
const char * rs2_get_notification_description(rs2_notification *notification, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:854
const char * rs2_get_sensor_info(const rs2_sensor *sensor, rs2_camera_info info, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:724
processing_blocks list
Definition: rs.cpp:63
rs2_pipeline_profile * rs2_pipeline_start(rs2_pipeline *pipe, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1827
void rs2_software_sensor_on_pose_frame(rs2_sensor *sensor, rs2_software_pose_frame frame, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2490
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
Definition: rs.cpp:533
virtual std::shared_ptr< context > get_context() const =0
#define HANDLE_EXCEPTIONS_AND_RETURN(R,...)
Definition: api.h:399
void rs2_delete_terminal_parser(rs2_terminal_parser *terminal_parser) BEGIN_API_CALL
Deletes RealSense terminal parser.
Definition: rs.cpp:3367
void rs2_synthetic_frame_ready(rs2_source *source, rs2_frame *frame, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1745
librealsense::sensor_interface * sensor
Definition: rs.cpp:75
void rs2_close(const rs2_sensor *sensor, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:614
unsigned rs2_get_log_message_line_number(rs2_log_message const *msg, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1361
#define VALIDATE_INTERFACE_NO_THROW(X, T)
Definition: api.h:411
int rs2_is_processing_block_extendable_to(const rs2_processing_block *f, rs2_extension extension_type, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1481
const char * rs2_option_to_string(rs2_option option)
Definition: rs.cpp:1265
const char * rs2_playback_status_to_string(rs2_playback_status status)
Definition: rs.cpp:1273
const char * rs2_get_log_message_filename(rs2_log_message const *msg, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1369
rs2_stream_profile * rs2_software_sensor_add_pose_stream(rs2_sensor *sensor, rs2_pose_stream pose_stream, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2546
rs2_processing_block * rs2_create_yuy_decoder(rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2193
int rs2_get_options_list_size(const rs2_options_list *options, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:658
void rs2_playback_device_set_real_time(const rs2_device *device, int real_time, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1605
rs2_pipeline * rs2_create_pipeline(rs2_context *ctx, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1756
GLdouble GLdouble r
rs2_device * rs2_device_hub_wait_for_device(const rs2_device_hub *hub, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:191
void rs2_delete_pipeline(rs2_pipeline *pipe) BEGIN_API_CALL
Definition: rs.cpp:1819
std::shared_ptr< librealsense::device_hub > hub
Definition: rs.cpp:90
void rs2_config_enable_device_from_file(rs2_config *config, const char *file, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1968
void rs2_enter_update_state(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:3041
unsigned get_log_message_line_number() const
Definition: log.h:304
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.
Definition: rs.cpp:3233
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
Definition: rs.cpp:3157
GLdouble x
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.
Definition: rs.cpp:3280
All the parameters required to define a pose stream.
Definition: rs_internal.h:66
rs2_calibration_status
Definition: rs_device.h:356
nlohmann::json json
Definition: json_loader.hpp:22
int rs2_get_frame_bits_per_pixel(const rs2_frame *frame_ref, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:978
int rs2_get_frame_height(const rs2_frame *frame_ref, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:955
rs2_matchers
Specifies types of different matchers.
Definition: rs_types.h:230
const rs2_raw_data_buffer * rs2_get_calibration_table(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:3147
rs2_pipeline_profile * rs2_pipeline_start_with_callback_cpp(rs2_pipeline *pipe, rs2_frame_callback *callback, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1859
#define NOARGS_HANDLE_EXCEPTIONS_AND_RETURN_VOID()
Definition: api.h:401
void rs2_software_sensor_add_read_only_option(rs2_sensor *sensor, rs2_option option, float val, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2562
std::shared_ptr< rs2_notifications_callback > notifications_callback_ptr
Definition: src/types.h:1073
void rs2_get_video_stream_resolution(const rs2_stream_profile *from, int *width, int *height, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:466
void rs2_config_enable_record_to_file(rs2_config *config, const char *file, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1977
float3 * get_vertices()
Definition: archive.cpp:26
rs2_frame_queue * rs2_create_frame_queue(int capacity, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1030
rs2_stream_profile_list * rs2_pipeline_profile_get_streams(rs2_pipeline_profile *profile, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1898
rs2_stream get_stream_type() const override
Definition: src/stream.cpp:24
const char * rs2_record_device_filename(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1695
GLint GLsizei GLsizei height
std::vector< std::shared_ptr< stream_profile_interface > > list
Definition: rs.cpp:58
const char * rs2_get_full_log_message(rs2_log_message const *msg, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1385
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
Definition: rs.cpp:519
int rs2_get_raw_data_size(const rs2_raw_data_buffer *buffer, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:574
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
Definition: rs.cpp:500
void(* rs2_devices_changed_callback_ptr)(rs2_device_list *, rs2_device_list *, void *)
Definition: rs_types.h:295
rs2_playback_status
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.
Definition: rs.cpp:3260
rs2_raw_data_buffer * rs2_serialize_json(rs2_device *dev, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:3169
struct rs2_log_message rs2_log_message
Definition: rs_types.h:259
unsigned long long int rs2_playback_get_position(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1581
void rs2_flush_queue(rs2_frame_queue *queue, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1103
rs2_processing_block * rs2_create_sync_processing_block(rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2062
const char * rs2_format_to_string(rs2_format format)
Definition: rs.cpp:1263
Definition: api.h:28
void rs2_delete_stream_profile(rs2_stream_profile *p) BEGIN_API_CALL
Definition: rs.cpp:512
def callback(frame)
Definition: t265_stereo.py:91
void rs2_pipeline_stop(rs2_pipeline *pipe, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1766
void rs2_playback_device_resume(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1589
void rs2_delete_stream_profiles_list(rs2_stream_profile_list *list) BEGIN_API_CALL
Definition: rs.cpp:367
void rs2_delete_device_hub(const rs2_device_hub *hub) BEGIN_API_CALL
Frees the relevant device hub object.
Definition: rs.cpp:184
rs2_processing_block * rs2_create_hole_filling_filter_block(rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2264
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.
Definition: rs.cpp:1136
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.
Definition: rs.cpp:3195
int rs2_device_list_contains(const rs2_device_list *info_list, const rs2_device *device, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:890
single_consumer_frame_queue< librealsense::frame_holder > queue
Definition: rs.cpp:115
void rs2_software_sensor_set_metadata(rs2_sensor *sensor, rs2_frame_metadata_value key, rs2_metadata_type value, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2506
All the parameters required to define a motion stream.
Definition: rs_internal.h:55
rs2_processing_block * rs2_create_processing_block(rs2_frame_processor_callback *proc, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2023
rs2_format
A stream&#39;s format identifies how binary data is encoded within a frame.
Definition: rs_sensor.h:59
#define VALIDATE_LE(ARG, MAX)
Definition: api.h:410
int rs2_supports_device_info(const rs2_device *dev, rs2_camera_info info, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:715
int rs2_is_option_read_only(const rs2_options *options, rs2_option option, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:621
float rs2_get_depth_scale(rs2_sensor *sensor, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2312
rs2_device * rs2_create_software_device(rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2428
int rs2_get_frame_points_count(const rs2_frame *frame, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2179
#define LOG_ERROR(...)
Definition: src/types.h:242
rs2_frame * rs2_extract_frame(rs2_frame *composite, int index, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2114
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
Definition: rs.cpp:2973
rs2_pipeline_profile * rs2_pipeline_get_active_profile(rs2_pipeline *pipe, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1880
#define RS2_PRODUCT_LINE_ANY_INTEL
Definition: rs_context.h:92
rs2_device parent
Definition: rs.cpp:74
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
Definition: rs.cpp:2891
int rs2_config_can_resolve(rs2_config *config, rs2_pipeline *pipe, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2015
const char * rs2_frame_metadata_value_to_string(rs2_frame_metadata_value metadata)
Definition: rs.cpp:1277
void rs2_release_frame(rs2_frame *frame) BEGIN_API_CALL
Definition: rs.cpp:993
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
Definition: json.hpp:12141
dictionary intrinsics
Definition: t265_stereo.py:142
void on_calibration_change(rs2_calibration_status status) noexceptoverride
Definition: rs.cpp:395
const char * rs2_host_perf_mode_to_string(rs2_host_perf_mode mode)
Definition: rs.cpp:1285
rs2_stream
Streams are different types of data provided by RealSense devices.
Definition: rs_sensor.h:42
void rs2_get_video_stream_intrinsics(const rs2_stream_profile *from, rs2_intrinsics *intr, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:374
void rs2_playback_seek(const rs2_device *device, long long int time, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1572
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
Definition: rs.cpp:1075
extrinsics_graph & get_extrinsics_graph()
int rs2_is_device_extendable_to(const rs2_device *dev, rs2_extension extension, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1425
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
Definition: rs.cpp:2658
void rs2_software_device_register_info(rs2_device *dev, rs2_camera_info info, const char *val, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2443
#define VALIDATE_INTERFACE(X, T)
Definition: api.h:428
rs2_device dev
Definition: rs.cpp:120
size_t get_vertex_count() const
Definition: archive.cpp:144
rs2_device_list * rs2_query_devices(const rs2_context *context, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:208
int rs2_get_api_version(rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1184
rs2_sensor_mode
For setting the camera_mode option.
Definition: rs_option.h:165
#define VALIDATE_OPTION(OBJ, OPT_ID)
Definition: api.h:408
static const double d2r
Definition: src/types.h:58
std::shared_ptr< librealsense::context > ctx
Definition: api.h:30
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
Definition: rs.cpp:3015
#define BEGIN_API_CALL
Definition: api.h:397
rs2_device_hub * rs2_create_device_hub(const rs2_context *context, rs2_error **error) BEGIN_API_CALL
Creates RealSense device_hub .
Definition: rs.cpp:178
rs2_processing_block * rs2_create_align(rs2_stream align_to, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2211
terminal_parser(const std::string &xml_content)
Cross-stream extrinsics: encodes the topology describing how the different devices are oriented...
Definition: rs_sensor.h:96
int rs2_device_hub_is_device_connected(const rs2_device_hub *hub, const rs2_device *device, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:199
void release() override
Definition: rs.cpp:1343
void rs2_register_calibration_change_callback_cpp(rs2_device *dev, rs2_calibration_change_callback *callback, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:431
void rs2_config_enable_all_stream(rs2_config *config, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1942
void rs2_delete_fw_log_message(rs2_firmware_log_message *msg) BEGIN_API_CALL
Definition: rs.cpp:3226
void rs2_config_disable_stream(rs2_config *config, rs2_stream stream, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1986
LOG_INFO("Log message using LOG_INFO()")
void rs2_record_device_resume(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1687
rs2_processing_block * rs2_create_hdr_merge_processing_block(rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2296
void rs2_playback_device_set_status_changed_callback(const rs2_device *device, rs2_playback_status_changed_callback *callback, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1621
Definition: example.hpp:70
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.
Definition: rs.cpp:3389
#define NOARGS_HANDLE_EXCEPTIONS_AND_RETURN(R)
Definition: api.h:400
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
Definition: rs.cpp:3102
void(* rs2_software_device_destruction_callback_ptr)(void *)
Definition: rs_types.h:294
3D vector in Euclidean coordinate space
Definition: rs_types.h:129
rs2_stream_profile_list * rs2_get_active_streams(rs2_sensor *sensor, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:344
const char * rs2_digital_gain_to_string(rs2_digital_gain gain)
Definition: rs.cpp:1281
fname
Definition: rmse.py:13
calibration_change_callback(rs2_calibration_change_callback_ptr callback, void *user_arg)
Definition: rs.cpp:392
rs2_processing_block * rs2_create_processing_block_fptr(rs2_frame_processor_callback_ptr proc, void *context, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2032
std::string function
Definition: rs.cpp:142
GLdouble GLdouble GLdouble q
void rs2_start_processing(rs2_processing_block *block, rs2_frame_callback *on_frame, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2070
void rs2_get_dsm_params(const rs2_sensor *sensor, rs2_dsm_params *p_params_out, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1146
void enable_rolling_log_file(unsigned max_size)
Definition: log.cpp:64
frame_interface * frame
Definition: streaming.h:126
struct rs2_processing_block rs2_processing_block
Definition: rs_types.h:275
All the parameters required to define a sensor notification.
Definition: rs_internal.h:122
void rs2_log_to_callback(rs2_log_severity min_severity, rs2_log_callback_ptr on_log, void *arg, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1351
int rs2_stream_profile_is(const rs2_stream_profile *f, rs2_extension extension_type, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1504
const char * rs2_get_option_name(const rs2_options *options, rs2_option option, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:651
int rs2_supports_sensor_info(const rs2_sensor *sensor, rs2_camera_info info, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:736
rs2_extension
Specifies advanced interfaces (capabilities) objects may implement.
Definition: rs_types.h:166
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
Definition: rs.cpp:1238
rs2_notification_category
Category of the librealsense notification.
Definition: rs_types.h:17
rs2_device * rs2_create_device(const rs2_device_list *info_list, int index, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:289
void rs2_delete_sensor_list(rs2_sensor_list *list) BEGIN_API_CALL
Definition: rs.cpp:282
::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
Definition: rs.cpp:1556
void rs2_config_disable_indexed_stream(rs2_config *config, rs2_stream stream, int index, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1993
void(* rs2_notification_callback_ptr)(rs2_notification *, void *)
Definition: rs_types.h:293
stream_profile to_profile(const stream_profile_interface *sp)
Definition: src/stream.h:185
long long rs2_metadata_type
Definition: rs_types.h:301
GLenum type
void rs2_open_multiple(rs2_sensor *sensor, const rs2_stream_profile **profiles, int count, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:599
const char * rs2_frame_metadata_to_string(rs2_frame_metadata_value metadata)
Definition: rs.cpp:1275
unsigned int rs2_fw_log_message_timestamp(rs2_firmware_log_message *msg, rs2_error **error) BEGIN_API_CALL
Gets RealSense firmware log message timestamp.
Definition: rs.cpp:3253
#define VALIDATE_RANGE(ARG, MIN, MAX)
Definition: api.h:409
int min(int a, int b)
Definition: lz4s.c:73
const char * rs2_get_failed_function(const rs2_error *error)
Definition: rs.cpp:1257
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...
Definition: rs.cpp:3353
void rs2_start_processing_fptr(rs2_processing_block *block, rs2_frame_callback_ptr on_frame, void *user, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2078
void rs2_write_calibration(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2749
const char * rs2_calibration_status_to_string(rs2_calibration_status status)
Definition: rs.cpp:1284
void rs2_playback_device_pause(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1597
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
Definition: rs.cpp:823
rs2_frame_queue(int cap)
Definition: rs.cpp:110
void rs2_start(const rs2_sensor *sensor, rs2_frame_callback_ptr on_frame, void *user, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:744
void rs2_register_calibration_change_callback(rs2_device *dev, rs2_calibration_change_callback_ptr callback, void *user, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:417
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
Definition: rs.cpp:3052
rs2_error * rs2_create_error(const char *what, const char *name, const char *args, rs2_exception_type type) BEGIN_API_CALL
Definition: rs.cpp:147
GLint GLsizei count
void rs2_get_motion_intrinsics(const rs2_stream_profile *mode, rs2_motion_device_intrinsic *intrinsics, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:455
All the parameters required to define a motion frame.
Definition: rs_internal.h:89
rs2_processing_block * rs2_create_colorizer(rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2221
float rs2_depth_frame_get_distance(const rs2_frame *frame_ref, int x, int y, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2346
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.
Definition: rs.cpp:3325
struct rs2_device rs2_device
Definition: rs_types.h:257
rs2_processing_block * rs2_create_disparity_transform_block(unsigned char transform_to_disparity, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2256
rs2_sensor * rs2_get_frame_sensor(const rs2_frame *frame, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:922
int rs2_supports_option(const rs2_options *options, rs2_option option, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:679
void(* rs2_calibration_change_callback_ptr)(rs2_calibration_status, void *arg)
Definition: rs_device.h:378
void rs2_delete_pipeline_profile(rs2_pipeline_profile *profile) BEGIN_API_CALL
Definition: rs.cpp:1905
typename::boost::move_detail::remove_reference< T >::type && move(T &&t) BOOST_NOEXCEPT
Video stream intrinsics.
Definition: rs_types.h:58
int rs2_is_frame_extendable_to(const rs2_frame *f, rs2_extension extension_type, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1461
void rs2_loopback_enable(const rs2_device *device, const char *from_file, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2629
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
Definition: rs.cpp:554
rs2_ambient_light
DEPRECATED! - Use RS2_OPTION_DIGITAL_GAIN instead.
Definition: rs_option.h:175
rs2_frame * rs2_wait_for_frame(rs2_frame_queue *queue, unsigned int timeout_ms, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1043
std::ostream & cerr()
GLsizei GLsizei GLchar * source
void rs2_log_to_file(rs2_log_severity min_severity, const char *file_path, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1293
float rs2_vector::* pos
void rs2_context_unload_tracking_module(rs2_context *ctx, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1547
void rs2_software_device_set_destruction_callback_cpp(const rs2_device *dev, rs2_software_device_destruction_callback *callback, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:814
rs2_vertex * rs2_get_frame_vertices(const rs2_frame *frame, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2154
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
Definition: rs.cpp:1718
rs2_digital_gain
digital gain for RS2_OPTION_DIGITAL_GAIN option.
Definition: rs_option.h:183
int rs2_get_frame_stride_in_bytes(const rs2_frame *frame_ref, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:963
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.
Definition: rs.cpp:163
void rs2_software_sensor_on_notification(rs2_sensor *sensor, rs2_software_notification notif, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2498
void set_devices_changed_callback(devices_changed_callback_ptr callback)
Definition: context.cpp:467
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
Definition: rs.cpp:686
GLsizei range
Motion device intrinsics: scale, bias, and variances.
Definition: rs_types.h:103
void rs2_disconnect_tm2_controller(const rs2_device *device, int id, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2668
const char * rs2_extension_type_to_string(rs2_extension type)
Definition: rs.cpp:1274
#define NULL
Definition: tinycthread.c:47
float rs2_get_option(const rs2_options *options, rs2_option option, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:628
device(std::shared_ptr< context > ctx, const platform::backend_device_group group, bool device_changed_notifications=false)
Definition: device.cpp:126
std::shared_ptr< librealsense::context > ctx
Definition: rs.cpp:85
int rs2_import_localization_map(const rs2_sensor *sensor, const unsigned char *lmap_blob, unsigned int blob_size, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2815
std::shared_ptr< rs2_devices_changed_callback > devices_changed_callback_ptr
Definition: src/types.h:1076
int i
GLuint res
Definition: glext.h:8856
int rs2_get_frame_data_size(const rs2_frame *frame_ref, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:933
void(* rs2_frame_callback_ptr)(rs2_frame *, void *)
Definition: rs_types.h:296
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
Definition: rs.cpp:1842
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
Definition: rs.cpp:2907
rs2_device * rs2_pipeline_profile_get_device(rs2_pipeline_profile *profile, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1888
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.
Definition: rs.cpp:2688
const char * rs2_calib_target_type_to_string(rs2_calib_target_type type)
Definition: rs.cpp:1269
const unsigned char * rs2_get_raw_data(const rs2_raw_data_buffer *buffer, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:567
const char * rs2_get_processing_block_info(const rs2_processing_block *block, rs2_camera_info info, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2795
rs2_stream_profile_list * rs2_get_debug_stream_profiles(rs2_sensor *sensor, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:334
unsigned long long rs2_get_frame_number(const rs2_frame *frame, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:986
All the parameters required to define a video frame.
Definition: rs_internal.h:76
void log_to_console(rs2_log_severity min_severity)
Definition: log.cpp:44
#define LOG_DEBUG(...)
Definition: src/types.h:239
int rs2_remove_static_node(const rs2_sensor *sensor, const char *guid, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2879
void rs2_stop(const rs2_sensor *sensor, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:831
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
Definition: rs.cpp:2996
const char * rs2_camera_info_to_string(rs2_camera_info info)
Definition: rs.cpp:1266
const char * get_raw_log_message() const
Definition: log.h:312
rs2_pipeline_profile * rs2_pipeline_start_with_config(rs2_pipeline *pipe, rs2_config *config, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1834
std::string message
Definition: rs.cpp:141
rs2_sensor * rs2_software_device_add_sensor(rs2_device *dev, const char *sensor_name, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2463
double rs2_time_t
Definition: rs_types.h:300
const char * rs2_timestamp_domain_to_string(rs2_timestamp_domain info)
Definition: rs.cpp:1267
void release() override
Definition: rs.cpp:409
const char * rs2_calibration_type_to_string(rs2_calibration_type type)
Definition: rs.cpp:1283
void rs2_config_disable_all_streams(rs2_config *config, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2000
rs2_log_severity
Severity of the librealsense logger.
Definition: rs_types.h:153
std::shared_ptr< rs2_software_device_destruction_callback > software_device_destruction_callback_ptr
Definition: src/types.h:1075
platform::backend_device_group get_device_data() const override
Definition: device.h:62
rs2_log_severity severity
Definition: src/types.h:1109
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
Definition: rs.cpp:2954
std::shared_ptr< librealsense::pipeline::pipeline > pipeline
Definition: rs.cpp:95
void rs2_delete_config(rs2_config *config) BEGIN_API_CALL
Definition: rs.cpp:1920
void rs2_loopback_disable(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2640
rs2_frame * rs2_allocate_composite_frame(rs2_source *source, rs2_frame **frames, int count, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2127
const char * rs2_get_option_description(const rs2_options *options, rs2_option option, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1007
rs2_stream_profile_list * rs2_get_stream_profiles(rs2_sensor *sensor, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:327
GLuint64EXT * result
Definition: glext.h:10921
const rs2_raw_data_buffer * rs2_export_localization_map(const rs2_sensor *sensor, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2828
void rs2_set_notifications_callback(const rs2_sensor *sensor, rs2_notification_callback_ptr on_notification, void *user, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:764
int rs2_fw_log_message_size(rs2_firmware_log_message *msg, rs2_error **error) BEGIN_API_CALL
Gets RealSense firmware log message size.
Definition: rs.cpp:3240
int rs2_get_device_count(const rs2_device_list *list, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:259
GLdouble v
const char * rs2_get_failed_args(const rs2_error *error)
Definition: rs.cpp:1258
void rs2_delete_device_list(rs2_device_list *list) BEGIN_API_CALL
Definition: rs.cpp:275
rs2_log_severity rs2_get_notification_severity(rs2_notification *notification, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:868
void rs2_reset_to_factory_calibration(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2733
rs2_frame * rs2_pipeline_wait_for_frames(rs2_pipeline *pipe, unsigned int timeout_ms, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1774
auto device
Definition: pyrs_net.cpp:17
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
Definition: rs.cpp:2698
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
Definition: rs.cpp:2046
rs2_device * rs2_create_device_from_sensor(const rs2_sensor *sensor, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2338
const std::string & get_filename() const
unsigned long long int rs2_playback_get_duration(const rs2_device *device, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1564
void rs2_keep_frame(rs2_frame *frame) BEGIN_API_CALL
Definition: rs.cpp:1000
void rs2_playback_device_set_playback_speed(const rs2_device *device, float speed, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1640
rs2_frame_metadata_value
Per-Frame-Metadata is the set of read-only properties that might be exposed for each individual frame...
Definition: rs_frame.h:29
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
Definition: rs.cpp:2522
void rs2_start_queue(const rs2_sensor *sensor, rs2_frame_queue *queue, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:754
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
Definition: rs.cpp:1850
#define VALIDATE_NOT_NULL(ARG)
Definition: api.h:406
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
Definition: rs.cpp:775
struct rs2_frame rs2_frame
Definition: rs_types.h:261
GLint GLsizei width
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...
Definition: rs.cpp:3211
void rs2_register_extrinsics(const rs2_stream_profile *from, const rs2_stream_profile *to, rs2_extrinsics extrin, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1125
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.
Definition: rs.cpp:3247
void rs2_config_enable_device(rs2_config *config, const char *serial, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:1949
void rs2_set_intrinsics(const rs2_sensor *sensor, const rs2_stream_profile *profile, const rs2_intrinsics *intrinsics, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2677
#define NOEXCEPT_RETURN(R,...)
Definition: api.h:398
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
Definition: rs.cpp:2538
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
Definition: rs.cpp:484
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.
Definition: rs.cpp:3295
Pixel location within 2D image. (0,0) is the topmost, left corner. Positive X is right, positive Y is down.
Definition: rs_types.h:123
rs2_firmware_log_message * rs2_create_fw_log_message(rs2_device *dev, rs2_error **error) BEGIN_API_CALL
Creates RealSense firmware log message.
Definition: rs.cpp:3186
std::vector< byte > data
Definition: archive.h:100
#define VALIDATE_ENUM(ARG)
Definition: api.h:407
void rs2_open(rs2_sensor *sensor, const rs2_stream_profile *profile, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:588
void on_log(rs2_log_severity severity, rs2_log_message const &msg) noexceptoverride
Definition: rs.cpp:1329
void rs2_export_to_ply(const rs2_frame *frame, const char *fname, rs2_frame *texture, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2162
float rs2_get_stereo_baseline(rs2_sensor *sensor, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2330
rs2_option rs2_get_option_from_list(const rs2_options_list *options, int i, rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:665
rs2_l500_visual_preset
For L500 devices: provides optimized settings (presets) for specific types of usage.
Definition: rs_option.h:151
rs2_time_t rs2_get_time(rs2_error **error) BEGIN_API_CALL
Definition: rs.cpp:2422
rs2_timestamp_domain
Specifies the clock in relation to which the frame timestamp was measured.
Definition: rs_frame.h:19


librealsense2
Author(s): Sergey Dorodnicov , Doron Hirshberg , Mark Horn , Reagan Lopez , Itay Carpis
autogenerated on Mon May 3 2021 02:47:40