4 #ifndef LIBREALSENSE_RS_HPP 5 #define LIBREALSENSE_RS_HPP 295 class error :
public std::runtime_error
297 std::string
function, args;
356 std::function<void(motion_data)> on_event_function;
370 std::function<void(timestamp_data)> on_event_function;
376 on_event_function(std::move(data));
400 std::swap(
device, other.device);
401 std::swap(frame_ref, other.frame_ref);
529 return static_cast<format>(r);
539 return static_cast<stream>(s);
545 std::function<void(frame)> on_frame_function;
988 return r?
true:
false;
1000 return r ? true :
false;
1070 std::function<void(log_severity, const char *)> on_event_function;
int get_stream_height(stream stream) const
Definition: rs.hpp:745
bool is_streaming() const
Definition: rs.hpp:874
int rs_get_stream_width(const rs_device *device, rs_stream stream, rs_error **error)
void log_to_console(log_severity min_severity)
Definition: rs.hpp:1082
#define RS_API_VERSION
Definition: rs.h:22
motion_data(rs_motion_data orig)
Definition: rs.hpp:288
int rs_supports(rs_device *device, rs_capabilities capability, rs_error **error)
void rs_get_motion_extrinsics_from(const rs_device *device, rs_stream from, rs_extrinsics *extrin, rs_error **error)
void rs_get_stream_intrinsics(const rs_device *device, rs_stream stream, rs_intrinsics *intrin, rs_error **error)
int get_bpp() const
Definition: rs.hpp:514
void enable_stream(stream stream, int width, int height, format format, int framerate, output_buffer_format output_buffer_type=output_buffer_format::continous)
Definition: rs.hpp:694
const char * rs_stream_to_string(rs_stream stream)
void rs_start_source(rs_device *device, rs_source source, rs_error **error)
void rs_disable_motion_tracking(rs_device *device, rs_error **error)
bool operator==(const intrinsics &r) const
Definition: rs.hpp:261
void rs_log_to_callback_cpp(rs_log_severity min_severity, rs_log_callback *callback, rs_error **error)
int get_width() const
Definition: rs.hpp:477
Definition: rscore.hpp:132
int get_stream_framerate(stream stream) const
Definition: rs.hpp:767
const char * rs_source_to_string(rs_source source)
unsigned long long get_frame_number(stream stream) const
Definition: rs.hpp:1017
float hfov() const
Definition: rs.hpp:245
int rs_supports_frame_metadata(const rs_frame_ref *frame, rs_frame_metadata frame_metadata, rs_error **error)
motion_intrinsics()
Definition: rs.hpp:268
float y
Definition: rs.hpp:239
int rs_get_device_count(const rs_context *context, rs_error **error)
std::ostream & operator<<(std::ostream &o, stream stream)
Definition: rs.hpp:1048
frame_metadata
Definition: rs.hpp:155
rs_blob_type
Definition: rs.h:219
void rs_log_to_console(rs_log_severity min_severity, rs_error **error)
log_severity
Definition: rs.hpp:1058
rs_format rs_get_detached_frame_format(const rs_frame_ref *frame, rs_error **error)
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)
void rs_get_device_options(rs_device *device, const rs_option *options, unsigned int count, double *values, rs_error **error)
void rs_set_device_options(rs_device *device, const rs_option *options, unsigned int count, const double *values, rs_error **error)
timestamp_domain get_frame_timestamp_domain() const
Definition: rs.hpp:426
bool supports_option(option option) const
Definition: rs.hpp:654
void on_event(rs_timestamp_data data) override
Definition: rs.hpp:374
unsigned long long rs_get_detached_frame_number(const rs_frame_ref *frame, rs_error **error)
void get_option_range(option option, double &min, double &max, double &step)
Definition: rs.hpp:887
int get_stride() const
Definition: rs.hpp:504
const char * get_name() const
Definition: rs.hpp:568
double rs_get_frame_timestamp(const rs_device *device, rs_stream stream, rs_error **error)
void on_event(rs_motion_data e) override
Definition: rs.hpp:360
const void * rs_get_frame_data(const rs_device *device, rs_stream stream, rs_error **error)
int rs_is_device_streaming(const rs_device *device, rs_error **error)
float ppy
Definition: rs.h:293
int get_framerate() const
Definition: rs.hpp:495
const char * get_serial() const
Definition: rs.hpp:578
void enable_stream(stream stream, preset preset)
Definition: rs.hpp:704
void apply_depth_control_preset(device *device, int preset)
Definition: rs.hpp:1104
rs_timestamp_domain rs_get_detached_frame_timestamp_domain(const rs_frame_ref *frameset, rs_error **error)
const char * rs_distortion_to_string(rs_distortion distortion)
const char * get_firmware_version() const
Definition: rs.hpp:598
void log_to_callback(log_severity min_severity, std::function< void(log_severity, const char *)> callback)
Definition: rs.hpp:1096
void rs_delete_context(rs_context *context, rs_error **error)
frame(frame &&other)
Definition: rs.hpp:392
camera_info
Definition: rs.hpp:185
const std::string & get_failed_function() const
Definition: rs.hpp:305
void enable_motion_tracking(std::function< void(motion_data)> motion_handler)
Definition: rs.hpp:831
void rs_set_device_option(rs_device *device, rs_option option, double value, rs_error **error)
intrinsics get_stream_intrinsics(stream stream) const
Definition: rs.hpp:778
const char * rs_get_device_name(const rs_device *device, rs_error **error)
int rs_get_detached_framerate(const rs_frame_ref *frameset, rs_error **error)
rs_option
Definition: rs.h:120
const char * rs_get_error_message(const rs_error *error)
float rs_get_device_depth_scale(const rs_device *device, rs_error **error)
bool supports(camera_info info_param) const
Definition: rs.hpp:995
const std::string & get_failed_args() const
Definition: rs.hpp:306
rs_output_buffer_format
Definition: rs.h:66
timestamp_data(rs_timestamp_data orig)
Definition: rs.hpp:281
const char * rs_get_device_usb_port_id(const rs_device *device, rs_error **error)
int get_height() const
Definition: rs.hpp:486
void rs_log_to_file(rs_log_severity min_severity, const char *file_path, rs_error **error)
context(rs_context *handle)
Definition: rs.hpp:325
option
Definition: rs.hpp:82
float3 deproject(const float2 &pixel, float depth) const
Definition: rs.hpp:254
float3 deproject_from_texcoord(const float2 &coord, float depth) const
Definition: rs.hpp:255
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)
event
Definition: rs.hpp:220
void send_blob_to_device(rs::blob_type type, void *data, int size)
Definition: rs.hpp:1040
float x
Definition: rs.hpp:239
int rs_get_stream_mode_count(const rs_device *device, rs_stream stream, rs_error **error)
frame & operator=(frame other)
Definition: rs.hpp:393
int rs_poll_for_frames(rs_device *device, rs_error **error)
void apply_ivcam_preset(device *device, rs_ivcam_preset preset)
Definition: rs.hpp:1105
frame_callback(std::function< void(frame)> on_frame)
Definition: rs.hpp:547
void release() override
Definition: rs.hpp:379
void stop(rs::source source=rs::source::video)
end streaming on all streams for this device
Definition: rs.hpp:865
format get_stream_format(stream stream) const
Definition: rs.hpp:756
float translation[3]
Definition: rs.h:323
const char * rs_get_failed_function(const rs_error *error)
float2 texcoord_to_pixel(const float2 &coord) const
Definition: rs.hpp:251
rs_format rs_get_stream_format(const rs_device *device, rs_stream stream, rs_error **error)
rs_context * rs_create_context(int api_version, rs_error **error)
const char * rs_capabilities_to_string(rs_capabilities capability)
double rs_get_device_option(rs_device *device, rs_option option, rs_error **error)
void rs_get_device_option_range_ex(rs_device *device, rs_option option, double *min, double *max, double *step, double *def, rs_error **error)
int rs_get_detached_frame_bpp(const rs_frame_ref *frame, rs_error **error)
float y
Definition: rs.hpp:240
stream
Definition: rs.hpp:20
timestamp_domain
Definition: rs.hpp:233
bool supports_frame_metadata(rs_frame_metadata frame_metadata) const
Definition: rs.hpp:448
void rs_disable_stream(rs_device *device, rs_stream stream, rs_error **error)
const void * get_data() const
Definition: rs.hpp:468
void rs_release_frame(rs_device *device, rs_frame_ref *frame, rs_error **error)
void set_options(const option *options, size_t count, const double *values)
Definition: rs.hpp:922
int get_stream_mode_count(stream stream) const
Definition: rs.hpp:665
void rs_get_device_extrinsics(const rs_device *device, rs_stream from_stream, rs_stream to_stream, rs_extrinsics *extrin, rs_error **error)
error(rs_error *err)
Definition: rs.hpp:299
distortion model() const
Definition: rs.hpp:247
void disable_motion_tracking(void)
disable events polling
Definition: rs.hpp:839
rs_camera_info
Definition: rs.h:227
void swap(frame &other)
Definition: rs.hpp:398
int rs_device_supports_option(const rs_device *device, rs_option option, rs_error **error)
format
Definition: rs.hpp:38
void rs_send_blob_to_device(rs_device *device, rs_blob_type type, void *data, int size, rs_error **error)
int rs_get_detached_frame_height(const rs_frame_ref *frame, rs_error **error)
void start(rs::source source=rs::source::video)
begin streaming on all enabled streams for this device
Definition: rs.hpp:857
const char * rs_get_device_firmware_version(const rs_device *device, rs_error **error)
void enable_motion_tracking(std::function< void(motion_data)> motion_handler, std::function< void(timestamp_data)> timestamp_handler)
Definition: rs.hpp:820
const void * get_frame_data(stream stream) const
Definition: rs.hpp:1028
void on_event(rs_log_severity severity, const char *message) override
Definition: rs.hpp:1074
double get_option(option option)
Definition: rs.hpp:932
float get_depth_scale() const
Definition: rs.hpp:643
bool is_stream_enabled(stream stream) const
Definition: rs.hpp:723
const char * get_info(camera_info info) const
Definition: rs.hpp:608
const char * rs_get_device_option_description(rs_device *device, rs_option option, rs_error **error)
float3 transform(const float3 &point) const
Definition: rs.hpp:275
source
Definition: rs.hpp:212
const char * rs_get_failed_args(const rs_error *error)
Definition: rscore.hpp:125
rs_format
Definition: rs.h:46
int get_device_count() const
Definition: rs.hpp:334
const char * rs_event_to_string(rs_event_source event)
void get_option_range(option option, double &min, double &max, double &step, double &def)
Definition: rs.hpp:900
Definition: rscore.hpp:118
double rs_get_detached_frame_timestamp(const rs_frame_ref *frame, rs_error **error)
int is_motion_tracking_active()
check if data acquisition is active
Definition: rs.hpp:847
Definition: rscore.hpp:146
const char * rs_get_device_info(const rs_device *device, rs_camera_info info, rs_error **error)
struct rs_error rs_error
Definition: rs.h:345
void rs_stop_source(rs_device *device, rs_source source, rs_error **error)
format get_format() const
Definition: rs.hpp:524
int rs_get_detached_frame_width(const rs_frame_ref *frame, rs_error **error)
void release() override
Definition: rs.hpp:365
void log_to_file(log_severity min_severity, const char *file_path)
Definition: rs.hpp:1089
int rs_get_detached_frame_stride(const rs_frame_ref *frame, rs_error **error)
int get_stream_width(stream stream) const
Definition: rs.hpp:734
unsigned long long rs_get_frame_number(const rs_device *device, rs_stream stream, rs_error **error)
int rs_supports_camera_info(rs_device *device, rs_camera_info info_param, rs_error **error)
static void handle(rs_error *e)
Definition: rs.hpp:307
motion_data()
Definition: rs.hpp:289
void rs_free_error(rs_error *error)
int height
Definition: rs.h:291
double get_frame_metadata(rs_frame_metadata frame_metadata) const
Definition: rs.hpp:437
bool is_identity() const
Definition: rs.hpp:274
float fy
Definition: rs.h:295
rs_source
Definition: rs.h:83
int width
Definition: rs.h:290
bool supports(capabilities capability) const
Definition: rs.hpp:983
float2 project(const float3 &point) const
Definition: rs.hpp:258
void on_frame(rs_device *device, rs_frame_ref *fref) override
Definition: rs.hpp:549
output_buffer_format
Definition: rs.hpp:57
int rs_is_motion_tracking_active(rs_device *device, rs_error **error)
blob_type
Definition: rs.hpp:177
void disable_stream(stream stream)
Definition: rs.hpp:713
void rs_get_device_option_range(rs_device *device, rs_option option, double *min, double *max, double *step, rs_error **error)
frame(rs_device *device, rs_frame_ref *frame_ref)
Definition: rs.hpp:391
frame()
Definition: rs.hpp:390
const char * rs_preset_to_string(rs_preset preset)
rs_preset
Definition: rs.h:74
int rs_get_stream_framerate(const rs_device *device, rs_stream stream, rs_error **error)
void get_stream_mode(stream stream, int index, int &width, int &height, format &format, int &framerate) const
Definition: rs.hpp:680
float rotation[9]
Definition: rs.h:322
double get_timestamp() const
Definition: rs.hpp:416
extrinsics get_extrinsics(stream from_stream, stream to_stream) const
Definition: rs.hpp:620
bool poll_for_frames()
Definition: rs.hpp:972
unsigned long long get_frame_number() const
Definition: rs.hpp:458
const char * rs_format_to_string(rs_format format)
distortion
Definition: rs.hpp:72
rs_stream
Definition: rs.h:27
const char * rs_option_to_string(rs_option option)
float z
Definition: rs.hpp:240
void release() override
Definition: rs.hpp:554
rs_log_severity
Definition: rs.h:255
double rs_get_detached_frame_metadata(const rs_frame_ref *frame, rs_frame_metadata frame_metadata, rs_error **error)
float fx
Definition: rs.h:294
rs_capabilities
Definition: rs.h:204
void rs_set_frame_callback_cpp(rs_device *device, rs_stream stream, rs_frame_callback *callback, rs_error **error)
void set_frame_callback(rs::stream stream, std::function< void(frame)> frame_handler)
Definition: rs.hpp:805
Definition: rscore.hpp:64
stream get_stream_type() const
Definition: rs.hpp:534
rs_device * rs_get_device(rs_context *context, int index, rs_error **error)
const char * rs_get_device_serial(const rs_device *device, rs_error **error)
void rs_wait_for_frames(rs_device *device, rs_error **error)
void rs_enable_stream_preset(rs_device *device, rs_stream stream, rs_preset preset, rs_error **error)
const char * get_option_description(option option)
Definition: rs.hpp:943
rs_distortion model
Definition: rs.h:296
const char * get_usb_port_id() const
Definition: rs.hpp:588
Definition: rscore.hpp:139
Definition: rscore.hpp:44
~frame()
Definition: rs.hpp:404
rs_distortion
Definition: rs.h:92
float x
Definition: rs.hpp:240
float ppx
Definition: rs.h:292
rs_frame_metadata
Definition: rs.h:195
context()
Definition: rs.hpp:318
float2 pixel_to_texcoord(const float2 &pixel) const
Definition: rs.hpp:250
timestamp_callback(std::function< void(timestamp_data)> on_event)
Definition: rs.hpp:372
timestamp_data()
Definition: rs.hpp:282
device * get_device(int index)
Definition: rs.hpp:345
void set_option(option option, double value)
Definition: rs.hpp:954
log_callback(std::function< void(log_severity, const char *)> on_event)
Definition: rs.hpp:1072
int rs_is_stream_enabled(const rs_device *device, rs_stream stream, rs_error **error)
rs_ivcam_preset
Definition: rs.h:102
extrinsics get_motion_extrinsics_from(stream from_stream) const
Definition: rs.hpp:632
capabilities
Definition: rs.hpp:163
double get_frame_timestamp(stream stream) const
Definition: rs.hpp:1006
int rs_get_stream_height(const rs_device *device, rs_stream stream, rs_error **error)
void release() override
Definition: rs.hpp:1079
rs_stream rs_get_detached_frame_stream_type(const rs_frame_ref *frameset, rs_error **error)
rs_event_source
Definition: rs.h:266
const void * rs_get_detached_frame_data(const rs_frame_ref *frame, rs_error **error)
void get_options(const option *options, size_t count, double *values)
Definition: rs.hpp:911
motion_callback(std::function< void(motion_data)> on_event)
Definition: rs.hpp:358
void wait_for_frames()
Definition: rs.hpp:963
float vfov() const
Definition: rs.hpp:246
void rs_get_motion_intrinsics(const rs_device *device, rs_motion_intrinsics *intrinsic, rs_error **error)
float2 project_to_texcoord(const float3 &point) const
Definition: rs.hpp:259
motion_intrinsics get_motion_intrinsics() const
Definition: rs.hpp:789
~context()
Definition: rs.hpp:327
preset
Definition: rs.hpp:64
void rs_enable_motion_tracking_cpp(rs_device *device, rs_motion_callback *motion_callback, rs_timestamp_callback *timestamp_callback, rs_error **error)