38 #ifndef PCL_ROS_FILTERS_RADIUSOUTLIERREMOVAL_H_ 39 #define PCL_ROS_FILTERS_RADIUSOUTLIERREMOVAL_H_ 42 #include <pcl/filters/radius_outlier_removal.h> 46 #include "pcl_ros/RadiusOutlierRemovalConfig.h" 70 pcl::PCLPointCloud2::Ptr pcl_input(
new pcl::PCLPointCloud2);
72 impl_.setInputCloud (pcl_input);
73 impl_.setIndices (indices);
74 pcl::PCLPointCloud2 pcl_output;
75 impl_.filter (pcl_output);
89 void config_callback (pcl_ros::RadiusOutlierRemovalConfig &config, uint32_t level);
94 pcl::RadiusOutlierRemoval<pcl::PCLPointCloud2>
impl_;
96 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
100 #endif //#ifndef PCL_FILTERS_RADIUSOUTLIERREMOVAL_H_
pcl::RadiusOutlierRemoval< pcl::PCLPointCloud2 > impl_
The PCL filter implementation used.
void filter(const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output)
Call the actual filter.
Filter represents the base filter class. Some generic 3D operations that are applicable to all filter...
virtual bool child_init(ros::NodeHandle &nh, bool &has_service)
Child initialization routine.
sensor_msgs::PointCloud2 PointCloud2
RadiusOutlierRemoval is a simple filter that removes outliers if the number of neighbors in a certain...
void moveFromPCL(pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
boost::shared_ptr< dynamic_reconfigure::Server< pcl_ros::RadiusOutlierRemovalConfig > > srv_
Pointer to a dynamic reconfigure service.
void toPCL(const ros::Time &stamp, pcl::uint64_t &pcl_stamp)
void config_callback(pcl_ros::RadiusOutlierRemovalConfig &config, uint32_t level)
Dynamic reconfigure callback.