Point Cloud Library (PCL)  1.14.0-dev
data_source.hpp
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  * Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com)
35  */
36 
37 
38 #ifndef PCL_GPU_FEATURES_TEST_DATA_SOURCE_HPP_
39 #define PCL_GPU_FEATURES_TEST_DATA_SOURCE_HPP_
40 
41 #include<string>
42 
43 #include <pcl/point_types.h>
44 #include <pcl/point_cloud.h>
45 #include <pcl/io/pcd_io.h>
46 #include <pcl/common/common.h>
47 #include <pcl/features/normal_3d.h>
48 #include <pcl/visualization/cloud_viewer.h>
49 #include <pcl/gpu/containers/kernel_containers.h>
50 #include <pcl/search/search.h>
51 
52 #include <Eigen/StdVector>
53 
54 #if defined (_WIN32) || defined(_WIN64)
55  EIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(pcl::PointXYZ)
56  EIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(pcl::Normal)
57 #endif
58 
59 #include <algorithm>
60 
61 namespace pcl
62 {
63  namespace gpu
64  {
65  struct DataSource
66  {
67  const static int k = 32;
68  const static int max_elements = 500;
69 
73 
76  float radius;
77 
78  std::vector< std::vector<int> > neighbors_all;
79  std::vector<int> sizes;
81 
82  DataSource(const std::string& file = "d:/office_chair_model.pcd")
83  : cloud(new PointCloud<PointXYZ>()), surface(new PointCloud<PointXYZ>()), indices( new std::vector<int>() ),
85  {
86  PCDReader pcd;
87  pcd.read(file, *cloud);
88 
89  PointXYZ minp, maxp;
90  pcl::getMinMax3D(*cloud, minp, maxp);
91  float sz = (maxp.x - minp.x + maxp.y - minp.y + maxp.z - minp.z) / 3;
92  radius = sz / 15;
93  }
94 
96  {
97  for (auto& p: *cloud)
98  {
99  int r = std::max(1, std::min(255, static_cast<int>((double(rand())/RAND_MAX)*255)));
100  int g = std::max(1, std::min(255, static_cast<int>((double(rand())/RAND_MAX)*255)));
101  int b = std::max(1, std::min(255, static_cast<int>((double(rand())/RAND_MAX)*255)));
102 
103  *reinterpret_cast<int*>(&p.data[3]) = (b << 16) + (g << 8) + r;
104  }
105  }
106 
108  {
110  ne.setInputCloud (cloud);
112  ne.setKSearch (k);
113  //ne.setRadiusSearch (radius);
114 
115  ne.compute (*normals);
116  }
117 
118  void runCloudViewer() const
119  {
120  pcl::visualization::CloudViewer viewer ("Simple Cloud Viewer");
121  viewer.showCloud (cloud);
122  while (!viewer.wasStopped ()) {}
123  }
124 
126  {
128  kdtree->setInputCloud(cloud);
129 
130  const auto cloud_size = cloud->size();
131 
132  std::vector<float> dists;
133  neighbors_all.resize(cloud_size);
134  for(std::size_t i = 0; i < cloud_size; ++i)
135  {
136  kdtree->nearestKSearch((*cloud)[i], k, neighbors_all[i], dists);
137  sizes.push_back((int)neighbors_all[i].size());
138  }
139  max_nn_size = *max_element(sizes.begin(), sizes.end());
140  }
141 
142  void findRadiusNeghbors(float radius = -1)
143  {
144  radius = radius == -1 ? this->radius : radius;
145 
147  kdtree->setInputCloud(cloud);
148 
149  const auto cloud_size = cloud->size();
150 
151  std::vector<float> dists;
152  neighbors_all.resize(cloud_size);
153  for(std::size_t i = 0; i < cloud_size; ++i)
154  {
155  kdtree->radiusSearch((*cloud)[i], radius, neighbors_all[i], dists);
156  sizes.push_back((int)neighbors_all[i].size());
157  }
158  max_nn_size = *max_element(sizes.begin(), sizes.end());
159  }
160 
161  void getNeghborsArray(std::vector<int>& data)
162  {
163  data.resize(max_nn_size * neighbors_all.size());
164  pcl::gpu::PtrStep<int> ps(&data[0], max_nn_size * sizeof(int));
165  for(std::size_t i = 0; i < neighbors_all.size(); ++i)
166  copy(neighbors_all[i].begin(), neighbors_all[i].end(), ps.ptr(i));
167  }
168 
170  {
171  surface->clear();
172  for(std::size_t i = 0; i < cloud->size(); i+= 10)
173  surface->push_back((*cloud)[i]);
174  surface->width = surface->size();
175  surface->height = 1;
176 
177  if (!normals->empty())
178  {
179  normals_surface->clear();
180  for(std::size_t i = 0; i < normals->size(); i+= 10)
181  normals_surface->push_back((*normals)[i]);
182 
183  normals_surface->width = surface->size();
184  normals_surface->height = 1;
185  }
186  }
187 
188  void generateIndices(std::size_t step = 100)
189  {
190  indices->clear();
191  for(std::size_t i = 0; i < cloud->size(); i += step)
192  indices->push_back(i);
193  }
194 
196  {
197  PointXYZ operator()(const Normal& n) const
198  {
199  PointXYZ xyz;
200  xyz.x = n.normal[0];
201  xyz.y = n.normal[1];
202  xyz.z = n.normal[2];
203  return xyz;
204  }
205  };
206  };
207  }
208 }
209 
210 #endif /* PCL_GPU_FEATURES_TEST_DATA_SOURCE_HPP_ */
void setKSearch(int k)
Set the number of k nearest neighbors to use for the feature estimation.
Definition: feature.h:184
void setSearchMethod(const KdTreePtr &tree)
Provide a pointer to the search object.
Definition: feature.h:164
void compute(PointCloudOut &output)
Base method for feature estimation for all points given in <setInputCloud (), setIndices ()> using th...
Definition: feature.hpp:194
KdTreeFLANN is a generic type of 3D spatial locator using kD-tree structures.
Definition: kdtree_flann.h:132
shared_ptr< KdTreeFLANN< PointT, Dist > > Ptr
Definition: kdtree_flann.h:151
int nearestKSearch(const PointT &point, unsigned int k, Indices &k_indices, std::vector< float > &k_sqr_distances) const override
Search for k-nearest neighbors for the given query point.
int radiusSearch(const PointT &point, double radius, Indices &k_indices, std::vector< float > &k_sqr_distances, unsigned int max_nn=0) const override
Search for all the nearest neighbors of the query point in a given radius.
void setInputCloud(const PointCloudConstPtr &cloud, const IndicesConstPtr &indices=IndicesConstPtr()) override
Provide a pointer to the input dataset.
NormalEstimation estimates local surface properties (surface normals and curvatures)at each 3D point.
Definition: normal_3d.h:244
void setInputCloud(const PointCloudConstPtr &cloud) override
Provide a pointer to the input dataset.
Definition: normal_3d.h:328
Point Cloud Data (PCD) file format reader.
Definition: pcd_io.h:55
int read(const std::string &file_name, pcl::PCLPointCloud2 &cloud, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &pcd_version, const int offset=0) override
Read a point cloud data from a PCD file and store it into a pcl/PCLPointCloud2.
PointCloud represents the base class in PCL for storing collections of 3D points.
Definition: point_cloud.h:173
shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:413
search::KdTree is a wrapper class which inherits the pcl::KdTree class for performing search function...
Definition: kdtree.h:62
shared_ptr< KdTree< PointT, Tree > > Ptr
Definition: kdtree.h:75
Simple point cloud visualization class.
Definition: cloud_viewer.h:53
bool wasStopped(int millis_to_wait=1)
Check if the gui was quit, you should quit also.
void showCloud(const ColorCloud::ConstPtr &cloud, const std::string &cloudname="cloud")
Show a cloud, with an optional key for multiple clouds.
Define standard C methods and C++ classes that are common to all methods.
Defines all the PCL implemented PointT point type structures.
void getMinMax3D(const pcl::PointCloud< PointT > &cloud, PointT &min_pt, PointT &max_pt)
Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud.
Definition: common.hpp:295
shared_ptr< Indices > IndicesPtr
Definition: pcl_base.h:58
A point structure representing normal coordinates and the surface curvature estimate.
A point structure representing Euclidean xyz coordinates.
PointXYZ operator()(const Normal &n) const
PointCloud< Normal >::Ptr normals_surface
Definition: data_source.hpp:75
PointCloud< Normal >::Ptr normals
Definition: data_source.hpp:74
static const int max_elements
Definition: data_source.hpp:68
PointCloud< PointXYZ >::Ptr surface
Definition: data_source.hpp:71
DataSource(const std::string &file="d:/office_chair_model.pcd")
Definition: data_source.hpp:82
static const int k
Definition: data_source.hpp:67
std::vector< std::vector< int > > neighbors_all
Definition: data_source.hpp:78
void getNeghborsArray(std::vector< int > &data)
void generateIndices(std::size_t step=100)
std::vector< int > sizes
Definition: data_source.hpp:79
void findRadiusNeghbors(float radius=-1)
void runCloudViewer() const
PointCloud< PointXYZ >::Ptr cloud
Definition: data_source.hpp:70
__PCL_GPU_HOST_DEVICE__ T * ptr(int y=0)