Public Member Functions | Static Public Member Functions | Protected Attributes | List of all members
grid_map::grid_map_pcl::PointcloudProcessor Class Reference

#include <PointcloudProcessor.hpp>

Public Member Functions

Pointcloud::Ptr applyRigidBodyTransformation (Pointcloud::ConstPtr inputCloud) const
 
Pointcloud::Ptr downsampleInputCloud (Pointcloud::ConstPtr inputCloud) const
 
std::vector< Pointcloud::Ptr > extractClusterCloudsFromPointcloud (Pointcloud::ConstPtr inputCloud) const
 
std::vector< pcl::PointIndices > extractClusterIndicesFromPointcloud (Pointcloud::ConstPtr inputCloud) const
 
void loadParameters (const std::string &filename)
 
 PointcloudProcessor ()
 
Pointcloud::Ptr removeOutliersFromInputCloud (Pointcloud::ConstPtr inputCloud) const
 
virtual ~PointcloudProcessor ()=default
 

Static Public Member Functions

static Pointcloud::Ptr makeCloudFromIndices (const std::vector< int > &indices, Pointcloud::ConstPtr inputCloud)
 
static void savePointCloudAsPcdFile (const std::string &filename, const Pointcloud &cloud)
 

Protected Attributes

std::unique_ptr< grid_map_pcl::PclLoaderParametersparams_
 

Detailed Description

Definition at line 19 of file PointcloudProcessor.hpp.

Constructor & Destructor Documentation

grid_map::grid_map_pcl::PointcloudProcessor::PointcloudProcessor ( )

Definition at line 27 of file PointcloudProcessor.cpp.

virtual grid_map::grid_map_pcl::PointcloudProcessor::~PointcloudProcessor ( )
virtualdefault

Member Function Documentation

Pointcloud::Ptr grid_map::grid_map_pcl::PointcloudProcessor::applyRigidBodyTransformation ( Pointcloud::ConstPtr  inputCloud) const

Applies a rigid body transformation to the input cloud. The transformation is specified in the configuration file

Parameters
[in]ptrto the input cloud
Returns
resulting cloud when rigid body transformation has been applied

Definition at line 104 of file PointcloudProcessor.cpp.

Pointcloud::Ptr grid_map::grid_map_pcl::PointcloudProcessor::downsampleInputCloud ( Pointcloud::ConstPtr  inputCloud) const

Downsample the point cloud using voxel grid method. Implementation is based on the implementation from pcl. The explanation of the algorithm can be found here: http://pointclouds.org/documentation/tutorials/voxel_grid.php

Parameters
[in]Inputpoint cloud
Returns
Downsampled point cloud

Definition at line 87 of file PointcloudProcessor.cpp.

std::vector< Pointcloud::Ptr > grid_map::grid_map_pcl::PointcloudProcessor::extractClusterCloudsFromPointcloud ( Pointcloud::ConstPtr  inputCloud) const

Finds clusters in the input cloud and returns vector point clouds. Each pointcloud in the vector is a cluster in the input cloud. There can be more than one cluster.

Parameters
[in]pointerto the pcl point cloud
Returns
vector of point clouds. Vector will be empty if no clusters are found.

Definition at line 45 of file PointcloudProcessor.cpp.

std::vector< pcl::PointIndices > grid_map::grid_map_pcl::PointcloudProcessor::extractClusterIndicesFromPointcloud ( Pointcloud::ConstPtr  inputCloud) const

Finds clusters in the input cloud and returns vector of sets of indices. Each set of indices corresponds to the points in the input cloud that belong to a cluster. There can be more than one cluster.

Parameters
[in]pointerto the pcl point cloud
Returns
vector of sets of indices. Vector will be empty if no clusters are found.

Definition at line 58 of file PointcloudProcessor.cpp.

void grid_map::grid_map_pcl::PointcloudProcessor::loadParameters ( const std::string &  filename)

Load parameters for the point cloud processing.

Parameters
[in]fullpath to the config file with parameters

Definition at line 31 of file PointcloudProcessor.cpp.

Pointcloud::Ptr grid_map::grid_map_pcl::PointcloudProcessor::makeCloudFromIndices ( const std::vector< int > &  indices,
Pointcloud::ConstPtr  inputCloud 
)
static

Given a vector of indices and an input point cloud, the function creates a new cloud that contains points from the input point cloud indexed by the vector of indices.

Parameters
[in]vectorof indices
[in]pointerto the pcl point cloud
Returns
Pointer to the point cloud with points indexed by indices.

Definition at line 74 of file PointcloudProcessor.cpp.

Pointcloud::Ptr grid_map::grid_map_pcl::PointcloudProcessor::removeOutliersFromInputCloud ( Pointcloud::ConstPtr  inputCloud) const

Remove outliers from the point cloud. Function is based on the StatisticalOutlierRemoval filter from pcl. The explanation on how the algorithm works can be found here: http://pointclouds.org/documentation/tutorials/statistical_outlier.php

Parameters
[in]Inputpoint cloud
Returns
Point cloud where outliers have been removed.

Definition at line 35 of file PointcloudProcessor.cpp.

void grid_map::grid_map_pcl::PointcloudProcessor::savePointCloudAsPcdFile ( const std::string &  filename,
const Pointcloud cloud 
)
static

Saves a point cloud to a pcd file.

Parameters
[in]fullpath to the output cloud

Definition at line 97 of file PointcloudProcessor.cpp.

Member Data Documentation

std::unique_ptr<grid_map_pcl::PclLoaderParameters> grid_map::grid_map_pcl::PointcloudProcessor::params_
protected

Definition at line 94 of file PointcloudProcessor.hpp.


The documentation for this class was generated from the following files:


grid_map_pcl
Author(s): Dominic Jud , Edo Jelavic
autogenerated on Tue Jun 1 2021 02:13:43