pcd_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) 2010-2012, Willow Garage, 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 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 
00038 #include <pcl/pcl_config.h>
00039 #include <pcl/io/pcd_grabber.h>
00040 #include <pcl/point_cloud.h>
00041 #include <pcl/point_types.h>
00042 #include <pcl/io/pcd_io.h>
00043 #include <pcl/io/tar.h>
00044         
00045 #ifdef _WIN32
00046 # include <io.h>
00047 # include <windows.h>
00048 # define pcl_open                    _open
00049 # define pcl_close(fd)               _close(fd)
00050 # define pcl_lseek(fd,offset,origin) _lseek(fd,offset,origin)
00051 #else
00052 # include <sys/mman.h>
00053 # define pcl_open                    open
00054 # define pcl_close(fd)               close(fd)
00055 # define pcl_lseek(fd,offset,origin) lseek(fd,offset,origin)
00056 #endif
00057 
00060 struct pcl::PCDGrabberBase::PCDGrabberImpl
00061 {
00062   PCDGrabberImpl (pcl::PCDGrabberBase& grabber, const std::string& pcd_path, float frames_per_second, bool repeat);
00063   PCDGrabberImpl (pcl::PCDGrabberBase& grabber, const std::vector<std::string>& pcd_files, float frames_per_second, bool repeat);
00064   void trigger ();
00065   void readAhead ();
00066   
00067   // TAR reading I/O
00068   int openTARFile (const std::string &file_name);
00069   void closeTARFile ();
00070   bool readTARHeader ();
00071   
00073   void
00074   scrapeForClouds (bool force=false);
00075 
00077   bool
00078   getCloudAt (size_t idx, 
00079               pcl::PCLPointCloud2 &blob,
00080               Eigen::Vector4f &origin, 
00081               Eigen::Quaternionf &orientation);
00082 
00084   size_t
00085   numFrames ();
00086 
00087   pcl::PCDGrabberBase& grabber_;
00088   float frames_per_second_;
00089   bool repeat_;
00090   bool running_;
00091   std::vector<std::string> pcd_files_;
00092   std::vector<std::string>::iterator pcd_iterator_;
00093   TimeTrigger time_trigger_;
00094 
00095   pcl::PCLPointCloud2 next_cloud_;
00096   Eigen::Vector4f origin_;
00097   Eigen::Quaternionf orientation_;
00098   bool valid_;
00099 
00100   // TAR reading I/O
00101   int tar_fd_;
00102   int tar_offset_;
00103   std::string tar_file_;
00104   pcl::io::TARHeader tar_header_;
00105 
00106   // True if we have already found the location of all clouds (for tar only)
00107   bool scraped_;
00108   std::vector<int> tar_offsets_;
00109   std::vector<size_t> cloud_idx_to_file_idx_;
00110 
00111   EIGEN_MAKE_ALIGNED_OPERATOR_NEW 
00112 };
00113 
00115 pcl::PCDGrabberBase::PCDGrabberImpl::PCDGrabberImpl (pcl::PCDGrabberBase& grabber, const std::string& pcd_path, float frames_per_second, bool repeat)
00116   : grabber_ (grabber)
00117   , frames_per_second_ (frames_per_second)
00118   , repeat_ (repeat)
00119   , running_ (false)
00120   , pcd_files_ ()
00121   , pcd_iterator_ ()
00122   , time_trigger_ (1.0 / static_cast<double> (std::max (frames_per_second, 0.001f)), boost::bind (&PCDGrabberImpl::trigger, this))
00123   , next_cloud_ ()
00124   , origin_ ()
00125   , orientation_ ()
00126   , valid_ (false)
00127   , tar_fd_ (-1)
00128   , tar_offset_ (0)
00129   , tar_file_ ()
00130   , tar_header_ ()
00131   , scraped_ (false)
00132 {
00133   pcd_files_.push_back (pcd_path);
00134   pcd_iterator_ = pcd_files_.begin ();
00135   readAhead ();
00136 }
00137 
00139 pcl::PCDGrabberBase::PCDGrabberImpl::PCDGrabberImpl (pcl::PCDGrabberBase& grabber, const std::vector<std::string>& pcd_files, float frames_per_second, bool repeat)
00140   : grabber_ (grabber)
00141   , frames_per_second_ (frames_per_second)
00142   , repeat_ (repeat)
00143   , running_ (false)
00144   , pcd_files_ ()
00145   , pcd_iterator_ ()
00146   , time_trigger_ (1.0 / static_cast<double> (std::max (frames_per_second, 0.001f)), boost::bind (&PCDGrabberImpl::trigger, this))
00147   , next_cloud_ ()
00148   , origin_ ()
00149   , orientation_ ()
00150   , valid_ (false)
00151   , tar_fd_ (-1)
00152   , tar_offset_ (0)
00153   , tar_file_ ()
00154   , tar_header_ ()
00155   , scraped_ (false)
00156 {
00157   pcd_files_ = pcd_files;
00158   pcd_iterator_ = pcd_files_.begin ();
00159   readAhead ();
00160 }
00161 
00163 void 
00164 pcl::PCDGrabberBase::PCDGrabberImpl::readAhead ()
00165 {
00166   PCDReader reader;
00167   int pcd_version;
00168 
00169   // Check if we're still reading files from a TAR file
00170   if (tar_fd_ != -1)
00171   {
00172     if (!readTARHeader ())
00173       return;
00174     valid_ = (reader.read (tar_file_, next_cloud_, origin_, orientation_, pcd_version, tar_offset_) == 0);
00175     if (!valid_)
00176       closeTARFile ();
00177     else
00178     {
00179       tar_offset_ += (tar_header_.getFileSize ()) + (512 - tar_header_.getFileSize () % 512);
00180       int result = static_cast<int> (pcl_lseek (tar_fd_, tar_offset_, SEEK_SET));
00181       if (result < 0)
00182         closeTARFile ();
00183     }
00184   }
00185   // We're not still reading from a TAR file, so check if there are other PCD/TAR files in the list
00186   else
00187   {
00188     if (pcd_iterator_ != pcd_files_.end ())
00189     {
00190       // Try to read in the file as a PCD first
00191       valid_ = (reader.read (*pcd_iterator_, next_cloud_, origin_, orientation_, pcd_version) == 0);
00192 
00193       // Has an error occured? Check if we can interpret the file as a TAR file first before going onto the next
00194       if (!valid_ && openTARFile (*pcd_iterator_) >= 0 && readTARHeader ())
00195       {
00196         tar_file_ = *pcd_iterator_;
00197         valid_ = (reader.read (tar_file_, next_cloud_, origin_, orientation_, pcd_version, tar_offset_) == 0);
00198         if (!valid_)
00199           closeTARFile ();
00200         else
00201         {
00202           tar_offset_ += (tar_header_.getFileSize ()) + (512 - tar_header_.getFileSize () % 512);
00203           int result = static_cast<int> (pcl_lseek (tar_fd_, tar_offset_, SEEK_SET));
00204           if (result < 0)
00205             closeTARFile ();
00206         }
00207       }
00208 
00209       if (++pcd_iterator_ == pcd_files_.end () && repeat_)
00210         pcd_iterator_ = pcd_files_.begin ();
00211     }
00212     else
00213       valid_ = false;
00214   }
00215 }
00216 
00218 bool
00219 pcl::PCDGrabberBase::PCDGrabberImpl::readTARHeader ()
00220 {
00221   // Read in the header
00222 #if WIN32
00223   int result = static_cast<int> (_read (tar_fd_, reinterpret_cast<char*> (&tar_header_), 512));
00224 #else
00225   int result = static_cast<int> (::read (tar_fd_, reinterpret_cast<char*> (&tar_header_), 512));
00226 #endif
00227   if (result == -1)
00228   {
00229     closeTARFile ();
00230     return (false);
00231   }
00232 
00233   // We only support regular files for now. 
00234   // Addional file types in TAR include: hard links, symbolic links, device/special files, block devices, 
00235   // directories, and named pipes.
00236   if (tar_header_.file_type[0] != '0' && tar_header_.file_type[0] != '\0')
00237   {
00238     closeTARFile ();
00239     return (false);
00240   }
00241 
00242   // We only support USTAR version 0 files for now
00243   if (std::string (tar_header_.ustar).substr (0, 5) != "ustar")
00244   {
00245     closeTARFile ();
00246     return (false);
00247   }
00248 
00249   if (tar_header_.getFileSize () == 0)
00250   {
00251     closeTARFile ();
00252     return (false);
00253   }
00254 
00255   tar_offset_ += 512;
00256 
00257   return (true);
00258 }
00259 
00261 void
00262 pcl::PCDGrabberBase::PCDGrabberImpl::closeTARFile ()
00263 {
00264   pcl_close (tar_fd_);
00265   tar_fd_ = -1;
00266   tar_offset_ = 0;
00267   memset (&tar_header_.file_name[0], 0, 512);
00268 }
00269 
00271 int
00272 pcl::PCDGrabberBase::PCDGrabberImpl::openTARFile (const std::string &file_name)
00273 {
00274   tar_fd_ = pcl_open (file_name.c_str (), O_RDONLY);
00275   if (tar_fd_ == -1)
00276     return (-1);
00277 
00278   return (0);
00279 }
00280 
00282 void 
00283 pcl::PCDGrabberBase::PCDGrabberImpl::trigger ()
00284 {
00285   if (valid_)
00286     grabber_.publish (next_cloud_,origin_,orientation_);
00287 
00288   // use remaining time, if there is time left!
00289   readAhead ();
00290 }
00291 
00293 void 
00294 pcl::PCDGrabberBase::PCDGrabberImpl::scrapeForClouds (bool force)
00295 {
00296   // Do nothing if we've already scraped (unless force is set)
00297   if (scraped_ && !force)
00298     return;
00299   // Store temporary information
00300   int tmp_fd = tar_fd_;
00301   int tmp_offset = tar_offset_;
00302   pcl::io::TARHeader tmp_header = tar_header_;
00303   tar_fd_ = -1;
00304   tar_offset_ = 0;
00305 
00306   // Go through and index the clouds
00307   PCDReader reader;
00308   pcl::PCLPointCloud2 blob;
00309   for (size_t i = 0; i < pcd_files_.size (); ++i)
00310   {
00311     std::string pcd_file = pcd_files_[i];
00312     // Try to read the file header (TODO this is a huge waste just to make sure it's PCD...is extension enough?)
00313     if (reader.readHeader (pcd_file, blob) == 0)
00314     {
00315       tar_offsets_.push_back (0);
00316       cloud_idx_to_file_idx_.push_back (i);
00317     }
00318     else if (openTARFile (pcd_file) >= 0)
00319     {
00320       while (readTARHeader () && (reader.readHeader (pcd_file, blob, tar_offset_) == 0))
00321       {
00322         tar_offsets_.push_back (tar_offset_);
00323         cloud_idx_to_file_idx_.push_back (i);
00324         // Update offset
00325         tar_offset_ += (tar_header_.getFileSize ()) + (512 - tar_header_.getFileSize () % 512);
00326         int result = static_cast<int> (pcl_lseek (tar_fd_, tar_offset_, SEEK_SET));
00327         if (result < 0)
00328           break;
00329         if (tar_fd_ == -1)
00330           break;
00331       }
00332       closeTARFile ();
00333     }
00334   }
00335 
00336   // Re-save temporary information
00337   tar_fd_ = tmp_fd;
00338   tar_offset_ = tmp_offset;
00339   tar_header_ = tmp_header;
00340   // Flag scraped
00341   scraped_ = true;
00342 }
00343 
00345 bool 
00346 pcl::PCDGrabberBase::PCDGrabberImpl::getCloudAt (size_t idx, 
00347                                                  pcl::PCLPointCloud2 &blob,
00348                                                  Eigen::Vector4f &origin, 
00349                                                  Eigen::Quaternionf &orientation)
00350 {
00351   scrapeForClouds (); // Make sure we've scraped
00352   if (idx >= numFrames ())
00353     return false;
00354   
00355   PCDReader reader;
00356   int pcd_version;
00357   std::string filename = pcd_files_[cloud_idx_to_file_idx_[idx]];
00358   return (reader.read (filename, blob, origin, orientation, pcd_version, tar_offsets_[idx]));
00359 }
00360 
00362 size_t
00363 pcl::PCDGrabberBase::PCDGrabberImpl::numFrames ()
00364 {
00365   scrapeForClouds (); // Make sure we've scraped
00366   return (cloud_idx_to_file_idx_.size ());
00367 }
00368 
00371 pcl::PCDGrabberBase::PCDGrabberBase (const std::string& pcd_path, float frames_per_second, bool repeat)
00372 : impl_ (new PCDGrabberImpl (*this, pcd_path, frames_per_second, repeat))
00373 {
00374 }
00375 
00377 pcl::PCDGrabberBase::PCDGrabberBase (const std::vector<std::string>& pcd_files, float frames_per_second, bool repeat)
00378 : impl_ (new PCDGrabberImpl (*this, pcd_files, frames_per_second, repeat))
00379 {
00380 }
00381 
00383 pcl::PCDGrabberBase::~PCDGrabberBase () throw ()
00384 {
00385   stop ();
00386   delete impl_;
00387 }
00388 
00390 void 
00391 pcl::PCDGrabberBase::start ()
00392 {
00393   if (impl_->frames_per_second_ > 0)
00394   {
00395     impl_->running_ = true;
00396     impl_->time_trigger_.start ();
00397   }
00398   else // manual trigger
00399   {
00400     boost::thread non_blocking_call (boost::bind (&PCDGrabberBase::PCDGrabberImpl::trigger, impl_));
00401   }
00402 }
00403 
00405 void 
00406 pcl::PCDGrabberBase::stop ()
00407 {
00408   if (impl_->frames_per_second_ > 0)
00409   {
00410     impl_->time_trigger_.stop ();
00411     impl_->running_ = false;
00412   }
00413 }
00414 
00416 void
00417 pcl::PCDGrabberBase::trigger ()
00418 {
00419   if (impl_->frames_per_second_ > 0)
00420     return;
00421   boost::thread non_blocking_call (boost::bind (&PCDGrabberBase::PCDGrabberImpl::trigger, impl_));
00422 
00423 //  impl_->trigger ();
00424 }
00425 
00427 bool 
00428 pcl::PCDGrabberBase::isRunning () const
00429 {
00430   return (impl_->running_ && (impl_->pcd_iterator_ != impl_->pcd_files_.end()));
00431 }
00432 
00434 std::string 
00435 pcl::PCDGrabberBase::getName () const
00436 {
00437   return ("PCDGrabber");
00438 }
00439 
00441 void 
00442 pcl::PCDGrabberBase::rewind ()
00443 {
00444   impl_->pcd_iterator_ = impl_->pcd_files_.begin ();
00445 }
00446 
00448 float 
00449 pcl::PCDGrabberBase::getFramesPerSecond () const
00450 {
00451   return (impl_->frames_per_second_);
00452 }
00453 
00455 bool 
00456 pcl::PCDGrabberBase::isRepeatOn () const
00457 {
00458   return (impl_->repeat_);
00459 }
00460 
00462 bool
00463 pcl::PCDGrabberBase::getCloudAt (size_t idx, 
00464                                  pcl::PCLPointCloud2 &blob,
00465                                  Eigen::Vector4f &origin, 
00466                                  Eigen::Quaternionf &orientation) const
00467 {
00468   return (impl_->getCloudAt (idx, blob, origin, orientation));
00469 }
00470 
00472 size_t
00473 pcl::PCDGrabberBase::numFrames () const
00474 {
00475   return (impl_->numFrames ());
00476 }
00477 
00478 


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