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


librealsense2
Author(s): Sergey Dorodnicov , Doron Hirshberg , Mark Horn , Reagan Lopez , Itay Carpis
autogenerated on Mon May 3 2021 02:45:06