pcl_base.hpp
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  */
00037 #ifndef PCL_PCL_IMPL_BASE_HPP_
00038 #define PCL_PCL_IMPL_BASE_HPP_
00039 
00040 #include <pcl/pcl_base.h>
00041 #include <pcl/console/print.h>
00042 #include <cstddef>
00043 
00045 template <typename PointT>
00046 pcl::PCLBase<PointT>::PCLBase ()
00047   : input_ ()
00048   , indices_ ()
00049   , use_indices_ (false)
00050   , fake_indices_ (false)
00051 {
00052 }
00053 
00055 template <typename PointT>
00056 pcl::PCLBase<PointT>::PCLBase (const PCLBase& base)
00057   : input_ (base.input_)
00058   , indices_ (base.indices_)
00059   , use_indices_ (base.use_indices_)
00060   , fake_indices_ (base.fake_indices_)
00061 {
00062 }
00063 
00065 template <typename PointT> void
00066 pcl::PCLBase<PointT>::setInputCloud (const PointCloudConstPtr &cloud)
00067 { 
00068   input_ = cloud; 
00069 }
00070 
00072 template <typename PointT> void
00073 pcl::PCLBase<PointT>::setIndices (const IndicesPtr &indices)
00074 {
00075   indices_ = indices;
00076   fake_indices_ = false;
00077   use_indices_  = true;
00078 }
00079 
00081 template <typename PointT> void
00082 pcl::PCLBase<PointT>::setIndices (const IndicesConstPtr &indices)
00083 {
00084   indices_.reset (new std::vector<int> (*indices));
00085   fake_indices_ = false;
00086   use_indices_  = true;
00087 }
00088 
00090 template <typename PointT> void
00091 pcl::PCLBase<PointT>::setIndices (const PointIndicesConstPtr &indices)
00092 {
00093   indices_.reset (new std::vector<int> (indices->indices));
00094   fake_indices_ = false;
00095   use_indices_  = true;
00096 }
00097 
00099 template <typename PointT> void
00100 pcl::PCLBase<PointT>::setIndices (size_t row_start, size_t col_start, size_t nb_rows, size_t nb_cols)
00101 {
00102   if ((nb_rows > input_->height) || (row_start > input_->height))
00103   {
00104     PCL_ERROR ("[PCLBase::setIndices] cloud is only %d height", input_->height);
00105     return;
00106   }
00107 
00108   if ((nb_cols > input_->width) || (col_start > input_->width))
00109   {
00110     PCL_ERROR ("[PCLBase::setIndices] cloud is only %d width", input_->width);
00111     return;
00112   }
00113 
00114   size_t row_end = row_start + nb_rows;
00115   if (row_end > input_->height)
00116   {
00117     PCL_ERROR ("[PCLBase::setIndices] %d is out of rows range %d", row_end, input_->height);
00118     return;
00119   }
00120 
00121   size_t col_end = col_start + nb_cols;
00122   if (col_end > input_->width)
00123   {
00124     PCL_ERROR ("[PCLBase::setIndices] %d is out of columns range %d", col_end, input_->width);
00125     return;
00126   }
00127 
00128   indices_.reset (new std::vector<int>);
00129   indices_->reserve (nb_cols * nb_rows);
00130   for(size_t i = row_start; i < row_end; i++)
00131     for(size_t j = col_start; j < col_end; j++)
00132       indices_->push_back (static_cast<int> ((i * input_->width) + j));
00133   fake_indices_ = false;
00134   use_indices_  = true;
00135 }
00136 
00138 template <typename PointT> bool
00139 pcl::PCLBase<PointT>::initCompute ()
00140 {
00141   // Check if input was set
00142   if (!input_)
00143     return (false);
00144 
00145   // If no point indices have been given, construct a set of indices for the entire input point cloud
00146   if (!indices_)
00147   {
00148     fake_indices_ = true;
00149     indices_.reset (new std::vector<int>);
00150     try
00151     {
00152       indices_->resize (input_->points.size ());
00153     }
00154     catch (std::bad_alloc)
00155     {
00156       PCL_ERROR ("[initCompute] Failed to allocate %zu indices.\n", input_->points.size ());
00157     }
00158     for (size_t i = 0; i < indices_->size (); ++i) { (*indices_)[i] = static_cast<int>(i); }
00159   }
00160 
00161   // If we have a set of fake indices, but they do not match the number of points in the cloud, update them
00162   if (fake_indices_ && indices_->size () != input_->points.size ())
00163   {
00164     size_t indices_size = indices_->size ();
00165     indices_->resize (input_->points.size ());
00166     for (size_t i = indices_size; i < indices_->size (); ++i) { (*indices_)[i] = static_cast<int>(i); }
00167   }
00168 
00169   return (true);
00170 }
00171 
00173 template <typename PointT> bool
00174 pcl::PCLBase<PointT>::deinitCompute ()
00175 {
00176   return (true);
00177 }
00178 
00179 #define PCL_INSTANTIATE_PCLBase(T) template class PCL_EXPORTS pcl::PCLBase<T>;
00180 
00181 #endif  //#ifndef PCL_PCL_IMPL_BASE_HPP_
00182 


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