Point Cloud Library (PCL)  1.9.1-dev
tsdf_volume.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2011, Willow Garage, Inc.
6  *
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of Willow Garage, Inc. nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  */
37 
38 #pragma once
39 
40 #include <pcl/pcl_macros.h>
41 #include <pcl/gpu/containers/device_array.h>
42 #include <pcl/point_types.h>
43 #include <pcl/point_cloud.h>
44 #include <Eigen/Core>
45 #include <vector>
46 
47 #include <pcl/gpu/kinfu_large_scale/tsdf_buffer.h>
48 
49 #include <pcl/gpu/kinfu_large_scale/point_intensity.h>
50 
51 
52 namespace pcl
53 {
54  namespace gpu
55  {
56  namespace kinfuLS
57  {
58  /** \brief TsdfVolume class
59  * \author Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com)
60  */
62  {
63  public:
64  using Ptr = boost::shared_ptr<TsdfVolume>;
65 
66  /** \brief Supported Point Types */
68  using NormalType = Normal;
69 
70  /** \brief Structure storing voxel grid resolution, volume size (in mm) and element_size of data stored on host*/
71  struct Header
72  {
73  Eigen::Vector3i resolution;
74  Eigen::Vector3f volume_size;
75  int volume_element_size, weights_element_size;
76 
77  Header ()
78  : resolution (0,0,0),
79  volume_size (0,0,0),
80  volume_element_size (sizeof(float)),
81  weights_element_size (sizeof(short))
82  {};
83 
84  Header (const Eigen::Vector3i &res, const Eigen::Vector3f &size)
85  : resolution (res),
86  volume_size (size),
87  volume_element_size (sizeof(float)),
88  weights_element_size (sizeof(short))
89  {};
90 
91  /** \brief Get the size of data stored on host*/
92  inline size_t
93  getVolumeSize () const { return resolution[0] * resolution[1] * resolution[2]; };
94 
95  friend inline std::ostream&
96  operator << (std::ostream& os, const Header& h)
97  {
98  os << "(resolution = " << h.resolution.transpose() << ", volume size = " << h.volume_size.transpose() << ")";
99  return (os);
100  }
101 
102  public:
104  };
105 
106  /** \brief Default buffer size for fetching cloud. It limits max number of points that can be extracted */
107  enum { DEFAULT_CLOUD_BUFFER_SIZE = 10 * 1000 * 1000 };
108 
109  /** \brief Constructor
110  * \param[in] resolution volume resolution
111  */
112  TsdfVolume (const Eigen::Vector3i& resolution);
113 
114  /** \brief Sets Tsdf volume size for each dimension
115  * \param[in] size size of tsdf volume in meters
116  */
117  void
118  setSize (const Eigen::Vector3f& size);
119 
120  /** \brief Sets Tsdf truncation distance. Must be greater than 2 * volume_voxel_size
121  * \param[in] distance TSDF truncation distance
122  */
123  void
124  setTsdfTruncDist (float distance);
125 
126  /** \brief Returns tsdf volume container that point to data in GPU memory */
128  data () const;
129 
130  /** \brief Returns volume size in meters */
131  const Eigen::Vector3f&
132  getSize () const;
133 
134  /** \brief Returns volume resolution */
135  const Eigen::Vector3i&
136  getResolution() const;
137 
138  /** \brief Returns volume voxel size in meters */
139  const Eigen::Vector3f
140  getVoxelSize () const;
141 
142  /** \brief Returns tsdf truncation distance in meters */
143  float
144  getTsdfTruncDist () const;
145 
146  /** \brief Resets tsdf volume data to uninitialized state */
147  void
148  reset ();
149 
150  /** \brief Generates cloud using CPU (downloads volumetric representation to CPU memory)
151  * \param[out] cloud output array for cloud
152  * \param[in] connected26 If false point cloud is extracted using 6 neighbor, otherwise 26.
153  */
154  void
155  fetchCloudHost (PointCloud<PointType>& cloud, bool connected26 = false) const;
156 
157  /** \brief Generates cloud using CPU (downloads volumetric representation to CPU memory)
158  * \param[out] cloud output array for cloud
159  * \param[in] connected26 If false point cloud is extracted using 6 neighbor, otherwise 26.
160  */
161  void
162  fetchCloudHost (PointCloud<PointXYZI>& cloud, bool connected26 = false) const;
163 
164  /** \brief Generates cloud using GPU in connected6 mode only
165  * \param[out] cloud_buffer buffer to store point cloud
166  * \return DeviceArray with disabled reference counting that points to filled part of cloud_buffer.
167  */
169  fetchCloud (DeviceArray<PointType>& cloud_buffer) const;
170 
171  /** \brief Push a point cloud of previously scanned tsdf slice to the TSDF volume
172  * \param[in] existing_data_cloud point cloud pointer to the existing data. This data will be pushed to the TSDf volume. The points with indices outside the range [0 ... VOLUME_X - 1][0 ... VOLUME_Y - 1][0 ... VOLUME_Z - 1] will not be added.
173  * \param buffer
174  */
175  void
176  pushSlice (const PointCloud<PointXYZI>::Ptr existing_data_cloud, const tsdf_buffer* buffer) const;
177 
178  /** \brief Generates cloud using GPU in connected6 mode only
179  * \param[out] cloud_buffer_xyz buffer to store point cloud
180  * \param cloud_buffer_intensity
181  * \param[in] buffer Pointer to the buffer struct that contains information about memory addresses of the tsdf volume memory block, which are used for the cyclic buffer.
182  * \param[in] shiftX Offset in indices.
183  * \param[in] shiftY Offset in indices.
184  * \param[in] shiftZ Offset in indices.
185  * \return DeviceArray with disabled reference counting that points to filled part of cloud_buffer.
186  */
187  size_t
188  fetchSliceAsCloud (DeviceArray<PointType>& cloud_buffer_xyz, DeviceArray<float>& cloud_buffer_intensity, const tsdf_buffer* buffer, int shiftX, int shiftY, int shiftZ ) const;
189 
190  /** \brief Computes normals as gradient of tsdf for given points
191  * \param[in] cloud Points where normals are computed.
192  * \param[out] normals array for normals
193  */
194 
195  void
196  fetchNormals (const DeviceArray<PointType>& cloud, DeviceArray<PointType>& normals) const;
197 
198  /** \brief Computes normals as gradient of tsdf for given points
199  * \param[in] cloud Points where normals are computed.
200  * \param[out] normals array for normals
201  */
202  void
203  fetchNormals(const DeviceArray<PointType>& cloud, DeviceArray<NormalType>& normals) const;
204 
205  /** \brief Downloads tsdf volume from GPU memory.
206  * \param[out] tsdf Array with tsdf values. if volume resolution is 512x512x512, so for voxel (x,y,z) tsdf value can be retrieved as volume[512*512*z + 512*y + x];
207  */
208  void
209  downloadTsdf (std::vector<float>& tsdf) const;
210 
211  /** \brief Downloads tsdf volume from GPU memory to local CPU buffer*/
212  void
213  downloadTsdfLocal () const;
214 
215  /** \brief Downloads TSDF volume and according voxel weights from GPU memory
216  * \param[out] tsdf Array with tsdf values. if volume resolution is 512x512x512, so for voxel (x,y,z) tsdf value can be retrieved as volume[512*512*z + 512*y + x];
217  * \param[out] weights Array with tsdf voxel weights. Same size and access index as for tsdf. A weight of 0 indicates the voxel was never used.
218  */
219  void
220  downloadTsdfAndWeights (std::vector<float>& tsdf, std::vector<short>& weights) const;
221 
222  /** \brief Downloads TSDF volume and according voxel weights from GPU memory to local CPU buffers*/
223  void
224  downloadTsdfAndWeightsLocal () const;
225 
226  /** \brief Releases tsdf buffer on GPU */
227  void releaseVolume () {volume_.release();}
228 
229  void print_warn(const char* arg1, size_t size);
230 
231  /** \brief Set the header for data stored on host directly. Useful if directly writing into volume and weights */
232  inline void
233  setHeader (const Eigen::Vector3i& resolution, const Eigen::Vector3f& volume_size) {
234  header_ = Header (resolution, volume_size);
235  if (volume_host_->size() != this->size())
236  pcl::console::print_warn ("[TSDFVolume::setHeader] Header volume size (%d) doesn't fit underlying data size (%d)", volume_host_->size(), size());
237  }
238 
239  /** \brief Returns overall number of voxels in grid stored on host */
240  inline size_t
241  size () const {
242  return header_.getVolumeSize ();
243  }
244 
245  /** \brief Converts volume stored on host to cloud of TSDF values
246  * \param[ou] cloud - the output point cloud
247  * \param[in] step - the decimation step to use
248  */
249  void
250  convertToTsdfCloud (pcl::PointCloud<pcl::PointXYZI>::Ptr &cloud,
251  const unsigned step = 2) const;
252 
253  /** \brief Returns the voxel grid resolution */
254  inline const Eigen::Vector3i &
255  gridResolution () const { return header_.resolution; };
256 
257  /** \brief Saves local volume buffer to file */
258  bool
259  save (const std::string &filename = "tsdf_volume.dat", bool binary = true) const;
260 
261  /** \brief Loads local volume from file */
262  bool
263  load (const std::string &filename, bool binary = true);
264 
265  private:
266  /** \brief tsdf volume size in meters */
267  Eigen::Vector3f size_;
268 
269  /** \brief tsdf volume resolution */
270  Eigen::Vector3i resolution_;
271 
272  /** \brief tsdf volume data container */
273  DeviceArray2D<int> volume_;
274 
275  /** \brief tsdf truncation distance */
276  float tranc_dist_;
277 
278  // The following member are resulting from the merge of TSDFVolume with TsdfVolume class.
279  using VolumePtr = boost::shared_ptr<std::vector<float> >;
280  using WeightsPtr = boost::shared_ptr<std::vector<short> >;
281 
282  Header header_;
283  VolumePtr volume_host_;
284  WeightsPtr weights_host_;
285 
286  public:
288  };
289  }
290  }
291 }
A point structure representing normal coordinates and the surface curvature estimate.
void setHeader(const Eigen::Vector3i &resolution, const Eigen::Vector3f &volume_size)
Set the header for data stored on host directly.
Definition: tsdf_volume.h:233
PCL_EXPORTS int load(const std::string &file_name, pcl::PCLPointCloud2 &blob)
Load a file into a PointCloud2 according to extension.
Structure to handle buffer addresses.
Definition: tsdf_buffer.h:50
boost::shared_ptr< TsdfVolume > Ptr
Definition: tsdf_volume.h:64
This file defines compatibility wrappers for low level I/O functions.
Definition: convolution.h:45
#define PCL_MAKE_ALIGNED_OPERATOR_NEW
Macro to signal a class requires a custom allocator.
Definition: pcl_macros.h:345
size_t size() const
Returns overall number of voxels in grid stored on host.
Definition: tsdf_volume.h:241
const Eigen::Vector3i & gridResolution() const
Returns the voxel grid resolution.
Definition: tsdf_volume.h:255
Defines all the PCL implemented PointT point type structures.
A point structure representing Euclidean xyz coordinates.
size_t getVolumeSize() const
Get the size of data stored on host.
Definition: tsdf_volume.h:93
TsdfVolume class.
Definition: tsdf_volume.h:61
Structure storing voxel grid resolution, volume size (in mm) and element_size of data stored on host...
Definition: tsdf_volume.h:71
float distance(const PointT &p1, const PointT &p2)
Definition: geometry.h:60
Header(const Eigen::Vector3i &res, const Eigen::Vector3f &size)
Definition: tsdf_volume.h:84
boost::shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:444
PointCloud represents the base class in PCL for storing collections of 3D points. ...
PCL_EXPORTS void print_warn(const char *format,...)
Print a warning message on stream with colors.
void releaseVolume()
Releases tsdf buffer on GPU.
Definition: tsdf_volume.h:227
PCL_EXPORTS int save(const std::string &file_name, const pcl::PCLPointCloud2 &blob, unsigned precision=5)
Save point cloud data to a binary file when available else to ASCII.
#define PCL_EXPORTS
Definition: pcl_macros.h:227
Defines all the PCL and non-PCL macros used.
std::ostream & operator<<(std::ostream &os, const float3 &v1)