37 #ifndef PCL_PCL_IMPL_BASE_HPP_ 38 #define PCL_PCL_IMPL_BASE_HPP_ 40 #include <pcl/pcl_base.h> 41 #include <pcl/console/print.h> 45 template <
typename Po
intT>
49 , use_indices_ (false)
50 , fake_indices_ (false)
55 template <
typename Po
intT>
65 template <
typename Po
intT>
void 72 template <
typename Po
intT>
void 81 template <
typename Po
intT>
void 84 indices_.reset (
new std::vector<int> (*indices));
90 template <
typename Po
intT>
void 93 indices_.reset (
new std::vector<int> (indices->indices));
99 template <
typename Po
intT>
void 102 if ((nb_rows >
input_->height) || (row_start >
input_->height))
104 PCL_ERROR (
"[PCLBase::setIndices] cloud is only %d height",
input_->height);
108 if ((nb_cols >
input_->width) || (col_start >
input_->width))
110 PCL_ERROR (
"[PCLBase::setIndices] cloud is only %d width",
input_->width);
114 size_t row_end = row_start + nb_rows;
115 if (row_end >
input_->height)
117 PCL_ERROR (
"[PCLBase::setIndices] %d is out of rows range %d", row_end,
input_->height);
121 size_t col_end = col_start + nb_cols;
122 if (col_end >
input_->width)
124 PCL_ERROR (
"[PCLBase::setIndices] %d is out of columns range %d", col_end,
input_->width);
128 indices_.reset (
new std::vector<int>);
129 indices_->reserve (nb_cols * nb_rows);
130 for(
size_t i = row_start; i < row_end; i++)
131 for(
size_t j = col_start; j < col_end; j++)
138 template <
typename Po
intT>
bool 149 indices_.reset (
new std::vector<int>);
154 catch (
const std::bad_alloc&)
156 PCL_ERROR (
"[initCompute] Failed to allocate %lu indices.\n",
input_->points.size ());
158 for (
size_t i = 0; i <
indices_->size (); ++i) { (*indices_)[i] =
static_cast<int>(i); }
164 size_t indices_size =
indices_->size ();
166 for (
size_t i = indices_size; i <
indices_->size (); ++i) { (*indices_)[i] =
static_cast<int>(i); }
173 template <
typename Po
intT>
bool 179 #define PCL_INSTANTIATE_PCLBase(T) template class PCL_EXPORTS pcl::PCLBase<T>; 181 #endif //#ifndef PCL_PCL_IMPL_BASE_HPP_ PointCloud::ConstPtr PointCloudConstPtr
boost::shared_ptr< std::vector< int > > IndicesPtr
IndicesPtr indices_
A pointer to the vector of point indices to use.
bool use_indices_
Set to true if point indices are used.
bool initCompute()
This method should get called before starting the actual computation.
boost::shared_ptr< PointIndices const > PointIndicesConstPtr
bool deinitCompute()
This method should get called after finishing the actual computation.
virtual void setIndices(const IndicesPtr &indices)
Provide a pointer to the vector of indices that represents the input data.
PCLBase()
Empty constructor.
virtual void setInputCloud(const PointCloudConstPtr &cloud)
Provide a pointer to the input dataset.
boost::shared_ptr< const std::vector< int > > IndicesConstPtr
PointCloudConstPtr input_
The input point cloud dataset.
bool fake_indices_
If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud...