pcl_base.h
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  *  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 #ifndef PCL_PCL_BASE_H_
00039 #define PCL_PCL_BASE_H_
00040 
00041 #if defined __GNUC__
00042 #  pragma GCC system_header
00043 #endif
00044 
00045 // Include PCL macros such as PCL_ERROR, etc
00046 #include <pcl/pcl_macros.h>
00047 
00048 #include <boost/shared_ptr.hpp>
00049 #include <Eigen/StdVector>
00050 #include <Eigen/Core>
00051 
00052 // Point Cloud message includes. Needed everywhere.
00053 #include <pcl/point_cloud.h>
00054 #include <pcl/PointIndices.h>
00055 #include <pcl/PCLPointCloud2.h>
00056 
00057 namespace pcl
00058 {
00059   // definitions used everywhere
00060   typedef boost::shared_ptr <std::vector<int> > IndicesPtr;
00061   typedef boost::shared_ptr <const std::vector<int> > IndicesConstPtr;
00062 
00064 
00067   template <typename PointT>
00068   class PCLBase
00069   {
00070     public:
00071       typedef pcl::PointCloud<PointT> PointCloud;
00072       typedef typename PointCloud::Ptr PointCloudPtr;
00073       typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00074 
00075       typedef boost::shared_ptr<PointIndices> PointIndicesPtr;
00076       typedef boost::shared_ptr<PointIndices const> PointIndicesConstPtr;
00077 
00079       PCLBase ();
00080       
00082       PCLBase (const PCLBase& base);
00083 
00085       virtual ~PCLBase ()
00086       {
00087         input_.reset ();
00088         indices_.reset ();
00089       }
00090       
00094       virtual void 
00095       setInputCloud (const PointCloudConstPtr &cloud);
00096 
00098       inline PointCloudConstPtr const 
00099       getInputCloud () { return (input_); }
00100 
00104       virtual void
00105       setIndices (const IndicesPtr &indices);
00106 
00110       virtual void
00111       setIndices (const IndicesConstPtr &indices);
00112 
00116       virtual void
00117       setIndices (const PointIndicesConstPtr &indices);
00118 
00127       virtual void 
00128       setIndices (size_t row_start, size_t col_start, size_t nb_rows, size_t nb_cols);
00129 
00131       inline IndicesPtr const 
00132       getIndices () { return (indices_); }
00133 
00139       inline const PointT& operator[] (size_t pos)
00140       {
00141         return ((*input_)[(*indices_)[pos]]);
00142       }
00143 
00144     protected:
00146       PointCloudConstPtr input_;
00147 
00149       IndicesPtr indices_;
00150 
00152       bool use_indices_;
00153 
00155       bool fake_indices_;
00156 
00166       bool
00167       initCompute ();
00168 
00171       bool
00172       deinitCompute ();
00173 
00174     public:
00175       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00176   };
00177 
00179   template <>
00180   class PCL_EXPORTS PCLBase<pcl::PCLPointCloud2>
00181   {
00182     public:
00183       typedef pcl::PCLPointCloud2 PCLPointCloud2;
00184       typedef boost::shared_ptr<PCLPointCloud2> PCLPointCloud2Ptr;
00185       typedef boost::shared_ptr<PCLPointCloud2 const> PCLPointCloud2ConstPtr;
00186 
00187       typedef boost::shared_ptr<PointIndices> PointIndicesPtr;
00188       typedef boost::shared_ptr<PointIndices const> PointIndicesConstPtr;
00189 
00191       PCLBase ();
00192      
00194       virtual ~PCLBase()
00195       {
00196         input_.reset ();
00197         indices_.reset ();
00198       }
00199 
00203       void 
00204       setInputCloud (const PCLPointCloud2ConstPtr &cloud);
00205 
00207       inline PCLPointCloud2ConstPtr const 
00208       getInputCloud () { return (input_); }
00209 
00213       void
00214       setIndices (const IndicesPtr &indices);
00215 
00219       void
00220       setIndices (const PointIndicesConstPtr &indices);
00221 
00223       inline IndicesPtr const 
00224       getIndices () { return (indices_); }
00225 
00226     protected:
00228       PCLPointCloud2ConstPtr input_;
00229 
00231       IndicesPtr indices_;
00232 
00234       bool use_indices_;
00235 
00237       bool fake_indices_;
00238 
00240       std::vector<int> field_sizes_;
00241 
00243       int x_idx_, y_idx_, z_idx_;
00244 
00246       std::string x_field_name_, y_field_name_, z_field_name_;
00247 
00248       bool initCompute ();
00249       bool deinitCompute ();
00250     public:
00251       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00252   };
00253 }
00254 
00255 #ifdef PCL_NO_PRECOMPILE
00256 #include <pcl/impl/pcl_base.hpp>
00257 #endif
00258 
00259 #endif  //#ifndef PCL_PCL_BASE_H_


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