|
Point Cloud Library (PCL)
1.4.0
|
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 * 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 * $Id: pcl_base.h 3771 2012-01-01 06:58:14Z rusu $ 00037 * 00038 */ 00039 #ifndef PCL_PCL_BASE_H_ 00040 #define PCL_PCL_BASE_H_ 00041 00042 #include <cstddef> 00043 // Eigen includes 00044 #include <Eigen/StdVector> 00045 // STD includes 00046 #include <vector> 00047 00048 // Include PCL macros such as PCL_ERROR, etc 00049 #include "pcl/pcl_macros.h" 00050 00051 // Boost includes. Needed everywhere. 00052 #include <boost/shared_ptr.hpp> 00053 00054 // Point Cloud message includes. Needed everywhere. 00055 #include <sensor_msgs/PointCloud2.h> 00056 #include "pcl/point_cloud.h" 00057 #include "pcl/PointIndices.h" 00058 #include <pcl/pcl_macros.h> 00059 00060 #include <pcl/console/print.h> 00061 00062 namespace pcl 00063 { 00064 // definitions used everywhere 00065 typedef boost::shared_ptr <std::vector<int> > IndicesPtr; 00066 typedef boost::shared_ptr <const std::vector<int> > IndicesConstPtr; 00067 00069 00072 template <typename PointT> 00073 class PCLBase 00074 { 00075 public: 00076 typedef pcl::PointCloud<PointT> PointCloud; 00077 typedef typename PointCloud::Ptr PointCloudPtr; 00078 typedef typename PointCloud::ConstPtr PointCloudConstPtr; 00079 00080 typedef PointIndices::Ptr PointIndicesPtr; 00081 typedef PointIndices::ConstPtr PointIndicesConstPtr; 00082 00084 PCLBase () : input_ (), indices_ (), use_indices_ (false), fake_indices_ (false) {} 00085 00087 PCLBase (const PCLBase& base) 00088 : input_ (base.input_) 00089 , indices_ (base.indices_) 00090 , use_indices_ (base.use_indices_) 00091 , fake_indices_ (base.fake_indices_) 00092 {} 00093 00095 virtual ~PCLBase() 00096 { 00097 input_.reset (); 00098 indices_.reset (); 00099 } 00100 00104 virtual inline void 00105 setInputCloud (const PointCloudConstPtr &cloud) { input_ = cloud; } 00106 00108 inline PointCloudConstPtr const 00109 getInputCloud () { return (input_); } 00110 00114 inline void 00115 setIndices (const IndicesPtr &indices) 00116 { 00117 indices_ = indices; 00118 fake_indices_ = false; 00119 use_indices_ = true; 00120 } 00121 00125 inline void 00126 setIndices (const IndicesConstPtr &indices) 00127 { 00128 indices_.reset (new std::vector<int> (*indices)); 00129 fake_indices_ = false; 00130 use_indices_ = true; 00131 } 00132 00136 inline void 00137 setIndices (const PointIndicesConstPtr &indices) 00138 { 00139 indices_.reset (new std::vector<int> (indices->indices)); 00140 fake_indices_ = false; 00141 use_indices_ = true; 00142 } 00143 00152 inline void 00153 setIndices (size_t row_start, size_t col_start, size_t nb_rows, size_t nb_cols) 00154 { 00155 if ((nb_rows > input_->height) || (row_start > input_->height)) 00156 { 00157 PCL_ERROR ("[PCLBase::setIndices] cloud is only %d height", input_->height); 00158 return; 00159 } 00160 00161 if ((nb_cols > input_->width) || (col_start > input_->width)) 00162 { 00163 PCL_ERROR ("[PCLBase::setIndices] cloud is only %d width", input_->width); 00164 return; 00165 } 00166 00167 size_t row_end = row_start + nb_rows; 00168 if (row_end > input_->height) 00169 { 00170 PCL_ERROR ("[PCLBase::setIndices] %d is out of rows range %d", row_end, input_->height); 00171 return; 00172 } 00173 00174 size_t col_end = col_start + nb_cols; 00175 if (col_end > input_->width) 00176 { 00177 PCL_ERROR ("[PCLBase::setIndices] %d is out of columns range %d", col_end, input_->width); 00178 return; 00179 } 00180 00181 indices_.reset (new std::vector<int>); 00182 indices_->reserve (nb_cols * nb_rows); 00183 for(size_t i = row_start; i < row_end; i++) 00184 for(size_t j = col_start; j < col_end; j++) 00185 indices_->push_back ((i * input_->width) + j); 00186 fake_indices_ = false; 00187 use_indices_ = true; 00188 } 00189 00191 inline IndicesPtr const 00192 getIndices () { return (indices_); } 00193 00199 const PointT& operator[] (size_t pos) 00200 { 00201 return ((*input_)[(*indices_)[pos]]); 00202 } 00203 00204 protected: 00206 PointCloudConstPtr input_; 00207 00209 IndicesPtr indices_; 00210 00212 bool use_indices_; 00213 00215 bool fake_indices_; 00216 00226 inline bool 00227 initCompute () 00228 { 00229 // Check if input was set 00230 if (!input_) 00231 return (false); 00232 00233 // If no point indices have been given, construct a set of indices for the entire input point cloud 00234 if (!indices_) 00235 { 00236 fake_indices_ = true; 00237 indices_.reset (new std::vector<int>); 00238 try 00239 { 00240 indices_->resize (input_->points.size ()); 00241 } 00242 catch (std::bad_alloc) 00243 { 00244 PCL_ERROR ("[initCompute] Failed to allocate %lu indices.\n", (unsigned long)input_->points.size ()); 00245 } 00246 for (size_t i = 0; i < indices_->size (); ++i) { (*indices_)[i] = (int) i; } 00247 } 00248 00249 // If we have a set of fake indices, but they do not match the number of points in the cloud, update them 00250 if (fake_indices_ && indices_->size () != input_->points.size ()) 00251 { 00252 size_t indices_size = indices_->size (); 00253 indices_->resize (input_->points.size ()); 00254 for (size_t i = indices_size; i < indices_->size (); ++i) { (*indices_)[i] = (int) i; } 00255 } 00256 00257 return (true); 00258 } 00259 00263 inline bool 00264 deinitCompute () 00265 { 00266 return (true); 00267 } 00268 public: 00269 EIGEN_MAKE_ALIGNED_OPERATOR_NEW 00270 }; 00271 00273 template <> 00274 class PCL_EXPORTS PCLBase<sensor_msgs::PointCloud2> 00275 { 00276 public: 00277 typedef sensor_msgs::PointCloud2 PointCloud2; 00278 typedef PointCloud2::Ptr PointCloud2Ptr; 00279 typedef PointCloud2::ConstPtr PointCloud2ConstPtr; 00280 00281 typedef PointIndices::Ptr PointIndicesPtr; 00282 typedef PointIndices::ConstPtr PointIndicesConstPtr; 00283 00285 PCLBase () : input_ (), indices_ (), use_indices_ (false), fake_indices_ (false), 00286 x_field_name_ ("x"), y_field_name_ ("y"), z_field_name_ ("z") 00287 {}; 00288 00290 virtual ~PCLBase() 00291 { 00292 input_.reset (); 00293 indices_.reset (); 00294 } 00295 00299 void 00300 setInputCloud (const PointCloud2ConstPtr &cloud); 00301 00303 inline PointCloud2ConstPtr const 00304 getInputCloud () { return (input_); } 00305 00309 inline void 00310 setIndices (const IndicesPtr &indices) 00311 { 00312 indices_ = indices; 00313 fake_indices_ = false; 00314 use_indices_ = true; 00315 } 00316 00320 inline void 00321 setIndices (const PointIndicesConstPtr &indices) 00322 { 00323 indices_.reset (new std::vector<int> (indices->indices)); 00324 fake_indices_ = false; 00325 use_indices_ = true; 00326 } 00327 00329 inline IndicesPtr const 00330 getIndices () { return (indices_); } 00331 00332 protected: 00334 PointCloud2ConstPtr input_; 00335 00337 IndicesPtr indices_; 00338 00340 bool use_indices_; 00341 00343 bool fake_indices_; 00344 00346 std::vector<int> field_sizes_; 00347 00349 int x_idx_, y_idx_, z_idx_; 00350 00352 std::string x_field_name_, y_field_name_, z_field_name_; 00353 00354 bool initCompute (); 00355 bool deinitCompute (); 00356 public: 00357 EIGEN_MAKE_ALIGNED_OPERATOR_NEW 00358 }; 00359 } 00360 00361 #endif //#ifndef PCL_PCL_BASE_H_
1.7.6.1