8 #ifndef LIBREALSENSE_RS_HPP 9 #define LIBREALSENSE_RS_HPP 254 float hfov()
const {
return (atan2f(ppx + 0.5
f, fx) + atan2f(
width - (ppx + 0.5
f), fx)) * 57.2957795f; }
255 float vfov()
const {
return (atan2f(ppy + 0.5
f, fy) + atan2f(
height - (ppy + 0.5
f), fy)) * 57.2957795f; }
283 bool is_identity()
const {
return (rotation[0] == 1) && (rotation[4] == 1) && (translation[0] == 0) && (translation[1] == 0) && (translation[2] == 0); }
304 class error :
public std::runtime_error
385 on_event_function(std::move(data));
400 frame() : device(nullptr), frame_ref(nullptr) {}
402 frame(
frame&& other) : device(other.device), frame_ref(other.frame_ref) { other.frame_ref =
nullptr; }
410 std::swap(device, other.
device);
416 if (device && frame_ref)
561 on_frame_function(std::move(
frame(device, fref)));
1010 return r?
true:
false;
1022 return r ?
true :
false;
float2 project_to_texcoord(const float3 &point) const
int rs_get_stream_width(const rs_device *device, rs_stream stream, rs_error **error)
Retrieves the width in pixels of a specific stream, equivalent to the width field from the stream's i...
void log_to_console(log_severity min_severity)
Provides convenience methods relating to devices.
intrinsics get_stream_intrinsics(stream stream) const
Retrieves intrinsic camera parameters for specific stream.
static void rs_apply_ivcam_preset(rs_device *device, rs_ivcam_preset preset)
motion_data(rs_motion_data orig)
void timestamp_callback(rs_device *, rs_timestamp_data, void *)
int get_width() const
Returns image width in pixels.
int rs_supports(rs_device *device, rs_capabilities capability, rs_error **error)
Determines device capabilities.
void rs_get_motion_extrinsics_from(const rs_device *device, rs_stream from, rs_extrinsics *extrin, rs_error **error)
Retrieves extrinsic transformation between specific stream and the motion module. ...
void rs_get_stream_intrinsics(const rs_device *device, rs_stream stream, rs_intrinsics *intrin, rs_error **error)
Retrieves intrinsic camera parameters for a specific stream.
void enable_stream(stream stream, int width, int height, format format, int framerate, output_buffer_format output_buffer_type=output_buffer_format::continous)
Enables specific stream and requests specific properties.
int get_stride() const
Retrieves frame stride, meaning the actual line width in memory in bytes (not the logical image width...
const char * rs_stream_to_string(rs_stream stream)
void rs_start_source(rs_device *device, rs_source source, rs_error **error)
Begins streaming on all enabled streams for this device.
void rs_disable_motion_tracking(rs_device *device, rs_error **error)
Disables motion-tracking handlers.
void rs_log_to_callback_cpp(rs_log_severity min_severity, rs_log_callback *callback, rs_error **error)
Starts logging to user-provided callback.
const char * rs_source_to_string(rs_source source)
const std::string & get_failed_args() const
int rs_supports_frame_metadata(const rs_frame_ref *frame, rs_frame_metadata frame_metadata, rs_error **error)
Determines device metadata.
float3 deproject_from_texcoord(const float2 &coord, float depth) const
std::function< void(log_severity, const char *)> on_event_function
extrinsics get_extrinsics(stream from_stream, stream to_stream) const
Retrieves extrinsic transformation between viewpoints of two different streams.
int rs_get_device_count(const rs_context *context, rs_error **error)
Determines number of connected devices.
std::ostream & operator<<(std::ostream &o, stream stream)
frame_metadata
Types of value provided from the device with each frame.
GLint GLint GLsizei GLsizei height
Cross-stream extrinsics: encode the topology describing how the different devices are connected...
const char * get_firmware_version() const
Retrieves version of firmware currently installed on device.
rs_blob_type
Proprietary formats for direct communication with device firmware.
GLint GLint GLint GLint GLint GLint y
void rs_log_to_console(rs_log_severity min_severity, rs_error **error)
Starts logging to console.
log_severity
Severity of the librealsense logger.
rs_format rs_get_detached_frame_format(const rs_frame_ref *frame, rs_error **error)
Retrieves frame format.
void rs_enable_stream_ex(rs_device *device, rs_stream stream, int width, int height, rs_format format, int framerate, rs_output_buffer_format output_format, rs_error **error)
Enables a specific stream and requests specific properties.
void rs_get_device_options(rs_device *device, const rs_option *options, unsigned int count, double *values, rs_error **error)
Efficiently retrieves the value of an arbitrary number of options, using minimal hardware IO...
void motion_callback(rs_device *, rs_motion_data, void *)
void rs_set_device_options(rs_device *device, const rs_option *options, unsigned int count, const double *values, rs_error **error)
Efficiently sets the value of an arbitrary number of options, using minimal hardware IO...
rs_timestamp_domain rs_get_detached_frame_timestamp_domain(const rs_frame_ref *frame, rs_error **error)
Retrieves timestamp domain from frame reference.
GLuint GLsizei const GLchar * message
const char * get_info(camera_info info) const
Retrieves camera-specific information such as versions of various components.
void on_event(rs_timestamp_data data) override
unsigned long long rs_get_detached_frame_number(const rs_frame_ref *frame, rs_error **error)
Retrieves frame number from frame reference.
double get_frame_metadata(rs_frame_metadata frame_metadata) const
void get_option_range(option option, double &min, double &max, double &step)
Retrieves available range of values of supported option.
double rs_get_frame_timestamp(const rs_device *device, rs_stream stream, rs_error **error)
Retrieves time at which the latest frame on a stream was captured.
void on_event(rs_motion_data e) override
const void * rs_get_frame_data(const rs_device *device, rs_stream stream, rs_error **error)
Retrieves the contents of the latest frame on a stream.
int rs_is_device_streaming(const rs_device *device, rs_error **error)
Determines if the device is currently streaming.
GLsizei const GLchar *const * string
bool supports(camera_info info_param) const
Determines device capabilities.
const char * get_usb_port_id() const
Retrieves USB port number of device.
int get_stream_width(stream stream) const
Retrieves width, in pixels, of a specific stream, equivalent to the width field from the stream's int...
Motion data from gyroscope and accelerometer from the microcontroller.
void enable_stream(stream stream, preset preset)
Enables specific stream and requests properties using preset.
void apply_depth_control_preset(device *device, int preset)
const char * rs_distortion_to_string(rs_distortion distortion)
GLint GLint GLsizei GLsizei GLsizei depth
void log_to_callback(log_severity min_severity, std::function< void(log_severity, const char *)> callback)
float2 pixel_to_texcoord(const float2 &pixel) const
void rs_delete_context(rs_context *context, rs_error **error)
Frees the relevant context object.
camera_info
Read-only strings that can be queried from the device.
void enable_motion_tracking(std::function< void(motion_data)> motion_handler)
Sets the callback for motion module event.
void rs_set_device_option(rs_device *device, rs_option option, double value, rs_error **error)
Sets the current value of a single option.
const char * rs_get_device_name(const rs_device *device, rs_error **error)
Retrieves human-readable device model string.
rs_option
Defines general configuration controls.
const char * rs_get_error_message(const rs_error *error)
Returns static pointer to error message.
float rs_get_device_depth_scale(const rs_device *device, rs_error **error)
Retrieves mapping between the units of the depth image and meters.
rs_output_buffer_format
Output buffer format: sets how librealsense works with frame memory.
const void * get_frame_data(stream stream) const
Retrieves contents of latest frame on a stream.
static void rs_project_point_to_pixel(float pixel[2], const struct rs_intrinsics *intrin, const float point[3])
timestamp_data(rs_timestamp_data orig)
const char * rs_get_device_usb_port_id(const rs_device *device, rs_error **error)
Retrieves the USB port number of the device.
void rs_log_to_file(rs_log_severity min_severity, const char *file_path, rs_error **error)
Starts logging to file.
static void rs_transform_point_to_point(float to_point[3], const struct rs_extrinsics *extrin, const float from_point[3])
context(rs_context *handle)
format get_stream_format(stream stream) const
Retrieves pixel format for specific stream.
rs_stream rs_get_detached_frame_stream_type(const rs_frame_ref *frame, rs_error **error)
Retrieves frame stream type.
void rs_get_stream_mode(const rs_device *device, rs_stream stream, int index, int *width, int *height, rs_format *format, int *framerate, rs_error **error)
Determines the properties of a specific streaming mode.
timestamp_domain get_frame_timestamp_domain() const
event
Source device that triggered specific timestamp event from the motion module.
void send_blob_to_device(rs::blob_type type, void *data, int size)
Sends device-specific data to device.
int rs_get_stream_mode_count(const rs_device *device, rs_stream stream, rs_error **error)
Determines the number of streaming modes available for a given stream.
frame & operator=(frame other)
int get_stream_mode_count(stream stream) const
Determines number of streaming modes available for given stream.
int rs_poll_for_frames(rs_device *device, rs_error **error)
Checks if new frames are available, without blocking.
void apply_ivcam_preset(device *device, rs_ivcam_preset preset)
frame_callback(std::function< void(frame)> on_frame)
Motion device intrinsics: scale, bias, and variances.
void stop(rs::source source=rs::source::video)
Ends streaming on all streams for this device.
const char * rs_get_failed_function(const rs_error *error)
Returns static pointer to name of a failing function in case of error.
std::function< void(motion_data)> on_event_function
rs_format rs_get_stream_format(const rs_device *device, rs_stream stream, rs_error **error)
Retrieves the pixel format for a specific stream.
rs_context * rs_create_context(int api_version, rs_error **error)
Creates RealSense context that is required for the rest of the API.
int get_height() const
Returns image height in pixels.
static void rs_apply_depth_control_preset(rs_device *device, int preset)
const char * rs_capabilities_to_string(rs_capabilities capability)
double rs_get_device_option(rs_device *device, rs_option option, rs_error **error)
Retrieves the current value of a single option.
void rs_get_device_option_range_ex(rs_device *device, rs_option option, double *min, double *max, double *step, double *def, rs_error **error)
Retrieves the available range of values for a supported option.
int rs_get_detached_frame_bpp(const rs_frame_ref *frame, rs_error **error)
Retrieves frame bits per pixel.
stream
Streams are different types of data provided by RealSense devices.
timestamp_domain
Specifies the clock in relation to which the frame timestamp was measured.
void rs_disable_stream(rs_device *device, rs_stream stream, rs_error **error)
Disables a specific stream.
int get_stream_height(stream stream) const
Retrieves height, in pixels, of a specific stream, equivalent to the height field from the stream's i...
int rs_get_detached_framerate(const rs_frame_ref *frame, rs_error **error)
Retrieves frame intrinsic frame rate.
void frame_callback(rs_device *dev, rs_frame_ref *frame, void *user)
void rs_release_frame(rs_device *device, rs_frame_ref *frame, rs_error **error)
Releases frame handle.
void set_options(const option *options, size_t count, const double *values)
Efficiently sets value of arbitrary number of options, using minimal hardware IO. ...
GLuint GLuint GLsizei count
Motion data from gyroscope and accelerometer from the microcontroller.
bool is_stream_enabled(stream stream) const
Determines if specific stream is enabled.
void rs_get_device_extrinsics(const rs_device *device, rs_stream from_stream, rs_stream to_stream, rs_extrinsics *extrin, rs_error **error)
Retrieves extrinsic transformation between the viewpoints of two different streams.
void disable_motion_tracking(void)
Disables events polling.
rs_camera_info
Read-only strings that can be queried from the device.
int rs_device_supports_option(const rs_device *device, rs_option option, rs_error **error)
Determines if the device allows a specific option to be queried and set.
Motion module intrinsics: includes accelerometer and gyroscope intrinsics structs of type rs_motion_d...
format get_format() const
Retrieves frame format.
const char * get_name() const
Retrieves human-readable device model string.
format
Formats: defines how each stream can be encoded. rs_format specifies how a frame is represented in me...
void rs_send_blob_to_device(rs_device *device, rs_blob_type type, void *data, int size, rs_error **error)
Sends arbitrary binary data to the device.
void get_stream_mode(stream stream, int index, int &width, int &height, format &format, int &framerate) const
Determines properties of specific streaming mode.
int rs_get_detached_frame_height(const rs_frame_ref *frame, rs_error **error)
Retrieves frame intrinsic height.
void start(rs::source source=rs::source::video)
Begins streaming on all enabled streams for this device.
int get_stream_framerate(stream stream) const
Retrieves frame rate for specific stream.
const char * rs_get_device_firmware_version(const rs_device *device, rs_error **error)
Retrieves the version of the firmware currently installed on the device.
void enable_motion_tracking(std::function< void(motion_data)> motion_handler, std::function< void(timestamp_data)> timestamp_handler)
Sets callback for motion module event.
float2 texcoord_to_pixel(const float2 &coord) const
void on_event(rs_log_severity severity, const char *message) override
GLint GLenum GLsizei GLsizei GLsizei GLint GLsizei const void * data
const void * get_data() const
double get_option(option option)
Retrieves current value of single option.
static void rs_deproject_pixel_to_point(float point[3], const struct rs_intrinsics *intrin, const float pixel[2], float depth)
unsigned long long get_frame_number(stream stream) const
Retrieves frame number.
const char * rs_get_device_option_description(rs_device *device, rs_option option, rs_error **error)
Retrieves a static description of what a particular option does on given device.
source
Allows the user to choose between available hardware subdevices.
const char * rs_get_failed_args(const rs_error *error)
Returns static pointer to arguments of a failing function in case of error.
rs_format
Formats: defines how each stream can be encoded.
std::function< void(timestamp_data)> on_event_function
const char * rs_event_to_string(rs_event_source event)
void get_option_range(option option, double &min, double &max, double &step, double &def)
Retrieves available range of values of supported option.
double rs_get_detached_frame_timestamp(const rs_frame_ref *frame, rs_error **error)
Retrieves timestamp from frame reference.
int is_motion_tracking_active()
Checks if data acquisition is active.
const char * rs_get_device_info(const rs_device *device, rs_camera_info info, rs_error **error)
Retrieves camera specific information, such as versions of various internal componnents.
int get_framerate() const
Returns configured frame rate.
void rs_stop_source(rs_device *device, rs_source source, rs_error **error)
Ends data acquisition for the specified source providers.
int rs_get_detached_frame_width(const rs_frame_ref *frame, rs_error **error)
Retrieves frame intrinsic width in pixels.
Timestamp data from the motion microcontroller.
extrinsics get_motion_extrinsics_from(stream from_stream) const
Retrieves extrinsic transformation between viewpoints of specific stream and motion module...
void log_to_file(log_severity min_severity, const char *file_path)
int rs_get_detached_frame_stride(const rs_frame_ref *frame, rs_error **error)
Retrieves frame stride, meaning the actual line width in memory in bytes (not the logical image width...
unsigned long long rs_get_frame_number(const rs_device *device, rs_stream stream, rs_error **error)
Retrieves frame number.
int rs_supports_camera_info(rs_device *device, rs_camera_info info_param, rs_error **error)
Returns true if given camera information parameter is supported by the device.
static void handle(rs_error *e)
GLsizei const GLfloat * value
void rs_free_error(rs_error *error)
Frees memory of an error object.
const char * get_serial() const
Retrieves unique serial number of device.
rs_source
Source: allows you to choose between available hardware subdevices.
void on_frame(rs_device *device, rs_frame_ref *fref) override
output_buffer_format
Output buffer format: sets how librealsense works with frame memory.
int rs_is_motion_tracking_active(rs_device *device, rs_error **error)
Checks if data acquisition is active.
bool supports_option(option option) const
Determines if device allows specific option to be queried and set.
double get_frame_timestamp(stream stream) const
Retrieves time at which the latest frame on a stream was captured.
blob_type
Proprietary formats for direct communication with device firmware.
Cross-stream extrinsics: encode the topology describing how the different devices are connected...
void disable_stream(stream stream)
Disables specific stream.
void rs_get_device_option_range(rs_device *device, rs_option option, double *min, double *max, double *step, rs_error **error)
Retrieves the available range of values for a supported option.
stream get_stream_type() const
Retrieves frame stream type.
frame(rs_device *device, rs_frame_ref *frame_ref)
const char * rs_preset_to_string(rs_preset preset)
rs_preset
Presets: general preferences that are translated by librealsense into concrete resolution and FPS...
int rs_get_stream_framerate(const rs_device *device, rs_stream stream, rs_error **error)
Retrieves the frame rate for a specific stream.
GLenum GLsizei GLsizei GLint * values
bool poll_for_frames()
Checks if new frames are available, without blocking.
const char * rs_format_to_string(rs_format format)
distortion
Distortion model: defines how pixel coordinates should be mapped to sensor coordinates.
rs_stream
Streams are different types of data provided by RealSense devices.
GLint GLint GLsizei width
const char * rs_option_to_string(rs_option option)
double get_timestamp() const
int get_bpp() const
Retrieves bits per pixel.
unsigned long long get_frame_number() const
motion_intrinsics get_motion_intrinsics() const
Retrieves intrinsic camera parameters for motion module.
rs_log_severity
Severity of the librealsense logger.
double rs_get_detached_frame_metadata(const rs_frame_ref *frame, rs_frame_metadata frame_metadata, rs_error **error)
Retrieves metadata from a frame reference.
rs_capabilities
Specifies various capabilities of a RealSense device.
void rs_set_frame_callback_cpp(rs_device *device, rs_stream stream, rs_frame_callback *callback, rs_error **error)
Sets up a frame callback that is called immediately when an image is available, with no synchronizati...
void set_frame_callback(rs::stream stream, std::function< void(frame)> frame_handler)
Sets callback for frame arrival event.
rs_device * rs_get_device(rs_context *context, int index, rs_error **error)
Retrieves connected device by index.
const char * rs_get_device_serial(const rs_device *device, rs_error **error)
Retrieves unique serial number of the device.
void rs_wait_for_frames(rs_device *device, rs_error **error)
Blocks until new frames are available.
void rs_enable_stream_preset(rs_device *device, rs_stream stream, rs_preset preset, rs_error **error)
Enables a specific stream and requests properties using a preset.
float get_depth_scale() const
Retrieves mapping between units of depth image and meters.
const char * get_option_description(option option)
Retrieves device-specific option description.
bool supports_frame_metadata(rs_frame_metadata frame_metadata) const
std::function< void(frame)> on_frame_function
bool supports(capabilities capability) const
Determines device capabilities.
rs_distortion
Distortion model: defines how pixel coordinates should be mapped to sensor coordinates.
rs_frame_metadata
Types of value provided from the device with each frame.
float3 deproject(const float2 &pixel, float depth) const
context()
Creates RealSense context that is required for the rest of the API.
bool is_streaming() const
Determines if device is currently streaming.
timestamp_callback(std::function< void(timestamp_data)> on_event)
bool operator==(const float3 &a, const float3 &b)
device * get_device(int index)
float3 transform(const float3 &point) const
void set_option(option option, double value)
Sets current value of single option.
log_callback(std::function< void(log_severity, const char *)> on_event)
int rs_is_stream_enabled(const rs_device *device, rs_stream stream, rs_error **error)
Determines if a specific stream is enabled.
rs_ivcam_preset
For SR300 devices: provides optimized settings (presets) for specific types of usage.
const std::string & get_failed_function() const
Timestamp data from the motion microcontroller.
capabilities
Specifies various capabilities of a RealSense device.
int rs_get_stream_height(const rs_device *device, rs_stream stream, rs_error **error)
Retrieves the height in pixels of a specific stream, equivalent to the height field from the stream's...
GLdouble GLdouble GLdouble r
GLint GLint GLint GLint GLint x
rs_event_source
Source device that triggered a specific timestamp event from the motion module.
const void * rs_get_detached_frame_data(const rs_frame_ref *frame, rs_error **error)
Retrieves data from frame reference.
void get_options(const option *options, size_t count, double *values)
Efficiently retrieves value of arbitrary number of options, using minimal hardware IO...
motion_callback(std::function< void(motion_data)> on_event)
float2 project(const float3 &point) const
void wait_for_frames()
Blocks until new frames are available.
int get_device_count() const
void rs_get_motion_intrinsics(const rs_device *device, rs_motion_intrinsics *intrinsic, rs_error **error)
Retrieves intrinsic camera parameters for a motion module.
GLuint GLuint GLsizei GLenum type
preset
Presets: general preferences that are translated by librealsense into concrete resolution and FPS...
void rs_enable_motion_tracking_cpp(rs_device *device, rs_motion_callback *motion_callback, rs_timestamp_callback *timestamp_callback, rs_error **error)
Enables and configures motion-tracking data handlers.