1 /* License: Apache 2.0. See LICENSE file in root directory.
2    Copyright(c) 2015 Intel Corporation. All Rights Reserved. */
3 
4 #ifndef LIBREALSENSE_RS_H
5 #define LIBREALSENSE_RS_H
6 
7 #ifdef __cplusplus
8 extern "C" {
9 #endif
10 
11 #define RS_API_VERSION 4
12 
13 typedef enum rs_stream
14 {
15     RS_STREAM_DEPTH                            = 0,  /**< Native stream of depth data produced by RealSense device */
16     RS_STREAM_COLOR                            = 1,  /**< Native stream of color data captured by RealSense device */
17     RS_STREAM_INFRARED                         = 2,  /**< Native stream of infrared data captured by RealSense device */
18     RS_STREAM_INFRARED2                        = 3,  /**< Native stream of infrared data captured from a second viewpoint by RealSense device */
19     RS_STREAM_POINTS                           = 4,  /**< Synthetic stream containing point cloud data generated by deprojecting the depth image */
20     RS_STREAM_RECTIFIED_COLOR                  = 5,  /**< Synthetic stream containing undistorted color data with no extrinsic rotation from the depth stream */
21     RS_STREAM_COLOR_ALIGNED_TO_DEPTH           = 6,  /**< Synthetic stream containing color data but sharing intrinsics of depth stream */
22     RS_STREAM_INFRARED2_ALIGNED_TO_DEPTH       = 7,  /**< Synthetic stream containing second viewpoint infrared data but sharing intrinsics of depth stream */
23     RS_STREAM_DEPTH_ALIGNED_TO_COLOR           = 8,  /**< Synthetic stream containing depth data but sharing intrinsics of color stream */
24     RS_STREAM_DEPTH_ALIGNED_TO_RECTIFIED_COLOR = 9,  /**< Synthetic stream containing depth data but sharing intrinsics of rectified color stream */
25     RS_STREAM_DEPTH_ALIGNED_TO_INFRARED2       = 10, /**< Synthetic stream containing depth data but sharing intrinsics of second viewpoint infrared stream */
26     RS_STREAM_COUNT                            = 11,
27     RS_STREAM_MAX_ENUM = 0x7FFFFFFF
28 } rs_stream;
29 
30 typedef enum rs_format
31 {
32     RS_FORMAT_ANY         = 0,
33     RS_FORMAT_Z16         = 1,  /**< 16 bit linear depth values. The depth is meters is equal to depth scale * pixel value */
34     RS_FORMAT_DISPARITY16 = 2,  /**< 16 bit linear disparity values. The depth in meters is equal to depth scale / pixel value */
35     RS_FORMAT_XYZ32F      = 3,  /**< 32 bit floating point 3D coordinates. */
36     RS_FORMAT_YUYV        = 4,
37     RS_FORMAT_RGB8        = 5,
38     RS_FORMAT_BGR8        = 6,
39     RS_FORMAT_RGBA8       = 7,
40     RS_FORMAT_BGRA8       = 8,
41     RS_FORMAT_Y8          = 9,
42     RS_FORMAT_Y16         = 10,
43     RS_FORMAT_RAW10       = 11, /**< Four 10-bit luminance values encoded into a 5-byte macropixel */
44     RS_FORMAT_COUNT       = 12,
45     RS_FORMAT_MAX_ENUM = 0x7FFFFFFF
46 } rs_format;
47 
48 typedef enum rs_preset
49 {
50     RS_PRESET_BEST_QUALITY      = 0,
51     RS_PRESET_LARGEST_IMAGE     = 1,
52     RS_PRESET_HIGHEST_FRAMERATE = 2,
53     RS_PRESET_COUNT             = 3,
54     RS_PRESET_MAX_ENUM = 0x7FFFFFFF
55 } rs_preset;
56 
57 typedef enum rs_distortion
58 {
59     RS_DISTORTION_NONE                   = 0, /**< Rectilinear images, no distortion compensation required */
60     RS_DISTORTION_MODIFIED_BROWN_CONRADY = 1, /**< Equivalent to Brown-Conrady distortion, except that tangential distortion is applied to radially distorted points */
61     RS_DISTORTION_INVERSE_BROWN_CONRADY  = 2, /**< Equivalent to Brown-Conrady distortion, except undistorts image instead of distorting it */
62     RS_DISTORTION_COUNT                  = 3,
63     RS_DISTORTION_MAX_ENUM = 0x7FFFFFFF
64 } rs_distortion;
65 
66 typedef enum rs_option
67 {
68     RS_OPTION_COLOR_BACKLIGHT_COMPENSATION                    = 0,
69     RS_OPTION_COLOR_BRIGHTNESS                                = 1,
70     RS_OPTION_COLOR_CONTRAST                                  = 2,
71     RS_OPTION_COLOR_EXPOSURE                                  = 3,  /**< Controls exposure time of color camera. Setting any value will disable auto exposure. */
72     RS_OPTION_COLOR_GAIN                                      = 4,
73     RS_OPTION_COLOR_GAMMA                                     = 5,
74     RS_OPTION_COLOR_HUE                                       = 6,
75     RS_OPTION_COLOR_SATURATION                                = 7,
76     RS_OPTION_COLOR_SHARPNESS                                 = 8,
77     RS_OPTION_COLOR_WHITE_BALANCE                             = 9,  /**< Controls white balance of color image. Setting any value will disable auto white balance. */
78     RS_OPTION_COLOR_ENABLE_AUTO_EXPOSURE                      = 10, /**< Set to 1 to enable automatic exposure control, or 0 to return to manual control */
79     RS_OPTION_COLOR_ENABLE_AUTO_WHITE_BALANCE                 = 11, /**< Set to 1 to enable automatic white balance control, or 0 to return to manual control */
80     RS_OPTION_F200_LASER_POWER                                = 12, /**< 0 - 15 */
81     RS_OPTION_F200_ACCURACY                                   = 13, /**< 0 - 3 */
82     RS_OPTION_F200_MOTION_RANGE                               = 14, /**< 0 - 100 */
83     RS_OPTION_F200_FILTER_OPTION                              = 15, /**< 0 - 7 */
84     RS_OPTION_F200_CONFIDENCE_THRESHOLD                       = 16, /**< 0 - 15 */
85     RS_OPTION_SR300_DYNAMIC_FPS                               = 17, /**< {2, 5, 15, 30, 60} */
86     RS_OPTION_SR300_AUTO_RANGE_ENABLE_MOTION_VERSUS_RANGE     = 18,
87     RS_OPTION_SR300_AUTO_RANGE_ENABLE_LASER                   = 19,
88     RS_OPTION_SR300_AUTO_RANGE_MIN_MOTION_VERSUS_RANGE        = 20,
89     RS_OPTION_SR300_AUTO_RANGE_MAX_MOTION_VERSUS_RANGE        = 21,
90     RS_OPTION_SR300_AUTO_RANGE_START_MOTION_VERSUS_RANGE      = 22,
91     RS_OPTION_SR300_AUTO_RANGE_MIN_LASER                      = 23,
92     RS_OPTION_SR300_AUTO_RANGE_MAX_LASER                      = 24,
93     RS_OPTION_SR300_AUTO_RANGE_START_LASER                    = 25,
94     RS_OPTION_SR300_AUTO_RANGE_UPPER_THRESHOLD                = 26,
95     RS_OPTION_SR300_AUTO_RANGE_LOWER_THRESHOLD                = 27,
96     RS_OPTION_SR300_WAKEUP_DEV_PHASE1_PERIOD                  = 28,
97     RS_OPTION_SR300_WAKEUP_DEV_PHASE1_FPS                     = 29,
98     RS_OPTION_SR300_WAKEUP_DEV_PHASE2_PERIOD                  = 30,
99     RS_OPTION_SR300_WAKEUP_DEV_PHASE2_FPS                     = 31,
100     RS_OPTION_SR300_WAKEUP_DEV_RESET                          = 32,
101     RS_OPTION_SR300_WAKE_ON_USB_REASON                        = 33,
102     RS_OPTION_SR300_WAKE_ON_USB_CONFIDENCE                    = 34,
103     RS_OPTION_R200_LR_AUTO_EXPOSURE_ENABLED                   = 35, /**< {0, 1} */
104     RS_OPTION_R200_LR_GAIN                                    = 36, /**< 100 - 1600 (Units of 0.01) */
105     RS_OPTION_R200_LR_EXPOSURE                                = 37, /**< > 0 (Units of 0.1 ms) */
106     RS_OPTION_R200_EMITTER_ENABLED                            = 38, /**< {0, 1} */
107     RS_OPTION_R200_DEPTH_UNITS                                = 39, /**< micrometers per increment in integer depth values, 1000 is default (mm scale) */
108     RS_OPTION_R200_DEPTH_CLAMP_MIN                            = 40, /**< {0 - USHORT_MAX}. Can only be set before streaming starts. */
109     RS_OPTION_R200_DEPTH_CLAMP_MAX                            = 41, /**< {0 - USHORT_MAX}. Can only be set before streaming starts. */
110     RS_OPTION_R200_DISPARITY_MULTIPLIER                       = 42, /**< {0 - 1000}. The increments in integer disparity values corresponding to one pixel of disparity. Can only be set before streaming starts. */
111     RS_OPTION_R200_DISPARITY_SHIFT                            = 43, /**< {0 - 512}. Can only be set before streaming starts. */
112     RS_OPTION_R200_AUTO_EXPOSURE_MEAN_INTENSITY_SET_POINT     = 44,
113     RS_OPTION_R200_AUTO_EXPOSURE_BRIGHT_RATIO_SET_POINT       = 45,
114     RS_OPTION_R200_AUTO_EXPOSURE_KP_GAIN                      = 46,
115     RS_OPTION_R200_AUTO_EXPOSURE_KP_EXPOSURE                  = 47,
116     RS_OPTION_R200_AUTO_EXPOSURE_KP_DARK_THRESHOLD            = 48,
117     RS_OPTION_R200_AUTO_EXPOSURE_TOP_EDGE                     = 49,
118     RS_OPTION_R200_AUTO_EXPOSURE_BOTTOM_EDGE                  = 50,
119     RS_OPTION_R200_AUTO_EXPOSURE_LEFT_EDGE                    = 51,
120     RS_OPTION_R200_AUTO_EXPOSURE_RIGHT_EDGE                   = 52,
121     RS_OPTION_R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_DECREMENT    = 53,
122     RS_OPTION_R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_INCREMENT    = 54,
123     RS_OPTION_R200_DEPTH_CONTROL_MEDIAN_THRESHOLD             = 55,
124     RS_OPTION_R200_DEPTH_CONTROL_SCORE_MINIMUM_THRESHOLD      = 56,
125     RS_OPTION_R200_DEPTH_CONTROL_SCORE_MAXIMUM_THRESHOLD      = 57,
126     RS_OPTION_R200_DEPTH_CONTROL_TEXTURE_COUNT_THRESHOLD      = 58,
127     RS_OPTION_R200_DEPTH_CONTROL_TEXTURE_DIFFERENCE_THRESHOLD = 59,
128     RS_OPTION_R200_DEPTH_CONTROL_SECOND_PEAK_THRESHOLD        = 60,
129     RS_OPTION_R200_DEPTH_CONTROL_NEIGHBOR_THRESHOLD           = 61,
130     RS_OPTION_R200_DEPTH_CONTROL_LR_THRESHOLD                 = 62,
131     RS_OPTION_COUNT                                           = 63,
132     RS_OPTION_MAX_ENUM = 0x7FFFFFFF
133 } rs_option;
134 
135 typedef struct rs_intrinsics
136 {
137     int           width;     /* width of the image in pixels */
138     int           height;    /* height of the image in pixels */
139     float         ppx;       /* horizontal coordinate of the principal point of the image, as a pixel offset from the left edge */
140     float         ppy;       /* vertical coordinate of the principal point of the image, as a pixel offset from the top edge */
141     float         fx;        /* focal length of the image plane, as a multiple of pixel width */
142     float         fy;        /* focal length of the image plane, as a multiple of pixel height */
143     rs_distortion model;     /* distortion model of the image */
144     float         coeffs[5]; /* distortion coefficients */
145 } rs_intrinsics;
146 
147 typedef struct rs_extrinsics
148 {
149     float rotation[9];    /* column-major 3x3 rotation matrix */
150     float translation[3]; /* 3 element translation vector, in meters */
151 } rs_extrinsics;
152 
153 typedef struct rs_context rs_context;
154 typedef struct rs_device rs_device;
155 typedef struct rs_error rs_error;
156 
157 rs_context * rs_create_context(int api_version, rs_error ** error);
158 void rs_delete_context(rs_context * context, rs_error ** error);
159 
160 /**
161  * determine number of connected devices
162  * \param[out] error  if non-null, receives any error that occurs during this call, otherwise, errors are ignored
163  * \return            the count of devices
164  */
165 int rs_get_device_count(const rs_context * context, rs_error ** error);
166 
167 /**
168  * retrieve connected device by index
169  * \param[in] index   the zero based index of device to retrieve
170  * \param[out] error  if non-null, receives any error that occurs during this call, otherwise, errors are ignored
171  * \return            the requested device
172  */
173 rs_device * rs_get_device(rs_context * context, int index, rs_error ** error);
174 
175 /**
176  * retrieve a human readable device model string
177  * \param[out] error  if non-null, receives any error that occurs during this call, otherwise, errors are ignored
178  * \return            the model string, such as "Intel RealSense F200" or "Intel RealSense R200"
179  */
180 const char * rs_get_device_name(const rs_device * device, rs_error ** error);
181 
182 /**
183  * retrieve the unique serial number of the device
184  * \param[out] error  if non-null, receives any error that occurs during this call, otherwise, errors are ignored
185  * \return            the serial number, in a format specific to the device model
186  */
187 const char * rs_get_device_serial(const rs_device * device, rs_error ** error);
188 
189 /**
190  * retrieve the version of the firmware currently installed on the device
191  * \param[out] error  if non-null, receives any error that occurs during this call, otherwise, errors are ignored
192  * \return            firmware version string, in a format is specific to device model
193  */
194 const char * rs_get_device_firmware_version(const rs_device * device, rs_error ** error);
195 
196 /**
197  * retrieve extrinsic transformation between the viewpoints of two different streams
198  * \param[in] from_stream  stream whose coordinate space we will transform from
199  * \param[in] to_stream    stream whose coordinate space we will transform to
200  * \param[out] extrin      the transformation between the two streams
201  * \param[out] error       if non-null, receives any error that occurs during this call, otherwise, errors are ignored
202  */
203 void rs_get_device_extrinsics(const rs_device * device, rs_stream from_stream, rs_stream to_stream, rs_extrinsics * extrin, rs_error ** error);
204 
205 /**
206  * retrieve mapping between the units of the depth image and meters
207  * \param[out] error  if non-null, receives any error that occurs during this call, otherwise, errors are ignored
208  * \return            depth in meters corresponding to a depth value of 1
209  */
210 float rs_get_device_depth_scale(const rs_device * device, rs_error ** error);
211 
212 /**
213  * determine if the device allows a specific option to be queried and set
214  * \param[in] option  the option to check for support
215  * \param[out] error  if non-null, receives any error that occurs during this call, otherwise, errors are ignored
216  * \return            true if the option can be queried and set
217  */
218 int rs_device_supports_option(const rs_device * device, rs_option option, rs_error ** error);
219 
220 /**
221  * determine the number of streaming modes available for a given stream
222  * \param[in] stream  the stream whose modes will be enumerated
223  * \param[out] error  if non-null, receives any error that occurs during this call, otherwise, errors are ignored
224  * \return            the count of available modes
225  */
226 int rs_get_stream_mode_count(const rs_device * device, rs_stream stream, rs_error ** error);
227 
228 /**
229  * determine the properties of a specific streaming mode
230  * \param[in] stream      the stream whose mode will be queried
231  * \param[in] index       the zero based index of the streaming mode
232  * \param[out] width      the width of a frame image in pixels
233  * \param[out] height     the height of a frame image in pixels
234  * \param[out] format     the pixel format of a frame image
235  * \param[out] framerate  the number of frames which will be streamed per second
236  * \param[out] error      if non-null, receives any error that occurs during this call, otherwise, errors are ignored
237  */
238 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);
239 
240 /**
241  * enable a specific stream and request specific properties
242  * \param[in] stream     the stream to enable
243  * \param[in] width      the desired width of a frame image in pixels, or 0 if any width is acceptable
244  * \param[in] height     the desired height of a frame image in pixels, or 0 if any height is acceptable
245  * \param[in] format     the pixel format of a frame image, or ANY if any format is acceptable
246  * \param[in] framerate  the number of frames which will be streamed per second, or 0 if any framerate is acceptable
247  * \param[out] error     if non-null, receives any error that occurs during this call, otherwise, errors are ignored
248  */
249 void rs_enable_stream(rs_device * device, rs_stream stream, int width, int height, rs_format format, int framerate, rs_error ** error);
250 
251 /**
252  * enable a specific stream and request properties using a preset
253  * \param[in] stream  the stream to enable
254  * \param[in] preset  the preset to use to enable the stream
255  * \param[out] error  if non-null, receives any error that occurs during this call, otherwise, errors are ignored
256  */
257 void rs_enable_stream_preset(rs_device * device, rs_stream stream, rs_preset preset, rs_error ** error);
258 
259 /**
260  * disable a specific stream
261  * \param[in] stream  the stream to disable
262  * \param[out] error  if non-null, receives any error that occurs during this call, otherwise, errors are ignored
263  */
264 void rs_disable_stream(rs_device * device, rs_stream stream, rs_error ** error);
265 
266 /**
267  * determine if a specific stream is enabled
268  * \param[in] stream  the stream to check
269  * \param[out] error  if non-null, receives any error that occurs during this call, otherwise, errors are ignored
270  * \return            true if the stream is currently enabled
271  */
272 int rs_is_stream_enabled(const rs_device * device, rs_stream stream, rs_error ** error);
273 
274 /**
275  * retrieve the width in pixels of a specific stream, equivalent to the width field from the stream's intrinsics
276  * \param[in] stream  the stream whose width to retrieve
277  * \param[out] error  if non-null, receives any error that occurs during this call, otherwise, errors are ignored
278  * \return            the width in pixels of images from this stream
279  */
280 int rs_get_stream_width(const rs_device * device, rs_stream stream, rs_error ** error);
281 
282 /**
283  * retrieve the height in pixels of a specific stream, equivalent to the height field from the stream's intrinsics
284  * \param[in] stream  the stream whose height to retrieve
285  * \param[out] error  if non-null, receives any error that occurs during this call, otherwise, errors are ignored
286  * \return            the height in pixels of images from this stream
287  */
288 int rs_get_stream_height(const rs_device * device, rs_stream stream, rs_error ** error);
289 
290 /**
291  * retrieve the pixel format for a specific stream
292  * \param[in] stream  the stream whose format to retrieve
293  * \param[out] error  if non-null, receives any error that occurs during this call, otherwise, errors are ignored
294  * \return            the pixel format of the stream
295  */
296 rs_format rs_get_stream_format(const rs_device * device, rs_stream stream, rs_error ** error);
297 
298 /**
299  * retrieve the framerate for a specific stream
300  * \param[in] stream  the stream whose framerate to retrieve
301  * \param[out] error  if non-null, receives any error that occurs during this call, otherwise, errors are ignored
302  * \return            the framerate of the stream, in frames per second
303  */
304 int rs_get_stream_framerate(const rs_device * device, rs_stream stream, rs_error ** error);
305 
306 /**
307  * retrieve intrinsic camera parameters for a specific stream
308  * \param[in] stream   the stream whose parameters to retrieve
309  * \param[out] intrin  the intrinsic parameters of the stream
310  * \param[out] error   if non-null, receives any error that occurs during this call, otherwise, errors are ignored
311  */
312 void rs_get_stream_intrinsics(const rs_device * device, rs_stream stream, rs_intrinsics * intrin, rs_error ** error);
313 
314 /**
315  * begin streaming on all enabled streams for this device
316  * \param[out] error  if non-null, receives any error that occurs during this call, otherwise, errors are ignored
317  */
318 void rs_start_device(rs_device * device, rs_error ** error);
319 
320 /**
321  * end streaming on all streams for this device
322  * \param[out] error  if non-null, receives any error that occurs during this call, otherwise, errors are ignored
323  */
324 void rs_stop_device(rs_device * device, rs_error ** error);
325 
326 /**
327  * determine if the device is currently streaming
328  * \param[out] error  if non-null, receives any error that occurs during this call, otherwise, errors are ignored
329  * \return            true if the device is currently streaming
330  */
331 int rs_is_device_streaming(const rs_device * device, rs_error ** error);
332 
333 /**
334  * retrieve the available range of values of a supported option
335  * \param[in] option  the option whose range should be queried
336  * \param[out] min    the minimum value which will be accepted for this option
337  * \param[out] max    the maximum value which will be accepted for this option
338  * \param[out] step   the granularity of options which accept discrete values, or zero if the option accepts continuous values
339  * \param[out] error  if non-null, receives any error that occurs during this call, otherwise, errors are ignored
340  */
341 void rs_get_device_option_range(rs_device * device, rs_option option, double * min, double * max, double * step, rs_error ** error);
342 
343 /**
344  * efficiently retrieve the value of an arbitrary number of options, using minimal hardware IO
345  * \param[in] options  the array of options which should be queried
346  * \param[in] count    the length of the options and values arrays
347  * \param[out] values  the array which will receive the values of the queried options
348  * \param[out] error   if non-null, receives any error that occurs during this call, otherwise, errors are ignored
349  */
350 void rs_get_device_options(rs_device * device, const rs_option * options, int count, double * values, rs_error ** error);
351 
352 /**
353  * efficiently set the value of an arbitrary number of options, using minimal hardware IO
354  * \param[in] options  the array of options which should be set
355  * \param[in] count    the length of the options and values arrays
356  * \param[in] values   the array of values to which the options should be set
357  * \param[out] error   if non-null, receives any error that occurs during this call, otherwise, errors are ignored
358  */
359 void rs_set_device_options(rs_device * device, const rs_option * options, int count, const double * values, rs_error ** error);
360 
361 /**
362  * retrieve the current value of a single option
363  * \param[in] option  the option whose value should be retrieved
364  * \param[out] error  if non-null, receives any error that occurs during this call, otherwise, errors are ignored
365  * \return            the value of the option
366  */
367 double rs_get_device_option(rs_device * device, rs_option option, rs_error ** error);
368 
369 /**
370  * set the current value of a single option
371  * \param[in] option  the option whose value should be set
372  * \param[in] value   the value of the option
373  * \param[out] error  if non-null, receives any error that occurs during this call, otherwise, errors are ignored
374  */
375 void rs_set_device_option(rs_device * device, rs_option option, double value, rs_error ** error);
376 
377 /**
378  * block until new frames are available
379  * \param[out] error  if non-null, receives any error that occurs during this call, otherwise, errors are ignored
380  */
381 void rs_wait_for_frames(rs_device * device, rs_error ** error);
382 
383 /**
384  * check if new frames are available, without blocking
385  * \param[out] error  if non-null, receives any error that occurs during this call, otherwise, errors are ignored
386  * \return            1 if new frames are available, 0 if no new frames have arrived
387  */
388 int rs_poll_for_frames(rs_device * device, rs_error ** error);
389 
390 /**
391  * retrieve the time at which the latest frame on a stream was captured
392  * \param[in] stream  the stream whose latest frame we are interested in
393  * \param[out] error  if non-null, receives any error that occurs during this call, otherwise, errors are ignored
394  * \return            the timestamp of the frame, in milliseconds since the device was started
395  */
396 int rs_get_frame_timestamp(const rs_device * device, rs_stream stream, rs_error ** error);
397 
398 /**
399  * retrieve the contents of the latest frame on a stream
400  * \param[in] stream  the stream whose latest frame we are interested in
401  * \param[out] error  if non-null, receives any error that occurs during this call, otherwise, errors are ignored
402  * \return            the pointer to the start of the frame data
403  */
404 const void * rs_get_frame_data(const rs_device * device, rs_stream stream, rs_error ** error);
405 
406 const char * rs_get_failed_function  (const rs_error * error);
407 const char * rs_get_failed_args      (const rs_error * error);
408 const char * rs_get_error_message    (const rs_error * error);
409 void         rs_free_error           (rs_error * error);
410 
411 const char * rs_stream_to_string     (rs_stream stream);
412 const char * rs_format_to_string     (rs_format format);
413 const char * rs_preset_to_string     (rs_preset preset);
414 const char * rs_distortion_to_string (rs_distortion distortion);
415 const char * rs_option_to_string     (rs_option option);
416 
417 typedef enum
418 {
419     RS_LOG_SEVERITY_DEBUG = 0, /* Detailed information about ordinary operations */
420     RS_LOG_SEVERITY_INFO  = 1, /* Terse information about ordinary operations */
421     RS_LOG_SEVERITY_WARN  = 2, /* Indication of possible failure */
422     RS_LOG_SEVERITY_ERROR = 3, /* Indication of definite failure */
423     RS_LOG_SEVERITY_FATAL = 4, /* Indication of unrecoverable failure */
424     RS_LOG_SEVERITY_NONE  = 5, /* No logging will occur */
425     RS_LOG_SEVERITY_MAX_ENUM = 0x7FFFFFFF
426 } rs_log_severity;
427 void rs_log_to_console(rs_log_severity min_severity, rs_error ** error);
428 void rs_log_to_file(rs_log_severity min_severity, const char * file_path, rs_error ** error);
429 
430 #ifdef __cplusplus
431 }
432 #endif
433 #endif
434