4 #ifndef LIBREALSENSE_RSCORE_HPP 5 #define LIBREALSENSE_RSCORE_HPP 52 virtual int get_frame_width()
const = 0;
53 virtual int get_frame_height()
const = 0;
54 virtual int get_frame_framerate()
const = 0;
57 virtual rs_format get_frame_format()
const = 0;
69 virtual const char * get_name()
const = 0;
70 virtual const char * get_serial()
const = 0;
71 virtual const char * get_firmware_version()
const = 0;
77 virtual void disable_stream(
rs_stream stream) = 0;
79 virtual void enable_motion_tracking() = 0;
82 virtual void disable_motion_tracking() = 0;
88 virtual void set_timestamp_callback(
void(*on_event)(
rs_device * device,
rs_timestamp_data data,
void * user),
void * user) = 0;
94 virtual void start_fw_logger(
char fw_log_op_code,
int grab_rate_in_ms, std::timed_mutex& mutex) = 0;
95 virtual void stop_fw_logger() = 0;
97 virtual bool is_capturing()
const = 0;
98 virtual int is_motion_tracking_active()
const = 0;
100 virtual void wait_all_streams() = 0;
101 virtual bool poll_all_streams() = 0;
107 virtual void get_option_range(
rs_option option,
double & min,
double & max,
double & step,
double & def) = 0;
109 virtual void get_options(
const rs_option options[],
size_t count,
double values[]) = 0;
110 virtual const char * get_option_description(
rs_option option)
const = 0;
120 virtual size_t get_device_count()
const = 0;
128 virtual void release() = 0;
135 virtual void release() = 0;
142 virtual void release() = 0;
149 virtual void release() = 0;
virtual rs_extrinsics get_extrinsics_to(const rs_stream_interface &r) const =0
virtual ~rs_log_callback()
virtual bool supports_frame_metadata(rs_frame_metadata frame_metadata) const =0
virtual rs_intrinsics get_rectified_intrinsics() const =0
virtual rs_intrinsics get_intrinsics() const =0
virtual int get_frame_stride() const =0
frame_metadata
Types of value provided from the device with each frame.
GLint GLint GLsizei GLsizei height
GLuint GLsizei const GLchar * message
virtual const uint8_t * get_frame_data() const =0
virtual long long get_frame_system_time() const =0
rs_option
Defines general configuration controls.
std::string get_usb_port_id(const device &device)
GLfloat GLfloat GLfloat GLfloat h
rs_output_buffer_format
Output buffer format: sets how librealsense works with frame memory.
rs_timestamp_domain
Specifies the clock in relation to which the frame timestamp was measured.
Exposes librealsense functionality for C compilers.
virtual ~rs_timestamp_callback()
virtual int get_mode_count() const =0
GLuint GLuint GLsizei count
Motion data from gyroscope and accelerometer from the microcontroller.
virtual bool is_enabled() const =0
virtual ~rs_motion_callback()
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...
virtual unsigned long long get_frame_number() const =0
virtual rs_stream get_stream_type() const =0
virtual int get_framerate() const =0
virtual double get_frame_timestamp() const =0
GLint GLenum GLsizei GLsizei GLsizei GLint GLsizei const void * data
rs_format
Formats: defines how each stream can be encoded.
Timestamp data from the motion microcontroller.
rs_source
Source: allows you to choose between available hardware subdevices.
Cross-stream extrinsics: encode the topology describing how the different devices are connected...
virtual int get_frame_bpp() const =0
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
rs_log_severity
Severity of the librealsense logger.
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
rs_frame_metadata
Types of value provided from the device with each frame.
virtual ~rs_frame_callback()
virtual rs_format get_format() const =0
virtual void get_mode(int mode, int *w, int *h, rs_format *f, int *fps) const =0
GLdouble GLdouble GLdouble r
virtual float get_depth_scale() const =0
GLubyte GLubyte GLubyte GLubyte w
virtual ~rs_stream_interface()
preset
Presets: general preferences that are translated by librealsense into concrete resolution and FPS...
virtual double get_frame_metadata(rs_frame_metadata frame_metadata) const =0