Go to the documentation of this file.
38 #ifndef PCL_ROS_FILTERS_PROJECT_INLIERS_H_
39 #define PCL_ROS_FILTERS_PROJECT_INLIERS_H_
42 #include <pcl/filters/project_inliers.h>
71 pcl::PCLPointCloud2::Ptr pcl_input(
new pcl::PCLPointCloud2);
73 impl_.setInputCloud (pcl_input);
74 impl_.setIndices (indices);
75 pcl::ModelCoefficients::Ptr pcl_model(
new pcl::ModelCoefficients);
77 impl_.setModelCoefficients (pcl_model);
78 pcl::PCLPointCloud2 pcl_output;
79 impl_.filter (pcl_output);
94 pcl::ProjectInliers<pcl::PCLPointCloud2>
impl_;
110 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
114 #endif //#ifndef PCL_FILTERS_PROJECT_INLIERS_H_
void filter(const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output)
Call the actual filter.
pcl::IndicesPtr IndicesPtr
void toPCL(const pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloud2, PointIndices, ModelCoefficients > > > sync_input_indices_model_e_
Synchronized input, indices, and model coefficients.
void unsubscribe()
Lazy transport unsubscribe routine.
PointIndices::ConstPtr PointIndicesConstPtr
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloud2, PointIndices, ModelCoefficients > > > sync_input_indices_model_a_
Filter represents the base filter class. Some generic 3D operations that are applicable to all filter...
message_filters::Subscriber< ModelCoefficients > sub_model_
The message filter subscriber for model coefficients.
ModelCoefficientsConstPtr model_
A pointer to the vector of model coefficients.
ModelCoefficients::ConstPtr ModelCoefficientsConstPtr
ProjectInliers uses a model and a set of inlier indices from a PointCloud to project them into a sepa...
pcl::ProjectInliers< pcl::PCLPointCloud2 > impl_
The PCL filter implementation used.
void subscribe()
NodeletLazy connection routine.
sensor_msgs::PointCloud2 PointCloud2
virtual void onInit()
Nodelet initialization routine.
void input_indices_model_callback(const PointCloud2::ConstPtr &cloud, const PointIndicesConstPtr &indices, const ModelCoefficientsConstPtr &model)
PointCloud2 + Indices + Model data callback.
void moveFromPCL(pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
pcl_ros
Author(s): Open Perception, Julius Kammerl
, William Woodall
autogenerated on Fri Jul 12 2024 02:54:40