device.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 #pragma once
5 #ifndef LIBREALSENSE_DEVICE_H
6 #define LIBREALSENSE_DEVICE_H
7 
8 #include "uvc.h"
9 #include "stream.h"
10 #include <chrono>
11 #include <memory>
12 #include <vector>
13 
14 namespace rsimpl
15 {
16  // This class is used to buffer up several writes to a structure-valued XU control, and send the entire structure all at once
17  // Additionally, it will ensure that any fields not set in a given struct will retain their original values
18  template<class T, class R, class W> struct struct_interface
19  {
21  R reader;
22  W writer;
23  bool active;
24 
25  struct_interface(R r, W w) : reader(r), writer(w), active(false) {}
26 
27  void activate() { if (!active) { struct_ = reader(); active = true; } }
28  template<class U> double get(U T::* field) { activate(); return static_cast<double>(struct_.*field); }
29  template<class U, class V> void set(U T::* field, V value) { activate(); struct_.*field = static_cast<U>(value); }
30  void commit() { if (active) writer(struct_); }
31  };
32 
33  template<class T, class R, class W> struct_interface<T, R, W> make_struct_interface(R r, W w) { return{ r,w }; }
34 
35  template <typename T>
37  {
38  public:
39  wraparound_mechanism(T min_value, T max_value)
40  : max_number(max_value - min_value + 1), last_number(min_value), num_of_wraparounds(0)
41  {}
42 
43  T fix(T number)
44  {
45  if ((number + (num_of_wraparounds*max_number)) < last_number)
46  ++num_of_wraparounds;
47 
48 
49  number += (num_of_wraparounds*max_number);
50  last_number = number;
51  return number;
52  }
53 
54  private:
57  unsigned long long num_of_wraparounds;
58  };
59 
61  {
62  virtual bool validate_frame(const subdevice_mode & mode, const void * frame) = 0;
63  virtual double get_frame_timestamp(const subdevice_mode & mode, const void * frame, double actual_fps) = 0;
64  virtual unsigned long long get_frame_counter(const subdevice_mode & mode, const void * frame) = 0;
65  };
66 
67 
68  namespace motion_module
69  {
70  struct motion_module_parser;
71  }
72 }
73 
75 {
76 private:
77  const std::shared_ptr<rsimpl::uvc::device> device;
78 protected:
80 private:
84  rsimpl::aligned_stream color_to_depth, depth_to_color, depth_to_rect_color, infrared2_to_depth, depth_to_infrared2;
87 
88  bool capturing;
90  std::chrono::high_resolution_clock::time_point capture_started;
91  std::atomic<uint32_t> max_publish_list_size;
92  std::atomic<uint32_t> event_queue_size;
93  std::atomic<uint32_t> events_timeout;
94  std::shared_ptr<rsimpl::syncronizing_archive> archive;
95 
97  mutable std::mutex usb_port_mutex;
98 
99  std::shared_ptr<std::thread> fw_logger;
100 
101 protected:
102  const rsimpl::uvc::device & get_device() const { return *device; }
103  rsimpl::uvc::device & get_device() { return *device; }
104 
105  virtual void start_video_streaming();
106  virtual void stop_video_streaming();
107  virtual void start_motion_tracking();
108  virtual void stop_motion_tracking();
109 
110  virtual void disable_auto_option(int subdevice, rs_option auto_opt);
111  virtual void on_before_callback(rs_stream, rs_frame_ref *, std::shared_ptr<rsimpl::frame_archive>) { }
112 
114  std::atomic<bool> keep_fw_logger_alive;
115 
116  std::atomic<int> frames_drops_counter;
117 
118 public:
119  rs_device_base(std::shared_ptr<rsimpl::uvc::device> device, const rsimpl::static_device_info & info, rsimpl::calibration_validator validator = rsimpl::calibration_validator());
120  virtual ~rs_device_base();
121 
122  const rsimpl::stream_interface & get_stream_interface(rs_stream stream) const override { return *streams[stream]; }
123 
124  const char * get_name() const override { return config.info.name.c_str(); }
125  const char * get_serial() const override { return config.info.serial.c_str(); }
126  const char * get_firmware_version() const override { return config.info.firmware_version.c_str(); }
127  float get_depth_scale() const override { return config.depth_scale; }
128 
129  const char* get_camera_info(rs_camera_info info) const override;
130 
131  void enable_stream(rs_stream stream, int width, int height, rs_format format, int fps, rs_output_buffer_format output) override;
132  void enable_stream_preset(rs_stream stream, rs_preset preset) override;
133  void disable_stream(rs_stream stream) override;
134 
135  rs_motion_intrinsics get_motion_intrinsics() const override;
136  rs_extrinsics get_motion_extrinsics_from(rs_stream from) const override;
137  void enable_motion_tracking() override;
138  void set_stream_callback(rs_stream stream, void(*on_frame)(rs_device * device, rs_frame_ref * frame, void * user), void * user) override;
139  void set_stream_callback(rs_stream stream, rs_frame_callback * callback) override;
140  void disable_motion_tracking() override;
141 
142  void set_motion_callback(rs_motion_callback * callback) override;
143  void set_motion_callback(void(*on_event)(rs_device * device, rs_motion_data data, void * user), void * user) override;
144  void set_timestamp_callback(void(*on_event)(rs_device * device, rs_timestamp_data data, void * user), void * user) override;
145  void set_timestamp_callback(rs_timestamp_callback * callback) override;
146 
147  virtual void start(rs_source source) override;
148  virtual void stop(rs_source source) override;
149 
150  virtual void start_fw_logger(char fw_log_op_code, int grab_rate_in_ms, std::timed_mutex& mutex) override;
151  virtual void stop_fw_logger() override;
152 
153  bool is_capturing() const override { return capturing; }
154  int is_motion_tracking_active() const override { return data_acquisition_active; }
155 
156  void wait_all_streams() override;
157  bool poll_all_streams() override;
158 
159  virtual bool supports(rs_capabilities capability) const override;
160  virtual bool supports(rs_camera_info info_param) const override;
161 
162  virtual bool supports_option(rs_option option) const override;
163  virtual void get_option_range(rs_option option, double & min, double & max, double & step, double & def) override;
164  virtual void set_options(const rs_option options[], size_t count, const double values[]) override;
165  virtual void get_options(const rs_option options[], size_t count, double values[])override;
166  virtual void on_before_start(const std::vector<rsimpl::subdevice_mode_selection> & selected_modes) = 0;
167  virtual rs_stream select_key_stream(const std::vector<rsimpl::subdevice_mode_selection> & selected_modes) = 0;
168  virtual std::vector<std::shared_ptr<rsimpl::frame_timestamp_reader>>
169  create_frame_timestamp_readers() const = 0;
170  void release_frame(rs_frame_ref * ref) override;
171  const char * get_usb_port_id() const override;
172  rs_frame_ref * clone_frame(rs_frame_ref * frame) override;
173 
174  virtual void send_blob_to_device(rs_blob_type /*type*/, void * /*data*/, int /*size*/) { throw std::runtime_error("not supported!"); }
175  static void update_device_info(rsimpl::static_device_info& info);
176 
177  const char * get_option_description(rs_option option) const override;
178 };
179 
180 #endif
rsimpl::native_stream infrared2
Definition: device.h:81
rsimpl::device_config config
Definition: device.h:79
const std::shared_ptr< rsimpl::uvc::device > device
Definition: device.h:77
std::shared_ptr< std::thread > fw_logger
Definition: device.h:99
const rsimpl::uvc::device & get_device() const
Definition: device.h:102
GLint GLint GLsizei GLsizei height
Definition: glext.h:112
const char * get_firmware_version() const override
Definition: device.h:126
rs_blob_type
Proprietary formats for direct communication with device firmware.
Definition: rs.h:228
GLsizei const GLchar *const * string
Definition: glext.h:683
struct_interface(R r, W w)
Definition: device.h:25
Definition: archive.h:12
rsimpl::point_stream points
Definition: device.h:82
GLint GLint GLsizei GLsizei GLsizei depth
Definition: glext.h:112
bool motion_module_ready
Definition: device.h:113
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
unsigned long long num_of_wraparounds
Definition: device.h:57
rs_output_buffer_format
Output buffer format: sets how librealsense works with frame memory.
Definition: rs.h:73
rsimpl::rectified_stream rect_color
Definition: device.h:83
std::atomic< uint32_t > event_queue_size
Definition: device.h:92
float get_depth_scale() const override
Definition: device.h:127
GLenum GLint ref
Definition: glext.h:652
const uint8_t RS_STREAM_NATIVE_COUNT
Definition: types.h:27
virtual void send_blob_to_device(rs_blob_type, void *, int)
Definition: device.h:174
std::string serial
Definition: types.h:280
std::string firmware_version
Definition: types.h:279
GLuint GLuint GLsizei count
Definition: glext.h:111
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
Motion module intrinsics: includes accelerometer and gyroscope intrinsics structs of type rs_motion_d...
Definition: rs.h:325
GLint GLenum GLsizei GLsizei GLsizei GLint GLsizei const void * data
Definition: glext.h:223
std::atomic< bool > keep_fw_logger_alive
Definition: device.h:114
rs_format
Formats: defines how each stream can be encoded.
Definition: rs.h:53
std::chrono::high_resolution_clock::time_point capture_started
Definition: device.h:90
Timestamp data from the motion microcontroller.
Definition: rs.h:339
int is_motion_tracking_active() const override
Definition: device.h:154
const char * get_serial() const override
Definition: device.h:125
std::shared_ptr< rsimpl::syncronizing_archive > archive
Definition: device.h:94
std::string usb_port_id
Definition: device.h:96
GLsizei const GLfloat * value
Definition: glext.h:693
std::atomic< uint32_t > max_publish_list_size
Definition: device.h:91
GLenum mode
Definition: glext.h:1117
const static_device_info info
Definition: types.h:450
rs_source
Source: allows you to choose between available hardware subdevices.
Definition: rs.h:90
Cross-stream extrinsics: encode the topology describing how the different devices are connected...
Definition: rs.h:332
rsimpl::aligned_stream infrared2_to_depth
Definition: device.h:84
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
rs_stream
Streams are different types of data provided by RealSense devices.
Definition: rs.h:33
GLint GLint GLsizei width
Definition: glext.h:112
GLsizei GLsizei GLchar * source
Definition: glext.h:672
void enable_stream(rs::device *dev, int stream, rs::format format, int w, int h, int fps, bool enable, std::stringstream &stream_name)
rs_capabilities
Specifies various capabilities of a RealSense device.
Definition: rs.h:213
GLint GLint GLsizei GLsizei GLsizei GLint GLenum format
Definition: glext.h:112
rsimpl::uvc::device & get_device()
Definition: device.h:103
bool data_acquisition_active
Definition: device.h:89
bool capturing
Definition: device.h:88
std::atomic< uint32_t > events_timeout
Definition: device.h:93
wraparound_mechanism(T min_value, T max_value)
Definition: device.h:39
GLdouble GLdouble GLdouble r
Definition: glext.h:247
GLubyte GLubyte GLubyte GLubyte w
Definition: glext.h:726
std::atomic< int > frames_drops_counter
Definition: device.h:116
struct_interface< T, R, W > make_struct_interface(R r, W w)
Definition: device.h:33
GLuint start
Definition: glext.h:111
const rsimpl::stream_interface & get_stream_interface(rs_stream stream) const override
Definition: device.h:122
std::mutex usb_port_mutex
Definition: device.h:97
bool is_capturing() const override
Definition: device.h:153
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