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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:26:23