dinast_grabber.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) 2012-, Open Perception, Inc.
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 the copyright holder(s) 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  * $Id$
00037  *
00038  */
00039 
00040 #include <pcl/pcl_config.h>
00041 #include <pcl/io/dinast_grabber.h>
00042 
00043 using namespace std;
00044 
00046 pcl::DinastGrabber::DinastGrabber (const int device_position)
00047   : image_width_ (320)
00048   , image_height_ (240)
00049   , sync_packet_size_ (512)
00050   , fov_ (64. * M_PI / 180.)
00051   , context_ (NULL)
00052   , bulk_ep_ (std::numeric_limits<unsigned char>::max ())
00053   , second_image_ (false)
00054   , running_ (false)
00055 {
00056   image_size_ = image_width_ * image_height_;
00057   dist_max_2d_ = 1. / (image_width_ / 2.);
00058   onInit(device_position);
00059   
00060   point_cloud_signal_ = createSignal<sig_cb_dinast_point_cloud> ();
00061   raw_buffer_ = new unsigned char[(RGB16 * (image_size_) + sync_packet_size_) * 2];
00062 }
00063 
00065 pcl::DinastGrabber::~DinastGrabber () throw ()
00066 {
00067   try
00068   {
00069     stop ();
00070 
00071     libusb_exit (context_);
00072     
00073     // Release the interface
00074     libusb_release_interface (device_handle_, 0);
00075     // Close it
00076     libusb_close (device_handle_); 
00077     delete[] raw_buffer_;
00078     delete[] image_;
00079   }
00080   catch (...)
00081   {
00082     // Destructor never throws
00083   }
00084 }
00085 
00087 bool
00088 pcl::DinastGrabber::isRunning () const
00089 {
00090   return (running_);
00091 }
00092 
00094 float
00095 pcl::DinastGrabber::getFramesPerSecond () const
00096 { 
00097   static double last = pcl::getTime ();
00098   double now = pcl::getTime (); 
00099   float rate = 1 / float(now - last);
00100   last = now; 
00101 
00102   return (rate);
00103 }
00104 
00106 void
00107 pcl::DinastGrabber::onInit (const int device_position)
00108 {
00109   setupDevice (device_position);
00110   capture_thread_ = boost::thread (&DinastGrabber::captureThreadFunction, this);
00111   image_ = new unsigned char [image_size_];
00112 }
00113 
00115 void
00116 pcl::DinastGrabber::setupDevice (int device_position, const int id_vendor, const int id_product)
00117 {
00118   int device_position_counter = 0;
00119   
00120   // Initialize libusb
00121   int ret=libusb_init (&context_);
00122   std::stringstream sstream;
00123   if (ret != 0)
00124   {
00125     sstream << "[pcl::DinastGrabber::setupDevice] libusb initialization failure, LIBUSB_ERROR: "<< ret;
00126     PCL_THROW_EXCEPTION (pcl::IOException, sstream.str ());
00127   }
00128   
00129   libusb_set_debug (context_, 3);
00130   libusb_device **devs = NULL;
00131   
00132   // Get the list of USB devices
00133   ssize_t number_devices = libusb_get_device_list (context_, &devs);
00134 
00135   if (number_devices < 0)
00136     PCL_THROW_EXCEPTION (pcl::IOException, "[pcl::DinastGrabber::setupDevice] No USB devices found!");
00137   
00138   // Iterate over all devices
00139   for (ssize_t i = 0; i < number_devices; ++i)
00140   {
00141     libusb_device_descriptor desc;
00142 
00143     if (libusb_get_device_descriptor (devs[i], &desc) < 0)
00144     {
00145       // Free the list
00146       libusb_free_device_list (devs, 1);
00147       // Return a NULL device
00148       return;
00149     }
00150 
00151     if (desc.idVendor != id_vendor || desc.idProduct != id_product)
00152       continue;
00153     libusb_config_descriptor *config;
00154     // Get the configuration descriptor
00155     libusb_get_config_descriptor (devs[i], 0, &config);
00156 
00157     // Iterate over all interfaces available
00158     for (int f = 0; f < int (config->bNumInterfaces); ++f)
00159     {
00160       // Iterate over the number of alternate settings
00161       for (int j = 0; j < config->interface[f].num_altsetting; ++j)
00162       {
00163         // Iterate over the number of end points present
00164         for (int k = 0; k < int (config->interface[f].altsetting[j].bNumEndpoints); ++k) 
00165         {
00166           if (config->interface[f].altsetting[j].endpoint[k].bmAttributes == LIBUSB_TRANSFER_TYPE_BULK)
00167           {
00168             // Initialize the bulk end point
00169             bulk_ep_ = config->interface[f].altsetting[j].endpoint[k].bEndpointAddress;
00170             break;
00171           }
00172         }
00173       }
00174     }
00175     device_position_counter++;
00176     if (device_position_counter == device_position)
00177       libusb_open(devs[i], &device_handle_);
00178     // Free the configuration descriptor
00179     libusb_free_config_descriptor (config);
00180   }
00181   
00182   // Free the list
00183   libusb_free_device_list (devs, 1);
00184   
00185   // Check if device founded if not notify
00186   if (device_handle_ == NULL)
00187     PCL_THROW_EXCEPTION (pcl::IOException, "[pcl::DinastGrabber::setupDevice] Failed to find any DINAST devices attached");
00188   
00189   // Claim device interface
00190   if (libusb_claim_interface(device_handle_, 0) < 0)
00191      PCL_THROW_EXCEPTION (pcl::IOException, "[pcl::DinastGrabber::setupDevice] Failed to open DINAST device");
00192 
00193 }
00194 
00196 std::string
00197 pcl::DinastGrabber::getDeviceVersion ()
00198 {
00199   unsigned char data[21];
00200   if (!USBRxControlData (CMD_GET_VERSION, data, 21))
00201      PCL_THROW_EXCEPTION (pcl::IOException, "[pcl::DinastGrabber::getDeviceVersion] Error trying to get device version");
00202  
00203   //data[21] = 0;
00204   return (std::string (reinterpret_cast<const char*> (data)));
00205 }
00206 
00208 void
00209 pcl::DinastGrabber::start ()
00210 {
00211   unsigned char ctrl_buf[1];
00212   if (!USBTxControlData (CMD_READ_START, ctrl_buf, 1))
00213     PCL_THROW_EXCEPTION (pcl::IOException, "[pcl::DinastGrabber::start] Could not start the USB data reading");
00214   running_ = true;
00215 }
00216 
00218 void
00219 pcl::DinastGrabber::stop ()
00220 {
00221   unsigned char ctrl_buf[1];
00222   if (!USBTxControlData (CMD_READ_STOP, ctrl_buf, 1))
00223     PCL_THROW_EXCEPTION (pcl::IOException, "[pcl::DinastGrabber::stop] Could not stop the USB data reading");
00224   running_ = false;
00225 }
00226 
00228 void
00229 pcl::DinastGrabber::readImage ()
00230 {
00231   // Do we have enough data in the buffer for the second image?
00232   if (second_image_)
00233   {
00234     for (int i = 0; i < image_size_; ++i)
00235       image_[i] = g_buffer_[i];
00236 
00237     g_buffer_.rerase (g_buffer_.begin (), g_buffer_.begin () + image_size_);
00238     second_image_ = false;
00239     
00240     return;
00241   }
00242 
00243   // Read data in two image blocks until we get a header
00244   bool first_image = false;
00245   int data_adr = -1;
00246   while (!second_image_)
00247   {
00248     // Read at least two images in synchronous mode
00249     int actual_length;
00250     int res = libusb_bulk_transfer (device_handle_, bulk_ep_, raw_buffer_,
00251                                     RGB16 * (image_size_) + sync_packet_size_, &actual_length, 1000);
00252     if (res != 0 || actual_length == 0)
00253     {
00254       memset (&image_[0], 0x00, image_size_);
00255       PCL_THROW_EXCEPTION (pcl::IOException, "[pcl::DinastGrabber::readImage] USB read error!");
00256     }
00257 
00258     // Copy data from the USB port if we actually read anything
00259     PCL_DEBUG ("[pcl::DinastGrabber::readImage] Read: %d, size of the buffer: %d\n" ,actual_length, g_buffer_.size ());
00260     
00261     // Copy data into the buffer
00262     int back = int (g_buffer_.size ());
00263     g_buffer_.resize (back + actual_length);
00264 
00265     for (int i = 0; i < actual_length; ++i)
00266       g_buffer_[back++] = raw_buffer_[i];
00267 
00268     PCL_DEBUG ("[pcl::DinastGrabber::readImage] Buffer size: %d\n", g_buffer_.size());
00269 
00270     // Check if the header is set already
00271     if (!first_image && data_adr == -1)
00272     {
00273       data_adr = checkHeader ();
00274       PCL_DEBUG ("[pcl::DinastGrabber::readImage] Searching for header at: %d", data_adr);
00275     }
00276 
00277     // Is there enough data in the buffer to return one image, and did we find the header?
00278     // If not, go back and read some more data off the USB port
00279     // Else, read the data, clean the g_buffer_, return to the user
00280     if (!first_image && (g_buffer_.size () >= image_size_ + data_adr) && data_adr != -1)
00281     {
00282       // An image found. Copy it from the buffer into the user given buffer
00283 
00284       for (int i = 0; i < image_size_; ++i)
00285         image_[i] = g_buffer_[data_adr + i];
00286 
00287       // Pop the data from the global buffer. 
00288       g_buffer_.rerase (g_buffer_.begin(), g_buffer_.begin() + data_adr + image_size_);
00289       first_image = true;
00290     }
00291 
00292     if (first_image && g_buffer_.size () >= image_size_)
00293       break;
00294   }
00295 }
00296 
00298 pcl::PointCloud<pcl::PointXYZI>::Ptr
00299 pcl::DinastGrabber::getXYZIPointCloud ()
00300 {
00301   pcl::PointCloud<pcl::PointXYZI>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZI>);
00302   
00303   cloud->points.resize (image_size_);
00304   cloud->width = image_width_;
00305   cloud->height = image_height_;
00306   cloud->is_dense = false;
00307   
00308   int depth_idx = 0;
00309 
00310   for (int x = 0; x < cloud->width; ++x)
00311   {
00312     for (int y = 0; y < cloud->height; ++y, ++depth_idx)
00313     {
00314       double pixel = image_[x + image_width_ * y];
00315 
00316       // Correcting distortion, data emprically got in a calibration test
00317       double xc = static_cast<double> (x - image_width_ / 2);
00318       double yc = static_cast<double> (y - image_height_ / 2);
00319       double r1 = sqrt (xc * xc + yc * yc);
00320       double r2 = r1 * r1;
00321       double r3 = r1 * r2;
00322       double A = -2e-5 * r3 + 0.004 * r2 + 0.1719 * r1 + 350.03;
00323       double B = -2e-9 * r3 + 3e-7 * r2 - 1e-5 * r1 - 0.01;
00324 
00325       // Compute distance
00326       if (pixel > A)
00327         pixel = A;
00328       double dy = y*0.1;
00329       double dist = (log (static_cast<double> (pixel / A)) / B - dy) * (7E-07*r3 - 0.0001*r2 + 0.004*r1 + 0.9985) * 1.5;
00330       double theta_colati = fov_ * r1 * dist_max_2d_;
00331       double c_theta = cos (theta_colati);
00332       double s_theta = sin (theta_colati);
00333       double c_ksai = static_cast<double> (x - 160) / r1;
00334       double s_ksai = static_cast<double> (y - 120) / r1;
00335       cloud->points[depth_idx].x = static_cast<float> ((dist * s_theta * c_ksai) / 500.0 + 0.5);
00336       cloud->points[depth_idx].y = static_cast<float> ((dist * s_theta * s_ksai) / 500.0 + 0.5);
00337       cloud->points[depth_idx].z = static_cast<float> (dist * c_theta);
00338       if (cloud->points[depth_idx].z < 0.01f)
00339         cloud->points[depth_idx].z = 0.01f;
00340       cloud->points[depth_idx].z /= 500.0f;
00341       cloud->points[depth_idx].intensity = static_cast<float> (pixel);
00342 
00343       
00344       // Get rid of the noise
00345       if(cloud->points[depth_idx].z > 0.8f or cloud->points[depth_idx].z < 0.02f)
00346       {
00347         cloud->points[depth_idx].x = std::numeric_limits<float>::quiet_NaN ();
00348         cloud->points[depth_idx].y = std::numeric_limits<float>::quiet_NaN ();
00349         cloud->points[depth_idx].z = std::numeric_limits<float>::quiet_NaN ();
00350         cloud->points[depth_idx].intensity = static_cast<float> (pixel);
00351       }
00352     }
00353   }
00354   return cloud;
00355 }
00356 
00358 bool
00359 pcl::DinastGrabber::USBRxControlData (const unsigned char req_code,
00360                                       unsigned char *buffer,
00361                                       int length)
00362 {
00363   // The direction of the transfer is inferred from the requesttype field of the setup packet.
00364   unsigned char requesttype = (LIBUSB_RECIPIENT_DEVICE | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_ENDPOINT_IN);
00365   // The value field for the setup packet
00366   uint16_t value = 0x02;
00367   // The index field for the setup packet
00368   uint16_t index = 0x08;
00369   // timeout (in ms) that this function should wait before giving up due to no response being received
00370   // For an unlimited timeout, use value 0.
00371   uint16_t timeout = 1000;
00372   
00373   int nr_read = libusb_control_transfer (device_handle_, requesttype,
00374                                          req_code, value, index, buffer, static_cast<uint16_t> (length), timeout);
00375   if (nr_read != int(length))
00376     PCL_THROW_EXCEPTION (pcl::IOException, "[pcl::DinastGrabber::USBRxControlData] Control data error");
00377 
00378   return (true);
00379 }
00380 
00382 bool
00383 pcl::DinastGrabber::USBTxControlData (const unsigned char req_code,
00384                                       unsigned char *buffer,
00385                                       int length)
00386 {
00387   // The direction of the transfer is inferred from the requesttype field of the setup packet.
00388   unsigned char requesttype = (LIBUSB_RECIPIENT_DEVICE | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_ENDPOINT_OUT);
00389   // The value field for the setup packet
00390   uint16_t value = 0x01;
00391   // The index field for the setup packet
00392   uint16_t index = 0x00;
00393   // timeout (in ms) that this function should wait before giving up due to no response being received
00394   // For an unlimited timeout, use value 0.
00395   uint16_t timeout = 1000;
00396   
00397   int nr_read = libusb_control_transfer (device_handle_, requesttype,
00398                                          req_code, value, index, buffer, static_cast<uint16_t> (length), timeout);
00399   if (nr_read != int(length))
00400   {
00401     std::stringstream sstream;
00402     sstream << "[pcl::DinastGrabber::USBTxControlData] USB control data error, LIBUSB_ERROR: " << nr_read;
00403     PCL_THROW_EXCEPTION (pcl::IOException, sstream.str ());
00404   }
00405 
00406   return (true);
00407 }
00408 
00410 int
00411 pcl::DinastGrabber::checkHeader ()
00412 {
00413   // We need at least 2 full sync packets, in case the header starts at the end of the first sync packet to 
00414   // guarantee that the index returned actually exists in g_buffer_ (we perform no checking in the rest of the code)
00415   if (g_buffer_.size () < 2 * sync_packet_size_)
00416     return (-1);
00417 
00418   int data_ptr = -1;
00419 
00420   for (size_t i = 0; i < g_buffer_.size (); ++i)
00421   {
00422     if ((g_buffer_[i + 0] == 0xAA) && (g_buffer_[i + 1] == 0xAA) &&
00423         (g_buffer_[i + 2] == 0x44) && (g_buffer_[i + 3] == 0x44) &&
00424         (g_buffer_[i + 4] == 0xBB) && (g_buffer_[i + 5] == 0xBB) &&
00425         (g_buffer_[i + 6] == 0x77) && (g_buffer_[i + 7] == 0x77))
00426     {
00427       data_ptr = int (i) + sync_packet_size_;
00428       break;
00429     }
00430   }
00431 
00432   return (data_ptr);
00433 }
00434 
00436 void 
00437 pcl::DinastGrabber::captureThreadFunction ()
00438 {
00439   while (true)
00440   {
00441     // Lock before checking running flag
00442     boost::unique_lock<boost::mutex> capture_lock (capture_mutex_);
00443     if(running_)
00444     {
00445       readImage ();
00446     
00447       // Check for point clouds slots
00448       if (num_slots<sig_cb_dinast_point_cloud> () > 0 )
00449         point_cloud_signal_->operator() (getXYZIPointCloud ());
00450     } 
00451     capture_lock.unlock ();
00452   }
00453 }


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