win-helpers.cpp
Go to the documentation of this file.
1 // License: Apache 2.0. See LICENSE file in root directory.
2 // Copyright(c) 2015 Intel Corporation. All Rights Reserved.
3 
4 #if (_MSC_FULL_VER < 180031101)
5  #error At least Visual Studio 2013 Update 4 is required to compile this backend
6 #endif
7 
8 #include "../types.h"
9 #include "win-helpers.h"
10 
11 #include <Cfgmgr32.h>
12 #include <usbioctl.h>
13 #include <SetupAPI.h>
14 #include <comdef.h>
15 #include <atlstr.h>
16 #include <Windows.h>
17 #include <SetupAPI.h>
18 #include <string>
19 #include <regex>
20 #include <Sddl.h>
21 
22 #pragma comment(lib, "cfgmgr32.lib")
23 #pragma comment(lib, "setupapi.lib")
24 
25 #include <initguid.h>
26 #include <devpkey.h> // DEVPKEY_...
27 
28 //https://docs.microsoft.com/en-us/windows-hardware/drivers/usbcon/supported-usb-classes#microsoft-provided-usb-device-class-drivers
29 #ifndef WITH_TRACKING
30 DEFINE_GUID(GUID_DEVINTERFACE_USB_DEVICE, 0xA5DCBF10L, 0x6530, 0x11D2, 0x90, 0x1F, 0x00, 0xC0, 0x4F, 0xB9, 0x51, 0xED);
31 #endif
32 DEFINE_GUID(GUID_DEVINTERFACE_IMAGE_WIN10, 0x6bdd1fc6L, 0x810f, 0x11d0, 0xbe, 0xc7, 0x08, 0x00, 0x2b, 0xe2, 0x09, 0x2f);
33 DEFINE_GUID(GUID_DEVINTERFACE_CAMERA_WIN10, 0xca3e7ab9, 0xb4c3, 0x4ae6, 0x82, 0x51, 0x57, 0x9e, 0xf9, 0x33, 0x89, 0x0f);
34 
35 // Intel(R) RealSense(TM) 415 Depth - MI 0: [Interface 0 video control] [Interface 1 video stream] [Interface 2 video stream]
36 DEFINE_GUID(GUID_DEVINTERFACE_IMAGE_WIN7, 0xe659c3ec, 0xbf3c, 0x48a5, 0x81, 0x92, 0x30, 0x73, 0xe8, 0x22, 0xd7, 0xcd);
37 
38 // Intel(R) RealSense(TM) 415 RGB - MI 3: [Interface 3 video control] [Interface 4 video stream]
39 DEFINE_GUID(GUID_DEVINTERFACE_CAMERA_WIN7, 0x50537bc3, 0x2919, 0x452d, 0x88, 0xa9, 0xb1, 0x3b, 0xbf, 0x7d, 0x24, 0x59);
40 
41 #define CREATE_MUTEX_RETRY_NUM (5)
42 
43 namespace librealsense
44 {
45  namespace platform
46  {
47  template<typename T>
48  size_t vector_bytes_size(const typename std::vector<T>& vec)
49  {
50  static_assert((std::is_arithmetic<T>::value), "vector_bytes_size requires numeric type for input data");
51  return sizeof(T) * vec.size();
52  }
53 
55  {
56  _com_error err(hr);
57  std::wstring errorMessage = (err.ErrorMessage()) ? err.ErrorMessage() : L"";
58  std::stringstream ss;
59  ss << "HResult 0x" << std::hex << hr << ": \"" << win_to_utf(errorMessage.data()) << "\"";
60  return ss.str();
61  }
62 
63  typedef ULONG(__stdcall* fnRtlGetVersion)(PRTL_OSVERSIONINFOW lpVersionInformation);
64 
65 
67  {
68  RTL_OSVERSIONINFOEXW verInfo = { 0 };
69  verInfo.dwOSVersionInfoSize = sizeof(verInfo);
70  static auto RtlGetVersion = reinterpret_cast<fnRtlGetVersion>(GetProcAddress(GetModuleHandleW(L"ntdll.dll"), "RtlGetVersion"));
71  if (RtlGetVersion != nullptr && RtlGetVersion(reinterpret_cast<PRTL_OSVERSIONINFOW>(&verInfo)) == 0)
72  {
73  return verInfo.dwMajorVersion >= 0x0A && verInfo.dwBuildNumber >= 15063;
74  }
75  else
76  return false;
77  }
78 
79  bool check(const char * call, HRESULT hr, bool to_throw)
80  {
81  if (FAILED(hr))
82  {
83  std::string descr = to_string() << call << " returned: " << hr_to_string(hr);
84  if (to_throw)
85  throw windows_backend_exception(descr);
86  else
87  LOG_DEBUG(descr);
88 
89  return false;
90  }
91  return true;
92  }
93 
94  std::string win_to_utf(const WCHAR * s)
95  {
96  auto len = WideCharToMultiByte(CP_UTF8, 0, s, -1, nullptr, 0, nullptr, nullptr);
97  if(len == 0)
98  throw std::runtime_error(to_string() << "WideCharToMultiByte(...) returned 0 and GetLastError() is " << GetLastError());
99 
100  std::string buffer(len-1, ' ');
101  len = WideCharToMultiByte(CP_UTF8, 0, s, -1, &buffer[0], static_cast<int>(buffer.size())+1, nullptr, nullptr);
102  if(len == 0)
103  throw std::runtime_error(to_string() << "WideCharToMultiByte(...) returned 0 and GetLastError() is " << GetLastError());
104 
105  return buffer;
106  }
107 
108  std::vector<std::string> tokenize(std::string string, char separator)
109  {
110  std::vector<std::string> tokens;
111  std::string::size_type i1 = 0;
112  while(true)
113  {
114  auto i2 = string.find(separator, i1);
115  if(i2 == std::string::npos)
116  {
117  tokens.push_back(string.substr(i1));
118  return tokens;
119  }
120  tokens.push_back(string.substr(i1, i2-i1));
121  i1 = i2+1;
122  }
123  }
124 
125 
126  // Parse the following USB path format = \?usb#vid_vvvv&pid_pppp&mi_ii#aaaaaaaaaaaaaaaa#{gggggggg-gggg-gggg-gggg-gggggggggggg}
127  // vvvv = USB vendor ID represented in 4 hexadecimal characters.
128  // pppp = USB product ID represented in 4 hexadecimal characters.
129  // ii = USB interface number.
130  // aaaaaaaaaaaaaaaa = unique Windows-generated string based on things such as the physical USB port address and/or interface number.
131  // gggggggg-gggg-gggg-gggg-gggggggggggg = device interface GUID assigned in the driver or driver INF file and is used to link applications to device with specific drivers loaded.
133  {
134  auto name = path;
135  std::transform(begin(name), end(name), begin(name), ::tolower);
136  auto tokens = tokenize(name, '#');
137  if(tokens.size() < 1 || (tokens[0] != R"(\\?\usb)" && tokens[0] != R"(\\?\hid)")) return false; // Not a USB device
138  if(tokens.size() < 3)
139  {
140  LOG_ERROR("malformed usb device path: " << name);
141  return false;
142  }
143 
144  auto ids = tokenize(tokens[1], '&');
145  if(ids[0].size() != 8 || ids[0].substr(0,4) != "vid_" || !(std::istringstream(ids[0].substr(4,4)) >> std::hex >> vid))
146  {
147  LOG_ERROR("malformed vid string: " << tokens[1]);
148  return false;
149  }
150 
151  if(ids[1].size() != 8 || ids[1].substr(0,4) != "pid_" || !(std::istringstream(ids[1].substr(4,4)) >> std::hex >> pid))
152  {
153  LOG_ERROR("malformed pid string: " << tokens[1]);
154  return false;
155  }
156 
157  if(ids.size() > 2 && (ids[2].size() != 5 || ids[2].substr(0,3) != "mi_" || !(std::istringstream(ids[2].substr(3,2)) >> mi)))
158  {
159  LOG_ERROR("malformed mi string: " << tokens[1]);
160  return false;
161  }
162 
163  ids = tokenize(tokens[2], '&');
164  if(ids.size() == 0)
165  {
166  LOG_ERROR("malformed id string: " << tokens[2]);
167  return false;
168  }
169 
170  if (ids.size() > 2)
171  unique_id = ids[1];
172  else
173  unique_id = "";
174 
175  if (tokens.size() >= 3)
176  device_guid = tokens[3];
177 
178  return true;
179  }
180 
181  // Parse the following USB path format = \?usb#vid_vvvv&pid_pppp#ssss#{gggggggg-gggg-gggg-gggg-gggggggggggg}
182  // vvvv = USB vendor ID represented in 4 hexadecimal characters.
183  // pppp = USB product ID represented in 4 hexadecimal characters.
184  // ssss = USB serial string represented in n characters.
185  // gggggggg-gggg-gggg-gggg-gggggggggggg = device interface GUID assigned in the driver or driver INF file and is used to link applications to device with specific drivers loaded.
187  {
188  auto name = path;
189  std::transform(begin(name), end(name), begin(name), ::tolower);
190  auto tokens = tokenize(name, '#');
191  if (tokens.size() < 1 || (tokens[0] != R"(\\?\usb)" && tokens[0] != R"(\\?\hid)")) return false; // Not a USB device
192  if (tokens.size() < 3)
193  {
194  LOG_ERROR("malformed usb device path: " << name);
195  return false;
196  }
197 
198  auto ids = tokenize(tokens[1], '&');
199  if (ids[0].size() != 8 || ids[0].substr(0, 4) != "vid_" || !(std::istringstream(ids[0].substr(4, 4)) >> std::hex >> vid))
200  {
201  LOG_ERROR("malformed vid string: " << tokens[1]);
202  return false;
203  }
204 
205  if (ids[1].size() != 8 || ids[1].substr(0, 4) != "pid_" || !(std::istringstream(ids[1].substr(4, 4)) >> std::hex >> pid))
206  {
207  LOG_ERROR("malformed pid string: " << tokens[1]);
208  return false;
209  }
210 
211  serial = tokens[2];
212 
213  return true;
214  }
215 
217  {
218  auto name = device_id;
219  std::transform(begin(name), end(name), begin(name), ::tolower);
220  auto tokens = tokenize(name, '\\');
221  if (tokens.size() < 1 )
222  return false;
223  if( tokens[0] != "usb" && tokens[0] != "hid" )
224  return false;
225 
226  // Expecting VID, PID, and MI
227  auto ids = tokenize( tokens[1], '&' );
228  if( ids.size() < 3 )
229  {
230  // MI may be missing, especially when we look at composite devices
231  if( ids.size() < 2 )
232  LOG_ERROR( "incomplete device id: " << device_id );
233  return false;
234  }
235 
236  if (ids[0].size() != 8 || ids[0].substr(0, 4) != "vid_" || !(std::istringstream(ids[0].substr(4, 4)) >> std::hex >> vid))
237  {
238  LOG_ERROR("malformed vid string: " << tokens[1]);
239  return false;
240  }
241 
242  if (ids[1].size() != 8 || ids[1].substr(0, 4) != "pid_" || !(std::istringstream(ids[1].substr(4, 4)) >> std::hex >> pid))
243  {
244  LOG_ERROR("malformed pid string: " << tokens[1]);
245  return false;
246  }
247 
248  if (ids[2].size() != 5 || ids[2].substr(0, 3) != "mi_" || !(std::istringstream(ids[2].substr(3, 2)) >> mi))
249  {
250  LOG_ERROR("malformed mi string: " << tokens[1]);
251  return false;
252  }
253 
254  ids = tokenize(tokens[2], '&');
255  if (ids.size() < 2)
256  {
257  LOG_ERROR("malformed id string: " << tokens[2]);
258  return false;
259  }
260  unique_id = ids[1];
261  return true;
262  }
263 
264  bool handle_node(const std::wstring & targetKey, HANDLE h, ULONG index)
265  {
266  USB_NODE_CONNECTION_DRIVERKEY_NAME key;
267  key.ConnectionIndex = index;
268 
269  if (!DeviceIoControl(h, IOCTL_USB_GET_NODE_CONNECTION_DRIVERKEY_NAME, &key, sizeof(key), &key, sizeof(key), nullptr, nullptr))
270  {
271  return false;
272  }
273 
274  if (key.ActualLength < sizeof(key)) return false;
275 
276  auto alloc = std::malloc(key.ActualLength);
277  if (!alloc)
278  throw std::bad_alloc();
279 
280  auto pKey = std::shared_ptr<USB_NODE_CONNECTION_DRIVERKEY_NAME>(reinterpret_cast<USB_NODE_CONNECTION_DRIVERKEY_NAME *>(alloc), std::free);
281 
282  pKey->ConnectionIndex = index;
283  if (DeviceIoControl(h, IOCTL_USB_GET_NODE_CONNECTION_DRIVERKEY_NAME, pKey.get(), key.ActualLength, pKey.get(), key.ActualLength, nullptr, nullptr))
284  {
285  //std::wcout << pKey->DriverKeyName << std::endl;
286  if (targetKey == pKey->DriverKeyName) {
287  return true;
288  }
289  else return false;
290  }
291 
292  return false;
293  }
294 
295  std::wstring get_path(HANDLE h, ULONG index)
296  {
297  // get name length
298  USB_NODE_CONNECTION_NAME name;
299  name.ConnectionIndex = index;
300  if (!DeviceIoControl(h, IOCTL_USB_GET_NODE_CONNECTION_NAME, &name, sizeof(name), &name, sizeof(name), nullptr, nullptr))
301  {
302  return std::wstring(L"");
303  }
304 
305  // alloc space
306  if (name.ActualLength < sizeof(name)) return std::wstring(L"");
307  auto alloc = std::malloc(name.ActualLength);
308  auto pName = std::shared_ptr<USB_NODE_CONNECTION_NAME>(reinterpret_cast<USB_NODE_CONNECTION_NAME *>(alloc), std::free);
309 
310  // get name
311  pName->ConnectionIndex = index;
312  if (DeviceIoControl(h, IOCTL_USB_GET_NODE_CONNECTION_NAME, pName.get(), name.ActualLength, pName.get(), name.ActualLength, nullptr, nullptr))
313  {
314  return std::wstring(pName->NodeName);
315  }
316 
317  return std::wstring(L"");
318  }
319 
320  std::tuple<std::string,usb_spec> handle_usb_hub(const std::wstring & targetKey, const std::wstring & path)
321  {
322  auto res = std::make_tuple(std::string(), usb_spec::usb_undefined);
323 
324  if (path.empty())
325  return res;
326  std::wstring fullPath = L"\\\\.\\" + path;
327 
328  HANDLE h = CreateFile(fullPath.c_str(), GENERIC_WRITE, FILE_SHARE_WRITE, nullptr, OPEN_EXISTING, 0, nullptr);
329  if (h == INVALID_HANDLE_VALUE) return res;
330  auto h_gc = std::shared_ptr<void>(h, CloseHandle);
331 
332  USB_NODE_INFORMATION info{};
333  if (!DeviceIoControl(h, IOCTL_USB_GET_NODE_INFORMATION, &info, sizeof(info), &info, sizeof(info), nullptr, nullptr))
334  return res;
335 
336  // for each port on the hub
337  for (ULONG i = 1; i <= info.u.HubInformation.HubDescriptor.bNumberOfPorts; ++i)
338  {
339  // allocate something or other
340  char buf[sizeof(USB_NODE_CONNECTION_INFORMATION_EX)] = { 0 };
341  PUSB_NODE_CONNECTION_INFORMATION_EX pConInfo = reinterpret_cast<PUSB_NODE_CONNECTION_INFORMATION_EX>(buf);
342 
343  // get info about port i
344  pConInfo->ConnectionIndex = i;
345  if (!DeviceIoControl(h, IOCTL_USB_GET_NODE_CONNECTION_INFORMATION_EX, pConInfo, sizeof(buf), pConInfo, sizeof(buf), nullptr, nullptr))
346  {
347  continue;
348  }
349 
350  // check if device is connected
351  if (pConInfo->ConnectionStatus != DeviceConnected)
352  {
353  continue; // almost assuredly silently. I think this flag gets set for any port without a device
354  }
355 
356  // if connected, handle correctly, setting the location info if the device is found
357  if (pConInfo->DeviceIsHub)
358  res = handle_usb_hub(targetKey, get_path(h, i)); // Invoke recursion to traverse USB hubs chain
359  else
360  {
361  if (handle_node(targetKey, h, i)) // exit condition
362  {
363  return std::make_tuple(win_to_utf(fullPath.c_str()) + " " + std::to_string(i),
364  static_cast<usb_spec>(pConInfo->DeviceDescriptor.bcdUSB));
365  }
366  }
367 
368  if( ! std::get<0>(res).empty() )
369  return res;
370  }
371 
372  return res;
373  }
374 
375 
376  bool get_id( DEVINST devinst, std::string* p_out_str )
377  {
378  ULONG cch_required = 0;
379  if( CM_Get_Device_ID_Size( &cch_required, devinst, 0 ) != CR_SUCCESS )
380  return false;
381 
382  if( p_out_str )
383  {
384  std::vector<WCHAR> buf( cch_required + 1 );
385  if( CM_Get_Device_ID( devinst, buf.data(), cch_required, 0 ) != CR_SUCCESS )
386  return false;
387  *p_out_str = win_to_utf( buf.data() );
388  }
389 
390  return true;
391  }
392 
393 
394  std::string get_id( DEVINST devinst )
395  {
396  std::string id;
397  get_id( devinst, &id );
398  return id;
399  }
400 
401 
403  {
404  return librealsense::platform::get_id( get() );
405  }
406 
407 
409  {
410  uint16_t vid, pid, mi;
412  if( !parse_usb_path_from_device_id( vid, pid, mi, uid, get_id() ) )
413  return std::string();
414  return uid;
415  }
416 
417 
418  /*
419  Convert a device path:
420  \\?\HID#VID_8086&PID_0B4D&MI_05#7&24fd3503&0&0000#{c317c286-c468-4288-9975-d4c4587c442c}\{560421A4-2F8D-47A0-A6D8-4110C6B2A202}
421  to an instance ID:
422  HID\VID_8086&PID_0B4D&MI_05\7&217e81dc&0&0000
423  which can then be used to get a DEVINST from the config manager.
424 
425  Returns an empty string on failure.
426  */
427  std::wstring instance_id_from_device_path( LPCWSTR path )
428  {
429  if( wcsncmp( path, L"\\\\?\\", 4 ) )
430  return std::wstring();
431  std::wstring inst_id( path + 4 );
432  // Remove the last "#{...}" part, and replace all '#' with '\' on the way:
433  for( auto x = inst_id.find( L'#' );
434  x != std::wstring::npos;
435  x = inst_id.find( L'#', x + 1 ) )
436  {
437  if( inst_id[x + 1] == L'{' )
438  {
439  inst_id.resize( x );
440  break;
441  }
442  inst_id.replace( x, 1, 1, L'\\' );
443  }
444  return inst_id;
445  }
446 
447 
448  /* static */ cm_node cm_node::root()
449  {
450  DEVINST devinst;
451  if( CM_Locate_DevNode( &devinst, nullptr, CM_LOCATE_DEVNODE_NORMAL ) != CR_SUCCESS )
452  return cm_node();
453  return cm_node( devinst );
454  }
455 
456 
457  /* static */ cm_node cm_node::from_instance_id( std::wstring const & inst_id )
458  {
459  DEVINST devinst;
460  if( CM_Locate_DevNode( &devinst, const_cast< DEVINSTID >( inst_id.data() ), CM_LOCATE_DEVNODE_PHANTOM ) != CR_SUCCESS )
461  return cm_node();
462  return cm_node( devinst );
463  }
464 
465 
467  {
468  DEVINST parent;
469  if( CM_Get_Parent( &parent, get(), 0 ) != CR_SUCCESS )
470  return cm_node();
471  return cm_node( parent );
472  }
473 
474 
476  {
477  DEVINST child;
478  if( CM_Get_Child( &child, get(), 0 ) != CR_SUCCESS )
479  return cm_node();
480  return cm_node( child );
481  }
482 
483 
485  {
486  DEVINST sibling;
487  if( CM_Get_Sibling( &sibling, get(), 0 ) != CR_SUCCESS )
488  return cm_node();
489  return cm_node( sibling );
490  }
491 
492 
493  std::string cm_node::get_property( DEVPROPKEY const & property ) const
494  {
495  DEVPROPTYPE type;
496  ULONG cb = 0;
497  auto rv = CM_Get_DevNode_Property( get(), &property, &type, nullptr, &cb, 0 );
498  if( rv != CR_BUFFER_SMALL )
499  return std::string();
500  if( type != DEVPROP_TYPE_STRING )
501  return std::string();
502  std::wstring str;
503  str.reserve( cb );
504  if( CM_Get_DevNode_Property( get(), &property, &type, (PBYTE) str.data(), &cb, 0 ) != CR_SUCCESS )
505  return std::string();
506  return win_to_utf( str.data() );
507  }
508 
509 
510  // Provides Port Id and the USB Specification (USB type)
511  bool get_usb_descriptors(uint16_t device_vid, uint16_t device_pid, const std::string& device_uid, std::string& location, usb_spec& spec, std::string& serial)
512  {
513  SP_DEVINFO_DATA devInfo = { sizeof(SP_DEVINFO_DATA) };
514  std::vector<GUID> guids = {
515  GUID_DEVINTERFACE_IMAGE_WIN7,
516  GUID_DEVINTERFACE_CAMERA_WIN7,
517  GUID_DEVINTERFACE_IMAGE_WIN10,
518  GUID_DEVINTERFACE_CAMERA_WIN10
519  };
520 
521  for (auto guid : guids)
522  {
523  // Build a device info represent all imaging devices
524  HDEVINFO device_info = SetupDiGetClassDevsEx(static_cast<const GUID *>(&guid), nullptr, nullptr, DIGCF_PRESENT, nullptr, nullptr, nullptr);
525 
526  // Add automatic destructor to the device info
527  auto di = std::shared_ptr<void>(device_info, SetupDiDestroyDeviceInfoList);
528 
529  if (device_info == INVALID_HANDLE_VALUE)
530  {
531  return false;
532  }
533 
534  // Enumerate all imaging devices
535  for (int member_index = 0; ; ++member_index)
536  {
537  // Get device information element from the device information set
538  if (SetupDiEnumDeviceInfo(device_info, member_index, &devInfo) == FALSE)
539  {
540  if( GetLastError() == ERROR_NO_MORE_ITEMS )
541  break; // stop when none left
542  continue; // silently ignore other errors
543  }
544 
545  std::string parent_uid;
546  if( get_usb_device_descriptors( devInfo.DevInst, device_vid, device_pid, device_uid, location, spec, serial, parent_uid ) )
547  return true;
548  }
549  }
550  LOG_ERROR( "Could not find camera (vid " << std::hex << device_vid << " pid " << std::hex << device_pid << " uid " << device_uid << ") in windows device tree" );
551  return false;
552  }
553 
554  // Provides Port Id and the USB Specification (USB type)
555  bool get_usb_device_descriptors( DEVINST devinst, uint16_t device_vid, uint16_t device_pid, const std::string& device_uid, std::string& location, usb_spec& spec, std::string& serial, std::string& parent_uid )
556  {
557  unsigned long buf_size = 0;
558 
559  // Check if this is our device
560  std::string device_id;
561  if( !get_id( devinst, &device_id ) )
562  {
563  LOG_ERROR( "CM_Get_Device_ID failed" );
564  return false;
565  }
566  //LOG_DEBUG( "??? dev ID " << device_id );
567  uint16_t usb_vid, usb_pid, usb_mi; std::string usb_unique_id;
568  if( ! parse_usb_path_from_device_id( usb_vid, usb_pid, usb_mi, usb_unique_id, device_id ))
569  return false;
570  //LOG_DEBUG( " uid " << usb_unique_id );
571  if (usb_vid != device_vid || usb_pid != device_pid || /* usb_mi != device->mi || */ usb_unique_id != device_uid)
572  return false;
573 
574  // Get parent (composite device) instance
575  DEVINST parent;
576  if (CM_Get_Parent(&parent, devinst, 0) != CR_SUCCESS)
577  {
578  LOG_ERROR("CM_Get_Parent failed");
579  return false;
580  }
581 
582  // Get the buffer size required to hold the parent (composite) device instance ID
583  if (CM_Get_Device_ID_Size(&buf_size, parent, 0) != CR_SUCCESS)
584  {
585  LOG_ERROR("CM_Get_Device_ID_Size failed");
586  return false;
587  }
588 
589  std::vector<WCHAR> pInstID2(buf_size + 1);
590 
591  if (CM_Get_Device_ID( parent, pInstID2.data(), ULONG(vector_bytes_size(pInstID2)), 0) != CR_SUCCESS)
592  {
593  LOG_ERROR("CM_Get_Device_ID failed");
594  return false;
595  }
596  std::string parent_id = win_to_utf( pInstID2.data() );
597  //LOG_DEBUG( "... parent device id " << parent_id );
598  uint16_t parent_vid, parent_pid, parent_mi;
599  parse_usb_path_from_device_id( parent_vid, parent_pid, parent_mi, parent_uid, parent_id ); // may fail -- but we try to get the parent_uid
600 
601  // Upgrade to DEVINFO_DATA for SetupDiGetDeviceRegistryProperty
602  HDEVINFO device_info = SetupDiGetClassDevs(nullptr, pInstID2.data(), nullptr, DIGCF_PRESENT | DIGCF_DEVICEINTERFACE | DIGCF_ALLCLASSES);
603  if (device_info == INVALID_HANDLE_VALUE)
604  {
605  // HID devices should always have a valid parent...
606  if( 0 == parent_id.compare( 0, 4, "HID\\" ))
607  LOG_ERROR("SetupDiGetClassDevs failed");
608  return false;
609  }
610 
611  // Add automatic destructor to the device info
612  auto di = std::shared_ptr<void>( device_info, SetupDiDestroyDeviceInfoList );
613 
614  SP_DEVICE_INTERFACE_DATA interfaceData = { sizeof( SP_DEVICE_INTERFACE_DATA ) };
615  if (SetupDiEnumDeviceInterfaces(device_info, nullptr, &GUID_DEVINTERFACE_USB_DEVICE, 0, &interfaceData) == FALSE)
616  {
617  LOG_ERROR("SetupDiEnumDeviceInterfaces failed");
618  return false;
619  }
620 
621  // get the SP_DEVICE_INTERFACE_DETAIL_DATA object, and also grab the SP_DEVINFO_DATA object for the device
622  buf_size = 0;
623  SetupDiGetDeviceInterfaceDetail(device_info, &interfaceData, nullptr, 0, &buf_size, nullptr);
624  if (GetLastError() != ERROR_INSUFFICIENT_BUFFER)
625  {
626  LOG_ERROR("SetupDiGetDeviceInterfaceDetail failed");
627  return false;
628  }
629 
630  std::vector<BYTE> detail_data_buff(buf_size);
631  SP_DEVICE_INTERFACE_DETAIL_DATA* detail_data = reinterpret_cast<SP_DEVICE_INTERFACE_DETAIL_DATA *>(detail_data_buff.data());
632 
633  detail_data->cbSize = sizeof(SP_DEVICE_INTERFACE_DETAIL_DATA);
634  SP_DEVINFO_DATA parent_data = { sizeof(SP_DEVINFO_DATA) };
635  if (!SetupDiGetDeviceInterfaceDetail(device_info, &interfaceData, detail_data, ULONG(vector_bytes_size(detail_data_buff)), nullptr, &parent_data))
636  {
637  LOG_ERROR("SetupDiGetDeviceInterfaceDetail failed");
638  return false;
639  }
640 
641  uint16_t vid = 0;
642  uint16_t pid = 0;
643  uint16_t mi = 0;
645  std::wstring ws(detail_data->DevicePath);
646  std::string path( win_to_utf( detail_data->DevicePath ));
647 
648  /* Parse the following USB path format = \?usb#vid_vvvv&pid_pppp&mi_ii#aaaaaaaaaaaaaaaa#{gggggggg-gggg-gggg-gggg-gggggggggggg} */
649  parse_usb_path_multiple_interface(vid, pid, mi, parent_uid, path, guid);
650  if ( parent_uid.empty())
651  {
652  /* Parse the following USB path format = \?usb#vid_vvvv&pid_pppp#ssss#{gggggggg - gggg - gggg - gggg - gggggggggggg} */
653  parse_usb_path_single_interface(vid, pid, serial, path);
654  }
655 
656  // get driver key for composite device
657  buf_size = 0;
658  SetupDiGetDeviceRegistryProperty(device_info, &parent_data, SPDRP_DRIVER, nullptr, nullptr, 0, &buf_size);
659  if (GetLastError() != ERROR_INSUFFICIENT_BUFFER)
660  {
661  LOG_ERROR("SetupDiGetDeviceRegistryProperty failed in an unexpected manner");
662  return false;
663  }
664 
665  std::vector<BYTE> driver_key(buf_size);
666 
667  if (!SetupDiGetDeviceRegistryProperty(device_info, &parent_data, SPDRP_DRIVER, nullptr, driver_key.data(), (ULONG) vector_bytes_size(driver_key), nullptr))
668  {
669  LOG_ERROR("SetupDiGetDeviceRegistryProperty failed");
670  return false;
671  }
672 
673  // contains composite device key
674  std::wstring targetKey(reinterpret_cast<const wchar_t*>(driver_key.data()));
675 
676  // recursively check all hubs, searching for composite device
677  for (int i = 0;; i++)
678  {
679  std::wstringstream buf;
680  buf << "\\\\.\\HCD" << i;
681  std::wstring hcd = buf.str();
682 
683  // grab handle
684  HANDLE h = CreateFile(hcd.c_str(), GENERIC_WRITE | GENERIC_READ, FILE_SHARE_READ | FILE_SHARE_WRITE, nullptr, OPEN_EXISTING, 0, nullptr);
685  auto h_gc = std::shared_ptr<void>(h, CloseHandle);
686  if (h == INVALID_HANDLE_VALUE)
687  {
688  LOG_ERROR("CreateFile failed");
689  break;
690  }
691  else
692  {
693  USB_ROOT_HUB_NAME name;
694 
695  // get required space
696  if (!DeviceIoControl(h, IOCTL_USB_GET_ROOT_HUB_NAME, nullptr, 0, &name, sizeof(name), nullptr, nullptr)) {
697  LOG_ERROR("DeviceIoControl failed");
698  return false; // alt: fail silently and hope its on a different root hub
699  }
700 
701  std::vector<char> name_buff(name.ActualLength);
702  USB_ROOT_HUB_NAME* pName = reinterpret_cast<USB_ROOT_HUB_NAME *>(name_buff.data());
703 
704  // get name
705  if (!DeviceIoControl(h, IOCTL_USB_GET_ROOT_HUB_NAME, nullptr, 0, pName, (ULONG) vector_bytes_size(name_buff), nullptr, nullptr)) {
706  LOG_ERROR("DeviceIoControl failed");
707  return false; // alt: fail silently and hope its on a different root hub
708  }
709 
710  // return location if device is connected under this root hub, also provide the port USB spec/speed
711  auto usb_res = handle_usb_hub(targetKey, std::wstring(pName->RootHubName));
712  if( ! std::get<0>(usb_res).empty() )
713  {
714  location = std::get<0>(usb_res);
715  spec = std::get<1>(usb_res);
716  return true;
717  }
718  }
719  }
720  return false;
721  }
722 
723 
724 #define MAX_HANDLES 64
725 
727  :_handle(handle)
728  {}
729 
731  {
732  if (_handle != nullptr)
733  {
734  CloseHandle(_handle);
735  _handle = nullptr;
736  }
737  }
738 
740  {
741  if (_handle == nullptr) return false;
742  SetEvent(_handle);
743  return true;
744  }
745 
746  bool event_base::wait(DWORD timeout) const
747  {
748  if (_handle == nullptr) return false;
749 
750  return WaitForSingleObject(_handle, timeout) == WAIT_OBJECT_0; // Return true only if object was signaled
751  }
752 
753  event_base* event_base::wait(const std::vector<event_base*>& events, bool waitAll, int timeout)
754  {
755  if (events.size() > MAX_HANDLES) return nullptr; // WaitForMultipleObjects doesn't support waiting on more then 64 handles
756 
757  HANDLE handles[MAX_HANDLES];
758  auto i = 0;
759  for (auto& evnt : events)
760  {
761  handles[i] = evnt->get_handle();
762  ++i;
763  }
764  auto res = WaitForMultipleObjects(static_cast<DWORD>(events.size()), handles, waitAll, timeout);
765  if (res < (WAIT_OBJECT_0 + events.size()))
766  {
767  return events[res - WAIT_OBJECT_0];
768  }
769  else
770  {
771  return nullptr;
772  }
773  }
774 
775  event_base* event_base::wait_all(const std::vector<event_base*>& events, int timeout)
776  {
777  return wait(events, true, timeout);
778  }
779 
780  event_base* event_base::wait_any(const std::vector<event_base*>& events, int timeout)
781  {
782  return wait(events, false, timeout);
783  }
784 
786  {
787  if (_handle == nullptr) return false;
788  return ResetEvent(_handle) != 0;
789  }
790 
792  :event_base(CreateEvent(nullptr, TRUE, FALSE, nullptr))
793  {}
794 
796  : event_base(CreateEvent(nullptr, FALSE, FALSE, nullptr))
797  {}
798 
799  PSECURITY_DESCRIPTOR make_allow_all_security_descriptor(void)
800  {
801  WCHAR *pszStringSecurityDescriptor;
802  pszStringSecurityDescriptor = L"D:(A;;GA;;;WD)(A;;GA;;;AN)S:(ML;;NW;;;ME)";
803  PSECURITY_DESCRIPTOR pSecDesc;
804  if (!ConvertStringSecurityDescriptorToSecurityDescriptor(
805  pszStringSecurityDescriptor, SDDL_REVISION_1, &pSecDesc, nullptr))
806  return nullptr;
807 
808  return pSecDesc;
809  }
810 
811  named_mutex::named_mutex(const char* id, unsigned timeout)
812  : _timeout(timeout),
813  _winusb_mutex(nullptr)
814  {
815  update_id(id);
816  }
817 
819  {
820  CString lstr;
821  CString IDstr(camID);
822  // IVCAM_DLL string is left in librealsense to allow safe
823  // interoperability with existing tools like DCM
824  lstr.Format(L"Global\\IVCAM_DLL_WINUSB_MUTEX%s", IDstr);
825  auto pSecDesc = make_allow_all_security_descriptor();
826  if (pSecDesc)
827  {
828  SECURITY_ATTRIBUTES SecAttr;
829  SecAttr.nLength = sizeof(SECURITY_ATTRIBUTES);
830  SecAttr.lpSecurityDescriptor = pSecDesc;
831  SecAttr.bInheritHandle = FALSE;
832 
833  _winusb_mutex = CreateMutex(
834  &SecAttr,
835  FALSE,
836  lstr);
837  LocalFree(pSecDesc);
838  }
839  //CreateMutex failed
840  if (_winusb_mutex == nullptr)
841  {
842  return Mutex_TotalFailure;
843  }
844  else if (GetLastError() == ERROR_ALREADY_EXISTS)
845  {
846  return Mutex_AlreadyExist;
847  }
848  return Mutex_Succeed;
849  }
850 
852  {
853  CString lstr;
854  CString IDstr(camID);
855  // IVCAM_DLL string is left in librealsense to allow safe
856  // interoperability with existing tools like DCM
857  lstr.Format(L"Global\\IVCAM_DLL_WINUSB_MUTEX%s", IDstr.GetString());
858 
859  _winusb_mutex = OpenMutex(
860  MUTEX_ALL_ACCESS, // request full access
861  FALSE, // handle not inheritable
862  lstr); // object name
863 
864  if (_winusb_mutex == nullptr)
865  {
866  return Mutex_TotalFailure;
867  }
868  else if (GetLastError() == ERROR_ALREADY_EXISTS)
869  {
870  return Mutex_AlreadyExist;
871  }
872 
873  return Mutex_Succeed;
874  }
875 
876  void named_mutex::update_id(const char* camID)
877  {
878  auto stsCreateMutex = Mutex_Succeed;
879  auto stsOpenMutex = Mutex_Succeed;
880 
881  if (_winusb_mutex == nullptr)
882  {
883 
884  for (int i = 0; i < CREATE_MUTEX_RETRY_NUM; i++)
885  {
886  stsCreateMutex = create_named_mutex(camID);
887 
888  switch (stsCreateMutex)
889  {
890  case Mutex_Succeed: return;
891  case Mutex_TotalFailure:
892  throw std::runtime_error("CreateNamedMutex returned Mutex_TotalFailure");
893  case Mutex_AlreadyExist:
894  {
895  stsOpenMutex = open_named_mutex(camID);
896 
897  //if OpenMutex failed retry to create the mutex
898  //it can caused by termination of the process that created the mutex
899  if (stsOpenMutex == Mutex_TotalFailure)
900  {
901  continue;
902  }
903  else if (stsOpenMutex == Mutex_Succeed)
904  {
905  return;
906  }
907  else
908  {
909  throw std::runtime_error("OpenNamedMutex returned error " + stsOpenMutex);
910  }
911  }
912  default:
913  break;
914  };
915  }
916  throw std::runtime_error("Open mutex failed!");
917  }
918  //Mutex is already exist this mean that
919  //the mutex already opened by this process and the method called again after connect event.
920  else
921  {
922  for (auto i = 0; i < CREATE_MUTEX_RETRY_NUM; i++)
923  {
924  auto tempMutex = _winusb_mutex;
925  stsCreateMutex = create_named_mutex(camID);
926 
927  switch (stsCreateMutex)
928  {
929  //if creation succeed this mean that new camera connected
930  //and we need to close the old mutex
931  case Mutex_Succeed:
932  {
933  auto res = CloseHandle(tempMutex);
934  if (!res)
935  {
936  throw std::runtime_error("CloseHandle failed");
937  }
938  return;
939  }
940  case Mutex_TotalFailure:
941  {
942  throw std::runtime_error("CreateNamedMutex returned Mutex_TotalFailure");
943  }
944  //Mutex already created by:
945  // 1. This process - which mean the same camera connected.
946  // 2. Other process created the mutex.
947  case Mutex_AlreadyExist:
948  {
949  stsOpenMutex = open_named_mutex(camID);
950 
951  if (stsOpenMutex == Mutex_TotalFailure)
952  {
953  continue;
954  }
955  else if (stsOpenMutex == Mutex_Succeed)
956  {
957  return;
958  }
959  else
960  {
961  throw std::runtime_error("OpenNamedMutex failed with error " + stsOpenMutex);
962  }
963  }
964  default:
965  break;
966  }
967  }
968 
969  throw std::runtime_error("Open mutex failed!");
970  }
971  }
972 
974  {
975  return (WaitForSingleObject(_winusb_mutex, _timeout) == WAIT_TIMEOUT) ? false : true;
976  }
977 
978  void named_mutex::acquire() const
979  {
980  if (!try_lock())
981  {
982  throw std::runtime_error("Acquire failed!");
983  }
984  }
985 
986  void named_mutex::release() const
987  {
988  auto sts = ReleaseMutex(_winusb_mutex);
989  if (!sts)
990  {
991  throw std::runtime_error("Failed to release winUsb named Mutex! LastError: " + GetLastError());
992  }
993  }
994 
996  {
997  close();
998  }
999 
1001  {
1002  if (_winusb_mutex != nullptr)
1003  {
1004  CloseHandle(_winusb_mutex);
1005  _winusb_mutex = nullptr;
1006  }
1007  }
1008 
1010  : runtime_error(generate_message(message).c_str())
1011  { }
1012 
1014  {
1015  std::stringstream ss;
1016  ss << message << " Last Error: " << last_error_string(GetLastError()) << std::endl;
1017  return ss.str();
1018  }
1019 
1021  {
1022  // TODO: Error handling
1023  LPSTR messageBuffer = nullptr;
1024  size_t size = FormatMessageA(FORMAT_MESSAGE_ALLOCATE_BUFFER | FORMAT_MESSAGE_FROM_SYSTEM | FORMAT_MESSAGE_IGNORE_INSERTS,
1025  nullptr, lastError, MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT), reinterpret_cast<LPSTR>(&messageBuffer), 0, nullptr);
1026 
1027  std::string message(messageBuffer, size);
1028 
1029  LocalFree(messageBuffer);
1030 
1031  return message;
1032  }
1033  }
1034 }
#define CREATE_MUTEX_RETRY_NUM
Definition: win-helpers.cpp:41
GLenum GLuint GLenum GLsizei const GLchar * message
GLuint GLuint end
std::istringstream istringstream
Definition: Arg.h:43
static event_base * wait_any(const std::vector< event_base * > &events, int timeout)
GLuint const GLchar * name
GLint i1
GLdouble s
bool parse_usb_path_from_device_id(uint16_t &vid, uint16_t &pid, uint16_t &mi, std::string &unique_id, const std::string &device_id)
std::tuple< std::string, usb_spec > handle_usb_hub(const std::wstring &targetKey, const std::wstring &path)
GLuint64 GLenum void * handle
Definition: glext.h:7785
GLint location
GLsizei const GLchar *const * path
Definition: glext.h:4276
GLfloat value
bool get_id(DEVINST devinst, std::string *p_out_str)
std::string win_to_utf(const WCHAR *s)
Definition: win-helpers.cpp:94
size_t vector_bytes_size(const typename std::vector< T > &vec)
Definition: win-helpers.cpp:48
unsigned short uint16_t
Definition: stdint.h:79
GLsizei const GLchar *const * string
PSECURITY_DESCRIPTOR make_allow_all_security_descriptor(void)
static cm_node from_instance_id(std::wstring const &instance_id)
GLfloat GLfloat GLfloat GLfloat h
Definition: glext.h:1960
GLenum GLfloat * buffer
GLenum GLuint id
GLuint index
GLenum GLuint GLenum GLsizei const GLchar * buf
GLenum GLsizei len
Definition: glext.h:3285
GLuint64 key
Definition: glext.h:8966
def info(name, value, persistent=False)
Definition: test.py:301
not_this_one begin(...)
std::string get_uid() const
GLsizeiptr size
bool get_usb_device_descriptors(DEVINST devinst, uint16_t device_vid, uint16_t device_pid, const std::string &device_uid, std::string &location, usb_spec &spec, std::string &serial, std::string &parent_uid)
GLdouble x
DEFINE_GUID(GUID_DEVINTERFACE_USB_DEVICE, 0xA5DCBF10L, 0x6530, 0x11D2, 0x90, 0x1F, 0x00, 0xC0, 0x4F, 0xB9, 0x51, 0xED)
bool handle_node(const std::wstring &targetKey, HANDLE h, ULONG index)
std::vector< std::string > tokenize(std::string string, char separator)
#define MAX_HANDLES
std::string hr_to_string(HRESULT hr)
Definition: win-helpers.cpp:54
static std::string last_error_string(DWORD lastError)
std::string get_id() const
ULONG(__stdcall * fnRtlGetVersion)(PRTL_OSVERSIONINFOW lpVersionInformation)
Definition: win-helpers.cpp:63
bool parse_usb_path_single_interface(uint16_t &vid, uint16_t &pid, std::string &serial, const std::string &path)
#define LOG_ERROR(...)
Definition: src/types.h:242
bool parse_usb_path_multiple_interface(uint16_t &vid, uint16_t &pid, uint16_t &mi, std::string &unique_id, const std::string &path, std::string &device_guid)
virtual bool wait(DWORD timeout) const
const std::map< std::string, usb_class > guids
static event_base * wait_all(const std::vector< event_base * > &events, int timeout)
std::wstring instance_id_from_device_path(LPCWSTR path)
named_mutex(const std::string &device_path, unsigned timeout)
create_and_open_status create_named_mutex(const char *camID)
std::wstring get_path(HANDLE h, ULONG index)
std::string get_property(DEVPROPKEY const &property) const
GLbitfield GLuint64 timeout
GLenum type
bool check(const char *call, HRESULT hr, bool to_throw)
Definition: win-helpers.cpp:79
#define TRUE
Definition: tinycthread.c:50
int i
GLuint res
Definition: glext.h:8856
static std::string generate_message(const std::string &message)
GLuint GLenum GLenum transform
Definition: glext.h:11553
#define LOG_DEBUG(...)
Definition: src/types.h:239
GLuint * ids
#define FALSE
Definition: tinycthread.c:53
GLint GLint i2
create_and_open_status open_named_mutex(const char *camID)
bool get_usb_descriptors(uint16_t device_vid, uint16_t device_pid, const std::string &device_uid, std::string &location, usb_spec &spec, std::string &serial)
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:50:23