ProjectInliers uses a model and a set of inlier indices from a PointCloud to project them into a separate PointCloud. More...
#include <project_inliers.h>
Public Member Functions | |
ProjectInliers () | |
Protected Member Functions | |
void | filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output) |
Call the actual filter. | |
Private Member Functions | |
void | input_indices_model_callback (const PointCloud2::ConstPtr &cloud, const PointIndicesConstPtr &indices, const ModelCoefficientsConstPtr &model) |
PointCloud2 + Indices + Model data callback. | |
virtual void | onInit () |
Nodelet initialization routine. | |
Private Attributes | |
pcl::ProjectInliers < pcl::PCLPointCloud2 > | impl_ |
The PCL filter implementation used. | |
ModelCoefficientsConstPtr | model_ |
A pointer to the vector of model coefficients. | |
message_filters::Subscriber < ModelCoefficients > | sub_model_ |
The message filter subscriber for model coefficients. | |
boost::shared_ptr < message_filters::Synchronizer < sync_policies::ApproximateTime < PointCloud2, PointIndices, ModelCoefficients > > > | sync_input_indices_model_a_ |
boost::shared_ptr < message_filters::Synchronizer < sync_policies::ExactTime < PointCloud2, PointIndices, ModelCoefficients > > > | sync_input_indices_model_e_ |
Synchronized input, indices, and model coefficients. |
ProjectInliers uses a model and a set of inlier indices from a PointCloud to project them into a separate PointCloud.
Definition at line 56 of file project_inliers.h.
pcl_ros::ProjectInliers::ProjectInliers | ( | ) | [inline] |
Definition at line 59 of file project_inliers.h.
void pcl_ros::ProjectInliers::filter | ( | const PointCloud2::ConstPtr & | input, |
const IndicesPtr & | indices, | ||
PointCloud2 & | output | ||
) | [inline, protected, virtual] |
Call the actual filter.
input | the input point cloud dataset |
indices | the input set of indices to use from input |
output | the resultant filtered dataset |
Implements pcl_ros::Filter.
Definition at line 68 of file project_inliers.h.
void pcl_ros::ProjectInliers::input_indices_model_callback | ( | const PointCloud2::ConstPtr & | cloud, |
const PointIndicesConstPtr & | indices, | ||
const ModelCoefficientsConstPtr & | model | ||
) | [private] |
PointCloud2 + Indices + Model data callback.
Definition at line 110 of file project_inliers.cpp.
void pcl_ros::ProjectInliers::onInit | ( | ) | [private, virtual] |
Nodelet initialization routine.
Reimplemented from pcl_ros::Filter.
Definition at line 44 of file project_inliers.cpp.
pcl::ProjectInliers<pcl::PCLPointCloud2> pcl_ros::ProjectInliers::impl_ [private] |
The PCL filter implementation used.
Definition at line 94 of file project_inliers.h.
A pointer to the vector of model coefficients.
Definition at line 85 of file project_inliers.h.
The message filter subscriber for model coefficients.
Definition at line 88 of file project_inliers.h.
boost::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud2, PointIndices, ModelCoefficients> > > pcl_ros::ProjectInliers::sync_input_indices_model_a_ [private] |
Definition at line 92 of file project_inliers.h.
boost::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloud2, PointIndices, ModelCoefficients> > > pcl_ros::ProjectInliers::sync_input_indices_model_e_ [private] |
Synchronized input, indices, and model coefficients.
Definition at line 91 of file project_inliers.h.