pcl_base.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-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 
00039 #include <pcl/impl/pcl_base.hpp>
00040 
00042 pcl::PCLBase<pcl::PCLPointCloud2>::PCLBase ()
00043   : input_ ()
00044   , indices_ ()
00045   , use_indices_ (false)
00046   , fake_indices_ (false)
00047   , field_sizes_ (0)
00048   , x_idx_ (-1)
00049   , y_idx_ (-1)
00050   , z_idx_ (-1)
00051   , x_field_name_ ("x")
00052   , y_field_name_ ("y")
00053   , z_field_name_ ("z")
00054 {
00055 }
00056 
00058 void
00059 pcl::PCLBase<pcl::PCLPointCloud2>::setInputCloud (const PCLPointCloud2ConstPtr &cloud)
00060 {
00061   input_ = cloud;
00062 
00063   for (int d = 0; d < static_cast<int>(cloud->fields.size ()); ++d)
00064   {
00065     if (cloud->fields[d].name == x_field_name_)
00066       x_idx_ = d;
00067     if (cloud->fields[d].name == y_field_name_)
00068       y_idx_ = d;
00069     if (cloud->fields[d].name == z_field_name_)
00070       z_idx_ = d;
00071   }
00072 
00073   // Obtain the size of all fields. Restrict to sizeof FLOAT32 for now
00074   field_sizes_.resize (input_->fields.size ());
00075   for (size_t d = 0; d < input_->fields.size (); ++d)
00076   {
00077     int fsize;
00078     switch (input_->fields[d].datatype)
00079     {
00080       case pcl::PCLPointField::INT8:
00081       case pcl::PCLPointField::UINT8:
00082       {
00083         fsize = 1;
00084         break;
00085       }
00086 
00087       case pcl::PCLPointField::INT16:
00088       case pcl::PCLPointField::UINT16:
00089       {
00090         fsize = 2;
00091         break;
00092       }
00093 
00094       case pcl::PCLPointField::INT32:
00095       case pcl::PCLPointField::UINT32:
00096       case pcl::PCLPointField::FLOAT32:
00097       {
00098         fsize = 4;
00099         break;
00100       }
00101 
00102       case pcl::PCLPointField::FLOAT64:
00103       {
00104         fsize = 8;
00105         break;
00106       }
00107 
00108       default:
00109       {
00110         PCL_ERROR ("[PCLBase::setInputCloud] Invalid field type (%d)!\n", input_->fields[d].datatype);
00111         fsize = 0;
00112         break;
00113       }
00114     }
00115     field_sizes_[d] = (std::min) (fsize, static_cast<int>(sizeof (float)));
00116   }
00117 }
00118 
00120 bool
00121 pcl::PCLBase<pcl::PCLPointCloud2>::deinitCompute ()
00122 {
00123   return (true);
00124 }
00125 
00127 bool
00128 pcl::PCLBase<pcl::PCLPointCloud2>::initCompute ()
00129 {
00130   // Check if input was set
00131   if (!input_)
00132     return (false);
00133 
00134   // If no point indices have been given, construct a set of indices for the entire input point cloud
00135   if (!indices_)
00136   {
00137     fake_indices_ = true;
00138     indices_.reset (new std::vector<int>);
00139     try
00140     {
00141       indices_->resize (input_->width * input_->height);
00142     }
00143     catch (std::bad_alloc)
00144     {
00145       PCL_ERROR ("[initCompute] Failed to allocate %zu indices.\n", (input_->width * input_->height));
00146     }
00147     for (size_t i = 0; i < indices_->size (); ++i) { (*indices_)[i] = static_cast<int>(i); }
00148   }
00149   // If we have a set of fake indices, but they do not match the number of points in the cloud, update them
00150   if (fake_indices_ && indices_->size () != (input_->width * input_->height))
00151   {
00152     size_t indices_size = indices_->size ();
00153     indices_->resize (input_->width * input_->height);
00154     for (size_t i = indices_size; i < indices_->size (); ++i) { (*indices_)[i] = static_cast<int>(i); }
00155   }
00156 
00157   return (true);
00158 }
00159 
00161 void
00162 pcl::PCLBase<pcl::PCLPointCloud2>::setIndices (const IndicesPtr &indices)
00163 {
00164   indices_ = indices;
00165   fake_indices_ = false;
00166   use_indices_  = true;
00167 }
00168 
00170 void
00171 pcl::PCLBase<pcl::PCLPointCloud2>::setIndices (const PointIndicesConstPtr &indices)
00172 {
00173   indices_.reset (new std::vector<int> (indices->indices));
00174   fake_indices_ = false;
00175   use_indices_  = true;
00176 }
00177 
00178 #ifndef PCL_NO_PRECOMPILE
00179 #include <pcl/impl/instantiate.hpp>
00180 #include <pcl/point_types.h>
00181 PCL_INSTANTIATE(PCLBase, PCL_POINT_TYPES)
00182 #endif    // PCL_NO_PRECOMPILE
00183 


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