$search
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2011 2011 Willow Garage, Inc. 00005 * Suat Gedikli <gedikli@willowgarage.com> 00006 * 00007 * All rights reserved. 00008 * 00009 * Redistribution and use in source and binary forms, with or without 00010 * modification, are permitted provided that the following conditions 00011 * are met: 00012 * 00013 * * Redistributions of source code must retain the above copyright 00014 * notice, this list of conditions and the following disclaimer. 00015 * * Redistributions in binary form must reproduce the above 00016 * copyright notice, this list of conditions and the following 00017 * disclaimer in the documentation and/or other materials provided 00018 * with the distribution. 00019 * * Neither the name of Willow Garage, Inc. nor the names of its 00020 * contributors may be used to endorse or promote products derived 00021 * from this software without specific prior written permission. 00022 * 00023 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00024 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00025 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00026 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00027 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00028 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00029 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00030 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00031 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00032 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00033 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00034 * POSSIBILITY OF SUCH DAMAGE. 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 <openni_camera/openni_device_oni.h> 00042 #include <sstream> 00043 #include <iostream> 00044 #include <algorithm> 00045 #include <locale> 00046 #include <cctype> 00047 #include <map> 00048 00049 #ifndef _WIN32 00050 #include <libusb-1.0/libusb.h> 00051 #else 00052 #include <boost/tokenizer.hpp> 00053 #endif 00054 00055 using namespace std; 00056 using namespace boost; 00057 00058 namespace openni_wrapper 00059 { 00060 00061 OpenNIDriver::OpenNIDriver () throw (OpenNIException) 00062 { 00063 // Initialize the Engine 00064 XnStatus status = context_.Init (); 00065 if (status != XN_STATUS_OK) 00066 THROW_OPENNI_EXCEPTION ("initialization failed. Reason: %s", xnGetStatusString (status)); 00067 00068 updateDeviceList (); 00069 } 00070 00071 unsigned OpenNIDriver::updateDeviceList () throw () 00072 { 00073 // clear current list of devices 00074 device_context_.clear (); 00075 // clear maps 00076 bus_map_.clear (); 00077 serial_map_.clear (); 00078 connection_string_map_.clear (); 00079 00080 // enumerate all devices 00081 static xn::NodeInfoList node_info_list; 00082 XnStatus status = context_.EnumerateProductionTrees (XN_NODE_TYPE_DEVICE, NULL, node_info_list); 00083 if (status != XN_STATUS_OK && node_info_list.Begin () != node_info_list.End ()) 00084 THROW_OPENNI_EXCEPTION ("enumerating devices failed. Reason: %s", xnGetStatusString (status)); 00085 else if (node_info_list.Begin () == node_info_list.End ()) 00086 return 0; // no exception 00087 00088 for (xn::NodeInfoList::Iterator nodeIt = node_info_list.Begin (); nodeIt != node_info_list.End (); ++nodeIt) 00089 { 00090 connection_string_map_[(*nodeIt).GetCreationInfo ()] = device_context_.size(); 00091 device_context_.push_back (DeviceContext (*nodeIt)); 00092 } 00093 00094 // enumerate depth nodes 00095 static xn::NodeInfoList depth_nodes; 00096 status = context_.EnumerateProductionTrees (XN_NODE_TYPE_DEPTH, NULL, depth_nodes, NULL); 00097 if (status != XN_STATUS_OK) 00098 THROW_OPENNI_EXCEPTION ("enumerating depth generators failed. Reason: %s", xnGetStatusString (status)); 00099 00100 for (xn::NodeInfoList::Iterator nodeIt = depth_nodes.Begin (); nodeIt != depth_nodes.End (); ++nodeIt) 00101 { 00102 // check if to which device this node is assigned to 00103 for (xn::NodeInfoList::Iterator neededIt = (*nodeIt).GetNeededNodes ().Begin (); neededIt != (*nodeIt).GetNeededNodes ().End (); ++neededIt) 00104 { 00105 if ( connection_string_map_.count ((*neededIt).GetCreationInfo ()) ) 00106 { 00107 unsigned device_index = connection_string_map_[(*neededIt).GetCreationInfo ()]; 00108 device_context_[device_index].depth_node.reset (new xn::NodeInfo(*nodeIt)); 00109 } 00110 } 00111 } 00112 00113 // enumerate image nodes 00114 static xn::NodeInfoList image_nodes; 00115 static xn::EnumerationErrors enumeration_errors; 00116 status = context_.EnumerateProductionTrees (XN_NODE_TYPE_IMAGE, NULL, image_nodes, &enumeration_errors); 00117 00118 00119 // Suat: This is an ugly ASUS Xtion workaround. 00120 if (status == XN_STATUS_OK) 00121 { 00122 //THROW_OPENNI_EXCEPTION ("enumerating image generators failed. Reason: %s", xnGetStatusString (status)); 00123 00124 for (xn::NodeInfoList::Iterator nodeIt = image_nodes.Begin (); nodeIt != image_nodes.End (); ++nodeIt) 00125 { 00126 // check to which device this node is assigned to 00127 for (xn::NodeInfoList::Iterator neededIt = (*nodeIt).GetNeededNodes ().Begin (); neededIt != (*nodeIt).GetNeededNodes ().End (); ++neededIt) 00128 { 00129 if ( connection_string_map_.count ((*neededIt).GetCreationInfo ()) ) 00130 { 00131 unsigned device_index = connection_string_map_[(*neededIt).GetCreationInfo ()]; 00132 device_context_[device_index].image_node.reset (new xn::NodeInfo(*nodeIt)); 00133 } 00134 } 00135 } 00136 } 00137 else { 00138 XnChar strError[1024]; 00139 enumeration_errors.ToString(strError, 1024); 00140 THROW_OPENNI_EXCEPTION( 00141 "enumerating image nodes failed (are the permissions set properly for the usb device?). Reason: %s", 00142 strError); 00143 } 00144 00145 // enumerate IR nodes 00146 static xn::NodeInfoList ir_nodes; 00147 status = context_.EnumerateProductionTrees (XN_NODE_TYPE_IR, NULL, ir_nodes, NULL); 00148 if (status != XN_STATUS_OK) 00149 THROW_OPENNI_EXCEPTION ("enumerating IR generators failed. Reason: %s", xnGetStatusString (status)); 00150 00151 for (xn::NodeInfoList::Iterator nodeIt = ir_nodes.Begin (); nodeIt != ir_nodes.End (); ++nodeIt) 00152 { 00153 // check if to which device this node is assigned to 00154 for (xn::NodeInfoList::Iterator neededIt = (*nodeIt).GetNeededNodes ().Begin (); neededIt != (*nodeIt).GetNeededNodes ().End (); ++neededIt) 00155 { 00156 if ( connection_string_map_.count ((*neededIt).GetCreationInfo ()) ) 00157 { 00158 unsigned device_index = connection_string_map_[(*neededIt).GetCreationInfo ()]; 00159 device_context_[device_index].ir_node.reset (new xn::NodeInfo(*nodeIt)); 00160 } 00161 } 00162 } 00163 00164 #ifndef _WIN32 00165 // add context object for each found device 00166 for (unsigned deviceIdx = 0; deviceIdx < device_context_.size (); ++deviceIdx) 00167 { 00168 // register bus@address to the corresponding context object 00169 unsigned short vendor_id; 00170 unsigned short product_id; 00171 unsigned char bus; 00172 unsigned char address; 00173 sscanf (device_context_[deviceIdx].device_node.GetCreationInfo (), "%hx/%hx@%hhu/%hhu", &vendor_id, &product_id, &bus, &address); 00174 bus_map_ [bus][address] = deviceIdx; 00175 } 00176 00177 // get additional info about connected devices like serial number, vendor name and prduct name 00178 getDeviceInfos (); 00179 // build serial number -> device index map 00180 for (unsigned deviceIdx = 0; deviceIdx < device_context_.size (); ++deviceIdx) 00181 { 00182 std::string serial_number = getSerialNumber (deviceIdx); 00183 if (!serial_number.empty ()) 00184 serial_map_[serial_number] = deviceIdx; 00185 } 00186 00187 #endif 00188 00189 // redundant, but needed for Windows right now and also for Xtion 00190 for (unsigned deviceIdx = 0; deviceIdx < device_context_.size (); ++deviceIdx) 00191 { 00192 unsigned short product_id; 00193 unsigned short vendor_id; 00194 00195 getDeviceType(device_context_[deviceIdx].device_node.GetCreationInfo (), vendor_id, product_id ); 00196 00197 #if _WIN32 00198 if (vendor_id == 0x45e) 00199 { 00200 strcpy ((char*)device_context_[deviceIdx].device_node.GetDescription().strVendor, "Microsoft"); 00201 strcpy ((char*)device_context_[deviceIdx].device_node.GetDescription().strName, "Xbox NUI Camera"); 00202 } 00203 else 00204 #endif 00205 if (vendor_id == 0x1d27 && device_context_[deviceIdx].image_node.get () == 0) 00206 { 00207 strcpy ((char*)device_context_[deviceIdx].device_node.GetDescription().strVendor, "ASUS"); 00208 strcpy ((char*)device_context_[deviceIdx].device_node.GetDescription().strName, "Xtion Pro"); 00209 } 00210 } 00211 return (device_context_.size ()); 00212 } 00213 00214 void OpenNIDriver::stopAll () throw (OpenNIException) 00215 { 00216 XnStatus status = context_.StopGeneratingAll (); 00217 if (status != XN_STATUS_OK) 00218 THROW_OPENNI_EXCEPTION ("stopping all streams failed. Reason: %s", xnGetStatusString (status)); 00219 } 00220 00221 OpenNIDriver::~OpenNIDriver () throw () 00222 { 00223 // no exception during destuctor 00224 try 00225 { 00226 stopAll (); 00227 } 00228 catch (...) 00229 { 00230 } 00231 00232 context_.Shutdown (); 00233 } 00234 00235 boost::shared_ptr<OpenNIDevice> OpenNIDriver::createVirtualDevice (const string& path, bool repeat, bool stream) const throw (OpenNIException) 00236 { 00237 return boost::shared_ptr<OpenNIDevice> (new DeviceONI (context_, path, repeat, stream)); 00238 } 00239 00240 boost::shared_ptr<OpenNIDevice> OpenNIDriver::getDeviceByIndex (unsigned index) const throw (OpenNIException) 00241 { 00242 using namespace std; 00243 00244 if (index >= device_context_.size ()) 00245 THROW_OPENNI_EXCEPTION ("device index out of range. only %d devices connected but device %d requested.", device_context_.size (), index); 00246 boost::shared_ptr<OpenNIDevice> device = device_context_[index].device.lock (); 00247 if (!device) 00248 { 00249 unsigned short vendor_id; 00250 unsigned short product_id; 00251 getDeviceType (device_context_[index].device_node.GetCreationInfo (), vendor_id, product_id ); 00252 00253 if (vendor_id == 0x45e) 00254 { 00255 device = boost::shared_ptr<OpenNIDevice > (new DeviceKinect (context_, device_context_[index].device_node, 00256 *device_context_[index].image_node, *device_context_[index].depth_node, 00257 *device_context_[index].ir_node)); 00258 device_context_[index].device = device; 00259 } 00260 else if (vendor_id == 0x1d27) 00261 { 00262 if (device_context_[index].image_node.get()) 00263 device = boost::shared_ptr<OpenNIDevice > (new DevicePrimesense (context_, device_context_[index].device_node, 00264 *device_context_[index].image_node, *device_context_[index].depth_node, 00265 *device_context_[index].ir_node)); 00266 else 00267 device = boost::shared_ptr<OpenNIDevice > (new DeviceXtionPro (context_, device_context_[index].device_node, 00268 *device_context_[index].depth_node, *device_context_[index].ir_node)); 00269 device_context_[index].device = device; 00270 } 00271 else 00272 { 00273 THROW_OPENNI_EXCEPTION ("vendor %s (%s) known by primesense driver, but not by ros driver. Contact maintainer of the ros driver.", 00274 getVendorName (index), vendor_id); 00275 } 00276 } 00277 return (device); 00278 } 00279 00280 #ifndef _WIN32 00281 boost::shared_ptr<OpenNIDevice> 00282 OpenNIDriver::getDeviceBySerialNumber (const std::string& serial_number) const throw (OpenNIException) 00283 { 00284 std::map<std::string, unsigned>::const_iterator it = serial_map_.find (serial_number); 00285 00286 if (it != serial_map_.end ()) 00287 { 00288 return getDeviceByIndex (it->second); 00289 } 00290 00291 THROW_OPENNI_EXCEPTION ("No device with serial number \'%s\' found", serial_number.c_str ()); 00292 00293 // because of warnings!!! 00294 return (boost::shared_ptr<OpenNIDevice > ((OpenNIDevice*)NULL)); 00295 } 00296 00297 boost::shared_ptr<OpenNIDevice> 00298 OpenNIDriver::getDeviceByAddress (unsigned char bus, unsigned char address) const throw (OpenNIException) 00299 { 00300 std::map<unsigned char, std::map<unsigned char, unsigned> >::const_iterator busIt = bus_map_.find (bus); 00301 if (busIt != bus_map_.end ()) 00302 { 00303 std::map<unsigned char, unsigned>::const_iterator devIt = busIt->second.find (address); 00304 if (devIt != busIt->second.end ()) 00305 { 00306 return getDeviceByIndex (devIt->second); 00307 } 00308 } 00309 00310 THROW_OPENNI_EXCEPTION ("No device on bus: %d @ %d found", (int)bus, (int)address); 00311 00312 // because of warnings!!! 00313 return (boost::shared_ptr<OpenNIDevice > ((OpenNIDevice*)NULL)); 00314 } 00315 00316 void 00317 OpenNIDriver::getDeviceInfos () throw () 00318 { 00319 libusb_context *context = NULL; 00320 int result; 00321 result = libusb_init (&context); //initialize a library session 00322 00323 if (result < 0) 00324 return; 00325 00326 libusb_device **devices; 00327 int count = libusb_get_device_list (context, &devices); 00328 if (count < 0) 00329 return; 00330 00331 for (int devIdx = 0; devIdx < count; ++devIdx) 00332 { 00333 libusb_device* device = devices[devIdx]; 00334 uint8_t busId = libusb_get_bus_number (device); 00335 std::map<unsigned char, std::map<unsigned char, unsigned> >::const_iterator busIt = bus_map_.find (busId); 00336 if (busIt == bus_map_.end ()) 00337 continue; 00338 00339 uint8_t address = libusb_get_device_address (device); 00340 std::map<unsigned char, unsigned>::const_iterator addressIt = busIt->second.find (address); 00341 if (addressIt == busIt->second.end ()) 00342 continue; 00343 00344 unsigned nodeIdx = addressIt->second; 00345 xn::NodeInfo& current_node = device_context_[nodeIdx].device_node; 00346 XnProductionNodeDescription& description = const_cast<XnProductionNodeDescription&>(current_node.GetDescription ()); 00347 00348 libusb_device_descriptor descriptor; 00349 result = libusb_get_device_descriptor (devices[devIdx], &descriptor); 00350 00351 if (result < 0) 00352 { 00353 strcpy (description.strVendor, "unknown"); 00354 strcpy (description.strName, "unknown"); 00355 current_node.SetInstanceName (""); 00356 } 00357 else 00358 { 00359 libusb_device_handle* dev_handle; 00360 result = libusb_open (device, &dev_handle); 00361 if (result < 0) 00362 { 00363 strcpy (description.strVendor, "unknown"); 00364 strcpy (description.strName, "unknown"); 00365 current_node.SetInstanceName (""); 00366 } 00367 else 00368 { 00369 unsigned char buffer[1024]; 00370 libusb_get_string_descriptor_ascii (dev_handle, descriptor.iManufacturer, buffer, 1024); 00371 strcpy (description.strVendor, (char*)buffer); 00372 00373 libusb_get_string_descriptor_ascii (dev_handle, descriptor.iProduct, buffer, 1024); 00374 strcpy (description.strName, (char*)buffer); 00375 00376 int len = libusb_get_string_descriptor_ascii (dev_handle, descriptor.iSerialNumber, buffer, 1024); 00377 if (len > 4) 00378 current_node.SetInstanceName ((char*)buffer); 00379 else 00380 current_node.SetInstanceName (""); 00381 00382 libusb_close (dev_handle); 00383 } 00384 } 00385 } 00386 libusb_free_device_list (devices, 1); 00387 libusb_exit (context); 00388 } 00389 #endif 00390 00391 const char* OpenNIDriver::getSerialNumber (unsigned index) const throw () 00392 { 00393 #ifndef _WIN32 00394 return device_context_[index].device_node.GetInstanceName (); 00395 #else 00396 return ""; 00397 #endif 00398 } 00399 00400 void OpenNIDriver::getDeviceType (const std::string& connectionString, unsigned short& vendorId, unsigned short& productId) 00401 { 00402 #if _WIN32 00403 // expected format: "\\?\usb#vid_[ID]&pid_[ID]#[SERIAL]#{GUID}" 00404 typedef boost::tokenizer<boost::char_separator<char> > tokenizer; 00405 boost::char_separator<char> separators("#&_"); 00406 tokenizer tokens(connectionString, separators); 00407 00408 unsigned int tokenIndex = 0; 00409 for (tokenizer::iterator tok_iter = tokens.begin(); tok_iter != tokens.end(); ++tok_iter, tokenIndex++) 00410 { 00411 std::string tokenValue = *tok_iter; 00412 00413 switch(tokenIndex) { 00414 case 2: // the vendor ID 00415 sscanf(tokenValue.c_str(), "%hx", &vendorId); 00416 break; 00417 case 4: // the product ID 00418 sscanf(tokenValue.c_str(), "%hx", &productId); 00419 break; 00420 } 00421 } 00422 #else 00423 unsigned char bus; 00424 unsigned char address; 00425 sscanf (connectionString.c_str(), "%hx/%hx@%hhu/%hhu", &vendorId, &productId, &bus, &address); 00426 #endif 00427 } 00428 00429 const char* OpenNIDriver::getConnectionString (unsigned index) const throw () 00430 { 00431 return device_context_[index].device_node.GetCreationInfo (); 00432 } 00433 00434 const char* OpenNIDriver::getVendorName (unsigned index) const throw () 00435 { 00436 return device_context_[index].device_node.GetDescription ().strVendor; 00437 } 00438 00439 const char* OpenNIDriver::getProductName (unsigned index) const throw () 00440 { 00441 return device_context_[index].device_node.GetDescription ().strName; 00442 } 00443 00444 unsigned short OpenNIDriver::getVendorID (unsigned index) const throw () 00445 { 00446 unsigned short vendor_id; 00447 unsigned short product_id; 00448 #ifndef _WIN32 00449 unsigned char bus; 00450 unsigned char address; 00451 sscanf (device_context_[index].device_node.GetCreationInfo (), "%hx/%hx@%hhu/%hhu", &vendor_id, &product_id, &bus, &address); 00452 00453 #else 00454 getDeviceType (device_context_[index].device_node.GetCreationInfo (), vendor_id, product_id); 00455 #endif 00456 return vendor_id; 00457 } 00458 00459 unsigned short OpenNIDriver::getProductID (unsigned index) const throw () 00460 { 00461 unsigned short vendor_id; 00462 unsigned short product_id; 00463 #ifndef _WIN32 00464 unsigned char bus; 00465 unsigned char address; 00466 sscanf (device_context_[index].device_node.GetCreationInfo (), "%hx/%hx@%hhu/%hhu", &vendor_id, &product_id, &bus, &address); 00467 00468 #else 00469 getDeviceType (device_context_[index].device_node.GetCreationInfo (), vendor_id, product_id); 00470 #endif 00471 return product_id; 00472 } 00473 00474 unsigned char OpenNIDriver::getBus (unsigned index) const throw () 00475 { 00476 unsigned char bus = 0; 00477 #ifndef _WIN32 00478 unsigned short vendor_id; 00479 unsigned short product_id; 00480 unsigned char address; 00481 sscanf (device_context_[index].device_node.GetCreationInfo (), "%hx/%hx@%hhu/%hhu", &vendor_id, &product_id, &bus, &address); 00482 #endif 00483 return bus; 00484 } 00485 00486 unsigned char OpenNIDriver::getAddress (unsigned index) const throw () 00487 { 00488 unsigned char address = 0; 00489 #ifndef _WIN32 00490 unsigned short vendor_id; 00491 unsigned short product_id; 00492 unsigned char bus; 00493 sscanf (device_context_[index].device_node.GetCreationInfo (), "%hx/%hx@%hhu/%hhu", &vendor_id, &product_id, &bus, &address); 00494 #endif 00495 return address; 00496 } 00497 00498 OpenNIDriver::DeviceContext::DeviceContext (const xn::NodeInfo& device, xn::NodeInfo* image, xn::NodeInfo* depth, xn::NodeInfo* ir) 00499 : device_node (device) 00500 , image_node (image) 00501 , depth_node (depth) 00502 , ir_node (ir) 00503 { 00504 } 00505 00506 OpenNIDriver::DeviceContext::DeviceContext (const xn::NodeInfo& device) 00507 : device_node (device) 00508 , image_node ((xn::NodeInfo*)0) 00509 , depth_node ((xn::NodeInfo*)0) 00510 , ir_node ((xn::NodeInfo*)0) 00511 { 00512 } 00513 00514 OpenNIDriver::DeviceContext::DeviceContext (const DeviceContext& other) 00515 : device_node (other.device_node) 00516 , image_node (other.image_node) 00517 , depth_node (other.depth_node) 00518 , ir_node (other.ir_node) 00519 , device (other.device) 00520 { 00521 } 00522 00523 } // namespace