device.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 "device.h"
5 #include "sync.h"
6 #include "motion-module.h"
7 #include "hw-monitor.h"
8 #include "image.h"
9 
10 #include <array>
11 #include <algorithm>
12 #include <sstream>
13 #include <iostream>
14 #include <functional>
15 
16 using namespace rsimpl;
17 using namespace rsimpl::motion_module;
18 
20 
21 rs_device_base::rs_device_base(std::shared_ptr<rsimpl::uvc::device> device, const rsimpl::static_device_info & info, calibration_validator validator) : device(device), config(info),
22  depth(config, RS_STREAM_DEPTH, validator), color(config, RS_STREAM_COLOR, validator), infrared(config, RS_STREAM_INFRARED, validator), infrared2(config, RS_STREAM_INFRARED2, validator), fisheye(config, RS_STREAM_FISHEYE, validator),
23  points(depth), rect_color(color), color_to_depth(color, depth), depth_to_color(depth, color), depth_to_rect_color(depth, rect_color), infrared2_to_depth(infrared2,depth), depth_to_infrared2(depth,infrared2),
24  capturing(false), data_acquisition_active(false), max_publish_list_size(RS_USER_QUEUE_SIZE), event_queue_size(RS_MAX_EVENT_QUEUE_SIZE), events_timeout(RS_MAX_EVENT_TIME_OUT),
25  usb_port_id(""), motion_module_ready(false), keep_fw_logger_alive(false), frames_drops_counter(0)
26 {
39 }
40 
42 {
43  try
44  {
45  if (capturing)
51  }
52  catch (...) {}
53 }
54 
56 {
57  if(uvc::is_pu_control(option)) return true;
58  for(auto & o : config.info.options) if(o.option == option) return true;
59  return false;
60 }
61 
63 {
64  auto it = config.info.camera_info.find(info);
65  if (it == config.info.camera_info.end())
66  throw std::runtime_error("selected camera info is not supported for this camera!");
67  return it->second.c_str();
68 }
69 
71 {
72  if(capturing) throw std::runtime_error("streams cannot be reconfigured after having called rs_start_device()");
73  if(config.info.stream_subdevices[stream] == -1) throw std::runtime_error("unsupported stream");
74 
75  config.requests[stream] = { true, width, height, format, fps, output };
76  for(auto & s : native_streams) s->archive.reset(); // Changing stream configuration invalidates the current stream info
77 }
78 
80 {
81  if(capturing) throw std::runtime_error("streams cannot be reconfigured after having called rs_start_device()");
82  if(!config.info.presets[stream][preset].enabled) throw std::runtime_error("unsupported stream");
83 
85  for(auto & s : native_streams) s->archive.reset(); // Changing stream configuration invalidates the current stream info
86 }
87 
89 {
90  throw std::runtime_error("Motion intrinsic is not supported for this device");
91 }
92 
94 {
95  throw std::runtime_error("Motion extrinsics does not supported");
96 }
97 
99 {
100  if(capturing) throw std::runtime_error("streams cannot be reconfigured after having called rs_start_device()");
101  if(config.info.stream_subdevices[stream] == -1) throw std::runtime_error("unsupported stream");
102 
103  config.callbacks[stream] = {};
104  config.requests[stream] = {};
105  for(auto & s : native_streams) s->archive.reset(); // Changing stream configuration invalidates the current stream info
106 }
107 
108 void rs_device_base::set_stream_callback(rs_stream stream, void (*on_frame)(rs_device * device, rs_frame_ref * frame, void * user), void * user)
109 {
110  config.callbacks[stream] = frame_callback_ptr(new frame_callback{ this, on_frame, user });
111 }
112 
114 {
116 }
117 
119 {
120  if (data_acquisition_active) throw std::runtime_error("motion-tracking cannot be reconfigured after having called rs_start_device()");
121 
122  config.data_request.enabled = true;
123 }
124 
126 {
127  if (data_acquisition_active) throw std::runtime_error("motion-tracking disabled after having called rs_start_device()");
128 
129  config.data_request.enabled = false;
130 }
131 
133 {
134  if (data_acquisition_active) throw std::runtime_error("cannot set motion callback when motion data is active");
135 
136  // replace previous, if needed
138 }
139 
141 {
142  if (data_acquisition_active) throw std::runtime_error("cannot restart data acquisition without stopping first");
143 
144  auto parser = std::make_shared<motion_module_parser>();
145 
146  // Activate data polling handler
148  {
149  // TODO -replace hard-coded value 3 which stands for fisheye subdevice
151  [this, parser](const unsigned char * data, const int size) mutable
152  {
153  if (motion_module_ready) // Flush all received data before MM is fully operational
154  {
155  // Parse motion data
156  auto events = (*parser)(data, size);
157 
158  // Handle events by user-provided handlers
159  for (auto & entry : events)
160  {
161  // Handle Motion data packets
163  for (int i = 0; i < entry.imu_entries_num; i++)
164  config.motion_callback->on_event(entry.imu_packets[i]);
165 
166  // Handle Timestamp packets
168  {
169  for (int i = 0; i < entry.non_imu_entries_num; i++)
170  {
171  auto tse = entry.non_imu_packets[i];
172  if (archive)
173  archive->on_timestamp(tse);
174 
175  config.timestamp_callback->on_event(entry.non_imu_packets[i]);
176  }
177  }
178  }
179  }
180  });
181  }
182 
183  start_data_acquisition(*device); // activate polling thread in the backend
185 }
186 
188 {
189  if (!data_acquisition_active) throw std::runtime_error("cannot stop data acquisition - is already stopped");
191  data_acquisition_active = false;
192 }
193 
194 void rs_device_base::set_motion_callback(void(*on_event)(rs_device * device, rs_motion_data data, void * user), void * user)
195 {
196  if (data_acquisition_active) throw std::runtime_error("cannot set motion callback when motion data is active");
197 
198  // replace previous, if needed
199  config.motion_callback = motion_callback_ptr(new motion_events_callback(this, on_event, user), [](rs_motion_callback* c) { delete c; });
200 }
201 
202 void rs_device_base::set_timestamp_callback(void(*on_event)(rs_device * device, rs_timestamp_data data, void * user), void * user)
203 {
204  if (data_acquisition_active) throw std::runtime_error("cannot set timestamp callback when motion data is active");
205 
206  config.timestamp_callback = timestamp_callback_ptr(new timestamp_events_callback{ this, on_event, user }, [](rs_timestamp_callback* c) { delete c; });
207 }
208 
210 {
211  // replace previous, if needed
213 }
214 
216 {
217  if (source == RS_SOURCE_MOTION_TRACKING)
218  {
221  else
222  throw std::runtime_error("motion-tracking is not supported by this device");
223  }
224  else if (source == RS_SOURCE_VIDEO)
225  {
227  }
228  else if (source == RS_SOURCE_ALL)
229  {
232  }
233  else
234  {
235  throw std::runtime_error("unsupported streaming source!");
236  }
237 }
238 
240 {
241  if (source == RS_SOURCE_VIDEO)
242  {
244  }
245  else if (source == RS_SOURCE_MOTION_TRACKING)
246  {
249  else
250  throw std::runtime_error("motion-tracking is not supported by this device");
251  }
252  else if (source == RS_SOURCE_ALL)
253  {
256  }
257  else
258  {
259  throw std::runtime_error("unsupported streaming source");
260  }
261 }
262 
263 std::string hexify(unsigned char n)
264 {
266 
267  do
268  {
269  res += "0123456789ABCDEF"[n % 16];
270  n >>= 4;
271  } while (n);
272 
273  reverse(res.begin(), res.end());
274 
275  if (res.size() == 1)
276  {
277  res.insert(0, "0");
278  }
279 
280  return res;
281 }
282 
283 void rs_device_base::start_fw_logger(char fw_log_op_code, int grab_rate_in_ms, std::timed_mutex& mutex)
284 {
286  throw std::logic_error("FW logger already started");
287 
288  keep_fw_logger_alive = true;
289  fw_logger = std::make_shared<std::thread>([this, fw_log_op_code, grab_rate_in_ms, &mutex]() {
290  const int data_size = 500;
291  hw_monitor::hwmon_cmd cmd((int)fw_log_op_code);
292  cmd.Param1 = data_size;
293  while (keep_fw_logger_alive)
294  {
295  std::this_thread::sleep_for(std::chrono::milliseconds(grab_rate_in_ms));
297  char data[data_size];
298  memcpy(data, cmd.receivedCommandData, cmd.receivedCommandDataLength);
299 
300  std::stringstream sstr;
301  sstr << "FW_Log_Data:";
302  for (size_t i = 0; i < cmd.receivedCommandDataLength; ++i)
303  sstr << hexify(data[i]) << " ";
304 
306  LOG_INFO(sstr.str());
307  }
308  });
309 }
310 
312 {
314  throw std::logic_error("FW logger not started");
315 
316  keep_fw_logger_alive = false;
317  fw_logger->join();
318 }
319 
321 {
322  bool was_initialized = false;
323  unsigned long long prev_frame_counter = 0;
324 };
325 
327 {
328  if(capturing) throw std::runtime_error("cannot restart device without first stopping device");
329 
330  auto capture_start_time = std::chrono::high_resolution_clock::now();
331  auto selected_modes = config.select_modes();
332  auto archive = std::make_shared<syncronizing_archive>(selected_modes, select_key_stream(selected_modes), &max_publish_list_size, &event_queue_size, &events_timeout, capture_start_time);
333 
334  for(auto & s : native_streams) s->archive.reset(); // Starting capture invalidates the current stream info, if any exists from previous capture
335 
336  auto timestamp_readers = create_frame_timestamp_readers();
337 
338  // Satisfy stream_requests as necessary for each subdevice, calling set_mode and
339  // dispatching the uvc configuration for a requested stream to the hardware
340  for(auto mode_selection : selected_modes)
341  {
342  assert(static_cast<size_t>(mode_selection.mode.subdevice) <= timestamp_readers.size());
343  auto timestamp_reader = timestamp_readers[mode_selection.mode.subdevice];
344 
345  // Create a stream buffer for each stream served by this subdevice mode
346  for(auto & stream_mode : mode_selection.get_outputs())
347  {
348  // If this is one of the streams requested by the user, store the buffer so they can access it
349  if(config.requests[stream_mode.first].enabled) native_streams[stream_mode.first]->archive = archive;
350  }
351 
352  // Copy the callbacks that apply to this stream, so that they can be captured by value
353  std::vector<rs_stream> streams;
354  for (auto & output : mode_selection.get_outputs())
355  {
356  streams.push_back(output.first);
357  }
358 
359  auto supported_metadata_vector = std::make_shared<std::vector<rs_frame_metadata>>(config.info.supported_metadata_vector);
360 
361  auto actual_fps_calc = std::make_shared<fps_calc>(NUMBER_OF_FRAMES_TO_SAMPLE, mode_selection.get_framerate());
362  std::shared_ptr<drops_status> frame_drops_status(new drops_status{});
363  // Initialize the subdevice and set it to the selected mode
364  set_subdevice_mode(*device, mode_selection.mode.subdevice, mode_selection.mode.native_dims.x, mode_selection.mode.native_dims.y, mode_selection.mode.pf.fourcc, mode_selection.mode.fps,
365  [this, mode_selection, archive, timestamp_reader, streams, capture_start_time, frame_drops_status, actual_fps_calc, supported_metadata_vector](const void * frame, std::function<void()> continuation) mutable
366  {
367  auto now = std::chrono::system_clock::now();
368  auto sys_time = std::chrono::duration_cast<std::chrono::milliseconds>(now.time_since_epoch()).count();
369 
370  frame_continuation release_and_enqueue(continuation, frame);
371 
372  // Ignore any frames which appear corrupted or invalid
373  if (!timestamp_reader->validate_frame(mode_selection.mode, frame)) return;
374 
375  auto actual_fps = actual_fps_calc->calc_fps(now);
376 
377  // Determine the timestamp for this frame
378  auto timestamp = timestamp_reader->get_frame_timestamp(mode_selection.mode, frame, actual_fps);
379  auto frame_counter = timestamp_reader->get_frame_counter(mode_selection.mode, frame);
380  auto recieved_time = std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::high_resolution_clock::now() - capture_start_time).count();
381 
382  auto requires_processing = mode_selection.requires_processing();
383 
384  double exposure_value[1] = {};
385  if (streams[0] == rs_stream::RS_STREAM_FISHEYE)
386  {
387  // fisheye exposure value is embedded in the frame data from version 1.27.2.90
389  if (firmware >= firmware_version("1.27.2.90"))
390  {
391  auto data = static_cast<const char*>(frame);
392  int exposure = 0; // Embedded Fisheye exposure value is in units of 0.2 mSec
393  for (int i = 4, j = 0; i < 12; ++i, ++j)
394  exposure |= ((data[i] & 0x01) << j);
395 
396  exposure_value[0] = exposure * 0.2 * 10.;
397  }
398  }
399 
400  auto width = mode_selection.get_width();
401  auto height = mode_selection.get_height();
402  auto fps = mode_selection.get_framerate();
403  std::vector<byte *> dest;
404 
405  auto stride_x = mode_selection.get_stride_x();
406  auto stride_y = mode_selection.get_stride_y();
407  for (auto & output : mode_selection.get_outputs())
408  {
409  LOG_DEBUG("FrameAccepted, RecievedAt," << recieved_time << ", FWTS," << timestamp << ", DLLTS," << recieved_time << ", Type," << rsimpl::get_string(output.first) << ",HasPair,0,F#," << frame_counter);
410  }
411 
412  frame_drops_status->was_initialized = true;
413 
414  // Not updating prev_frame_counter when first frame arrival
415  if (frame_drops_status->was_initialized)
416  {
417  frames_drops_counter.fetch_add(frame_counter - frame_drops_status->prev_frame_counter - 1);
418  frame_drops_status->prev_frame_counter = frame_counter;
419  }
420 
421  for (auto & output : mode_selection.get_outputs())
422  {
423  auto bpp = get_image_bpp(output.second);
424  frame_archive::frame_additional_data additional_data( timestamp,
425  frame_counter,
426  sys_time,
427  width,
428  height,
429  fps,
430  stride_x,
431  stride_y,
432  bpp,
433  output.second,
434  output.first,
435  mode_selection.pad_crop,
436  supported_metadata_vector,
437  exposure_value[0],
438  actual_fps);
439 
440  // Obtain buffers for unpacking the frame
441  dest.push_back(archive->alloc_frame(output.first, additional_data, requires_processing));
442 
443 
444  if (motion_module_ready) // try to correct timestamp only if motion module is enabled
445  {
446  archive->correct_timestamp(output.first);
447  }
448  }
449  // Unpack the frame
450  if (requires_processing)
451  {
452  mode_selection.unpack(dest.data(), reinterpret_cast<const byte *>(frame));
453  }
454 
455  // If any frame callbacks were specified, dispatch them now
456  for (size_t i = 0; i < dest.size(); ++i)
457  {
458  if (!requires_processing)
459  {
460  archive->attach_continuation(streams[i], std::move(release_and_enqueue));
461  }
462 
463  if (config.callbacks[streams[i]])
464  {
465  auto frame_ref = archive->track_frame(streams[i]);
466  if (frame_ref)
467  {
468  frame_ref->update_frame_callback_start_ts(std::chrono::high_resolution_clock::now());
469  frame_ref->log_callback_start(capture_start_time);
470  on_before_callback(streams[i], frame_ref, archive);
471  (*config.callbacks[streams[i]])->on_frame(this, frame_ref);
472  }
473  }
474  else
475  {
476  // Commit the frame to the archive
477  archive->commit_frame(streams[i]);
478  }
479  }
480  });
481  }
482 
483  this->archive = archive;
484  on_before_start(selected_modes);
486  capture_started = std::chrono::high_resolution_clock::now();
487  capturing = true;
488 }
489 
491 {
492  if(!capturing) throw std::runtime_error("cannot stop device without first starting device");
494  archive->flush();
495  capturing = false;
496 }
497 
499 {
500  if(!capturing) return;
501  if(!archive) return;
502 
503  archive->wait_for_frames();
504 }
505 
507 {
508  if(!capturing) return false;
509  if(!archive) return false;
510  return archive->poll_for_frames();
511 }
512 
514 {
515  archive->release_frame_ref((frame_archive::frame_ref *)ref);
516 }
517 
519 {
520  auto result = archive->clone_frame((frame_archive::frame_ref *)frame);
521  if (!result) throw std::runtime_error("Not enough resources to clone frame!");
522  return result;
523 }
524 
526 {
527  info.options.push_back({ RS_OPTION_FRAMES_QUEUE_SIZE, 1, RS_USER_QUEUE_SIZE, 1, RS_USER_QUEUE_SIZE });
528 }
529 
531 {
532  switch (option)
533  {
534  case RS_OPTION_COLOR_BACKLIGHT_COMPENSATION : return "Enable / disable color backlight compensation";
535  case RS_OPTION_COLOR_BRIGHTNESS : return "Color image brightness";
536  case RS_OPTION_COLOR_CONTRAST : return "Color image contrast";
537  case RS_OPTION_COLOR_EXPOSURE : return "Controls exposure time of color camera. Setting any value will disable auto exposure";
538  case RS_OPTION_COLOR_GAIN : return "Color image gain";
539  case RS_OPTION_COLOR_GAMMA : return "Color image gamma setting";
540  case RS_OPTION_COLOR_HUE : return "Color image hue";
541  case RS_OPTION_COLOR_SATURATION : return "Color image saturation setting";
542  case RS_OPTION_COLOR_SHARPNESS : return "Color image sharpness setting";
543  case RS_OPTION_COLOR_WHITE_BALANCE : return "Controls white balance of color image. Setting any value will disable auto white balance";
544  case RS_OPTION_COLOR_ENABLE_AUTO_EXPOSURE : return "Enable / disable color image auto-exposure";
545  case RS_OPTION_COLOR_ENABLE_AUTO_WHITE_BALANCE : return "Enable / disable color image auto-white-balance";
546  case RS_OPTION_F200_LASER_POWER : return "Power of the F200 / SR300 projector, with 0 meaning projector off";
547  case RS_OPTION_F200_ACCURACY : return "Set the number of patterns projected per frame. The higher the accuracy value the more patterns projected. Increasing the number of patterns help to achieve better accuracy. Note that this control is affecting the Depth FPS";
548  case RS_OPTION_F200_MOTION_RANGE : return "Motion vs. Range trade-off, with lower values allowing for better motion sensitivity and higher values allowing for better depth range";
549  case RS_OPTION_F200_FILTER_OPTION : return "Set the filter to apply to each depth frame. Each one of the filter is optimized per the application requirements";
550  case RS_OPTION_F200_CONFIDENCE_THRESHOLD : return "The confidence level threshold used by the Depth algorithm pipe to set whether a pixel will get a valid range or will be marked with invalid range";
551  case RS_OPTION_F200_DYNAMIC_FPS : return "(F200-only) Allows to reduce FPS without restarting streaming. Valid values are {2, 5, 15, 30, 60}";
552  case RS_OPTION_SR300_AUTO_RANGE_ENABLE_MOTION_VERSUS_RANGE : return "Configures SR300 Depth Auto-Range setting (Should be used through set IVCAM preset method)";
553  case RS_OPTION_SR300_AUTO_RANGE_ENABLE_LASER : return "Configures SR300 Depth Auto-Range Laser setting (Should be used through set IVCAM preset method)";
554  case RS_OPTION_SR300_AUTO_RANGE_MIN_MOTION_VERSUS_RANGE : return "Configures SR300 Depth Auto-Range Min laser motion setting (Should be used through set IVCAM preset method)";
555  case RS_OPTION_SR300_AUTO_RANGE_MAX_MOTION_VERSUS_RANGE : return "Configures SR300 Depth Auto-Range Max laser motion setting (Should be used through set IVCAM preset method)";
556  case RS_OPTION_SR300_AUTO_RANGE_START_MOTION_VERSUS_RANGE : return "Configures SR300 Depth Auto-Range start laser motion setting (Should be used through set IVCAM preset method)";
557  case RS_OPTION_SR300_AUTO_RANGE_MIN_LASER : return "Configures SR300 Depth Auto-Range Min laser setting (Should be used through set IVCAM preset method)";
558  case RS_OPTION_SR300_AUTO_RANGE_MAX_LASER : return "Configures SR300 Depth Auto-Range Max laser setting (Should be used through set IVCAM preset method)";
559  case RS_OPTION_SR300_AUTO_RANGE_START_LASER : return "Configures SR300 Depth Auto-Range Start laser setting (Should be used through set IVCAM preset method)";
560  case RS_OPTION_SR300_AUTO_RANGE_UPPER_THRESHOLD : return "Configures SR300 Depth Auto-Range upper threshold setting (Should be used through set IVCAM preset method)";
561  case RS_OPTION_SR300_AUTO_RANGE_LOWER_THRESHOLD : return "Configures SR300 Depth Auto-Range lower threshold setting (Should be used through set IVCAM preset method)";
562  case RS_OPTION_R200_LR_AUTO_EXPOSURE_ENABLED : return "Enables / disables R200 auto-exposure. This will affect both IR and depth image.";
563  case RS_OPTION_R200_LR_GAIN : return "IR image gain";
564  case RS_OPTION_R200_LR_EXPOSURE : return "This control allows manual adjustment of the exposure time value for the L/R imagers";
565  case RS_OPTION_R200_EMITTER_ENABLED : return "Enables / disables R200 emitter";
566  case RS_OPTION_R200_DEPTH_UNITS : return "Micrometers per increment in integer depth values, 1000 is default (mm scale). Set before streaming";
567  case RS_OPTION_R200_DEPTH_CLAMP_MIN : return "Minimum depth in current depth units that will be output. Any values less than 'Min Depth' will be mapped to 0 during the conversion between disparity and depth. Set before streaming";
568  case RS_OPTION_R200_DEPTH_CLAMP_MAX : return "Maximum depth in current depth units that will be output. Any values greater than 'Max Depth' will be mapped to 0 during the conversion between disparity and depth. Set before streaming";
569  case RS_OPTION_R200_DISPARITY_MULTIPLIER : return "The disparity scale factor used when in disparity output mode. Can only be set before streaming";
570  case RS_OPTION_R200_DISPARITY_SHIFT : return "{0 - 512}. Can only be set before streaming starts";
571  case RS_OPTION_R200_AUTO_EXPOSURE_MEAN_INTENSITY_SET_POINT : return "(Requires LR-Auto-Exposure ON) Mean intensity set point";
572  case RS_OPTION_R200_AUTO_EXPOSURE_BRIGHT_RATIO_SET_POINT : return "(Requires LR-Auto-Exposure ON) Bright ratio set point";
573  case RS_OPTION_R200_AUTO_EXPOSURE_KP_GAIN : return "(Requires LR-Auto-Exposure ON) Kp Gain";
574  case RS_OPTION_R200_AUTO_EXPOSURE_KP_EXPOSURE : return "(Requires LR-Auto-Exposure ON) Kp Exposure";
575  case RS_OPTION_R200_AUTO_EXPOSURE_KP_DARK_THRESHOLD : return "(Requires LR-Auto-Exposure ON) Kp Dark Threshold";
576  case RS_OPTION_R200_AUTO_EXPOSURE_TOP_EDGE : return "(Requires LR-Auto-Exposure ON) Auto-Exposure region-of-interest top edge (in pixels)";
577  case RS_OPTION_R200_AUTO_EXPOSURE_BOTTOM_EDGE : return "(Requires LR-Auto-Exposure ON) Auto-Exposure region-of-interest bottom edge (in pixels)";
578  case RS_OPTION_R200_AUTO_EXPOSURE_LEFT_EDGE : return "(Requires LR-Auto-Exposure ON) Auto-Exposure region-of-interest left edge (in pixels)";
579  case RS_OPTION_R200_AUTO_EXPOSURE_RIGHT_EDGE : return "(Requires LR-Auto-Exposure ON) Auto-Exposure region-of-interest right edge (in pixels)";
580  case RS_OPTION_R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_DECREMENT : return "Value to subtract when estimating the median of the correlation surface";
581  case RS_OPTION_R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_INCREMENT : return "Value to add when estimating the median of the correlation surface";
582  case RS_OPTION_R200_DEPTH_CONTROL_MEDIAN_THRESHOLD : return "A threshold by how much the winning score must beat the median";
583  case RS_OPTION_R200_DEPTH_CONTROL_SCORE_MINIMUM_THRESHOLD : return "The minimum correlation score that is considered acceptable";
584  case RS_OPTION_R200_DEPTH_CONTROL_SCORE_MAXIMUM_THRESHOLD : return "The maximum correlation score that is considered acceptable";
585  case RS_OPTION_R200_DEPTH_CONTROL_TEXTURE_COUNT_THRESHOLD : return "A parameter for determining whether the texture in the region is sufficient to justify a depth result";
586  case RS_OPTION_R200_DEPTH_CONTROL_TEXTURE_DIFFERENCE_THRESHOLD : return "A parameter for determining whether the texture in the region is sufficient to justify a depth result";
587  case RS_OPTION_R200_DEPTH_CONTROL_SECOND_PEAK_THRESHOLD : return "A threshold on how much the minimum correlation score must differ from the next best score";
588  case RS_OPTION_R200_DEPTH_CONTROL_NEIGHBOR_THRESHOLD : return "Neighbor threshold value for depth calculation";
589  case RS_OPTION_R200_DEPTH_CONTROL_LR_THRESHOLD : return "Left-Right threshold value for depth calculation";
590  case RS_OPTION_FISHEYE_EXPOSURE : return "Fisheye image exposure time in msec";
591  case RS_OPTION_FISHEYE_GAIN : return "Fisheye image gain";
592  case RS_OPTION_FISHEYE_STROBE : return "Enables / disables fisheye strobe. When enabled this will align timestamps to common clock-domain with the motion events";
593  case RS_OPTION_FISHEYE_EXTERNAL_TRIGGER : return "Enables / disables fisheye external trigger mode. When enabled fisheye image will be acquired in-sync with the depth image";
594  case RS_OPTION_FRAMES_QUEUE_SIZE : return "Number of frames the user is allowed to keep per stream. Trying to hold-on to more frames will cause frame-drops.";
595  case RS_OPTION_FISHEYE_ENABLE_AUTO_EXPOSURE : return "Enable / disable fisheye auto-exposure";
596  case RS_OPTION_FISHEYE_AUTO_EXPOSURE_MODE : return "0 - static auto-exposure, 1 - anti-flicker auto-exposure, 2 - hybrid";
597  case RS_OPTION_FISHEYE_AUTO_EXPOSURE_ANTIFLICKER_RATE : return "Fisheye auto-exposure anti-flicker rate, can be 50 or 60 Hz";
598  case RS_OPTION_FISHEYE_AUTO_EXPOSURE_PIXEL_SAMPLE_RATE : return "In Fisheye auto-exposure sample frame every given number of pixels";
599  case RS_OPTION_FISHEYE_AUTO_EXPOSURE_SKIP_FRAMES : return "In Fisheye auto-exposure sample every given number of frames";
600  case RS_OPTION_HARDWARE_LOGGER_ENABLED : return "Enables / disables fetching diagnostic information from hardware (and writting the results to log)";
601  case RS_OPTION_TOTAL_FRAME_DROPS : return "Total number of detected frame drops from all streams";
602  default: return rs_option_to_string(option);
603  }
604 }
605 
607 {
608  auto found = false;
609  auto version_ok = true;
610  for (auto supported : config.info.capabilities_vector)
611  {
612  if (supported.capability == capability)
613  {
614  found = true;
615 
616  firmware_version firmware(get_camera_info(supported.firmware_type));
617  if (!firmware.is_between(supported.from, supported.until)) // unsupported due to versioning constraint
618  {
619  LOG_WARNING("capability " << rs_capabilities_to_string(capability) << " requires " << rs_camera_info_to_string(supported.firmware_type) << " to be from " << supported.from << " up-to " << supported.until << ", but is " << firmware << "!");
620  version_ok = false;
621  }
622  }
623  }
624  return found && version_ok;
625 }
626 
628 {
629  auto it = config.info.camera_info.find(info_param);
630  return (it != config.info.camera_info.end());
631 }
632 
633 void rs_device_base::get_option_range(rs_option option, double & min, double & max, double & step, double & def)
634 {
635  if(uvc::is_pu_control(option))
636  {
637  int mn, mx, stp, df;
639  min = mn;
640  max = mx;
641  step = stp;
642  def = df;
643  return;
644  }
645 
646  for(auto & o : config.info.options)
647  {
648  if(o.option == option)
649  {
650  min = o.min;
651  max = o.max;
652  step = o.step;
653  def = o.def;
654  return;
655  }
656  }
657 
658  throw std::logic_error("range not specified");
659 }
660 
661 void rs_device_base::set_options(const rs_option options[], size_t count, const double values[])
662 {
663  for (size_t i = 0; i < count; ++i)
664  {
665  switch (options[i])
666  {
668  max_publish_list_size = (uint32_t)values[i];
669  break;
671  frames_drops_counter = (uint32_t)values[i];
672  break;
673  default:
674  LOG_WARNING("Cannot set " << options[i] << " to " << values[i] << " on " << get_name());
675  throw std::logic_error("Option unsupported");
676  break;
677  }
678  }
679 }
680 
681 void rs_device_base::get_options(const rs_option options[], size_t count, double values[])
682 {
683  for (size_t i = 0; i < count; ++i)
684  {
685  switch (options[i])
686  {
688  values[i] = max_publish_list_size;
689  break;
691  values[i] = frames_drops_counter;
692  break;
693  default:
694  LOG_WARNING("Cannot get " << options[i] << " on " << get_name());
695  throw std::logic_error("Option unsupported");
696  break;
697  }
698  }
699 }
700 
701 void rs_device_base::disable_auto_option(int subdevice, rs_option auto_opt)
702 {
703  static const int reset_state = 0;
704  // Probe , then deactivate
705  if (uvc::get_pu_control(get_device(), subdevice, auto_opt))
706  uvc::set_pu_control(get_device(), subdevice, auto_opt, reset_state);
707 }
708 
709 
711 {
712  std::lock_guard<std::mutex> lock(usb_port_mutex);
714  return usb_port_id.c_str();
715 }
void enable_stream_preset(rs_stream stream, rs_preset preset) override
Definition: device.cpp:79
rsimpl::native_stream infrared2
Definition: device.h:81
motion_callback_ptr motion_callback
Definition: types.h:454
std::unique_ptr< rs_motion_callback, void(*)(rs_motion_callback *)> motion_callback_ptr
Definition: types.h:427
rsimpl::device_config config
Definition: device.h:79
static void update_device_info(rsimpl::static_device_info &info)
Definition: device.cpp:525
virtual bool supports(rs_capabilities capability) const override
Definition: device.cpp:606
rs_device_base(std::shared_ptr< rsimpl::uvc::device > device, const rsimpl::static_device_info &info, rsimpl::calibration_validator validator=rsimpl::calibration_validator())
Definition: device.cpp:21
virtual void get_option_range(rs_option option, double &min, double &max, double &step, double &def) override
Definition: device.cpp:633
const std::shared_ptr< rsimpl::uvc::device > device
Definition: device.h:77
std::shared_ptr< std::thread > fw_logger
Definition: device.h:99
std::vector< rs_frame_metadata > supported_metadata_vector
Definition: types.h:283
void get_pu_control_range(const device &device, int subdevice, rs_option option, int *min, int *max, int *step, int *def)
virtual void get_options(const rs_option options[], size_t count, double values[]) override
Definition: device.cpp:681
virtual void stop_motion_tracking()
Definition: device.cpp:187
const rsimpl::uvc::device & get_device() const
Definition: device.h:102
frame_callback_ptr callbacks[RS_STREAM_NATIVE_COUNT]
Definition: types.h:452
rsimpl::native_stream fisheye
Definition: device.h:81
void set_stream_callback(rs_stream stream, void(*on_frame)(rs_device *device, rs_frame_ref *frame, void *user), void *user) override
Definition: device.cpp:108
const int RS_USER_QUEUE_SIZE
Definition: types.h:28
void set_subdevice_mode(device &device, int subdevice_index, int width, int height, uint32_t fourcc, int fps, video_channel_callback callback)
const char * rs_camera_info_to_string(rs_camera_info info)
Definition: rs.cpp:764
GLint GLint GLsizei GLsizei height
Definition: glext.h:112
#define LOG_WARNING(...)
Definition: types.h:79
rsimpl::aligned_stream depth_to_infrared2
Definition: device.h:84
GLsizei const GLchar *const * string
Definition: glext.h:683
const int NUMBER_OF_FRAMES_TO_SAMPLE
Definition: device.cpp:19
virtual void release()=0
timestamp_callback_ptr timestamp_callback
Definition: types.h:455
Definition: archive.h:12
const int RS_MAX_EVENT_QUEUE_SIZE
Definition: types.h:31
rsimpl::point_stream points
Definition: device.h:82
GLint GLint GLsizei GLsizei GLsizei depth
Definition: glext.h:112
int get_image_bpp(rs_format format)
Definition: image.cpp:29
bool motion_module_ready
Definition: device.h:113
virtual void stop(rs_source source) override
Definition: device.cpp:239
uint8_t receivedCommandData[HW_MONITOR_BUFFER_SIZE]
Definition: hw-monitor.h:75
rs_option
Defines general configuration controls.
Definition: rs.h:128
const char * get_name() const override
Definition: device.h:124
virtual void on_before_callback(rs_stream, rs_frame_ref *, std::shared_ptr< rsimpl::frame_archive >)
Definition: device.h:111
std::string get_usb_port_id(const device &device)
GLuint GLuint stream
Definition: glext.h:1774
rs_output_buffer_format
Output buffer format: sets how librealsense works with frame memory.
Definition: rs.h:73
GLdouble n
Definition: glext.h:1950
void config(uvc::device &device, uint8_t gyro_bw, uint8_t gyro_range, uint8_t accel_bw, uint8_t accel_range, uint32_t time_seed)
bool is_between(const firmware_version &from, const firmware_version &until)
Definition: types.h:243
stream_request presets[RS_STREAM_NATIVE_COUNT][RS_PRESET_COUNT]
Definition: types.h:275
const char * get_option_description(rs_option option) const override
Definition: device.cpp:530
void perform_and_send_monitor_command(uvc::device &device, std::timed_mutex &mutex, hwmon_cmd &newCommand)
Definition: hw-monitor.cpp:95
rsimpl::rectified_stream rect_color
Definition: device.h:83
virtual void on_before_start(const std::vector< rsimpl::subdevice_mode_selection > &selected_modes)=0
std::atomic< uint32_t > event_queue_size
Definition: device.h:92
void release_frame(rs_frame_ref *ref) override
Definition: device.cpp:513
const char * get_usb_port_id() const override
Definition: device.cpp:710
rs_motion_intrinsics get_motion_intrinsics() const override
Definition: device.cpp:88
GLenum GLint ref
Definition: glext.h:652
rs_extrinsics get_motion_extrinsics_from(rs_stream from) const override
Definition: device.cpp:93
std::vector< supported_capability > capabilities_vector
Definition: types.h:282
virtual void stop_video_streaming()
Definition: device.cpp:490
const char * rs_capabilities_to_string(rs_capabilities capability)
Definition: rs.cpp:759
int stream_subdevices[RS_STREAM_NATIVE_COUNT]
Definition: types.h:271
void set_subdevice_data_channel_handler(device &device, int subdevice_index, data_channel_callback callback)
#define LOG_DEBUG(...)
Definition: types.h:77
void start_streaming(device &device, int num_transfer_bufs)
const GLubyte * c
Definition: glext.h:11542
GLfixed GLfixed GLint GLint GLfixed points
Definition: glext.h:4927
GLuint GLuint GLsizei count
Definition: glext.h:111
void start_data_acquisition(device &device)
rsimpl::native_stream * native_streams[RS_STREAM_NATIVE_COUNT]
Definition: device.h:85
Motion data from gyroscope and accelerometer from the microcontroller.
Definition: rs.h:347
rs_camera_info
Read-only strings that can be queried from the device.
Definition: rs.h:237
stream_request requests[RS_STREAM_NATIVE_COUNT]
Definition: types.h:451
Motion module intrinsics: includes accelerometer and gyroscope intrinsics structs of type rs_motion_d...
Definition: rs.h:325
rsimpl::aligned_stream depth_to_color
Definition: device.h:84
rsimpl::aligned_stream depth_to_rect_color
Definition: device.h:84
void enable_stream(rs_stream stream, int width, int height, rs_format format, int fps, rs_output_buffer_format output) override
Definition: device.cpp:70
format
Formats: defines how each stream can be encoded. rs_format specifies how a frame is represented in me...
Definition: rs.hpp:42
rsimpl::native_stream color
Definition: device.h:81
void disable_stream(rs_stream stream) override
Definition: device.cpp:98
virtual ~rs_device_base()
Definition: device.cpp:41
GLint GLenum GLsizei GLsizei GLsizei GLint GLsizei const void * data
Definition: glext.h:223
void enable_motion_tracking() override
Definition: device.cpp:118
const char * get_camera_info(rs_camera_info info) const override
Definition: device.cpp:62
std::atomic< bool > keep_fw_logger_alive
Definition: device.h:114
std::map< rs_camera_info, std::string > camera_info
Definition: types.h:284
rs_format
Formats: defines how each stream can be encoded.
Definition: rs.h:53
std::vector< supported_option > options
Definition: types.h:276
virtual void disable_auto_option(int subdevice, rs_option auto_opt)
Definition: device.cpp:701
std::chrono::high_resolution_clock::time_point capture_started
Definition: device.h:90
Timestamp data from the motion microcontroller.
Definition: rs.h:339
std::shared_ptr< rsimpl::syncronizing_archive > archive
Definition: device.h:94
bool poll_all_streams() override
Definition: device.cpp:506
std::string usb_port_id
Definition: device.h:96
std::atomic< uint32_t > max_publish_list_size
Definition: device.h:91
virtual void start_video_streaming()
Definition: device.cpp:326
const static_device_info info
Definition: types.h:450
rs_source
Source: allows you to choose between available hardware subdevices.
Definition: rs.h:90
virtual bool supports_option(rs_option option) const override
Definition: device.cpp:55
virtual std::vector< std::shared_ptr< rsimpl::frame_timestamp_reader > > create_frame_timestamp_readers() const =0
#define LOG_INFO(...)
Definition: types.h:78
rsimpl::stream_interface * streams[RS_STREAM_COUNT]
Definition: device.h:86
int get_pu_control(const device &device, int subdevice, rs_option option)
Cross-stream extrinsics: encode the topology describing how the different devices are connected...
Definition: rs.h:332
const char * get_string(rs_stream value)
Definition: types.cpp:19
rsimpl::aligned_stream infrared2_to_depth
Definition: device.h:84
virtual rs_stream select_key_stream(const std::vector< rsimpl::subdevice_mode_selection > &selected_modes)=0
rs_preset
Presets: general preferences that are translated by librealsense into concrete resolution and FPS...
Definition: rs.h:81
GLenum GLsizei GLsizei GLint * values
Definition: glext.h:1484
std::unique_ptr< rs_timestamp_callback, void(*)(rs_timestamp_callback *)> timestamp_callback_ptr
Definition: types.h:428
uint8_t byte
Definition: types.h:42
GLdouble s
Definition: glext.h:231
rs_stream
Streams are different types of data provided by RealSense devices.
Definition: rs.h:33
rsimpl::aligned_stream color_to_depth
Definition: device.h:84
GLint GLint GLsizei width
Definition: glext.h:112
const char * rs_option_to_string(rs_option option)
Definition: rs.cpp:758
GLsizei GLsizei GLchar * source
Definition: glext.h:672
GLsizeiptr size
Definition: glext.h:532
void set_pu_control(device &device, int subdevice, rs_option option, int value)
virtual void release()=0
static std::atomic< bool > stop_streaming
rs_capabilities
Specifies various capabilities of a RealSense device.
Definition: rs.h:213
data_polling_request data_request
Definition: types.h:453
void set_motion_callback(rs_motion_callback *callback) override
Definition: device.cpp:132
GLint GLint GLsizei GLsizei GLsizei GLint GLenum format
Definition: glext.h:112
rsimpl::native_stream depth
Definition: device.h:81
bool is_pu_control(rs_option option)
Definition: uvc.h:46
bool data_acquisition_active
Definition: device.h:89
GLuint res
Definition: glext.h:8310
virtual void start(rs_source source) override
Definition: device.cpp:215
virtual void set_options(const rs_option options[], size_t count, const double values[]) override
Definition: device.cpp:661
void disable_motion_tracking() override
Definition: device.cpp:125
virtual void stop_fw_logger() override
Definition: device.cpp:311
void wait_all_streams() override
Definition: device.cpp:498
virtual void start_fw_logger(char fw_log_op_code, int grab_rate_in_ms, std::timed_mutex &mutex) override
Definition: device.cpp:283
void stop_data_acquisition(device &device)
bool capturing
Definition: device.h:88
std::atomic< uint32_t > events_timeout
Definition: device.h:93
virtual void start_motion_tracking()
Definition: device.cpp:140
void set_timestamp_callback(void(*on_event)(rs_device *device, rs_timestamp_data data, void *user), void *user) override
Definition: device.cpp:202
GLuint64EXT * result
Definition: glext.h:9881
std::atomic< int > frames_drops_counter
Definition: device.h:116
std::string hexify(unsigned char n)
Definition: device.cpp:263
const int RS_MAX_EVENT_TIME_OUT
Definition: types.h:32
std::vector< subdevice_mode_selection > select_modes(const stream_request(&requests)[RS_STREAM_NATIVE_COUNT]) const
Definition: types.cpp:599
std::mutex usb_port_mutex
Definition: device.h:97
rsimpl::native_stream infrared
Definition: device.h:81
rs_frame_ref * clone_frame(rs_frame_ref *frame) override
Definition: device.cpp:518
preset
Presets: general preferences that are translated by librealsense into concrete resolution and FPS...
Definition: rs.hpp:68


librealsense
Author(s): Sergey Dorodnicov , Mark Horn , Reagan Lopez
autogenerated on Fri Mar 13 2020 03:16:17