void rs_get_device_extrinsics(const rs_device * device, rs_stream from, rs_stream to, rs_extrinsics * extrin, rs_error ** error) try { VALIDATE_NOT_NULL(device); VALIDATE_ENUM(from); VALIDATE_ENUM(to); VALIDATE_NOT_NULL(extrin); *extrin = device->get_stream_interface(from).get_extrinsics_to(device->get_stream_interface(to)); }
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, rs_error ** error) try { VALIDATE_NOT_NULL(device); VALIDATE_NATIVE_STREAM(stream); VALIDATE_RANGE(width, 0, INT_MAX); VALIDATE_RANGE(height, 0, INT_MAX); VALIDATE_ENUM(format); VALIDATE_ENUM(output); VALIDATE_RANGE(framerate, 0, INT_MAX); device->enable_stream(stream, width, height, format, framerate, output); }
void rs_get_motion_extrinsics_from(const rs_device * device, rs_stream from, rs_extrinsics * extrin, rs_error ** error) try { VALIDATE_NOT_NULL(device); VALIDATE_ENUM(from); VALIDATE_NOT_NULL(extrin); *extrin = device->get_motion_extrinsics_from(from); }
void rs_enable_stream_preset(rs_device * device, rs_stream stream, rs_preset preset, rs_error ** error) try { VALIDATE_NOT_NULL(device); VALIDATE_NATIVE_STREAM(stream); VALIDATE_ENUM(preset); device->enable_stream_preset(stream, preset); }
void rs_get_stream_intrinsics(const rs_device * device, rs_stream stream, rs_intrinsics * intrin, rs_error ** error) try { VALIDATE_NOT_NULL(device); VALIDATE_ENUM(stream); VALIDATE_NOT_NULL(intrin); *intrin = device->get_stream_interface(stream).get_intrinsics(); }
void rs_get_device_option_range(rs_device * device, rs_option option, double * min, double * max, double * step, rs_error ** error) try { VALIDATE_NOT_NULL(device); VALIDATE_ENUM(option); double x; // Prevent internal code from having to worry about whether nulls are passed in for min/max/step by giving it somewhere to write to device->get_option_range(option, min ? *min : x, max ? *max : x, step ? *step : x); }
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) try { VALIDATE_NOT_NULL(device); VALIDATE_ENUM(stream); VALIDATE_RANGE(index, 0, device->get_stream_interface(stream).get_mode_count()-1); device->get_stream_interface(stream).get_mode(index, width, height, format, framerate); }
double rs_get_device_option(rs_device * device, rs_option option, rs_error ** error) try { VALIDATE_NOT_NULL(device); VALIDATE_ENUM(option); double value; device->get_options(&option, 1, &value); return value; }
void rs_get_device_options(rs_device * device, const rs_option options[], unsigned int count, double values[], rs_error ** error) try { VALIDATE_NOT_NULL(device); VALIDATE_LE(count, INT_MAX); VALIDATE_NOT_NULL(options); for(size_t i=0; i<count; ++i) VALIDATE_ENUM(options[i]); VALIDATE_NOT_NULL(values); device->get_options(options, count, values); }
void rs_set_device_options(rs_device * device, const rs_option options[], int count, const double values[], rs_error ** error) try { VALIDATE_NOT_NULL(device); VALIDATE_RANGE(count, 0, INT_MAX); VALIDATE_NOT_NULL(options); for(int i=0; i<count; ++i) VALIDATE_ENUM(options[i]); VALIDATE_NOT_NULL(values); device->set_options(options, count, values); }
void rs_enable_stream(rs_device * device, rs_stream stream, int width, int height, rs_format format, int framerate, rs_error ** error) try { VALIDATE_NOT_NULL(device); VALIDATE_NATIVE_STREAM(stream); VALIDATE_RANGE(width, 0, INT_MAX); VALIDATE_RANGE(height, 0, INT_MAX); VALIDATE_ENUM(format); VALIDATE_RANGE(framerate, 0, INT_MAX); device->enable_stream(stream, width, height, format, framerate, RS_OUTPUT_BUFFER_FORMAT_CONTINUOUS); }
void rs_reset_device_options_to_default(rs_device * device, const rs_option* options, int count, rs_error ** error) try { VALIDATE_NOT_NULL(device); VALIDATE_RANGE(count, 0, INT_MAX); VALIDATE_NOT_NULL(options); for (int i = 0; i<count; ++i) VALIDATE_ENUM(options[i]); std::vector<double> values; for (int i = 0; i < count; ++i) { double def; rs_get_device_option_range_ex(device, options[i], NULL, NULL, NULL, &def, 0); values.push_back(def); } device->set_options(options, count, values.data()); }
const char * rs_get_capabilities_name(rs_capabilities capability, rs_error ** error) try { VALIDATE_ENUM(capability); return rsimpl::get_string(capability); }
const char * rs_get_option_name(rs_option option, rs_error ** error) try { VALIDATE_ENUM(option); return rsimpl::get_string(option); }
const char * rs_get_distortion_name(rs_distortion distortion, rs_error ** error) try { VALIDATE_ENUM(distortion); return rsimpl::get_string(distortion); }
const char * rs_get_preset_name(rs_preset preset, rs_error ** error) try { VALIDATE_ENUM(preset); return rsimpl::get_string(preset); }
const char * rs_get_format_name(rs_format format, rs_error ** error) try { VALIDATE_ENUM(format); return rsimpl::get_string(format); }
const char * rs_get_stream_name(rs_stream stream, rs_error ** error) try { VALIDATE_ENUM(stream); return rsimpl::get_string(stream); }
const char * rs_get_device_option_description(rs_device * device, rs_option option, rs_error ** error) try { VALIDATE_NOT_NULL(device); VALIDATE_ENUM(option); return device->get_option_description(option); }
int rs_get_frame_timestamp(const rs_device * device, rs_stream stream, rs_error ** error) try { VALIDATE_NOT_NULL(device); VALIDATE_ENUM(stream); return device->get_frame_timestamp(stream); }
const char * rs_get_event_name(rs_event_source event, rs_error ** error) try { VALIDATE_ENUM(event); return rsimpl::get_string(event); }
int rs_supports_camera_info(rs_device * device, rs_camera_info info_param, rs_error ** error) try { VALIDATE_NOT_NULL(device); VALIDATE_ENUM(info_param); return device->supports(info_param); }
void rs_set_device_option(rs_device * device, rs_option option, double value, rs_error ** error) try { VALIDATE_NOT_NULL(device); VALIDATE_ENUM(option); device->set_options(&option, 1, &value); }
int rs_is_stream_enabled(const rs_device * device, rs_stream stream, rs_error ** error) try { VALIDATE_NOT_NULL(device); VALIDATE_ENUM(stream); return device->get_stream_interface(stream).is_enabled(); }
unsigned long long rs_get_frame_number(const rs_device * device, rs_stream stream, rs_error ** error) try { VALIDATE_NOT_NULL(device); VALIDATE_ENUM(stream); return device->get_stream_interface(stream).get_frame_number(); }
const void * rs_get_frame_data(const rs_device * device, rs_stream stream, rs_error ** error) try { VALIDATE_NOT_NULL(device); VALIDATE_ENUM(stream); return device->get_frame_data(stream); }
int rs_get_stream_framerate(const rs_device * device, rs_stream stream, rs_error ** error) try { VALIDATE_NOT_NULL(device); VALIDATE_ENUM(stream); return device->get_stream_interface(stream).get_framerate(); }
int rs_device_supports_option(const rs_device * device, rs_option option, rs_error ** error) try { VALIDATE_NOT_NULL(device); VALIDATE_ENUM(option); return device->supports_option(option); }
int rs_get_stream_height(const rs_device * device, rs_stream stream, rs_error ** error) try { VALIDATE_NOT_NULL(device); VALIDATE_ENUM(stream); return device->get_stream_interface(stream).get_intrinsics().height; }
int rs_supports(rs_device * device, rs_capabilities capability, rs_error ** error) try { VALIDATE_NOT_NULL(device); VALIDATE_ENUM(capability); return device->supports(capability); }