Class PointcloudProcessor
Defined in File PointcloudProcessor.hpp
Class Documentation
-
class PointcloudProcessor
Public Functions
-
explicit PointcloudProcessor(const rclcpp::Logger &node_logger)
-
virtual ~PointcloudProcessor() = default
-
void loadParameters(const std::string &filename)
Load parameters for the point cloud processing.
- Parameters:
full – [in] path to the config file with parameters
-
Pointcloud::Ptr 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:
Input – [in] point cloud
- Returns:
Point cloud where outliers have been removed.
-
Pointcloud::Ptr 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:
Input – [in] point cloud
- Returns:
Downsampled point cloud
-
std::vector<pcl::PointIndices> 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:
pointer – [in] to the pcl point cloud
- Returns:
vector of sets of indices. Vector will be empty if no clusters are found.
-
std::vector<Pointcloud::Ptr> 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:
pointer – [in] to the pcl point cloud
- Returns:
vector of point clouds. Vector will be empty if no clusters are found.
-
Pointcloud::Ptr makeCloudFromIndices(const std::vector<int> &indices, Pointcloud::ConstPtr inputCloud) const
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:
vector – [in] of indices
pointer – [in] to the pcl point cloud
- Returns:
Pointer to the point cloud with points indexed by indices.
-
void savePointCloudAsPcdFile(const std::string &filename, const Pointcloud &cloud) const
Saves a point cloud to a pcd file.
- Parameters:
full – [in] path to the output cloud
-
Pointcloud::Ptr applyRigidBodyTransformation(Pointcloud::ConstPtr inputCloud) const
Applies a rigid body transformation to the input cloud. The transformation is specified in the configuration file
- Parameters:
ptr – [in] to the input cloud
- Returns:
resulting cloud when rigid body transformation has been applied
Protected Attributes
-
std::unique_ptr<grid_map_pcl::PclLoaderParameters> params_
-
explicit PointcloudProcessor(const rclcpp::Logger &node_logger)