api.h
Go to the documentation of this file.
1 // License: Apache 2.0. See LICENSE file in root directory.
2 // Copyright(c) 2017 Intel Corporation. All Rights Reserved.
3 #pragma once
4 
5 #include "core/extension.h"
6 #include "device.h"
7 #include <rsutils/string/from.h>
8 #include <rsutils/subscription.h>
9 #include "pose.h"
10 #include "librealsense-exception.h"
11 
12 #include <librealsense2/rs.h>
13 #include <type_traits>
14 #include <iostream>
15 
16 namespace librealsense {
17 struct notification;
18 }
19 
20 
22 {
23  std::vector<uint8_t> buffer;
24 };
25 
26 typedef struct rs2_error rs2_error;
27 
29 {
31  :_notification(notification) {}
32 
34 };
35 
36 struct rs2_device
37 {
38  std::shared_ptr<librealsense::device_interface> device;
40 };
41 
42 rs2_error * rs2_create_error(const char* what, const char* name, const char* args, rs2_exception_type type);
43 
44 namespace librealsense
45 {
46  // Facilities for streaming function arguments
47 
48  // First, we define a generic parameter streaming
49  // Assumes T is streamable, reasonable for C API parameters
50  template<class T, bool S>
51  struct arg_streamer
52  {
53  void stream_arg(std::ostream & out, const T& val, bool last)
54  {
55  out << ':' << val << (last ? "" : ", ");
56  }
57  };
58 
59  // Next we define type trait for testing if *t for some T* is streamable
60  template<typename T>
62  {
63  template <typename S>
64  static auto test(const S* t) -> decltype(std::cout << **t);
65  static auto test(...)->std::false_type;
66  public:
67  enum { value = !std::is_same<decltype(test((T*)0)), std::false_type>::value };
68  };
69 
70  // Using above trait, we can now specialize our streamer
71  // for streamable pointers:
72  template<class T>
73  struct arg_streamer<T*, true>
74  {
75  void stream_arg(std::ostream & out, T* val, bool last)
76  {
77  out << ':'; // If pointer not null, stream its content
78  if (val) out << *val;
79  else out << "nullptr";
80  out << (last ? "" : ", ");
81  }
82  };
83 
84  // .. and for not streamable pointers
85  template<class T>
86  struct arg_streamer<T*, false>
87  {
88  void stream_arg(std::ostream & out, T* val, bool last)
89  {
90  out << ':'; // If pointer is not null, stream the pointer
91  if (val) out << (int*)val; // Go through (int*) to avoid dumping the content of char*
92  else out << "nullptr";
93  out << (last ? "" : ", ");
94  }
95  };
96 
97  // This facility allows for translation of exceptions to rs2_error structs at the API boundary
98  template<class T> void stream_args(std::ostream & out, const char * names, const T & last)
99  {
100  out << names;
102  s.stream_arg(out, last, true);
103  }
104  template<class T, class... U> void stream_args(std::ostream & out, const char * names, const T & first, const U &... rest)
105  {
106  while (*names && *names != ',') out << *names++;
108  s.stream_arg(out, first, false);
109  while (*names && (*names == ',' || isspace(*names))) ++names;
110  stream_args(out, names, rest...);
111  }
112 
113 
114 
115  static void translate_exception(const char * name, std::string const & args, rs2_error ** error)
116  {
117  try { throw; }
118  catch (const librealsense_exception& e) { if (error) *error = rs2_create_error(e.what(), name, args.c_str(), e.get_exception_type() ); }
119  catch (const std::exception& e) { if (error) *error = rs2_create_error(e.what(), name, args.c_str(), RS2_EXCEPTION_TYPE_COUNT); }
120  catch (...) { if (error) *error = rs2_create_error("unknown error", name, args.c_str(), RS2_EXCEPTION_TYPE_COUNT); }
121  }
122 
123 #ifdef TRACE_API
124  // API objects repository holds all live objects
125  // created from API calls and not released yet.
126  // This is useful for two tasks:
127  // 1. More easily follow API calls in logs
128  // 2. See a snapshot of all not deallocated objects
129  class api_objects
130  {
131  public:
132  // Define singleton
133  static api_objects& instance() {
134  static api_objects instance;
135  return instance;
136  }
137 
138  // Place new object into the registry and give it a name
139  // according to the class type and the index of the instance
140  // to be presented in the log instead of the object memory address
141  std::string register_new_object(const std::string& type, const std::string& address)
142  {
143  std::lock_guard<std::mutex> lock(_m);
144  return internal_register(type, address);
145  }
146 
147  // Given a list of parameters in form of "param:val,param:val"
148  // This function will replace all val that have alternative names in this repository
149  // with their names
150  // the function is used by the log with param = function input param name from the prototype,
151  // and val = the address of the param.
152  // the function will change the val field from memory address to instance class and index name
153  std::string augment_params(std::string p)
154  {
155  std::lock_guard<std::mutex> lock(_m);
156  std::string acc = "";
157  std::string res = "";
158  std::string param = "";
159  p += ",";
160  bool is_value = false;
161  for (auto i = 0; i < p.size(); i++)
162  {
163  if (p[i] == ':')
164  {
165  param = acc;
166  acc = "";
167  is_value = true;
168  }
169  else if (is_value)
170  {
171  if (p[i] == ',')
172  {
173  auto it = _names.find(acc);
174  if (it != _names.end()) acc = it->second;
175  else
176  {
177  // Heuristic: Assume things that are the same length
178  // as pointers are in-fact pointers
179  std::stringstream ss; ss << (int*)0;
180  if (acc.size() == ss.str().size())
181  {
182  acc = internal_register(param, acc);
183  }
184  }
185  res += param + ":" + acc;
186  if (i != p.size() - 1) res += ",";
187  acc = "";
188  is_value = false;
189  }
190  else acc += p[i];
191  }
192  else acc += p[i];
193  }
194  return res;
195  }
196 
197  // Mark that a certain object is de-allocated
198  void remove_object(const std::string& name)
199  {
200  std::lock_guard<std::mutex> lock(_m);
201  auto it = _names.find(name);
202  if (it != _names.end())
203  _names.erase(it);
204  }
205  private:
206  std::string internal_register(const std::string& type, const std::string& address)
207  {
208  auto it = _counters.find(type);
209  if (it == _counters.end()) _counters[type] = 0;
210  _counters[type]++;
211  std::stringstream ss;
212  ss << type << _counters[type];
213  _names[address] = ss.str();
214  return _names[address];
215  }
216 
217  std::mutex _m;
218  std::map<std::string, std::string> _names;
219  std::map<std::string, int> _counters;
220  };
221 
222  // This class wraps every API call and reports on it once its done
223  class api_logger
224  {
225  public:
226  api_logger(std::string function)
227  : _function(std::move(function)), _result(""), _param_str(""), _type(""),
228  _params([]() { return std::string{}; })
229  {
231  LOG_DEBUG("/* Begin " << _function << " */");
232 
233  // Define the returning "type" as the last word in function name
234  std::size_t found = _function.find_last_of("_");
235  _type = _function.substr(found + 1);
236 
237  check_if_deleter("rs2_delete");
238  check_if_deleter("rs2_release");
239  }
240 
241  // if the calling function is going to release an API object - remove it from the tracing list
242  void check_if_deleter(const char* prefix)
243  {
244  auto deleter_pos = _function.find(prefix);
245  if (deleter_pos == 0)
246  {
247  _is_deleter = true;
248  }
249  }
250 
251  void set_return_value(std::string result)
252  {
253  _result = std::move(result);
254  }
255 
256  void set_params(std::function<std::string()> params)
257  {
258  _params = std::move(params);
259  }
260 
261  std::string get_params() { return _param_str = _params(); }
262 
263  void report_error() { _error = true; }
264  void report_pointer_return_type() { _returns_pointer = true; }
265 
266  ~api_logger()
267  {
268  auto d = std::chrono::high_resolution_clock::now() - _start;
269  auto ms = std::chrono::duration_cast<std::chrono::milliseconds>(d).count();
270  std::stringstream ss;
271  std::string prefix = "";
272  if (_param_str == "") _param_str = _params();
273 
274  auto&& objs = api_objects::instance();
275  if (_returns_pointer)
276  {
277  prefix = objs.register_new_object(_type, _result) + " = ";
278  _result = "";
279  }
280  if (_is_deleter) objs.remove_object(_result);
281  if (_param_str != "") _param_str = objs.augment_params(_param_str);
282 
283  ss << prefix << _function << "(" << _param_str << ")";
284  if (_result != "") ss << " returned " << _result;
285  ss << ";";
286  if (ms > 0) ss << " /* Took " << ms << "ms */";
287  if (_error) LOG_ERROR(ss.str());
288  else LOG_INFO(ss.str());
289  }
290  private:
291  std::string _function, _result, _type, _param_str;
292  std::function<std::string()> _params;
293  bool _returns_pointer = false;
294  bool _is_deleter = false;
295  bool _error = false;
296  std::chrono::high_resolution_clock::time_point _start;
297  };
298 
299  // This dummy helper function lets us fetch return type from lambda
300  // this is used for result_printer, to be able to be used
301  // similarly for functions with and without return parameter
302  template<typename F, typename R>
303  R fetch_return_type(F& f, R(F::*mf)() const);
304 
305  // Result printer class will capture lambda result value
306  // and pass it as string to the api logger
307  template<class T>
308  class result_printer
309  {
310  public:
311  result_printer(api_logger* logger) : _logger(logger) {}
312 
313  template<class F>
314  T invoke(F func)
315  {
316  _res = func(); // Invoke lambda and save result for later
317  // I assume this will not have any side-effects, since it is applied
318  // to types that are about to be passed from C API
319  return _res;
320  }
321 
322  ~result_printer()
323  {
324  std::stringstream ss; ss << _res;
325  _logger->set_return_value(ss.str());
326  }
327  private:
328  T _res;
329  api_logger* _logger;
330  };
331 
332  // Result printer class for T* should not dump memory content
333  template<class T>
334  class result_printer<T*>
335  {
336  public:
337  result_printer(api_logger* logger) : _logger(logger) {}
338 
339  template<class F>
340  T* invoke(F func)
341  {
342  _res = func(); // Invoke lambda and save result for later
343  // I assume this will not have any side-effects, since it is applied
344  // to types that are about to be passed from C API
345  return _res;
346  }
347 
348  ~result_printer()
349  {
350  std::stringstream ss; ss << (int*)_res; // Force case to int* to avoid char* and such
351  // being dumped to log
352  _logger->report_pointer_return_type();
353  _logger->set_return_value(ss.str());
354  }
355  private:
356  T* _res;
357  api_logger* _logger;
358  };
359 
360  // To work-around the fact that void can't be "stringified"
361  // we define an alternative printer just for void returning lambdas
362  template<>
363  class result_printer<void>
364  {
365  public:
366  result_printer(api_logger* logger) {}
367  template<class F>
368  void invoke(F func) { func(); }
369  };
370 
371 // Begin API macro defines new API logger and redirects function body into a lambda
372 // The extra brace ensures api_logger will die after everything else
373 #define BEGIN_API_CALL { api_logger __api_logger(__FUNCTION__); {\
374 auto func = [&](){
375 
376 // The various return macros finish the lambda and invoke it using the type printer
377 // practically capturing function return value
378 // In addition, error flag and function parameters are captured into the API logger
379 #define NOEXCEPT_RETURN(R, ...) };\
380 result_printer<decltype(fetch_return_type(func, &decltype(func)::operator()))> __p(&__api_logger);\
381 __api_logger.set_params([&](){ std::ostringstream ss; librealsense::stream_args(ss, #__VA_ARGS__, __VA_ARGS__); return ss.str(); });\
382 try {\
383 return __p.invoke(func);\
384 } catch(...) {\
385 rs2_error* e; librealsense::translate_exception(__FUNCTION__, __api_logger.get_params(), &e);\
386 LOG_WARNING(rs2_get_error_message(e)); rs2_free_error(e); __api_logger.report_error(); return R; } } }
387 
388 #define HANDLE_EXCEPTIONS_AND_RETURN(R, ...) };\
389 result_printer<decltype(fetch_return_type(func, &decltype(func)::operator()))> __p(&__api_logger);\
390 __api_logger.set_params([&](){ std::ostringstream ss; librealsense::stream_args(ss, #__VA_ARGS__, __VA_ARGS__); return ss.str(); });\
391 try {\
392 return __p.invoke(func);\
393 } catch(...) {\
394 librealsense::translate_exception(__FUNCTION__, __api_logger.get_params(), error); __api_logger.report_error(); return R; } } }
395 
396 #define NOARGS_HANDLE_EXCEPTIONS_AND_RETURN(R, ...) };\
397 result_printer<decltype(fetch_return_type(func, &decltype(func)::operator()))> __p(&__api_logger);\
398 try {\
399 return __p.invoke(func);\
400 } catch(...) { librealsense::translate_exception(__FUNCTION__, "", error); __api_logger.report_error(); return R; } } }
401 
402 #else // No API tracing:
403 
404 #define BEGIN_API_CALL try
405 #define NOEXCEPT_RETURN(R, ...) catch(...) { std::ostringstream ss; librealsense::stream_args(ss, #__VA_ARGS__, __VA_ARGS__); rs2_error* e; librealsense::translate_exception(__FUNCTION__, ss.str(), &e); LOG_WARNING(rs2_get_error_message(e)); rs2_free_error(e); return R; }
406 #define HANDLE_EXCEPTIONS_AND_RETURN(R, ...) catch(...) { std::ostringstream ss; librealsense::stream_args(ss, #__VA_ARGS__, __VA_ARGS__); librealsense::translate_exception(__FUNCTION__, ss.str(), error); return R; }
407 #define NOARGS_HANDLE_EXCEPTIONS_AND_RETURN(R) catch(...) { librealsense::translate_exception(__FUNCTION__, "", error); return R; }
408 #define NOARGS_HANDLE_EXCEPTIONS_AND_RETURN_VOID() catch(...) { librealsense::translate_exception(__FUNCTION__, "", error); }
409 
410 #endif
411 
412  #define VALIDATE_FIXED_SIZE(ARG, SIZE) if((ARG) != (SIZE)) { std::ostringstream ss; ss << "Unsupported size provided { " << ARG << " }," " expecting { " << SIZE << " }"; throw librealsense::invalid_value_exception(ss.str()); }
413  #define VALIDATE_NOT_NULL(ARG) if(!(ARG)) throw std::runtime_error("null pointer passed for argument \"" #ARG "\"");
414  #define VALIDATE_ENUM(ARG) if(!librealsense::is_valid(ARG)) { std::ostringstream ss; ss << "invalid enum value for argument \"" #ARG "\""; throw librealsense::invalid_value_exception(ss.str()); }
415 #define VALIDATE_OPTION_ENABLED( OBJ, OPT_ID ) \
416  if( ! OBJ->options->supports_option( OPT_ID ) ) \
417  { \
418  std::ostringstream ss; \
419  ss << "object doesn't support option " << librealsense::get_string( OPT_ID ); \
420  throw librealsense::invalid_value_exception( ss.str() ); \
421  }
422  #define VALIDATE_RANGE(ARG, MIN, MAX) if((ARG) < (MIN) || (ARG) > (MAX)) { std::ostringstream ss; ss << "out of range value for argument \"" #ARG "\""; throw librealsense::invalid_value_exception(ss.str()); }
423  #define VALIDATE_LE(ARG, MAX) if((ARG) > (MAX)) { std::ostringstream ss; ss << "out of range value for argument \"" #ARG "\""; throw std::runtime_error(ss.str()); }
424  #define VALIDATE_GT(ARG, MIN) if((ARG) <= (MIN)) { std::ostringstream ss; ss << "value is below allowed min for argument \"" #ARG "\""; throw std::runtime_error(ss.str()); }
425  #define VALIDATE_LT(ARG, MAX) if((ARG) >= (MAX)) { std::ostringstream ss; ss << "value is bigger than allowed max for argument \"" #ARG "\""; throw std::runtime_error(ss.str()); }
426  #define VALIDATE_INTERFACE_NO_THROW(X, T) \
427  ([&]() -> T* { \
428  T* p = dynamic_cast<T*>(&(*X)); \
429  if (p == nullptr) \
430  { \
431  auto ext = dynamic_cast<librealsense::extendable_interface*>(&(*X)); \
432  if (ext == nullptr) return nullptr; \
433  else \
434  { \
435  if(!ext->extend_to(TypeToExtension<T>::value, (void**)&p)) \
436  return nullptr; \
437  return p; \
438  } \
439  } \
440  return p; \
441  })()
442 
443  #define VALIDATE_INTERFACE(X,T) \
444  ([&]() -> T* { \
445  T* p = VALIDATE_INTERFACE_NO_THROW(X,T); \
446  if(p == nullptr) \
447  throw std::runtime_error("Object does not support \"" #T "\" interface! " ); \
448  return p; \
449  })()
450 }
451 
452 inline int lrs_major(int version)
453 {
454  return version / 10000;
455 }
456 inline int lrs_minor(int version)
457 {
458  return (version % 10000) / 100;
459 }
460 inline int lrs_patch(int version)
461 {
462  return (version % 100);
463 }
464 
466 {
467  if( lrs_major( version ) == 0 )
468  return rsutils::string::from( version );
469  return rsutils::string::from() << lrs_major( version ) << "." << lrs_minor( version ) << "."
470  << lrs_patch( version );
471 }
472 
473 inline void report_version_mismatch(int runtime, int compiletime)
474 {
476  rsutils::string::from() << "API version mismatch: librealsense.so was compiled with API version "
477  << api_version_to_string( runtime ) << " but the application was compiled with "
478  << api_version_to_string( compiletime )
479  << "! Make sure correct version of the library is installed (make install)" );
480 }
481 
482 inline void verify_version_compatibility(int api_version)
483 {
484  rs2_error* error = nullptr;
485  auto runtime_api_version = rs2_get_api_version(&error);
486  if (error)
488 
489  if ((runtime_api_version < 10) || (api_version < 10))
490  {
491  // when dealing with version < 1.0.0 that were still using single number for API version, require exact match
492  if (api_version != runtime_api_version)
493  report_version_mismatch(runtime_api_version, api_version);
494  }
495  else if ((lrs_major(runtime_api_version) == 1 && lrs_minor(runtime_api_version) <= 9)
496  || (lrs_major(api_version) == 1 && lrs_minor(api_version) <= 9))
497  {
498  // when dealing with version < 1.10.0, API breaking changes are still possible without minor version change, require exact match
499  if (api_version != runtime_api_version)
500  report_version_mismatch(runtime_api_version, api_version);
501  }
502  else
503  {
504  // starting with 1.10.0, versions with same patch are compatible
505  // Incompatible versions differ on major, or with the executable's minor bigger than the library's one.
506  if ((lrs_major(api_version) != lrs_major(runtime_api_version))
507  || (lrs_minor(api_version) > lrs_minor(runtime_api_version)))
508  report_version_mismatch(runtime_api_version, api_version);
509  }
510 }
api_version_to_string
std::string api_version_to_string(int version)
Definition: api.h:465
librealsense
Definition: algo.h:18
librealsense::translate_exception
static void translate_exception(const char *name, std::string const &args, rs2_error **error)
Definition: api.h:115
lrs_patch
int lrs_patch(int version)
Definition: api.h:460
librealsense::invalid_value_exception
Definition: librealsense-exception.h:114
RS2_EXCEPTION_TYPE_COUNT
@ RS2_EXCEPTION_TYPE_COUNT
Definition: rs_types.h:40
rs2_get_error_message
const char * rs2_get_error_message(const rs2_error *error)
Definition: rs.cpp:1669
librealsense::arg_streamer::stream_arg
void stream_arg(std::ostream &out, const T &val, bool last)
Definition: api.h:53
params
GLenum const GLfloat * params
Definition: glad/glad/glad.h:1403
rs2::sw_update::version
rsutils::version version
Definition: versions-db-manager.h:30
rs2_notification
Definition: api.h:28
rs2_create_error
rs2_error * rs2_create_error(const char *what, const char *name, const char *args, rs2_exception_type type)
Definition: rs.cpp:235
lrs_major
int lrs_major(int version)
Definition: api.h:452
rs2_error
Definition: rs.cpp:227
string
GLsizei const GLchar *const * string
Definition: glad/glad/glad.h:2861
void
typedef void(APIENTRY *GLDEBUGPROC)(GLenum source
LOG_DEBUG
#define LOG_DEBUG(...)
Definition: easyloggingpp.h:70
from.h
opencv_pointcloud_viewer.out
out
Definition: opencv_pointcloud_viewer.py:276
librealsense::is_streamable
Definition: api.h:61
param
GLenum GLfloat param
Definition: glad/glad/glad.h:1400
subscription.h
device.h
type
GLenum type
Definition: glad/glad/glad.h:135
rs2_notification::rs2_notification
rs2_notification(const librealsense::notification *notification)
Definition: api.h:30
librealsense::arg_streamer< T *, true >::stream_arg
void stream_arg(std::ostream &out, T *val, bool last)
Definition: api.h:75
val
GLuint GLfloat * val
Definition: glad/glad/glad.h:3411
librealsense-exception.h
rs2_device::device
std::shared_ptr< librealsense::device_interface > device
Definition: api.h:38
value
GLfloat value
Definition: glad/glad/glad.h:2099
f
GLdouble f
Definition: glad/glad/glad.h:1517
i
int i
Definition: rs-pcl-color.cpp:54
extension.h
lrs_minor
int lrs_minor(int version)
Definition: api.h:456
test-shorten-json.ss
string ss
Definition: test-shorten-json.py:119
name
GLuint const GLchar * name
Definition: glad/glad/glad.h:2777
opencv_pointcloud_viewer.now
now
Definition: opencv_pointcloud_viewer.py:314
report_version_mismatch
void report_version_mismatch(int runtime, int compiletime)
Definition: api.h:473
rs2_raw_data_buffer
Definition: api.h:21
librealsense::stream_args
void stream_args(std::ostream &out, const char *names, const T &last)
Definition: api.h:98
rs2_get_api_version
int rs2_get_api_version(rs2_error **error)
Definition: rs.cpp:1606
librealsense::notification
Definition: notification.h:14
rsutils::string::from
Definition: from.h:19
t
GLdouble t
Definition: glad/glad/glad.h:1829
p
double p[GRIDW][GRIDH]
Definition: wave.c:109
std
Definition: android_helpers.h:13
librealsense::librealsense_exception
Definition: librealsense-exception.h:17
first
GLint first
Definition: glad/glad/glad.h:2301
verify_version_compatibility
void verify_version_compatibility(int api_version)
Definition: api.h:482
rs.h
Exposes librealsense functionality for C compilers.
rsutils::subscription
Definition: subscription.h:25
invoke
dispatcher invoke([&](dispatcher::cancellable_timer c) { std::this_thread::sleep_for(std::chrono::seconds(3));dispatched_end_verifier=true;})
rmse.e
e
Definition: rmse.py:177
rs2::textual_icons::lock
static const textual_icon lock
Definition: device-model.h:186
report_error
void report_error(std::string error)
Definition: windows-app-bootstrap.cpp:89
rs2_notification::_notification
const librealsense::notification * _notification
Definition: api.h:33
it
static auto it
Definition: openvino-face-detection.cpp:375
test-depth.result
result
Definition: test-depth.py:183
librealsense::is_streamable::test
static auto test(const S *t) -> decltype(std::cout<< **t)
rs2_device
Definition: api.h:36
s
GLdouble s
Definition: glad/glad/glad.h:2441
rs2_device::playback_status_changed
rsutils::subscription playback_status_changed
Definition: api.h:39
librealsense::arg_streamer< T *, false >::stream_arg
void stream_arg(std::ostream &out, T *val, bool last)
Definition: api.h:88
LOG_INFO
LOG_INFO("Log message using LOG_INFO()")
rs2_raw_data_buffer::buffer
std::vector< uint8_t > buffer
Definition: api.h:23
pose.h
rmse.d
d
Definition: rmse.py:171
librealsense::arg_streamer
Definition: api.h:51
LOG_ERROR
#define LOG_ERROR(...)
Definition: easyloggingpp.h:73
func
GLenum func
Definition: glad/glad/glad.h:2768
rs2_exception_type
rs2_exception_type
Exception types are the different categories of errors that RealSense API might return.
Definition: rs_types.h:30
devices.args
args
Definition: third-party/realdds/scripts/devices.py:5


librealsense2
Author(s): LibRealSense ROS Team
autogenerated on Mon Apr 22 2024 02:12:55