Skip to content

Commit

Permalink
Merge pull request #2099 from SergioRAgostinho/decimation-step
Browse files Browse the repository at this point in the history
Allow specifying decimation step in convertToTsdfCloud
  • Loading branch information
taketwo committed Nov 23, 2017
2 parents 651c06a + 2ba23b9 commit cd302dc
Show file tree
Hide file tree
Showing 4 changed files with 16 additions and 8 deletions.
8 changes: 6 additions & 2 deletions gpu/kinfu/tools/tsdf_volume.h
Original file line number Diff line number Diff line change
Expand Up @@ -225,9 +225,13 @@ EIGEN_MAKE_ALIGNED_OPERATOR_NEW
////////////////////////////////////////////////////////////////////////////////////////
// Functionality

/** \brief Converts volume to cloud of TSDF values*/
/** \brief Converts volume to cloud of TSDF values
* \param[ou] cloud - the output point cloud
* \param[in] step - the decimation step to use
*/
void
convertToTsdfCloud (pcl::PointCloud<pcl::PointXYZI>::Ptr &cloud) const;
convertToTsdfCloud (pcl::PointCloud<pcl::PointXYZI>::Ptr &cloud,
const unsigned step = 2) const;

/** \brief Converts the volume to a surface representation via a point cloud */
// void
Expand Down
4 changes: 2 additions & 2 deletions gpu/kinfu/tools/tsdf_volume.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -155,13 +155,13 @@ pcl::TSDFVolume<VoxelT, WeightT>::save (const std::string &filename, bool binary


template <typename VoxelT, typename WeightT> void
pcl::TSDFVolume<VoxelT, WeightT>::convertToTsdfCloud (pcl::PointCloud<pcl::PointXYZI>::Ptr &cloud) const
pcl::TSDFVolume<VoxelT, WeightT>::convertToTsdfCloud (pcl::PointCloud<pcl::PointXYZI>::Ptr &cloud,
const unsigned step) const
{
int sx = header_.resolution(0);
int sy = header_.resolution(1);
int sz = header_.resolution(2);

const int step = 2;
const int cloud_size = header_.getVolumeSize() / (step*step*step);

cloud->clear();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -243,9 +243,13 @@ EIGEN_MAKE_ALIGNED_OPERATOR_NEW
return header_.getVolumeSize ();
}

/** \brief Converts volume stored on host to cloud of TSDF values*/
/** \brief Converts volume stored on host to cloud of TSDF values
* \param[ou] cloud - the output point cloud
* \param[in] step - the decimation step to use
*/
void
convertToTsdfCloud (pcl::PointCloud<pcl::PointXYZI>::Ptr &cloud) const;
convertToTsdfCloud (pcl::PointCloud<pcl::PointXYZI>::Ptr &cloud,
const unsigned step = 2) const;

/** \brief Returns the voxel grid resolution */
inline const Eigen::Vector3i &
Expand Down
4 changes: 2 additions & 2 deletions gpu/kinfu_large_scale/src/tsdf_volume.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -354,13 +354,13 @@ pcl::gpu::kinfuLS::TsdfVolume::fetchNormals (const DeviceArray<PointType>& cloud
///////////////////////////////////////////////////////////////////////////////////////////////////////////////////

void
pcl::gpu::kinfuLS::TsdfVolume::convertToTsdfCloud (pcl::PointCloud<pcl::PointXYZI>::Ptr &cloud) const
pcl::gpu::kinfuLS::TsdfVolume::convertToTsdfCloud ( pcl::PointCloud<pcl::PointXYZI>::Ptr &cloud,
const unsigned step) const
{
int sx = header_.resolution(0);
int sy = header_.resolution(1);
int sz = header_.resolution(2);

const int step = 2;
const int cloud_size = static_cast<int> (header_.getVolumeSize() / (step*step*step));

cloud->clear();
Expand Down

0 comments on commit cd302dc

Please sign in to comment.