5 #ifndef LIBREALSENSE_DEVICE_H 6 #define LIBREALSENSE_DEVICE_H 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); }
40 : max_number(max_value - min_value + 1), last_number(min_value), num_of_wraparounds(0)
45 if ((number + (num_of_wraparounds*max_number)) < last_number)
49 number += (num_of_wraparounds*max_number);
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;
68 namespace motion_module
77 const std::shared_ptr<rsimpl::uvc::device>
device;
94 std::shared_ptr<rsimpl::syncronizing_archive>
archive;
102 const rsimpl::uvc::device &
get_device()
const {
return *device; }
105 virtual void start_video_streaming();
106 virtual void stop_video_streaming();
107 virtual void start_motion_tracking();
108 virtual void stop_motion_tracking();
110 virtual void disable_auto_option(
int subdevice,
rs_option auto_opt);
133 void disable_stream(
rs_stream stream)
override;
137 void enable_motion_tracking()
override;
140 void disable_motion_tracking()
override;
148 virtual void stop(
rs_source source)
override;
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;
156 void wait_all_streams()
override;
157 bool poll_all_streams()
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;
177 const char * get_option_description(
rs_option option)
const override;
rsimpl::native_stream infrared2
rsimpl::device_config config
const std::shared_ptr< rsimpl::uvc::device > device
std::shared_ptr< std::thread > fw_logger
const rsimpl::uvc::device & get_device() const
GLint GLint GLsizei GLsizei height
const char * get_firmware_version() const override
rs_blob_type
Proprietary formats for direct communication with device firmware.
GLsizei const GLchar *const * string
struct_interface(R r, W w)
rsimpl::point_stream points
GLint GLint GLsizei GLsizei GLsizei depth
rs_option
Defines general configuration controls.
const char * get_name() const override
virtual void on_before_callback(rs_stream, rs_frame_ref *, std::shared_ptr< rsimpl::frame_archive >)
std::string get_usb_port_id(const device &device)
unsigned long long num_of_wraparounds
rs_output_buffer_format
Output buffer format: sets how librealsense works with frame memory.
rsimpl::rectified_stream rect_color
std::atomic< uint32_t > event_queue_size
float get_depth_scale() const override
const uint8_t RS_STREAM_NATIVE_COUNT
virtual void send_blob_to_device(rs_blob_type, void *, int)
std::string firmware_version
GLuint GLuint GLsizei count
Motion data from gyroscope and accelerometer from the microcontroller.
rs_camera_info
Read-only strings that can be queried from the device.
Motion module intrinsics: includes accelerometer and gyroscope intrinsics structs of type rs_motion_d...
GLint GLenum GLsizei GLsizei GLsizei GLint GLsizei const void * data
std::atomic< bool > keep_fw_logger_alive
rs_format
Formats: defines how each stream can be encoded.
std::chrono::high_resolution_clock::time_point capture_started
Timestamp data from the motion microcontroller.
int is_motion_tracking_active() const override
const char * get_serial() const override
std::shared_ptr< rsimpl::syncronizing_archive > archive
GLsizei const GLfloat * value
std::atomic< uint32_t > max_publish_list_size
const static_device_info info
rs_source
Source: allows you to choose between available hardware subdevices.
Cross-stream extrinsics: encode the topology describing how the different devices are connected...
rsimpl::aligned_stream infrared2_to_depth
rs_preset
Presets: general preferences that are translated by librealsense into concrete resolution and FPS...
GLenum GLsizei GLsizei GLint * values
rs_stream
Streams are different types of data provided by RealSense devices.
GLint GLint GLsizei width
GLsizei GLsizei GLchar * source
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.
GLint GLint GLsizei GLsizei GLsizei GLint GLenum format
rsimpl::uvc::device & get_device()
bool data_acquisition_active
std::atomic< uint32_t > events_timeout
wraparound_mechanism(T min_value, T max_value)
GLdouble GLdouble GLdouble r
GLubyte GLubyte GLubyte GLubyte w
std::atomic< int > frames_drops_counter
struct_interface< T, R, W > make_struct_interface(R r, W w)
const rsimpl::stream_interface & get_stream_interface(rs_stream stream) const override
std::mutex usb_port_mutex
bool is_capturing() const override
preset
Presets: general preferences that are translated by librealsense into concrete resolution and FPS...