00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <openni_camera/openni_driver.h>
00038 #include <openni_camera/openni_device_kinect.h>
00039 #include <openni_camera/openni_device_primesense.h>
00040 #include <openni_camera/openni_device_xtion.h>
00041 #include <sstream>
00042 #include <iostream>
00043 #include <algorithm>
00044 #include <locale>
00045 #include <cctype>
00046 #include <map>
00047
00048 #ifndef _WIN32
00049 #include <libusb-1.0/libusb.h>
00050 #else
00051 #include <boost/tokenizer.hpp>
00052 #endif
00053
00054 using namespace std;
00055 using namespace boost;
00056
00057 namespace openni_wrapper
00058 {
00059
00060 OpenNIDriver::OpenNIDriver () throw (OpenNIException)
00061 {
00062
00063 XnStatus status = context_.Init ();
00064 if (status != XN_STATUS_OK)
00065 THROW_OPENNI_EXCEPTION ("initialization failed. Reason: %s", xnGetStatusString (status));
00066
00067 updateDeviceList ();
00068 }
00069
00070 unsigned OpenNIDriver::updateDeviceList () throw ()
00071 {
00072
00073 device_context_.clear ();
00074
00075 bus_map_.clear ();
00076 serial_map_.clear ();
00077 connection_string_map_.clear ();
00078
00079
00080 static xn::NodeInfoList node_info_list;
00081 XnStatus status = context_.EnumerateProductionTrees (XN_NODE_TYPE_DEVICE, NULL, node_info_list);
00082 if (status != XN_STATUS_OK && node_info_list.Begin () != node_info_list.End ())
00083 THROW_OPENNI_EXCEPTION ("enumerating devices failed. Reason: %s", xnGetStatusString (status));
00084 else if (node_info_list.Begin () == node_info_list.End ())
00085 return 0;
00086
00087 for (xn::NodeInfoList::Iterator nodeIt = node_info_list.Begin (); nodeIt != node_info_list.End (); ++nodeIt)
00088 {
00089 connection_string_map_[(*nodeIt).GetCreationInfo ()] = device_context_.size();
00090 device_context_.push_back (DeviceContext (*nodeIt));
00091 }
00092
00093
00094 static xn::NodeInfoList depth_nodes;
00095 status = context_.EnumerateProductionTrees (XN_NODE_TYPE_DEPTH, NULL, depth_nodes, NULL);
00096 if (status != XN_STATUS_OK)
00097 THROW_OPENNI_EXCEPTION ("enumerating depth generators failed. Reason: %s", xnGetStatusString (status));
00098
00099 for (xn::NodeInfoList::Iterator nodeIt = depth_nodes.Begin (); nodeIt != depth_nodes.End (); ++nodeIt)
00100 {
00101
00102 for (xn::NodeInfoList::Iterator neededIt = (*nodeIt).GetNeededNodes ().Begin (); neededIt != (*nodeIt).GetNeededNodes ().End (); ++neededIt)
00103 {
00104 if ( connection_string_map_.count ((*neededIt).GetCreationInfo ()) )
00105 {
00106 unsigned device_index = connection_string_map_[(*neededIt).GetCreationInfo ()];
00107 device_context_[device_index].depth_node.reset (new xn::NodeInfo(*nodeIt));
00108 }
00109 }
00110 }
00111
00112
00113 static xn::NodeInfoList image_nodes;
00114 status = context_.EnumerateProductionTrees (XN_NODE_TYPE_IMAGE, NULL, image_nodes, NULL);
00115 if (status != XN_STATUS_OK)
00116 THROW_OPENNI_EXCEPTION ("enumerating image generators failed. Reason: %s", xnGetStatusString (status));
00117
00118 for (xn::NodeInfoList::Iterator nodeIt = image_nodes.Begin (); nodeIt != image_nodes.End (); ++nodeIt)
00119 {
00120
00121 for (xn::NodeInfoList::Iterator neededIt = (*nodeIt).GetNeededNodes ().Begin (); neededIt != (*nodeIt).GetNeededNodes ().End (); ++neededIt)
00122 {
00123 if ( connection_string_map_.count ((*neededIt).GetCreationInfo ()) )
00124 {
00125 unsigned device_index = connection_string_map_[(*neededIt).GetCreationInfo ()];
00126 device_context_[device_index].image_node.reset (new xn::NodeInfo(*nodeIt));
00127 }
00128 }
00129 }
00130
00131
00132 static xn::NodeInfoList ir_nodes;
00133 status = context_.EnumerateProductionTrees (XN_NODE_TYPE_IR, NULL, ir_nodes, NULL);
00134 if (status != XN_STATUS_OK)
00135 THROW_OPENNI_EXCEPTION ("enumerating IR generators failed. Reason: %s", xnGetStatusString (status));
00136
00137 for (xn::NodeInfoList::Iterator nodeIt = ir_nodes.Begin (); nodeIt != ir_nodes.End (); ++nodeIt)
00138 {
00139
00140 for (xn::NodeInfoList::Iterator neededIt = (*nodeIt).GetNeededNodes ().Begin (); neededIt != (*nodeIt).GetNeededNodes ().End (); ++neededIt)
00141 {
00142 if ( connection_string_map_.count ((*neededIt).GetCreationInfo ()) )
00143 {
00144 unsigned device_index = connection_string_map_[(*neededIt).GetCreationInfo ()];
00145 device_context_[device_index].ir_node.reset (new xn::NodeInfo(*nodeIt));
00146 }
00147 }
00148 }
00149
00150 #ifndef _WIN32
00151
00152 for (unsigned deviceIdx = 0; deviceIdx < device_context_.size (); ++deviceIdx)
00153 {
00154
00155 unsigned short vendor_id;
00156 unsigned short product_id;
00157 unsigned char bus;
00158 unsigned char address;
00159 sscanf (device_context_[deviceIdx].device_node.GetCreationInfo (), "%hx/%hx@%hhu/%hhu", &vendor_id, &product_id, &bus, &address);
00160 bus_map_ [bus][address] = deviceIdx;
00161 }
00162
00163
00164 getDeviceInfos ();
00165
00166 for (unsigned deviceIdx = 0; deviceIdx < device_context_.size (); ++deviceIdx)
00167 {
00168 std::string serial_number = getSerialNumber (deviceIdx);
00169 if (!serial_number.empty ())
00170 serial_map_[serial_number] = deviceIdx;
00171 }
00172
00173 #endif
00174
00175
00176 for (unsigned deviceIdx = 0; deviceIdx < device_context_.size (); ++deviceIdx)
00177 {
00178 unsigned short product_id;
00179 unsigned short vendor_id;
00180
00181 getDeviceType(device_context_[deviceIdx].device_node.GetCreationInfo (), vendor_id, product_id );
00182
00183 #if _WIN32
00184 if (vendor_id == 0x45e)
00185 {
00186 strcpy ((char*)device_context_[deviceIdx].device_node.GetDescription().strVendor, "Microsoft");
00187 strcpy ((char*)device_context_[deviceIdx].device_node.GetDescription().strName, "Xbox NUI Camera");
00188 }
00189 else
00190 #endif
00191 if (vendor_id == 0x1d27 && device_context_[deviceIdx].image_node.get () == 0)
00192 {
00193 strcpy ((char*)device_context_[deviceIdx].device_node.GetDescription().strVendor, "ASUS");
00194 strcpy ((char*)device_context_[deviceIdx].device_node.GetDescription().strName, "Xtion Pro");
00195 }
00196 }
00197 return (device_context_.size ());
00198 }
00199
00200 void OpenNIDriver::stopAll () throw (OpenNIException)
00201 {
00202 XnStatus status = context_.StopGeneratingAll ();
00203 if (status != XN_STATUS_OK)
00204 THROW_OPENNI_EXCEPTION ("stopping all streams failed. Reason: %s", xnGetStatusString (status));
00205 }
00206
00207 OpenNIDriver::~OpenNIDriver () throw ()
00208 {
00209
00210 try
00211 {
00212 stopAll ();
00213 }
00214 catch (...)
00215 {
00216 }
00217
00218 context_.Shutdown ();
00219 }
00220
00221 boost::shared_ptr<OpenNIDevice> OpenNIDriver::getDeviceByIndex (unsigned index) const throw (OpenNIException)
00222 {
00223 using namespace std;
00224
00225 if (index >= device_context_.size ())
00226 THROW_OPENNI_EXCEPTION ("device index out of range. only %d devices connected but device %d requested.", device_context_.size (), index);
00227 boost::shared_ptr<OpenNIDevice> device = device_context_[index].device.lock ();
00228 if (!device)
00229 {
00230 unsigned short vendor_id;
00231 unsigned short product_id;
00232 getDeviceType (device_context_[index].device_node.GetCreationInfo (), vendor_id, product_id );
00233
00234 if (vendor_id == 0x45e)
00235 {
00236 device = boost::shared_ptr<OpenNIDevice > (new DeviceKinect (context_, device_context_[index].device_node,
00237 *device_context_[index].image_node, *device_context_[index].depth_node,
00238 *device_context_[index].ir_node));
00239 device_context_[index].device = device;
00240 }
00241 else if (vendor_id == 0x1d27)
00242 {
00243 if (device_context_[index].image_node.get())
00244 device = boost::shared_ptr<OpenNIDevice > (new DevicePrimesense (context_, device_context_[index].device_node,
00245 *device_context_[index].image_node, *device_context_[index].depth_node,
00246 *device_context_[index].ir_node));
00247 else
00248 device = boost::shared_ptr<OpenNIDevice > (new DeviceXtionPro (context_, device_context_[index].device_node,
00249 *device_context_[index].depth_node, *device_context_[index].ir_node));
00250 device_context_[index].device = device;
00251 }
00252 else
00253 {
00254 THROW_OPENNI_EXCEPTION ("vendor %s (%s) known by primesense driver, but not by ros driver. Contact maintainer of the ros driver.",
00255 getVendorName (index), vendor_id);
00256 }
00257 }
00258 return (device);
00259 }
00260
00261 #ifndef _WIN32
00262 boost::shared_ptr<OpenNIDevice>
00263 OpenNIDriver::getDeviceBySerialNumber (const std::string& serial_number) const throw (OpenNIException)
00264 {
00265 std::map<std::string, unsigned>::const_iterator it = serial_map_.find (serial_number);
00266
00267 if (it != serial_map_.end ())
00268 {
00269 return getDeviceByIndex (it->second);
00270 }
00271
00272 THROW_OPENNI_EXCEPTION ("No device with serial number \'%s\' found", serial_number.c_str ());
00273
00274
00275 return (boost::shared_ptr<OpenNIDevice > ((OpenNIDevice*)NULL));
00276 }
00277
00278 boost::shared_ptr<OpenNIDevice>
00279 OpenNIDriver::getDeviceByAddress (unsigned char bus, unsigned char address) const throw (OpenNIException)
00280 {
00281 std::map<unsigned char, std::map<unsigned char, unsigned> >::const_iterator busIt = bus_map_.find (bus);
00282 if (busIt != bus_map_.end ())
00283 {
00284 std::map<unsigned char, unsigned>::const_iterator devIt = busIt->second.find (address);
00285 if (devIt != busIt->second.end ())
00286 {
00287 return getDeviceByIndex (devIt->second);
00288 }
00289 }
00290
00291 THROW_OPENNI_EXCEPTION ("No device on bus: %d @ %d found", (int)bus, (int)address);
00292
00293
00294 return (boost::shared_ptr<OpenNIDevice > ((OpenNIDevice*)NULL));
00295 }
00296
00297 void
00298 OpenNIDriver::getDeviceInfos () throw ()
00299 {
00300 libusb_context *context = NULL;
00301 int result;
00302 result = libusb_init (&context);
00303
00304 if (result < 0)
00305 return;
00306
00307 libusb_device **devices;
00308 int count = libusb_get_device_list (context, &devices);
00309 if (count < 0)
00310 return;
00311
00312 for (int devIdx = 0; devIdx < count; ++devIdx)
00313 {
00314 libusb_device* device = devices[devIdx];
00315 uint8_t busId = libusb_get_bus_number (device);
00316 std::map<unsigned char, std::map<unsigned char, unsigned> >::const_iterator busIt = bus_map_.find (busId);
00317 if (busIt == bus_map_.end ())
00318 continue;
00319
00320 uint8_t address = libusb_get_device_address (device);
00321 std::map<unsigned char, unsigned>::const_iterator addressIt = busIt->second.find (address);
00322 if (addressIt == busIt->second.end ())
00323 continue;
00324
00325 unsigned nodeIdx = addressIt->second;
00326 xn::NodeInfo& current_node = device_context_[nodeIdx].device_node;
00327 XnProductionNodeDescription& description = const_cast<XnProductionNodeDescription&>(current_node.GetDescription ());
00328
00329 libusb_device_descriptor descriptor;
00330 result = libusb_get_device_descriptor (devices[devIdx], &descriptor);
00331
00332 if (result < 0)
00333 {
00334 strcpy (description.strVendor, "unknown");
00335 strcpy (description.strName, "unknown");
00336 current_node.SetInstanceName ("");
00337 }
00338 else
00339 {
00340 libusb_device_handle* dev_handle;
00341 result = libusb_open (device, &dev_handle);
00342 if (result < 0)
00343 {
00344 strcpy (description.strVendor, "unknown");
00345 strcpy (description.strName, "unknown");
00346 current_node.SetInstanceName ("");
00347 }
00348 else
00349 {
00350 unsigned char buffer[1024];
00351 libusb_get_string_descriptor_ascii (dev_handle, descriptor.iManufacturer, buffer, 1024);
00352 strcpy (description.strVendor, (char*)buffer);
00353
00354 libusb_get_string_descriptor_ascii (dev_handle, descriptor.iProduct, buffer, 1024);
00355 strcpy (description.strName, (char*)buffer);
00356
00357 int len = libusb_get_string_descriptor_ascii (dev_handle, descriptor.iSerialNumber, buffer, 1024);
00358 if (len > 4)
00359 current_node.SetInstanceName ((char*)buffer);
00360 else
00361 current_node.SetInstanceName ("");
00362
00363 libusb_close (dev_handle);
00364 }
00365 }
00366 }
00367 libusb_free_device_list (devices, 1);
00368 libusb_exit (context);
00369 }
00370 #endif
00371
00372 const char* OpenNIDriver::getSerialNumber (unsigned index) const throw ()
00373 {
00374 #ifndef _WIN32
00375 return device_context_[index].device_node.GetInstanceName ();
00376 #else
00377 return "";
00378 #endif
00379 }
00380
00381 void OpenNIDriver::getDeviceType (const std::string& connectionString, unsigned short& vendorId, unsigned short& productId)
00382 {
00383 #if _WIN32
00384
00385 typedef boost::tokenizer<boost::char_separator<char> > tokenizer;
00386 boost::char_separator<char> separators("#&_");
00387 tokenizer tokens(connectionString, separators);
00388
00389 unsigned int tokenIndex = 0;
00390 for (tokenizer::iterator tok_iter = tokens.begin(); tok_iter != tokens.end(); ++tok_iter, tokenIndex++)
00391 {
00392 std::string tokenValue = *tok_iter;
00393
00394 switch(tokenIndex) {
00395 case 2:
00396 sscanf(tokenValue.c_str(), "%hx", &vendorId);
00397 break;
00398 case 4:
00399 sscanf(tokenValue.c_str(), "%hx", &productId);
00400 break;
00401 }
00402 }
00403 #else
00404 unsigned char bus;
00405 unsigned char address;
00406 sscanf (connectionString.c_str(), "%hx/%hx@%hhu/%hhu", &vendorId, &productId, &bus, &address);
00407 #endif
00408 }
00409
00410 const char* OpenNIDriver::getConnectionString (unsigned index) const throw ()
00411 {
00412 return device_context_[index].device_node.GetCreationInfo ();
00413 }
00414
00415 const char* OpenNIDriver::getVendorName (unsigned index) const throw ()
00416 {
00417 return device_context_[index].device_node.GetDescription ().strVendor;
00418 }
00419
00420 const char* OpenNIDriver::getProductName (unsigned index) const throw ()
00421 {
00422 return device_context_[index].device_node.GetDescription ().strName;
00423 }
00424
00425 unsigned short OpenNIDriver::getVendorID (unsigned index) const throw ()
00426 {
00427 unsigned short vendor_id;
00428 unsigned short product_id;
00429 #ifndef _WIN32
00430 unsigned char bus;
00431 unsigned char address;
00432 sscanf (device_context_[index].device_node.GetCreationInfo (), "%hx/%hx@%hhu/%hhu", &vendor_id, &product_id, &bus, &address);
00433
00434 #else
00435 getDeviceType (device_context_[index].device_node.GetCreationInfo (), vendor_id, product_id);
00436 #endif
00437 return vendor_id;
00438 }
00439
00440 unsigned short OpenNIDriver::getProductID (unsigned index) const throw ()
00441 {
00442 unsigned short vendor_id;
00443 unsigned short product_id;
00444 #ifndef _WIN32
00445 unsigned char bus;
00446 unsigned char address;
00447 sscanf (device_context_[index].device_node.GetCreationInfo (), "%hx/%hx@%hhu/%hhu", &vendor_id, &product_id, &bus, &address);
00448
00449 #else
00450 getDeviceType (device_context_[index].device_node.GetCreationInfo (), vendor_id, product_id);
00451 #endif
00452 return product_id;
00453 }
00454
00455 unsigned char OpenNIDriver::getBus (unsigned index) const throw ()
00456 {
00457 unsigned char bus = 0;
00458 #ifndef _WIN32
00459 unsigned short vendor_id;
00460 unsigned short product_id;
00461 unsigned char address;
00462 sscanf (device_context_[index].device_node.GetCreationInfo (), "%hx/%hx@%hhu/%hhu", &vendor_id, &product_id, &bus, &address);
00463 #endif
00464 return bus;
00465 }
00466
00467 unsigned char OpenNIDriver::getAddress (unsigned index) const throw ()
00468 {
00469 unsigned char address = 0;
00470 #ifndef _WIN32
00471 unsigned short vendor_id;
00472 unsigned short product_id;
00473 unsigned char bus;
00474 sscanf (device_context_[index].device_node.GetCreationInfo (), "%hx/%hx@%hhu/%hhu", &vendor_id, &product_id, &bus, &address);
00475 #endif
00476 return address;
00477 }
00478
00479 OpenNIDriver::DeviceContext::DeviceContext (const xn::NodeInfo& device, xn::NodeInfo* image, xn::NodeInfo* depth, xn::NodeInfo* ir)
00480 : device_node (device)
00481 , image_node (image)
00482 , depth_node (depth)
00483 , ir_node (ir)
00484 {
00485 }
00486
00487 OpenNIDriver::DeviceContext::DeviceContext (const xn::NodeInfo& device)
00488 : device_node (device)
00489 , image_node ((xn::NodeInfo*)0)
00490 , depth_node ((xn::NodeInfo*)0)
00491 , ir_node ((xn::NodeInfo*)0)
00492 {
00493 }
00494
00495 OpenNIDriver::DeviceContext::DeviceContext (const DeviceContext& other)
00496 : device_node (other.device_node)
00497 , image_node (other.image_node)
00498 , depth_node (other.depth_node)
00499 , ir_node (other.ir_node)
00500 , device (other.device)
00501 {
00502 }
00503
00504 }