voxel_grid.h File Reference

#include "pcl/filters/filter.h"
#include <map>
#include <boost/mpl/size.hpp>
#include <boost/fusion/sequence/intrinsic/at_key.hpp>
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

struct  pcl::VoxelGrid< sensor_msgs::PointCloud2 >::Leaf
 Simple structure to hold an nD centroid and the number of points in a leaf. More...
struct  pcl::VoxelGrid< PointT >::Leaf
 Simple structure to hold an nD centroid and the number of points in a leaf. More...
struct  pcl::NdCopyEigenPointFunctor< PointT >
 Helper functor structure for copying data between an Eigen::VectorXf and a PointT. More...
struct  pcl::NdCopyPointEigenFunctor< PointT >
 Helper functor structure for copying data between an Eigen::VectorXf and a PointT. More...
class  pcl::VoxelGrid< PointT >
 VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. More...
class  pcl::VoxelGrid< sensor_msgs::PointCloud2 >
 VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. More...

Namespaces

namespace  pcl

Functions

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.
void pcl::getMinMax3D (const sensor_msgs::PointCloud2ConstPtr &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)
void pcl::getMinMax3D (const sensor_msgs::PointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx, Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt)
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


pcl
Author(s): See http://pcl.ros.org/authors for the complete list of authors.
autogenerated on Fri Jan 11 09:57:09 2013