Point Cloud Library (PCL)
1.11.1-dev
|
42 #include <pcl/pcl_base.h>
43 #include <pcl/common/io.h>
44 #include <pcl/PointIndices.h>
56 template<
typename Po
intT>
void
69 template<
typename Po
intT>
void
79 template<
typename Po
intT>
83 using Ptr = shared_ptr<Filter<PointT> >;
84 using ConstPtr = shared_ptr<const Filter<PointT> >;
95 Filter (
bool extract_removed_indices =
false) :
126 if (
input_.get () == &output)
173 inline const std::string&
189 using Ptr = shared_ptr<Filter<pcl::PCLPointCloud2> >;
190 using ConstPtr = shared_ptr<const Filter<pcl::PCLPointCloud2> >;
200 Filter (
bool extract_removed_indices =
false) :
201 removed_indices_ (new
Indices),
202 extract_removed_indices_ (extract_removed_indices)
210 return (removed_indices_);
219 pi.
indices = *removed_indices_;
249 inline const std::string&
252 return (filter_name_);
257 #ifdef PCL_NO_PRECOMPILE
258 #include <pcl/filters/impl/filter.hpp>
IndicesPtr removed_indices_
Indices of the points that are removed.
shared_ptr< Indices > IndicesPtr
shared_ptr< Filter< pcl::PointXYZRGBL > > Ptr
typename PointCloud::ConstPtr PointCloudConstPtr
PointCloudConstPtr input_
The input point cloud dataset.
typename PointCloud::Ptr PointCloudPtr
void removeNaNNormalsFromPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, Indices &index)
Removes points that have their normals invalid (i.e., equal to NaN)
shared_ptr< ::pcl::PCLPointCloud2 > Ptr
virtual void applyFilter(PointCloud &output)=0
Abstract filter method.
shared_ptr< const Filter< pcl::PCLPointCloud2 > > ConstPtr
shared_ptr< const Indices > IndicesConstPtr
const IndicesConstPtr getRemovedIndices() const
Get the point indices being removed.
Filter(bool extract_removed_indices=false)
Empty constructor.
void getRemovedIndices(PointIndices &pi)
Get the point indices being removed.
void filter(PointCloud &output)
Calls the filtering method and returns the filtered dataset in output.
PCLPointCloud2::ConstPtr PCLPointCloud2ConstPtr
PointCloud represents the base class in PCL for storing collections of 3D points.
void copyPointCloud(const pcl::PointCloud< PointInT > &cloud_in, pcl::PointCloud< PointOutT > &cloud_out)
Copy all the fields from a given point cloud into a new point cloud.
void getRemovedIndices(PointIndices &pi)
Get the point indices being removed.
PCLPointCloud2::Ptr PCLPointCloud2Ptr
Filter(bool extract_removed_indices=false)
Empty constructor.
shared_ptr< Filter< pcl::PCLPointCloud2 > > Ptr
shared_ptr< const ::pcl::PCLPointCloud2 > ConstPtr
shared_ptr< const Filter< pcl::PointXYZRGBL > > ConstPtr
const IndicesConstPtr getRemovedIndices() const
Get the point indices being removed.
IndicesPtr removed_indices_
Indices of the points that are removed.
Eigen::Vector4f sensor_origin_
Sensor acquisition pose (origin/translation).
std::string filter_name_
The filter name.
Eigen::Quaternionf sensor_orientation_
Sensor acquisition pose (rotation).
Filter represents the base filter class.
void removeNaNFromPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, Indices &index)
Removes points with x, y, or z equal to NaN.
pcl::PCLHeader header
The point cloud header.
IndicesAllocator<> Indices
Type used for indices in PCL.
bool extract_removed_indices_
Set to true if we want to return the indices of the removed points.
std::string filter_name_
The filter name.
shared_ptr< PointCloud< PointT > > Ptr
bool deinitCompute()
This method should get called after finishing the actual computation.
const std::string & getClassName() const
Get a string representation of the name of this class.
shared_ptr< const PointCloud< PointT > > ConstPtr
const std::string & getClassName() const
Get a string representation of the name of this class.
bool initCompute()
This method should get called before starting the actual computation.
bool extract_removed_indices_
Set to true if we want to return the indices of the removed points.