50 #include <libusb-1.0/libusb.h>    52 #include <boost/tokenizer.hpp>    56 using namespace boost;
    64   XnStatus 
status = context_.Init ();
    65   if (status != XN_STATUS_OK)
    71 unsigned OpenNIDriver::updateDeviceList () throw ()
    74   device_context_.clear ();
    78   connection_string_map_.clear ();
    81   static xn::NodeInfoList node_info_list;
    82   XnStatus 
status = context_.EnumerateProductionTrees (XN_NODE_TYPE_DEVICE, NULL, node_info_list);
    83   if (status != XN_STATUS_OK && node_info_list.Begin () != node_info_list.End ())
    85   else if (node_info_list.Begin () == node_info_list.End ())
    88   for (xn::NodeInfoList::Iterator nodeIt = node_info_list.Begin (); nodeIt != node_info_list.End (); ++nodeIt)
    90     connection_string_map_[(*nodeIt).GetCreationInfo ()] = device_context_.size();
    95   static xn::NodeInfoList depth_nodes;
    96   status = context_.EnumerateProductionTrees (XN_NODE_TYPE_DEPTH, NULL, depth_nodes, NULL);
    97   if (status != XN_STATUS_OK)
   100   for (xn::NodeInfoList::Iterator nodeIt = depth_nodes.Begin (); nodeIt != depth_nodes.End (); ++nodeIt)
   103     for (xn::NodeInfoList::Iterator neededIt = (*nodeIt).GetNeededNodes ().Begin (); neededIt != (*nodeIt).GetNeededNodes ().End (); ++neededIt)
   105       if ( connection_string_map_.count ((*neededIt).GetCreationInfo ()) )
   107         unsigned device_index = connection_string_map_[(*neededIt).GetCreationInfo ()];
   108         device_context_[device_index].depth_node.reset (
new xn::NodeInfo(*nodeIt));
   114   static xn::NodeInfoList image_nodes;
   115   static xn::EnumerationErrors enumeration_errors;
   116   status = context_.EnumerateProductionTrees (XN_NODE_TYPE_IMAGE, NULL, image_nodes, &enumeration_errors);
   117   if (status != XN_STATUS_OK)
   122     if((enumeration_errors.Begin()).
Error() != 65565) {
   123       XnChar strError[1024];
   124       enumeration_errors.ToString(strError, 1024);
   129   for (xn::NodeInfoList::Iterator nodeIt = image_nodes.Begin (); nodeIt != image_nodes.End (); ++nodeIt)
   132       for (xn::NodeInfoList::Iterator neededIt = (*nodeIt).GetNeededNodes ().Begin (); neededIt != (*nodeIt).GetNeededNodes ().End (); ++neededIt)
   134           if ( connection_string_map_.count ((*neededIt).GetCreationInfo ()) )
   136               unsigned device_index = connection_string_map_[(*neededIt).GetCreationInfo ()];
   137               device_context_[device_index].image_node.reset (
new xn::NodeInfo(*nodeIt));
   143   static xn::NodeInfoList ir_nodes;
   144   status = context_.EnumerateProductionTrees (XN_NODE_TYPE_IR, NULL, ir_nodes, NULL);
   145   if (status != XN_STATUS_OK)
   148   for (xn::NodeInfoList::Iterator nodeIt = ir_nodes.Begin (); nodeIt != ir_nodes.End (); ++nodeIt)
   151     for (xn::NodeInfoList::Iterator neededIt = (*nodeIt).GetNeededNodes ().Begin (); neededIt != (*nodeIt).GetNeededNodes ().End (); ++neededIt)
   153       if ( connection_string_map_.count ((*neededIt).GetCreationInfo ()) )
   155         unsigned device_index = connection_string_map_[(*neededIt).GetCreationInfo ()];
   156         device_context_[device_index].ir_node.reset (
new xn::NodeInfo(*nodeIt));
   163   for (
unsigned deviceIdx = 0; deviceIdx < device_context_.size (); ++deviceIdx)
   166     unsigned short vendor_id;
   167     unsigned short product_id;
   169     unsigned char address;
   170     sscanf (device_context_[deviceIdx].device_node.GetCreationInfo (), 
"%hx/%hx@%hhu/%hhu", &vendor_id, &product_id, &bus, &address);
   171     bus_map_ [bus][address] = deviceIdx;
   177   for (
unsigned deviceIdx = 0; deviceIdx < device_context_.size (); ++deviceIdx)
   179     std::string serial_number = getSerialNumber (deviceIdx);
   180     if (!serial_number.empty ())
   181       serial_map_[serial_number] = deviceIdx;
   187   for (
unsigned deviceIdx = 0; deviceIdx < device_context_.size (); ++deviceIdx)
   189     unsigned short product_id;
   190     unsigned short vendor_id;
   192     getDeviceType(device_context_[deviceIdx].device_node.GetCreationInfo (), vendor_id, product_id );
   195     if (vendor_id == 0x45e)
   197       strcpy ((
char*)device_context_[deviceIdx].device_node.GetDescription().strVendor, 
"Microsoft");
   198       strcpy ((
char*)device_context_[deviceIdx].device_node.GetDescription().strName, 
"Xbox NUI Camera");
   202     if (vendor_id == 0x1d27 && device_context_[deviceIdx].image_node.get () == 0)
   204       strcpy ((
char*)device_context_[deviceIdx].device_node.GetDescription().strVendor, 
"ASUS");
   205       strcpy ((
char*)device_context_[deviceIdx].device_node.GetDescription().strName, 
"Xtion Pro");
   208   return (device_context_.size ());
   213   XnStatus 
status = context_.StopGeneratingAll ();
   214   if (status != XN_STATUS_OK)
   218 OpenNIDriver::~OpenNIDriver () throw ()
   229   context_.Shutdown ();
   237 void OpenNIDriver::getPrimesenseSerial(xn::NodeInfo info, 
char* buffer, 
unsigned buf_size) 
const throw () {
   239         context_.CreateProductionTree(info);
   242         if(info.GetInstance(device) != XN_STATUS_OK) {
   246         xn::DeviceIdentificationCapability d = device.GetIdentificationCap();
   248         d.GetSerialNumber(buffer,buf_size);
   257   if (index >= device_context_.size ())
   258     THROW_OPENNI_EXCEPTION (
"device index out of range. only %d devices connected but device %d requested.", device_context_.size (), index);
   262     unsigned short vendor_id;
   263     unsigned short product_id;
   264     getDeviceType (device_context_[index].device_node.GetCreationInfo (), vendor_id, product_id );
   266     if (vendor_id == 0x45e)
   269                                                                    *device_context_[index].image_node, *device_context_[index].depth_node,
   270                                                                    *device_context_[index].ir_node));
   271       device_context_[index].device = device;
   273     else if (vendor_id == 0x1d27)
   275       if (device_context_[index].image_node.get())
   277                                                                          *device_context_[index].image_node, *device_context_[index].depth_node,
   278                                                                          *device_context_[index].ir_node));
   281                                                                        *device_context_[index].depth_node, *device_context_[index].ir_node));
   282       device_context_[index].device = device;
   286       THROW_OPENNI_EXCEPTION (
"vendor %s (%s) known by primesense driver, but not by ros driver. Contact maintainer of the ros driver.",
   287                               getVendorName (index), vendor_id);
   295 OpenNIDriver::getDeviceBySerialNumber (
const std::string& serial_number) 
const throw (
OpenNIException)
   297   std::map<std::string, unsigned>::const_iterator it = serial_map_.find (serial_number);
   299   if (it != serial_map_.end ())
   301     return getDeviceByIndex (it->second);
   311 OpenNIDriver::getDeviceByAddress (
unsigned char bus, 
unsigned char address) 
const throw (
OpenNIException)
   313   std::map<unsigned char, std::map<unsigned char, unsigned> >::const_iterator busIt = bus_map_.find (bus);
   314   if (busIt != bus_map_.end ())
   316     std::map<unsigned char, unsigned>::const_iterator devIt;
   319       devIt = busIt->second.begin ();
   321       devIt = busIt->second.find (address);
   323     if (devIt != busIt->second.end ())
   325       return getDeviceByIndex (devIt->second);
   336 OpenNIDriver::getDeviceInfos () throw ()
   338   libusb_context *context = NULL;
   340   result = libusb_init (&context); 
   345   libusb_device **devices;
   346   int count = libusb_get_device_list (context, &devices);
   350   for (
int devIdx = 0; devIdx < count; ++devIdx)
   352     libusb_device* device = devices[devIdx];
   353     uint8_t busId = libusb_get_bus_number (device);
   354     std::map<unsigned char, std::map<unsigned char, unsigned> >::const_iterator busIt = bus_map_.find (busId);
   355     if (busIt == bus_map_.end ())
   358     uint8_t address = libusb_get_device_address (device);
   359     std::map<unsigned char, unsigned>::const_iterator addressIt = busIt->second.find (address);
   360     if (addressIt == busIt->second.end ())
   363     unsigned nodeIdx = addressIt->second;
   364     xn::NodeInfo& current_node = device_context_[nodeIdx].device_node;
   366     libusb_device_descriptor descriptor;
   367     result = libusb_get_device_descriptor (devices[devIdx], &descriptor);
   371       current_node.SetInstanceName (
"");
   375       libusb_device_handle* dev_handle;
   376       result = libusb_open (device, &dev_handle);
   379         current_node.SetInstanceName (
"");
   383         unsigned char buffer[1024];
   385         int len = libusb_get_string_descriptor_ascii (dev_handle, descriptor.iSerialNumber, buffer, 1024);
   387           current_node.SetInstanceName ((
char*)buffer);
   389           current_node.SetInstanceName (
"");
   391         libusb_close (dev_handle);
   395   libusb_free_device_list (devices, 1);
   396   libusb_exit (context);
   400 const char* OpenNIDriver::getSerialNumber (
unsigned index) 
const throw ()
   405     const char* openni_serial = con.
device_node.GetInstanceName ();
   407     if (strlen(openni_serial)>0 && strcmp(openni_serial, 
"Device1")) {
   408         return openni_serial;
   410         char *primesense_serial = (
char*)malloc(XN_MAX_NAME_LENGTH); 
   411         getPrimesenseSerial(con.
device_node, primesense_serial, XN_MAX_NAME_LENGTH);
   413         return primesense_serial;
   421 void OpenNIDriver::getDeviceType (
const std::string& connectionString, 
unsigned short& vendorId, 
unsigned short& productId)
   425     typedef boost::tokenizer<boost::char_separator<char> > tokenizer;
   426     boost::char_separator<char> separators(
"#&_");
   427     tokenizer tokens(connectionString, separators);
   429     unsigned int tokenIndex = 0;
   430     for (tokenizer::iterator tok_iter = tokens.begin(); tok_iter != tokens.end(); ++tok_iter, tokenIndex++)
   432         std::string tokenValue = *tok_iter;
   436                 sscanf(tokenValue.c_str(), 
"%hx", &vendorId);
   439                 sscanf(tokenValue.c_str(), 
"%hx", &productId);
   445     unsigned char address;
   446     sscanf (connectionString.c_str(), 
"%hx/%hx@%hhu/%hhu", &vendorId, &productId, &bus, &address);
   450 const char* OpenNIDriver::getConnectionString (
unsigned index) 
const throw ()
   452   return device_context_[index].device_node.GetCreationInfo ();
   455 const char* OpenNIDriver::getVendorName (
unsigned index) 
const throw ()
   457   return device_context_[index].device_node.GetDescription ().strVendor;
   460 const char* OpenNIDriver::getProductName (
unsigned index) 
const throw ()
   462   return device_context_[index].device_node.GetDescription ().strName;
   465 unsigned short OpenNIDriver::getVendorID (
unsigned index) 
const throw ()
   467   unsigned short vendor_id;
   468   unsigned short product_id;
   471   unsigned char address;
   472   sscanf (device_context_[index].device_node.GetCreationInfo (), 
"%hx/%hx@%hhu/%hhu", &vendor_id, &product_id, &bus, &address);
   475   getDeviceType (device_context_[index].device_node.GetCreationInfo (), vendor_id, product_id);
   480 unsigned short OpenNIDriver::getProductID (
unsigned index) 
const throw ()
   482   unsigned short vendor_id;
   483   unsigned short product_id;
   486   unsigned char address;
   487   sscanf (device_context_[index].device_node.GetCreationInfo (), 
"%hx/%hx@%hhu/%hhu", &vendor_id, &product_id, &bus, &address);
   490   getDeviceType (device_context_[index].device_node.GetCreationInfo (), vendor_id, product_id);
   495 unsigned char OpenNIDriver::getBus (
unsigned index) 
const throw ()
   497   unsigned char bus = 0;
   499   unsigned short vendor_id;
   500   unsigned short product_id;
   501   unsigned char address;
   502   sscanf (device_context_[index].device_node.GetCreationInfo (), 
"%hx/%hx@%hhu/%hhu", &vendor_id, &product_id, &bus, &address);
   507 unsigned char OpenNIDriver::getAddress (
unsigned index) 
const throw ()
   509   unsigned char address = 0;
   511   unsigned short vendor_id;
   512   unsigned short product_id;
   514   sscanf (device_context_[index].device_node.GetCreationInfo (), 
"%hx/%hx@%hhu/%hhu", &vendor_id, &product_id, &bus, &address);
   519 OpenNIDriver::DeviceContext::DeviceContext (
const xn::NodeInfo& device, xn::NodeInfo* image, xn::NodeInfo* depth, xn::NodeInfo* ir)
   520 : device_node (device)
 
boost::weak_ptr< OpenNIDevice > device
#define THROW_OPENNI_EXCEPTION(format,...)
boost::shared_ptr< xn::NodeInfo > image_node
Concrete implementation of the interface OpenNIDevice for a Primesense device. 
Concrete implementation of the interface OpenNIDevice for a MS Kinect device. 
Concrete implementation of the interface OpenNIDevice for a Asus Xtion Pro device. 
boost::shared_ptr< xn::NodeInfo > ir_node
Concrete implementation of the interface OpenNIDevice for a virtual device playing back an ONI file...
Class representing an astract device for Primesense or MS Kinect devices. 
boost::shared_ptr< xn::NodeInfo > depth_node
DeviceContext(const xn::NodeInfo &device_node, xn::NodeInfo *image_node, xn::NodeInfo *depth_node, xn::NodeInfo *ir_node)