Classes | Namespaces | Functions
voxel_grid.h File Reference
#include <pcl/filters/boost.h>
#include <pcl/filters/filter.h>
#include <map>
Include dependency graph for voxel_grid.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  pcl::VoxelGrid< PointT >
 VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. More...
class  pcl::VoxelGrid< pcl::PCLPointCloud2 >
 VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. More...

Namespaces

namespace  pcl

Functions

Eigen::MatrixXi pcl::getAllNeighborCellIndices ()
 Get the relative cell indices of all the 26 neighbors.
Eigen::MatrixXi pcl::getHalfNeighborCellIndices ()
 Get the relative cell indices of the "upper half" 13 neighbors.
PCL_EXPORTS void pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx, Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt)
 Obtain the maximum and minimum points in 3D from a given point cloud.
PCL_EXPORTS void pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx, const std::string &distance_field_name, float min_distance, float max_distance, Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative=false)
 Obtain the maximum and minimum points in 3D from a given point cloud.
template<typename PointT >
void pcl::getMinMax3D (const typename pcl::PointCloud< PointT >::ConstPtr &cloud, const std::string &distance_field_name, float min_distance, float max_distance, Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative=false)
 Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud, without considering points outside of a distance threshold from the laser origin.
template<typename PointT >
void pcl::getMinMax3D (const typename pcl::PointCloud< PointT >::ConstPtr &cloud, const std::vector< int > &indices, const std::string &distance_field_name, float min_distance, float max_distance, Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative=false)
 Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud, without considering points outside of a distance threshold from the laser origin.


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:38:49