types.h
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 // This header defines vocabulary types and utility mechanisms used ubiquitously by the
5 // rest of the library. As clearer module boundaries form, declarations might be moved
6 // out of this file and into more appropriate locations.
7 
8 #pragma once
9 #ifndef LIBREALSENSE_TYPES_H
10 #define LIBREALSENSE_TYPES_H
11 
12 #include "../include/librealsense/rs.h" // Inherit all type definitions in the public API
13 #include "../include/librealsense/rscore.hpp" // Inherit public interfaces
14 
15 #include <cassert> // For assert
16 #include <cstring> // For memcmp
17 #include <vector> // For vector
18 #include <sstream> // For ostringstream
19 #include <mutex> // For mutex, unique_lock
20 #include <condition_variable> // For condition_variable
21 #include <memory> // For unique_ptr
22 #include <atomic>
23 #include <map>
24 #include <algorithm>
25 #include <functional>
26 
27 const uint8_t RS_STREAM_NATIVE_COUNT = 5;
28 const int RS_USER_QUEUE_SIZE = 20;
29 
30 // Timestamp syncronization settings:
31 const int RS_MAX_EVENT_QUEUE_SIZE = 500; // Max number of timestamp events to keep for all streams
32 const int RS_MAX_EVENT_TIME_OUT = 20; // Max timeout in milliseconds that a frame can wait for its corresponding timestamp event
33 // Usually timestamp events arrive much faster then frames, but due to USB arbitration the QoS isn't guaranteed.
34 // RS_MAX_EVENT_TIME_OUT controls how much time the user is willing to wait before "giving-up" on a particular frame
35 
36 namespace rsimpl
37 {
39  // Utility types for general use //
41 
42  typedef uint8_t byte;
43 
44  struct to_string
45  {
46  std::ostringstream ss;
47  template<class T> to_string & operator << (const T & val) { ss << val; return *this; }
48  operator std::string() const { return ss.str(); }
49  };
50 
51 #pragma pack(push, 1)
52  template<class T> class big_endian
53  {
55  public:
56  operator T () const
57  {
58  T le_value = 0;
59  for (unsigned int i = 0; i < sizeof(T); ++i) reinterpret_cast<char *>(&le_value)[i] = reinterpret_cast<const char *>(&be_value)[sizeof(T) - i - 1];
60  return le_value;
61  }
62  };
63 #pragma pack(pop)
64 
66  // Logging mechanism //
68 
70  void log_to_console(rs_log_severity min_severity);
71  void log_to_file(rs_log_severity min_severity, const char * file_path);
72  void log_to_callback(rs_log_severity min_severity, rs_log_callback * callback);
73  void log_to_callback(rs_log_severity min_severity, void(*on_log)(rs_log_severity min_severity, const char * message, void * user), void * user);
75 
76 #define LOG(SEVERITY, ...) do { if(static_cast<int>(SEVERITY) >= rsimpl::get_minimum_severity()) { std::ostringstream ss; ss << __VA_ARGS__; rsimpl::log(SEVERITY, ss.str()); } } while(false)
77 #define LOG_DEBUG(...) LOG(RS_LOG_SEVERITY_DEBUG, __VA_ARGS__)
78 #define LOG_INFO(...) LOG(RS_LOG_SEVERITY_INFO, __VA_ARGS__)
79 #define LOG_WARNING(...) LOG(RS_LOG_SEVERITY_WARN, __VA_ARGS__)
80 #define LOG_ERROR(...) LOG(RS_LOG_SEVERITY_ERROR, __VA_ARGS__)
81 #define LOG_FATAL(...) LOG(RS_LOG_SEVERITY_FATAL, __VA_ARGS__)
82 
84  // Enumerated type support //
86 
87 #define RS_ENUM_HELPERS(TYPE, PREFIX) const char * get_string(TYPE value); \
88  inline bool is_valid(TYPE value) { return value >= 0 && value < RS_##PREFIX##_COUNT; } \
89  inline std::ostream & operator << (std::ostream & out, TYPE value) { if(is_valid(value)) return out << get_string(value); else return out << (int)value; }
90  RS_ENUM_HELPERS(rs_stream, STREAM)
91  RS_ENUM_HELPERS(rs_format, FORMAT)
92  RS_ENUM_HELPERS(rs_preset, PRESET)
93  RS_ENUM_HELPERS(rs_distortion, DISTORTION)
94  RS_ENUM_HELPERS(rs_option, OPTION)
95  RS_ENUM_HELPERS(rs_capabilities, CAPABILITIES)
96  RS_ENUM_HELPERS(rs_source, SOURCE)
97  RS_ENUM_HELPERS(rs_output_buffer_format, OUTPUT_BUFFER_FORMAT)
98  RS_ENUM_HELPERS(rs_event_source, EVENT_SOURCE)
99  RS_ENUM_HELPERS(rs_blob_type, BLOB_TYPE)
100  RS_ENUM_HELPERS(rs_camera_info, CAMERA_INFO)
101  RS_ENUM_HELPERS(rs_timestamp_domain, TIMESTAMP_DOMAIN)
102  RS_ENUM_HELPERS(rs_frame_metadata, FRAME_METADATA)
103  #undef RS_ENUM_HELPERS
104 
106  // World's tiniest linear algebra library //
108 
109  struct int2 { int x,y; };
110  struct float3 { float x,y,z; float & operator [] (int i) { return (&x)[i]; } };
111  struct float3x3 { float3 x,y,z; float & operator () (int i, int j) { return (&x)[j][i]; } }; // column-major
112  struct pose { float3x3 orientation; float3 position; };
113  inline bool operator == (const float3 & a, const float3 & b) { return a.x==b.x && a.y==b.y && a.z==b.z; }
114  inline float3 operator + (const float3 & a, const float3 & b) { return {a.x+b.x, a.y+b.y, a.z+b.z}; }
115  inline float3 operator * (const float3 & a, float b) { return {a.x*b, a.y*b, a.z*b}; }
116  inline bool operator == (const float3x3 & a, const float3x3 & b) { return a.x==b.x && a.y==b.y && a.z==b.z; }
117  inline float3 operator * (const float3x3 & a, const float3 & b) { return a.x*b.x + a.y*b.y + a.z*b.z; }
118  inline float3x3 operator * (const float3x3 & a, const float3x3 & b) { return {a*b.x, a*b.y, a*b.z}; }
119  inline float3x3 transpose(const float3x3 & a) { return {{a.x.x,a.y.x,a.z.x}, {a.x.y,a.y.y,a.z.y}, {a.x.z,a.y.z,a.z.z}}; }
120  inline bool operator == (const pose & a, const pose & b) { return a.orientation==b.orientation && a.position==b.position; }
121  inline float3 operator * (const pose & a, const float3 & b) { return a.orientation * b + a.position; }
122  inline pose operator * (const pose & a, const pose & b) { return {a.orientation * b.orientation, a * b.position}; }
123  inline pose inverse(const pose & a) { auto inv = transpose(a.orientation); return {inv, inv * a.position * -1}; }
124 
126  // Pixel formats //
128 
130  {
132  void(*unpack)(byte * const dest[], const byte * source, int count);
133  std::vector<std::pair<rs_stream, rs_format>> outputs;
134 
135  bool provides_stream(rs_stream stream) const { for (auto & o : outputs) if (o.first == stream) return true; return false; }
136  rs_format get_format(rs_stream stream) const { for (auto & o : outputs) if (o.first == stream) return o.second; throw std::logic_error("missing output"); }
137  };
138 
140  {
141  uint32_t fourcc;
144  std::vector<pixel_format_unpacker> unpackers;
145 
146  size_t get_image_size(int width, int height) const { return width * height * plane_count * bytes_per_pixel; }
147 
148  };
149 
151  // Static camera info //
153 
155  {
156  int subdevice; // 0, 1, 2, etc...
157  int2 native_dims; // Resolution advertised over UVC
158  native_pixel_format pf; // Pixel format advertised over UVC
159  int fps; // Framerate advertised over UVC
160  rs_intrinsics native_intrinsics; // Intrinsics structure corresponding to the content of image (Note: width,height may be subset of native_dims)
161  std::vector<rs_intrinsics> rect_modes; // Potential intrinsics of image after being rectified in software by librealsense
162  std::vector<int> pad_crop_options; // Acceptable padding/cropping values
163  };
164 
166  {
167  bool enabled;
168  int width, height;
169  rs_format format;
170  int fps;
171  rs_output_buffer_format output_format;
172 
173  bool contradict(stream_request req) const;
174  bool is_filled() const;
175  };
176 
177  struct interstream_rule // Requires a.*field + delta == b.*field OR a.*field + delta2 == b.*field
178  {
181  int delta, delta2;
182  rs_stream bigger; // if this equals to a or b, this stream must have field value bigger then the other stream
183  bool divides, divides2; // divides = a must divide b; divides2 = b must divide a
185  };
186 
188  {
189  rs_option option;
190  double min, max, step, def;
191  };
192 
194  {
195  bool enabled;
196 
197  data_polling_request(): enabled(false) {};
198  };
199 
201  {
202  int m_major, m_minor, m_patch, m_build;
203  bool is_any;
205 
206  std::string to_string() const;
207  static std::vector<std::string> split(const std::string& str);
208  static int parse_part(const std::string& name, int part);
209 
210  public:
211  firmware_version() : m_major(0), m_minor(0), m_patch(0), m_build(0), is_any(true), string_representation(to_string()) {}
212 
213  firmware_version(int major, int minor, int patch, int build, bool is_any = false)
214  : m_major(major), m_minor(minor), m_patch(patch), m_build(build), is_any(is_any), string_representation(to_string()) {}
215 
217  {
218  return{};
219  }
220 
222  : m_major(parse_part(name, 0)), m_minor(parse_part(name, 1)), m_patch(parse_part(name, 2)), m_build(parse_part(name, 3)), is_any(false), string_representation(to_string()) {}
223 
224  bool operator<=(const firmware_version& other) const
225  {
226  if (is_any || other.is_any) return true;
227  if (m_major > other.m_major) return false;
228  if ((m_major == other.m_major) && (m_minor > other.m_minor)) return false;
229  if ((m_major == other.m_major) && (m_minor == other.m_minor) && (m_patch > other.m_patch)) return false;
230  if ((m_major == other.m_major) && (m_minor == other.m_minor) && (m_patch == other.m_patch) && (m_build > other.m_build)) return false;
231  return true;
232  }
233  bool operator==(const firmware_version& other) const
234  {
235  return is_any || (other.m_major == m_major && other.m_minor == m_minor && other.m_patch == m_patch && other.m_build == m_build);
236  }
237 
238  bool operator> (const firmware_version& other) const { return !(*this < other) || is_any; }
239  bool operator!=(const firmware_version& other) const { return !(*this == other); }
240  bool operator<(const firmware_version& other) const { return !(*this == other) && (*this <= other); }
241  bool operator>=(const firmware_version& other) const { return (*this == other) || (*this > other); }
242 
243  bool is_between(const firmware_version& from, const firmware_version& until)
244  {
245  return (from <= *this) && (*this <= until);
246  }
247 
248  operator const char*() const
249  {
250  return string_representation.c_str();
251  }
252  };
253 
255  {
256  rs_capabilities capability;
259  rs_camera_info firmware_type;
260 
261  supported_capability(rs_capabilities capability, firmware_version from, firmware_version until, rs_camera_info firmware_type = RS_CAMERA_INFO_CAMERA_FIRMWARE_VERSION)
262  : capability(capability), from(from), until(until), firmware_type(firmware_type) {}
263 
264  supported_capability(rs_capabilities capability)
265  : capability(capability), from(), until(), firmware_type(RS_CAMERA_INFO_CAMERA_FIRMWARE_VERSION) {}
266  };
267 
269  {
270  std::string name; // Model name of the camera
271  int stream_subdevices[RS_STREAM_NATIVE_COUNT]; // Which subdevice is used to support each stream, or -1 if stream is unavailable
272  int data_subdevices[RS_STREAM_NATIVE_COUNT]; // Specify whether the subdevice supports events pipe in addition to streaming, -1 if data channels are unavailable
273  std::vector<subdevice_mode> subdevice_modes; // A list of available modes each subdevice can be put into
274  std::vector<interstream_rule> interstream_rules; // Rules which constrain the set of available modes
275  stream_request presets[RS_STREAM_NATIVE_COUNT][RS_PRESET_COUNT]; // Presets available for each stream
276  std::vector<supported_option> options;
277  pose stream_poses[RS_STREAM_NATIVE_COUNT]; // Static pose of each camera on the device
278  int num_libuvc_transfer_buffers; // Number of transfer buffers to use in LibUVC backend
279  std::string firmware_version; // Firmware version string
280  std::string serial; // Serial number of the camera (from USB or from SPI memory)
281  float nominal_depth_scale; // Default scale
282  std::vector<supported_capability> capabilities_vector;
283  std::vector<rs_frame_metadata> supported_metadata_vector;
284  std::map<rs_camera_info, std::string> camera_info;
285 
287  };
288 
290  // Runtime device configuration //
292 
294  {
295  subdevice_mode mode; // The streaming mode in which to place the hardware
296  int pad_crop; // The number of pixels of padding (positive values) or cropping (negative values) to apply to all four edges of the image
297  size_t unpacker_index; // The specific unpacker used to unpack the encoded format into the desired output formats
298  rs_output_buffer_format output_format = RS_OUTPUT_BUFFER_FORMAT_CONTINUOUS; // The output buffer format.
299 
300  subdevice_mode_selection() : mode({}), pad_crop(), unpacker_index(), output_format(RS_OUTPUT_BUFFER_FORMAT_CONTINUOUS){}
301  subdevice_mode_selection(const subdevice_mode & mode, int pad_crop, int unpacker_index) : mode(mode), pad_crop(pad_crop), unpacker_index(unpacker_index){}
302 
304  if ((size_t)unpacker_index < mode.pf.unpackers.size())
305  return mode.pf.unpackers[unpacker_index];
306  throw std::runtime_error("failed to fetch an unpakcer, most likely because enable_stream was not called!");
307  }
308  const std::vector<std::pair<rs_stream, rs_format>> & get_outputs() const { return get_unpacker().outputs; }
309  int get_width() const { return mode.native_intrinsics.width + pad_crop * 2; }
310  int get_height() const { return mode.native_intrinsics.height + pad_crop * 2; }
311  int get_framerate() const { return mode.fps; }
312  int get_stride_x() const { return requires_processing() ? get_width() : mode.native_dims.x; }
313  int get_stride_y() const { return requires_processing() ? get_height() : mode.native_dims.y; }
314  size_t get_image_size(rs_stream stream) const;
315  bool provides_stream(rs_stream stream) const { return get_unpacker().provides_stream(stream); }
316  rs_format get_format(rs_stream stream) const { return get_unpacker().get_format(stream); }
317  void set_output_buffer_format(const rs_output_buffer_format in_output_format);
318 
319  void unpack(byte * const dest[], const byte * source) const;
320  int get_unpacked_width() const;
321  int get_unpacked_height() const;
322 
323  bool requires_processing() const { return (output_format == RS_OUTPUT_BUFFER_FORMAT_CONTINUOUS) || (mode.pf.unpackers[unpacker_index].requires_processing); }
324 
325  };
326 
327  typedef void(*frame_callback_function_ptr)(rs_device * dev, rs_frame_ref * frame, void * user);
330  typedef void(*log_callback_function_ptr)(rs_log_severity severity, const char * message, void * user);
331 
333  {
335  void * user;
337  public:
338  frame_callback() : frame_callback(nullptr, nullptr, nullptr) {}
339  frame_callback(rs_device * dev, frame_callback_function_ptr on_frame, void * user) : fptr(on_frame), user(user), device(dev) {}
340 
341  operator bool() { return fptr != nullptr; }
342  void on_frame (rs_device * dev, rs_frame_ref * frame) override {
343  if (fptr)
344  {
345  try { fptr(dev, frame, user); } catch (...)
346  {
347  LOG_ERROR("Received an execption from frame callback!");
348  }
349  }
350  }
351  void release() override { delete this; }
352  };
353 
355  {
357  void * user;
359  public:
360  motion_events_callback() : motion_events_callback(nullptr, nullptr, nullptr) {}
361  motion_events_callback(rs_device * dev, motion_callback_function_ptr fptr, void * user) : fptr(fptr), user(user), device(dev) {}
362 
363  operator bool() { return fptr != nullptr; }
364 
365  void on_event(rs_motion_data data) override
366  {
367  if (fptr)
368  {
369  try { fptr(device, data, user); } catch (...)
370  {
371  LOG_ERROR("Received an execption from motion events callback!");
372  }
373  }
374  }
375 
376  void release() override { }
377  };
378 
380  {
382  void * user;
384  public:
385  timestamp_events_callback() : timestamp_events_callback(nullptr, nullptr, nullptr) {}
386  timestamp_events_callback(rs_device * dev, timestamp_callback_function_ptr fptr, void * user) : fptr(fptr), user(user), device(dev) {}
387 
388  operator bool() { return fptr != nullptr; }
389  void on_event(rs_timestamp_data data) override {
390  if (fptr)
391  {
392  try { fptr(device, data, user); } catch (...)
393  {
394  LOG_ERROR("Received an execption from timestamp events callback!");
395  }
396  }
397  }
398  void release() override { }
399  };
400 
402  {
404  void * user;
405  public:
406  log_callback() : log_callback(nullptr, nullptr) {}
407  log_callback(log_callback_function_ptr fptr, void * user) : fptr(fptr), user(user) {}
408 
409  operator bool() { return fptr != nullptr; }
410 
411  void on_event(rs_log_severity severity, const char * message) override
412  {
413  if (fptr)
414  {
415  try { fptr(severity, message, user); }
416  catch (...)
417  {
418  LOG_ERROR("Received an execption from log callback!");
419  }
420  }
421  }
422 
423  void release() override { }
424  };
425 
426  typedef std::unique_ptr<rs_log_callback, void(*)(rs_log_callback*)> log_callback_ptr;
427  typedef std::unique_ptr<rs_motion_callback, void(*)(rs_motion_callback*)> motion_callback_ptr;
428  typedef std::unique_ptr<rs_timestamp_callback, void(*)(rs_timestamp_callback*)> timestamp_callback_ptr;
430  {
432  public:
433  frame_callback_ptr() : callback(nullptr) {}
434  explicit frame_callback_ptr(rs_frame_callback * callback) : callback(callback) {}
435  frame_callback_ptr(const frame_callback_ptr&) = delete;
437  {
438  if (callback) callback->release();
439  callback = other.callback;
440  other.callback = nullptr;
441  return *this;
442  }
443  ~frame_callback_ptr() { if (callback) callback->release(); }
444  operator rs_frame_callback *() { return callback; }
445  rs_frame_callback * operator*() { return callback; }
446  };
447 
449  {
451  stream_request requests[RS_STREAM_NATIVE_COUNT]; // Modified by enable/disable_stream calls
452  frame_callback_ptr callbacks[RS_STREAM_NATIVE_COUNT]; // Modified by set_frame_callback calls
453  data_polling_request data_request; // Modified by enable/disable_events calls
454  motion_callback_ptr motion_callback{ nullptr, [](rs_motion_callback*){} }; // Modified by set_events_callback calls
455  timestamp_callback_ptr timestamp_callback{ nullptr, [](rs_timestamp_callback*){} };
456  float depth_scale; // Scale of depth values
457 
458  explicit device_config(const rsimpl::static_device_info & info) : info(info), depth_scale(info.nominal_depth_scale)
459  {
460  for (auto & req : requests) req = rsimpl::stream_request();
461  }
462 
463  subdevice_mode_selection select_mode(const stream_request(&requests)[RS_STREAM_NATIVE_COUNT], int subdevice_index) const;
464  bool all_requests_filled(const stream_request(&original_requests)[RS_STREAM_NATIVE_COUNT]) const;
465  bool find_good_requests_combination(stream_request(&output_requests)[RS_STREAM_NATIVE_COUNT], std::vector<stream_request> stream_requests[RS_STREAM_NATIVE_COUNT]) const;
466  bool fill_requests(stream_request(&requests)[RS_STREAM_NATIVE_COUNT]) const;
467  void get_all_possible_requestes(std::vector<stream_request> (&stream_requests)[RS_STREAM_NATIVE_COUNT]) const;
468  std::vector<subdevice_mode_selection> select_modes(const stream_request(&requests)[RS_STREAM_NATIVE_COUNT]) const;
469  std::vector<subdevice_mode_selection> select_modes() const { return select_modes(requests); }
470  bool validate_requests(stream_request(&requests)[RS_STREAM_NATIVE_COUNT], bool throw_exception = false) const;
471  };
472 
474  // Helper functions for library types //
476 
477  inline rs_intrinsics pad_crop_intrinsics(const rs_intrinsics & i, int pad_crop)
478  {
479  return{ i.width + pad_crop * 2, i.height + pad_crop * 2, i.ppx + pad_crop, i.ppy + pad_crop, i.fx, i.fy, i.model, {i.coeffs[0], i.coeffs[1], i.coeffs[2], i.coeffs[3], i.coeffs[4]} };
480  }
481 
483  {
484  const float sx = (float)width / i.width, sy = (float)height / i.height;
485  return{ width, height, i.ppx*sx, i.ppy*sy, i.fx*sx, i.fy*sy, i.model, {i.coeffs[0], i.coeffs[1], i.coeffs[2], i.coeffs[3], i.coeffs[4]} };
486  }
487 
488  inline bool operator == (const rs_intrinsics & a, const rs_intrinsics & b) { return std::memcmp(&a, &b, sizeof(a)) == 0; }
489 
490  inline uint32_t pack(uint8_t c0, uint8_t c1, uint8_t c2, uint8_t c3)
491  {
492  return (c0 << 24) | (c1 << 16) | (c2 << 8) | c3;
493  }
494 
495  template<class T, int C>
497  {
498  T buffer[C];
499  bool is_free[C];
500  std::mutex mutex;
501  bool keep_allocating = true;
502  std::condition_variable cv;
503  int size = 0;
504 
505  public:
507  {
508  for (auto i = 0; i < C; i++)
509  {
510  is_free[i] = true;
511  buffer[i] = std::move(T());
512  }
513  }
514 
515  T * allocate()
516  {
517  std::unique_lock<std::mutex> lock(mutex);
518  if (!keep_allocating) return nullptr;
519 
520  for (auto i = 0; i < C; i++)
521  {
522  if (is_free[i])
523  {
524  is_free[i] = false;
525  size++;
526  return &buffer[i];
527  }
528  }
529  return nullptr;
530  }
531 
532  void deallocate(T * item)
533  {
534  if (item < buffer || item >= buffer + C)
535  {
536  throw std::runtime_error("Trying to return item to a heap that didn't allocate it!");
537  }
538  auto i = item - buffer;
539  buffer[i] = std::move(T());
540 
541  {
542  std::unique_lock<std::mutex> lock(mutex);
543 
544  is_free[i] = true;
545  size--;
546 
547  if (size == 0)
548  {
549  lock.unlock();
550  cv.notify_one();
551  }
552  }
553  }
554 
556  {
557  std::unique_lock<std::mutex> lock(mutex);
558  keep_allocating = false;
559  }
560 
562  {
563  std::unique_lock<std::mutex> lock(mutex);
564 
565  const auto ready = [this]()
566  {
567  return size == 0;
568  };
569  if (!ready() && !cv.wait_for(lock, std::chrono::hours(1000), ready)) // for some reason passing std::chrono::duration::max makes it return instantly
570  {
571  throw std::runtime_error("Could not flush one of the user controlled objects!");
572  }
573  }
574  };
575 
577  {
578  std::function<void()> continuation;
579  const void* protected_data = nullptr;
580 
581  frame_continuation(const frame_continuation &) = delete;
582  frame_continuation & operator=(const frame_continuation &) = delete;
583  public:
584  frame_continuation() : continuation([]() {}) {}
585 
586  explicit frame_continuation(std::function<void()> continuation, const void* protected_data) : continuation(continuation), protected_data(protected_data) {}
587 
588 
589  frame_continuation(frame_continuation && other) : continuation(std::move(other.continuation)), protected_data(other.protected_data)
590  {
591  other.continuation = []() {};
592  other.protected_data = nullptr;
593  }
594 
595  void operator()()
596  {
597  continuation();
598  continuation = []() {};
599  protected_data = nullptr;
600  }
601 
602  void reset()
603  {
604  protected_data = nullptr;
605  continuation = [](){};
606  }
607 
608  const void* get_data() const { return protected_data; }
609 
611  {
612  continuation();
613  protected_data = other.protected_data;
614  continuation = other.continuation;
615  other.continuation = []() {};
616  other.protected_data = nullptr;
617  return *this;
618  }
619 
621  {
622  continuation();
623  }
624 
625  };
626 
627  // this class is a convenience wrapper for intrinsics / extrinsics validation methods
629  {
630  public:
631  calibration_validator(std::function<bool(rs_stream, rs_stream)> extrinsic_validator,
632  std::function<bool(rs_stream)> intrinsic_validator);
634 
635  bool validate_extrinsics(rs_stream from_stream, rs_stream to_stream) const;
636  bool validate_intrinsics(rs_stream stream) const;
637 
638  private:
639  std::function<bool(rs_stream from_stream, rs_stream to_stream)> extrinsic_validator;
640  std::function<bool(rs_stream stream)> intrinsic_validator;
641  };
642 
643  inline bool check_not_all_zeros(std::vector<byte> data)
644  {
645  return std::find_if(data.begin(), data.end(), [](byte b){ return b!=0; }) != data.end();
646  }
647 }
648 
649 #endif
std::function< void()> continuation
Definition: types.h:578
to_string & operator<<(const T &val)
Definition: types.h:47
std::vector< rs_intrinsics > rect_modes
Definition: types.h:161
void timestamp_callback(rs_device *, rs_timestamp_data, void *)
bool operator<=(const firmware_version &other) const
Definition: types.h:224
std::unique_ptr< rs_motion_callback, void(*)(rs_motion_callback *)> motion_callback_ptr
Definition: types.h:427
float coeffs[5]
Definition: rs.h:309
void wait_until_empty()
Definition: types.h:561
void on_event(rs_log_severity severity, const char *message) override
Definition: types.h:411
bool operator==(const firmware_version &other) const
Definition: types.h:233
std::vector< rs_frame_metadata > supported_metadata_vector
Definition: types.h:283
rs_frame_callback * callback
Definition: types.h:431
frame_continuation(std::function< void()> continuation, const void *protected_data)
Definition: types.h:586
int major(int version)
Definition: rs.cpp:49
bool operator>=(const firmware_version &other) const
Definition: types.h:241
const int RS_USER_QUEUE_SIZE
Definition: types.h:28
GLint GLint GLsizei GLsizei height
Definition: glext.h:112
std::mutex mutex
Definition: types.h:500
rs_blob_type
Proprietary formats for direct communication with device firmware.
Definition: rs.h:228
GLint GLint GLint GLint GLint GLint y
Definition: glext.h:114
native_pixel_format pf
Definition: types.h:158
uint32_t pack(uint8_t c0, uint8_t c1, uint8_t c2, uint8_t c3)
Definition: types.h:490
void(* timestamp_callback_function_ptr)(rs_device *dev, rs_timestamp_data data, void *user)
Definition: types.h:329
rs_log_severity get_minimum_severity()
Definition: log.cpp:91
void motion_callback(rs_device *, rs_motion_data, void *)
float3 operator*(const float3 &a, float b)
Definition: types.h:115
std::vector< int > pad_crop_options
Definition: types.h:162
GLuint GLsizei const GLchar * message
Definition: glext.h:2482
bool provides_stream(rs_stream stream) const
Definition: types.h:135
rs_format get_format(rs_stream stream) const
Definition: types.h:136
float z
Definition: types.h:110
float ppy
Definition: rs.h:305
GLsizei const GLchar *const * string
Definition: glext.h:683
std::function< bool(rs_stream stream)> intrinsic_validator
Definition: types.h:640
bool provides_stream(rs_stream stream) const
Definition: types.h:315
Definition: archive.h:12
const int RS_MAX_EVENT_QUEUE_SIZE
Definition: types.h:31
std::string string_representation
Definition: types.h:204
rs_intrinsics pad_crop_intrinsics(const rs_intrinsics &i, int pad_crop)
Definition: types.h:477
log_callback(log_callback_function_ptr fptr, void *user)
Definition: types.h:407
firmware_version(int major, int minor, int patch, int build, bool is_any=false)
Definition: types.h:213
void log_to_file(rs_log_severity min_severity, const char *file_path)
Definition: log.cpp:106
rs_option
Defines general configuration controls.
Definition: rs.h:128
GLuint GLuint stream
Definition: glext.h:1774
float x
Definition: types.h:110
rs_output_buffer_format
Output buffer format: sets how librealsense works with frame memory.
Definition: rs.h:73
rs_timestamp_domain
Specifies the clock in relation to which the frame timestamp was measured.
Definition: rs.h:292
std::vector< std::pair< rs_stream, rs_format > > outputs
Definition: types.h:133
bool is_between(const firmware_version &from, const firmware_version &until)
Definition: types.h:243
std::vector< subdevice_mode > subdevice_modes
Definition: types.h:273
GLuint buffer
Definition: glext.h:528
void(* motion_callback_function_ptr)(rs_device *dev, rs_motion_data data, void *user)
Definition: types.h:328
rs_format get_format(rs_stream stream) const
Definition: types.h:316
device_config(const rsimpl::static_device_info &info)
Definition: types.h:458
const uint8_t RS_STREAM_NATIVE_COUNT
Definition: types.h:27
std::vector< supported_capability > capabilities_vector
Definition: types.h:282
rs_intrinsics native_intrinsics
Definition: types.h:160
frame_continuation(frame_continuation &&other)
Definition: types.h:589
std::string serial
Definition: types.h:280
virtual void release()=0
float3 x
Definition: types.h:111
std::string firmware_version
Definition: types.h:279
void log_to_console(rs_log_severity min_severity)
Definition: log.cpp:101
supported_capability(rs_capabilities capability)
Definition: types.h:264
rs_device * device
Definition: types.h:336
float3 operator+(const float3 &a, const float3 &b)
Definition: types.h:114
GLuint GLuint GLsizei count
Definition: glext.h:111
Motion data from gyroscope and accelerometer from the microcontroller.
Definition: rs.h:347
void(* frame_callback_function_ptr)(rs_device *dev, rs_frame_ref *frame, void *user)
Definition: types.h:327
const void * get_data() const
Definition: types.h:608
frame_callback(rs_device *dev, frame_callback_function_ptr on_frame, void *user)
Definition: types.h:339
rs_camera_info
Read-only strings that can be queried from the device.
Definition: rs.h:237
std::condition_variable cv
Definition: types.h:502
void on_event(rs_motion_data data) override
Definition: types.h:365
void log_to_callback(rs_log_severity min_severity, rs_log_callback *callback)
Definition: log.cpp:111
#define RS_ENUM_HELPERS(TYPE, PREFIX)
Definition: types.h:87
bool operator<(const firmware_version &other) const
Definition: types.h:240
void deallocate(T *item)
Definition: types.h:532
size_t get_image_size(int width, int height) const
Definition: types.h:146
void(* log_callback_function_ptr)(rs_log_severity severity, const char *message, void *user)
Definition: types.h:330
int stream_request::* field
Definition: types.h:180
bool check_not_all_zeros(std::vector< byte > data)
Definition: types.h:643
std::unique_ptr< rs_log_callback, void(*)(rs_log_callback *)> log_callback_ptr
Definition: types.h:426
GLint GLenum GLsizei GLsizei GLsizei GLint GLsizei const void * data
Definition: glext.h:223
int patch(int version)
Definition: rs.cpp:57
void on_frame(rs_device *dev, rs_frame_ref *frame) override
Definition: types.h:342
supported_capability(rs_capabilities capability, firmware_version from, firmware_version until, rs_camera_info firmware_type=RS_CAMERA_INFO_CAMERA_FIRMWARE_VERSION)
Definition: types.h:261
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
bool requires_processing() const
Definition: types.h:323
std::vector< supported_option > options
Definition: types.h:276
Timestamp data from the motion microcontroller.
Definition: rs.h:339
GLboolean GLboolean GLboolean GLboolean a
Definition: glext.h:1104
bool operator!=(const firmware_version &other) const
Definition: types.h:239
int height
Definition: rs.h:303
const std::vector< std::pair< rs_stream, rs_format > > & get_outputs() const
Definition: types.h:308
float fy
Definition: rs.h:307
const static_device_info info
Definition: types.h:450
rs_source
Source: allows you to choose between available hardware subdevices.
Definition: rs.h:90
std::vector< pixel_format_unpacker > unpackers
Definition: types.h:144
int width
Definition: rs.h:302
float3 y
Definition: types.h:111
Video stream intrinsics.
Definition: rs.h:300
std::ostringstream ss
Definition: types.h:46
GLboolean GLboolean GLboolean b
Definition: glext.h:1104
void release() override
Definition: types.h:376
typedef void(APIENTRYP PFNGLDRAWRANGEELEMENTSPROC)(GLenum mode
firmware_version(const std::string &name)
Definition: types.h:221
rs_preset
Presets: general preferences that are translated by librealsense into concrete resolution and FPS...
Definition: rs.h:81
frame_callback_function_ptr fptr
Definition: types.h:334
timestamp_callback_function_ptr fptr
Definition: types.h:381
std::vector< subdevice_mode_selection > select_modes() const
Definition: types.h:469
std::unique_ptr< rs_timestamp_callback, void(*)(rs_timestamp_callback *)> timestamp_callback_ptr
Definition: types.h:428
firmware_version from
Definition: types.h:257
pose inverse(const pose &a)
Definition: types.h:123
void log(rs_log_severity severity, const std::string &message)
Definition: log.cpp:96
uint8_t byte
Definition: types.h:42
float3x3 orientation
Definition: types.h:112
rs_stream
Streams are different types of data provided by RealSense devices.
Definition: rs.h:33
rs_format format
Definition: types.h:169
GLint GLint GLsizei width
Definition: glext.h:112
void release() override
Definition: types.h:351
GLuint const GLchar * name
Definition: glext.h:655
void release() override
Definition: types.h:423
std::function< bool(rs_stream from_stream, rs_stream to_stream)> extrinsic_validator
Definition: types.h:639
GLsizei GLsizei GLchar * source
Definition: glext.h:672
static firmware_version any()
Definition: types.h:216
rs_device * dev
frame_callback_ptr(rs_frame_callback *callback)
Definition: types.h:434
GLsizeiptr size
Definition: glext.h:532
int minor(int version)
Definition: rs.cpp:53
size_t get_image_size(int width, int height, rs_format format)
Definition: image.cpp:22
rs_log_severity
Severity of the librealsense logger.
Definition: rs.h:265
const pixel_format_unpacker & get_unpacker() const
Definition: types.h:303
float fx
Definition: rs.h:306
rs_capabilities
Specifies various capabilities of a RealSense device.
Definition: rs.h:213
float y
Definition: types.h:110
data_polling_request data_request
Definition: types.h:453
subdevice_mode_selection(const subdevice_mode &mode, int pad_crop, int unpacker_index)
Definition: types.h:301
std::vector< interstream_rule > interstream_rules
Definition: types.h:274
T * allocate()
Definition: types.h:515
rs_output_buffer_format output_format
Definition: types.h:171
rs_distortion model
Definition: rs.h:308
rs_distortion
Distortion model: defines how pixel coordinates should be mapped to sensor coordinates.
Definition: rs.h:99
float3x3 transpose(const float3x3 &a)
Definition: types.h:119
float ppx
Definition: rs.h:304
rs_frame_metadata
Types of value provided from the device with each frame.
Definition: rs.h:203
rs_camera_info firmware_type
Definition: types.h:259
rs_intrinsics scale_intrinsics(const rs_intrinsics &i, int width, int height)
Definition: types.h:482
bool operator==(const float3 &a, const float3 &b)
Definition: types.h:113
rs_capabilities capability
Definition: types.h:256
rs_frame_callback * operator*()
Definition: types.h:445
firmware_version until
Definition: types.h:258
motion_callback_function_ptr fptr
Definition: types.h:356
void on_event(rs_timestamp_data data) override
Definition: types.h:389
frame_continuation & operator=(frame_continuation &&other)
Definition: types.h:610
GLenum GLenum severity
Definition: glext.h:2478
float3 position
Definition: types.h:112
void stop_allocation()
Definition: types.h:555
float3 z
Definition: types.h:111
GLint GLint GLint GLint GLint x
Definition: glext.h:114
rs_event_source
Source device that triggered a specific timestamp event from the motion module.
Definition: rs.h:276
log_callback_function_ptr fptr
Definition: types.h:403
timestamp_events_callback(rs_device *dev, timestamp_callback_function_ptr fptr, void *user)
Definition: types.h:386
const int RS_MAX_EVENT_TIME_OUT
Definition: types.h:32
motion_events_callback(rs_device *dev, motion_callback_function_ptr fptr, void *user)
Definition: types.h:361
GLuint GLfloat * val
Definition: glext.h:1490
#define LOG_ERROR(...)
Definition: types.h:80


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