00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #ifndef PCL_ROS_FILTERS_PROJECT_INLIERS_H_
00039 #define PCL_ROS_FILTERS_PROJECT_INLIERS_H_
00040
00041
00042 #include <pcl/filters/project_inliers.h>
00043 #include "pcl_ros/filters/filter.h"
00044
00045 #include <message_filters/subscriber.h>
00046
00047 namespace pcl_ros
00048 {
00049 namespace sync_policies = message_filters::sync_policies;
00050
00056 class ProjectInliers : public Filter
00057 {
00058 public:
00059 ProjectInliers () : model_ () {}
00060
00061 protected:
00067 inline void
00068 filter (const PointCloud2::ConstPtr &input, const IndicesConstPtr &indices,
00069 PointCloud2 &output)
00070 {
00071 impl_.setInputCloud (input);
00072 impl_.setIndices (indices);
00073 impl_.setModelCoefficients (model_);
00074 impl_.filter (output);
00075 }
00076
00077 private:
00079 ModelCoefficientsConstPtr model_;
00080
00082 message_filters::Subscriber<ModelCoefficients> sub_model_;
00083
00085 boost::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloud2, PointIndices, ModelCoefficients> > > sync_input_indices_model_e_;
00086 boost::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud2, PointIndices, ModelCoefficients> > > sync_input_indices_model_a_;
00088 pcl::ProjectInliers<PointCloud2> impl_;
00089
00091 virtual void
00092 onInit ();
00093
00095 void
00096 input_indices_model_callback (const PointCloud2::ConstPtr &cloud,
00097 const PointIndicesConstPtr &indices,
00098 const ModelCoefficientsConstPtr &model);
00099 public:
00100 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00101 };
00102 }
00103
00104 #endif //#ifndef PCL_FILTERS_PROJECT_INLIERS_H_