Point Cloud Library (PCL)  1.10.0-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:
66 
67  /** \brief Supported Point Types */
69  using NormalType = Normal;
70 
71  /** \brief Structure storing voxel grid resolution, volume size (in mm) and element_size of data stored on host*/
72  struct Header
73  {
74  Eigen::Vector3i resolution;
75  Eigen::Vector3f volume_size;
76  int volume_element_size, weights_element_size;
77 
78  Header ()
79  : resolution (0,0,0),
80  volume_size (0,0,0),
81  volume_element_size (sizeof(float)),
82  weights_element_size (sizeof(short))
83  {};
84 
85  Header (const Eigen::Vector3i &res, const Eigen::Vector3f &size)
86  : resolution (res),
87  volume_size (size),
88  volume_element_size (sizeof(float)),
89  weights_element_size (sizeof(short))
90  {};
91 
92  /** \brief Get the size of data stored on host*/
93  inline std::size_t
94  getVolumeSize () const { return resolution[0] * resolution[1] * resolution[2]; };
95 
96  friend inline std::ostream&
97  operator << (std::ostream& os, const Header& h)
98  {
99  os << "(resolution = " << h.resolution.transpose() << ", volume size = " << h.volume_size.transpose() << ")";
100  return (os);
101  }
102 
103  public:
105  };
106 
107  /** \brief Default buffer size for fetching cloud. It limits max number of points that can be extracted */
108  enum { DEFAULT_CLOUD_BUFFER_SIZE = 10 * 1000 * 1000 };
109 
110  /** \brief Constructor
111  * \param[in] resolution volume resolution
112  */
113  TsdfVolume (const Eigen::Vector3i& resolution);
114 
115  /** \brief Sets Tsdf volume size for each dimension
116  * \param[in] size size of tsdf volume in meters
117  */
118  void
119  setSize (const Eigen::Vector3f& size);
120 
121  /** \brief Sets Tsdf truncation distance. Must be greater than 2 * volume_voxel_size
122  * \param[in] distance TSDF truncation distance
123  */
124  void
125  setTsdfTruncDist (float distance);
126 
127  /** \brief Returns tsdf volume container that point to data in GPU memory */
129  data () const;
130 
131  /** \brief Returns volume size in meters */
132  const Eigen::Vector3f&
133  getSize () const;
134 
135  /** \brief Returns volume resolution */
136  const Eigen::Vector3i&
137  getResolution() const;
138 
139  /** \brief Returns volume voxel size in meters */
140  const Eigen::Vector3f
141  getVoxelSize () const;
142 
143  /** \brief Returns tsdf truncation distance in meters */
144  float
145  getTsdfTruncDist () const;
146 
147  /** \brief Resets tsdf volume data to uninitialized state */
148  void
149  reset ();
150 
151  /** \brief Generates cloud using CPU (downloads volumetric representation to CPU memory)
152  * \param[out] cloud output array for cloud
153  * \param[in] connected26 If false point cloud is extracted using 6 neighbor, otherwise 26.
154  */
155  void
156  fetchCloudHost (PointCloud<PointType>& cloud, bool connected26 = false) const;
157 
158  /** \brief Generates cloud using CPU (downloads volumetric representation to CPU memory)
159  * \param[out] cloud output array for cloud
160  * \param[in] connected26 If false point cloud is extracted using 6 neighbor, otherwise 26.
161  */
162  void
163  fetchCloudHost (PointCloud<PointXYZI>& cloud, bool connected26 = false) const;
164 
165  /** \brief Generates cloud using GPU in connected6 mode only
166  * \param[out] cloud_buffer buffer to store point cloud
167  * \return DeviceArray with disabled reference counting that points to filled part of cloud_buffer.
168  */
170  fetchCloud (DeviceArray<PointType>& cloud_buffer) const;
171 
172  /** \brief Push a point cloud of previously scanned tsdf slice to the TSDF volume
173  * \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.
174  * \param buffer
175  */
176  void
177  pushSlice (const PointCloud<PointXYZI>::Ptr existing_data_cloud, const tsdf_buffer* buffer) const;
178 
179  /** \brief Generates cloud using GPU in connected6 mode only
180  * \param[out] cloud_buffer_xyz buffer to store point cloud
181  * \param cloud_buffer_intensity
182  * \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.
183  * \param[in] shiftX Offset in indices.
184  * \param[in] shiftY Offset in indices.
185  * \param[in] shiftZ Offset in indices.
186  * \return DeviceArray with disabled reference counting that points to filled part of cloud_buffer.
187  */
188  std::size_t
189  fetchSliceAsCloud (DeviceArray<PointType>& cloud_buffer_xyz, DeviceArray<float>& cloud_buffer_intensity, const tsdf_buffer* buffer, int shiftX, int shiftY, int shiftZ ) const;
190 
191  /** \brief Computes normals as gradient of tsdf for given points
192  * \param[in] cloud Points where normals are computed.
193  * \param[out] normals array for normals
194  */
195 
196  void
197  fetchNormals (const DeviceArray<PointType>& cloud, DeviceArray<PointType>& normals) const;
198 
199  /** \brief Computes normals as gradient of tsdf for given points
200  * \param[in] cloud Points where normals are computed.
201  * \param[out] normals array for normals
202  */
203  void
204  fetchNormals(const DeviceArray<PointType>& cloud, DeviceArray<NormalType>& normals) const;
205 
206  /** \brief Downloads tsdf volume from GPU memory.
207  * \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];
208  */
209  void
210  downloadTsdf (std::vector<float>& tsdf) const;
211 
212  /** \brief Downloads tsdf volume from GPU memory to local CPU buffer*/
213  void
214  downloadTsdfLocal () const;
215 
216  /** \brief Downloads TSDF volume and according voxel weights from GPU memory
217  * \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];
218  * \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.
219  */
220  void
221  downloadTsdfAndWeights (std::vector<float>& tsdf, std::vector<short>& weights) const;
222 
223  /** \brief Downloads TSDF volume and according voxel weights from GPU memory to local CPU buffers*/
224  void
225  downloadTsdfAndWeightsLocal () const;
226 
227  /** \brief Releases tsdf buffer on GPU */
228  void releaseVolume () {volume_.release();}
229 
230  void print_warn(const char* arg1, std::size_t size);
231 
232  /** \brief Set the header for data stored on host directly. Useful if directly writing into volume and weights */
233  inline void
234  setHeader (const Eigen::Vector3i& resolution, const Eigen::Vector3f& volume_size) {
235  header_ = Header (resolution, volume_size);
236  if (volume_host_->size() != this->size())
237  pcl::console::print_warn ("[TSDFVolume::setHeader] Header volume size (%d) doesn't fit underlying data size (%d)", volume_host_->size(), size());
238  }
239 
240  /** \brief Returns overall number of voxels in grid stored on host */
241  inline std::size_t
242  size () const {
243  return header_.getVolumeSize ();
244  }
245 
246  /** \brief Converts volume stored on host to cloud of TSDF values
247  * \param[ou] cloud - the output point cloud
248  * \param[in] step - the decimation step to use
249  */
250  void
251  convertToTsdfCloud (pcl::PointCloud<pcl::PointXYZI>::Ptr &cloud,
252  const unsigned step = 2) const;
253 
254  /** \brief Returns the voxel grid resolution */
255  inline const Eigen::Vector3i &
256  gridResolution () const { return header_.resolution; };
257 
258  /** \brief Saves local volume buffer to file */
259  bool
260  save (const std::string &filename = "tsdf_volume.dat", bool binary = true) const;
261 
262  /** \brief Loads local volume from file */
263  bool
264  load (const std::string &filename, bool binary = true);
265 
266  private:
267  /** \brief tsdf volume size in meters */
268  Eigen::Vector3f size_;
269 
270  /** \brief tsdf volume resolution */
271  Eigen::Vector3i resolution_;
272 
273  /** \brief tsdf volume data container */
274  DeviceArray2D<int> volume_;
275 
276  /** \brief tsdf truncation distance */
277  float tranc_dist_;
278 
279  // The following member are resulting from the merge of TSDFVolume with TsdfVolume class.
280  using VolumePtr = shared_ptr<std::vector<float> >;
281  using WeightsPtr = shared_ptr<std::vector<short> >;
282 
283  Header header_;
284  VolumePtr volume_host_;
285  WeightsPtr weights_host_;
286 
287  public:
289  };
290  }
291  }
292 }
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:234
shared_ptr< const TsdfVolume > ConstPtr
Definition: tsdf_volume.h:65
PCL_EXPORTS int load(const std::string &file_name, pcl::PCLPointCloud2 &blob)
Load a file into a PointCloud2 according to extension.
shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:415
Structure to handle buffer addresses.
Definition: tsdf_buffer.h:50
This file defines compatibility wrappers for low level I/O functions.
Definition: convolution.h:45
shared_ptr< TsdfVolume > Ptr
Definition: tsdf_volume.h:64
#define PCL_MAKE_ALIGNED_OPERATOR_NEW
Macro to signal a class requires a custom allocator.
Definition: pcl_macros.h:371
const Eigen::Vector3i & gridResolution() const
Returns the voxel grid resolution.
Definition: tsdf_volume.h:256
Defines all the PCL implemented PointT point type structures.
A point structure representing Euclidean xyz coordinates.
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:72
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:85
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:228
std::size_t getVolumeSize() const
Get the size of data stored on host.
Definition: tsdf_volume.h:94
std::size_t size() const
Returns overall number of voxels in grid stored on host.
Definition: tsdf_volume.h:242
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.
boost::shared_ptr< T > shared_ptr
Alias for boost::shared_ptr.
Definition: pcl_macros.h:90
#define PCL_EXPORTS
Definition: pcl_macros.h:253
Defines all the PCL and non-PCL macros used.
std::ostream & operator<<(std::ostream &os, const float3 &v1)