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 <sstream>
00041 #include <iostream>
00042 #include <algorithm>
00043 #include <locale>
00044 #include <cctype>
00045 #ifndef _WIN32
00046 #include <libusb-1.0/libusb.h>
00047 #endif
00048 #include <map>
00049
00050 #ifndef _WIN32
00051 #include <libusb-1.0/libusb.h>
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
00078
00079 static xn::NodeInfoList node_info_list;
00080 XnStatus status = context_.EnumerateProductionTrees (XN_NODE_TYPE_DEVICE, NULL, node_info_list);
00081 if (status != XN_STATUS_OK && node_info_list.Begin () != node_info_list.End ())
00082 THROW_OPENNI_EXCEPTION ("enumerating devices failed. Reason: %s", xnGetStatusString (status));
00083 else if (node_info_list.Begin () == node_info_list.End ())
00084 return 0;
00085
00086
00087 std::vector<xn::NodeInfo> device_info;
00088 for (xn::NodeInfoList::Iterator nodeIt = node_info_list.Begin (); nodeIt != node_info_list.End (); ++nodeIt)
00089 {
00090 device_info.push_back (*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 std::vector<xn::NodeInfo> depth_info;
00100 for (xn::NodeInfoList::Iterator nodeIt = depth_nodes.Begin (); nodeIt != depth_nodes.End (); ++nodeIt)
00101 {
00102 depth_info.push_back (*nodeIt);
00103 }
00104
00105
00106 static xn::NodeInfoList image_nodes;
00107 status = context_.EnumerateProductionTrees (XN_NODE_TYPE_IMAGE, NULL, image_nodes, NULL);
00108 if (status != XN_STATUS_OK)
00109 THROW_OPENNI_EXCEPTION ("enumerating image generators failed. Reason: %s", xnGetStatusString (status));
00110
00111 std::vector<xn::NodeInfo> image_info;
00112 for (xn::NodeInfoList::Iterator nodeIt = image_nodes.Begin (); nodeIt != image_nodes.End (); ++nodeIt)
00113 {
00114 image_info.push_back (*nodeIt);
00115 }
00116
00117
00118 if (device_info.size () != depth_info.size () || device_info.size () != image_info.size ())
00119 THROW_OPENNI_EXCEPTION ("number of streams and devices does not match: %d devices, %d depth streams, %d image streams",
00120 device_info.size (), depth_info.size (), image_info.size ());
00121
00122
00123 for (unsigned deviceIdx = 0; deviceIdx < device_info.size (); ++deviceIdx)
00124 {
00125
00126 device_context_.push_back (DeviceContext (device_info[deviceIdx], image_info[deviceIdx], depth_info[deviceIdx]));
00127
00128
00129 unsigned short vendor_id;
00130 unsigned short product_id;
00131 unsigned char bus;
00132 unsigned char address;
00133 sscanf (device_info[deviceIdx].GetCreationInfo (), "%hx/%hx@%hhu/%hhu", &vendor_id, &product_id, &bus, &address);
00134 bus_map_ [bus][address] = deviceIdx;
00135 }
00136
00137 #ifndef _WIN32
00138
00139 getDeviceInfos ();
00140 #endif
00141
00142
00143 for (unsigned deviceIdx = 0; deviceIdx < device_info.size (); ++deviceIdx)
00144 {
00145 std::string serial_number = getSerialNumber (deviceIdx);
00146 if (!serial_number.empty ())
00147 serial_map_[serial_number] = deviceIdx;
00148 }
00149
00150 return (device_info.size ());
00151 }
00152
00153 void OpenNIDriver::stopAll () throw (OpenNIException)
00154 {
00155 XnStatus status = context_.StopGeneratingAll ();
00156 if (status != XN_STATUS_OK)
00157 THROW_OPENNI_EXCEPTION ("stopping all streams failed. Reason: %s", xnGetStatusString (status));
00158 }
00159
00160 OpenNIDriver::~OpenNIDriver () throw ()
00161 {
00162
00163 try
00164 {
00165 stopAll ();
00166 }
00167 catch (...)
00168 {
00169 }
00170
00171 context_.Shutdown ();
00172 }
00173
00174 boost::shared_ptr<OpenNIDevice> OpenNIDriver::getDeviceByIndex (unsigned index) const throw (OpenNIException)
00175 {
00176 using namespace std;
00177
00178 if (index >= device_context_.size ())
00179 THROW_OPENNI_EXCEPTION ("device index out of range. only %d devices connected but device %d requested.", device_context_.size (), index);
00180 boost::shared_ptr<OpenNIDevice> device = device_context_[index].device.lock ();
00181 if (!device)
00182 {
00183 unsigned short vendor_id;
00184 unsigned short product_id;
00185 getDeviceType (device_context_[index].device_node.GetCreationInfo (), vendor_id, product_id );
00186
00187 if (vendor_id == 0x45e)
00188 {
00189 device = boost::shared_ptr<OpenNIDevice > (new DeviceKinect (context_, device_context_[index].device_node,
00190 device_context_[index].image_node, device_context_[index].depth_node));
00191 device_context_[index].device = device;
00192 }
00193 else if (vendor_id == 0x1d27)
00194 {
00195 device = boost::shared_ptr<OpenNIDevice > (new DevicePrimesense (context_, device_context_[index].device_node,
00196 device_context_[index].image_node, device_context_[index].depth_node));
00197 device_context_[index].device = device;
00198 }
00199 else
00200 {
00201 THROW_OPENNI_EXCEPTION ("vendor %s (%s) known by primesense driver, but not by ros driver. Contact maintainer of the ros driver.",
00202 getVendorName (index), vendor_id);
00203 }
00204 }
00205 return (device);
00206 }
00207
00208 #ifndef _WIN32
00209 boost::shared_ptr<OpenNIDevice>
00210 OpenNIDriver::getDeviceBySerialNumber (const std::string& serial_number) const throw (OpenNIException)
00211 {
00212 std::map<std::string, unsigned>::const_iterator it = serial_map_.find (serial_number);
00213
00214 if (it != serial_map_.end ())
00215 {
00216 return getDeviceByIndex (it->second);
00217 }
00218
00219 THROW_OPENNI_EXCEPTION ("No device with serial number \'%s\' found", serial_number.c_str ());
00220
00221
00222 return (boost::shared_ptr<OpenNIDevice > ((OpenNIDevice*)NULL));
00223 }
00224
00225 boost::shared_ptr<OpenNIDevice>
00226 OpenNIDriver::getDeviceByAddress (unsigned char bus, unsigned char address) const throw (OpenNIException)
00227 {
00228 std::map<unsigned char, std::map<unsigned char, unsigned> >::const_iterator busIt = bus_map_.find (bus);
00229 if (busIt != bus_map_.end ())
00230 {
00231 std::map<unsigned char, unsigned>::const_iterator devIt = busIt->second.find (address);
00232 if (devIt != busIt->second.end ())
00233 {
00234 return getDeviceByIndex (devIt->second);
00235 }
00236 }
00237
00238 THROW_OPENNI_EXCEPTION ("No device on bus: %d @ %d found", (int)bus, (int)address);
00239
00240
00241 return (boost::shared_ptr<OpenNIDevice > ((OpenNIDevice*)NULL));
00242 }
00243
00244 void
00245 OpenNIDriver::getDeviceInfos () throw ()
00246 {
00247 libusb_context *context = NULL;
00248 int result;
00249 result = libusb_init (&context);
00250
00251 if (result < 0)
00252 return;
00253
00254 libusb_device **devices;
00255 int count = libusb_get_device_list (context, &devices);
00256 if (count < 0)
00257 return;
00258
00259 for (int devIdx = 0; devIdx < count; ++devIdx)
00260 {
00261 libusb_device* device = devices[devIdx];
00262 uint8_t busId = libusb_get_bus_number (device);
00263 std::map<unsigned char, std::map<unsigned char, unsigned> >::const_iterator busIt = bus_map_.find (busId);
00264 if (busIt == bus_map_.end ())
00265 continue;
00266
00267 uint8_t address = libusb_get_device_address (device);
00268 std::map<unsigned char, unsigned>::const_iterator addressIt = busIt->second.find (address);
00269 if (addressIt == busIt->second.end ())
00270 continue;
00271
00272 unsigned nodeIdx = addressIt->second;
00273 xn::NodeInfo& current_node = device_context_[nodeIdx].device_node;
00274 XnProductionNodeDescription& description = const_cast<XnProductionNodeDescription&>(current_node.GetDescription ());
00275
00276 libusb_device_descriptor descriptor;
00277 result = libusb_get_device_descriptor (devices[devIdx], &descriptor);
00278
00279 if (result < 0)
00280 {
00281 strcpy (description.strVendor, "unknown");
00282 strcpy (description.strName, "unknown");
00283 current_node.SetInstanceName ("");
00284 }
00285 else
00286 {
00287 libusb_device_handle* dev_handle;
00288 result = libusb_open (device, &dev_handle);
00289 if (result < 0)
00290 {
00291 strcpy (description.strVendor, "unknown");
00292 strcpy (description.strName, "unknown");
00293 current_node.SetInstanceName ("");
00294 }
00295 else
00296 {
00297 unsigned char buffer[1024];
00298 libusb_get_string_descriptor_ascii (dev_handle, descriptor.iManufacturer, buffer, 1024);
00299 strcpy (description.strVendor, (char*)buffer);
00300
00301 libusb_get_string_descriptor_ascii (dev_handle, descriptor.iProduct, buffer, 1024);
00302 strcpy (description.strName, (char*)buffer);
00303
00304 int len = libusb_get_string_descriptor_ascii (dev_handle, descriptor.iSerialNumber, buffer, 1024);
00305 if (len > 4)
00306 current_node.SetInstanceName ((char*)buffer);
00307 else
00308 current_node.SetInstanceName ("");
00309
00310 libusb_close (dev_handle);
00311 }
00312 }
00313 }
00314 libusb_free_device_list (devices, 1);
00315 libusb_exit (context);
00316 }
00317 #endif
00318
00319 const char* OpenNIDriver::getSerialNumber (unsigned index) const throw ()
00320 {
00321 #ifndef _WIN32
00322 return device_context_[index].device_node.GetInstanceName ();
00323 #else
00324 return "";
00325 #endif
00326 }
00327
00328 void OpenNIDriver::getDeviceType (const std::string& connectionString, unsigned short& vendorId, unsigned short& productId)
00329 {
00330 #if _WIN32
00331
00332 typedef boost::tokenizer<boost::char_separator<char> > tokenizer;
00333 boost::char_separator<char> separators("#&_");
00334 tokenizer tokens(connectionString, separators);
00335
00336 unsigned int tokenIndex = 0;
00337 for (tokenizer::iterator tok_iter = tokens.begin(); tok_iter != tokens.end(); ++tok_iter, tokenIndex++)
00338 {
00339 std::string tokenValue = *tok_iter;
00340
00341 switch(tokenIndex) {
00342 case 2:
00343 sscanf(tokenValue.c_str(), "%hx", &vendorId);
00344 break;
00345 case 4:
00346 sscanf(tokenValue.c_str(), "%hx", &productId);
00347 break;
00348 }
00349 }
00350 #else
00351 unsigned char bus;
00352 unsigned char address;
00353 sscanf (connectionString.c_str(), "%hx/%hx@%hhu/%hhu", &vendorId, &productId, &bus, &address);
00354 #endif
00355 }
00356
00357 const char* OpenNIDriver::getConnectionString (unsigned index) const throw ()
00358 {
00359 return device_context_[index].device_node.GetCreationInfo ();
00360 }
00361
00362 const char* OpenNIDriver::getVendorName (unsigned index) const throw ()
00363 {
00364 return device_context_[index].device_node.GetDescription ().strVendor;
00365 }
00366
00367 const char* OpenNIDriver::getProductName (unsigned index) const throw ()
00368 {
00369 return device_context_[index].device_node.GetDescription ().strName;
00370 }
00371
00372 unsigned short OpenNIDriver::getVendorID (unsigned index) const throw ()
00373 {
00374 unsigned short vendor_id;
00375 unsigned short product_id;
00376 #ifndef _WIN32
00377 unsigned char bus;
00378 unsigned char address;
00379 sscanf (device_context_[index].device_node.GetCreationInfo (), "%hx/%hx@%hhu/%hhu", &vendor_id, &product_id, &bus, &address);
00380
00381 #else
00382 getDeviceType (device_context_[index].device_node.GetCreationInfo (), vendor_id, product_id);
00383 #endif
00384 return vendor_id;
00385 }
00386
00387 unsigned short OpenNIDriver::getProductID (unsigned index) const throw ()
00388 {
00389 unsigned short vendor_id;
00390 unsigned short product_id;
00391 #ifndef _WIN32
00392 unsigned char bus;
00393 unsigned char address;
00394 sscanf (device_context_[index].device_node.GetCreationInfo (), "%hx/%hx@%hhu/%hhu", &vendor_id, &product_id, &bus, &address);
00395
00396 #else
00397 getDeviceType (device_context_[index].device_node.GetCreationInfo (), vendor_id, product_id);
00398 #endif
00399 return product_id;
00400 }
00401
00402 unsigned char OpenNIDriver::getBus (unsigned index) const throw ()
00403 {
00404 unsigned char bus = 0;
00405 #ifndef _WIN32
00406 unsigned short vendor_id;
00407 unsigned short product_id;
00408 unsigned char address;
00409 sscanf (device_context_[index].device_node.GetCreationInfo (), "%hx/%hx@%hhu/%hhu", &vendor_id, &product_id, &bus, &address);
00410 #endif
00411 return bus;
00412 }
00413
00414 unsigned char OpenNIDriver::getAddress (unsigned index) const throw ()
00415 {
00416 unsigned char address = 0;
00417 #ifndef _WIN32
00418 unsigned short vendor_id;
00419 unsigned short product_id;
00420 unsigned char bus;
00421 sscanf (device_context_[index].device_node.GetCreationInfo (), "%hx/%hx@%hhu/%hhu", &vendor_id, &product_id, &bus, &address);
00422 #endif
00423 return address;
00424 }
00425
00426 OpenNIDriver::DeviceContext::DeviceContext (const xn::NodeInfo& device, const xn::NodeInfo& image, const xn::NodeInfo& depth)
00427 : device_node (device)
00428 , image_node (image)
00429 , depth_node (depth)
00430 {
00431 }
00432
00433 OpenNIDriver::DeviceContext::DeviceContext (const DeviceContext& other)
00434 : device_node (other.device_node)
00435 , image_node (other.image_node)
00436 , depth_node (other.depth_node)
00437 , device (other.device)
00438 {
00439 }
00440
00441 }