00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef PCL_PCL_BASE_H_
00038 #define PCL_PCL_BASE_H_
00039
00040
00041 #include <Eigen/StdVector>
00042
00043 #include <vector>
00044
00045
00046 #include "pcl/ros_macros.h"
00047
00048
00049 #include <boost/shared_ptr.hpp>
00050 #include <boost/make_shared.hpp>
00051
00052
00053 #include <sensor_msgs/PointCloud2.h>
00054 #include "pcl/point_cloud.h"
00055 #include "pcl/PointIndices.h"
00056 #include "pcl/win32_macros.h"
00057
00058 namespace pcl
00059 {
00060
00061 typedef boost::shared_ptr <std::vector<int> > IndicesPtr;
00062 typedef boost::shared_ptr <const std::vector<int> > IndicesConstPtr;
00063
00065
00066 template <typename PointT>
00067 class PCLBase
00068 {
00069 public:
00070 typedef pcl::PointCloud<PointT> PointCloud;
00071 typedef typename PointCloud::Ptr PointCloudPtr;
00072 typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00073
00074 typedef PointIndices::Ptr PointIndicesPtr;
00075 typedef PointIndices::ConstPtr PointIndicesConstPtr;
00076
00078 PCLBase () : input_ (), indices_ (), use_indices_ (false), fake_indices_ (false) {};
00079
00083 virtual inline void
00084 setInputCloud (const PointCloudConstPtr &cloud) { input_ = cloud; }
00085
00087 inline PointCloudConstPtr const
00088 getInputCloud () { return (input_); }
00089
00093 inline void
00094 setIndices (const IndicesConstPtr &indices)
00095 {
00096 indices_ = indices;
00097 fake_indices_ = false;
00098 use_indices_ = true;
00099 }
00100
00104 inline void
00105 setIndices (const PointIndicesConstPtr &indices)
00106 {
00107 indices_ = boost::make_shared<std::vector<int> > (indices->indices);
00108 fake_indices_ = false;
00109 use_indices_ = true;
00110 }
00111
00113 inline IndicesConstPtr const
00114 getIndices () { return (indices_); }
00115
00116 protected:
00118 PointCloudConstPtr input_;
00119
00121 IndicesConstPtr indices_;
00122
00124 bool use_indices_;
00125
00127 bool fake_indices_;
00128
00130 bool
00131 initCompute ()
00132 {
00133
00134 if (!input_)
00135 return (false);
00136
00137
00138 if (!indices_)
00139 {
00140 fake_indices_ = true;
00141 std::vector<int> *indices = NULL;
00142 try
00143 {
00144 indices = new std::vector<int> (input_->points.size ());
00145 }
00146 catch (std::bad_alloc)
00147 {
00148 ROS_ERROR ("[initCompute] Failed to allocate %zu indices.", input_->points.size ());
00149 }
00150 for (size_t i = 0; i < indices->size (); ++i) { (*indices)[i] = i; }
00151 indices_.reset (indices);
00152 }
00153 return (true);
00154 }
00155
00157 bool
00158 deinitCompute ()
00159 {
00160
00161 if (fake_indices_)
00162 {
00163 indices_.reset ();
00164 fake_indices_ = false;
00165 }
00166 return (true);
00167 }
00168 public:
00169 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00170 };
00171
00173 template <>
00174 class PCLBase<sensor_msgs::PointCloud2>
00175 {
00176 public:
00177 typedef sensor_msgs::PointCloud2 PointCloud2;
00178 typedef PointCloud2::Ptr PointCloud2Ptr;
00179 typedef PointCloud2::ConstPtr PointCloud2ConstPtr;
00180
00181 typedef PointIndices::Ptr PointIndicesPtr;
00182 typedef PointIndices::ConstPtr PointIndicesConstPtr;
00183
00185 PCLBase () : input_ (), indices_ (), use_indices_ (false), fake_indices_ (false),
00186 x_field_name_ ("x"), y_field_name_ ("y"), z_field_name_ ("z")
00187 {};
00188
00192 void
00193 setInputCloud (const PointCloud2ConstPtr &cloud);
00194
00196 inline PointCloud2ConstPtr const
00197 getInputCloud () { return (input_); }
00198
00202 inline void
00203 setIndices (const IndicesConstPtr &indices)
00204 {
00205 indices_ = indices;
00206 fake_indices_ = false;
00207 use_indices_ = true;
00208 }
00209
00213 inline void
00214 setIndices (const PointIndicesConstPtr &indices)
00215 {
00216 indices_ = boost::make_shared<std::vector<int> > (indices->indices);
00217 fake_indices_ = false;
00218 use_indices_ = true;
00219 }
00220
00222 inline IndicesConstPtr const
00223 getIndices () { return (indices_); }
00224
00225 protected:
00227 PointCloud2ConstPtr input_;
00228
00230 IndicesConstPtr indices_;
00231
00233 bool use_indices_;
00234
00236 bool fake_indices_;
00237
00239 std::vector<int> field_sizes_;
00240
00242 int x_idx_, y_idx_, z_idx_;
00243
00245 std::string x_field_name_, y_field_name_, z_field_name_;
00246
00247 bool initCompute ();
00248 bool deinitCompute ();
00249 public:
00250 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00251 };
00252 }
00253
00254 #endif //#ifndef PCL_PCL_BASE_H_