38 #ifndef PCL_ROS_FILTERS_STATISTICALOUTLIERREMOVAL_H_ 39 #define PCL_ROS_FILTERS_STATISTICALOUTLIERREMOVAL_H_ 42 #include <pcl/filters/statistical_outlier_removal.h> 46 #include "pcl_ros/StatisticalOutlierRemovalConfig.h" 76 boost::mutex::scoped_lock lock (
mutex_);
77 pcl::PCLPointCloud2::Ptr pcl_input(
new pcl::PCLPointCloud2);
79 impl_.setInputCloud (pcl_input);
80 impl_.setIndices (indices);
81 pcl::PCLPointCloud2 pcl_output;
82 impl_.filter (pcl_output);
96 void config_callback (pcl_ros::StatisticalOutlierRemovalConfig &config, uint32_t level);
100 pcl::StatisticalOutlierRemoval<pcl::PCLPointCloud2>
impl_;
102 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
106 #endif //#ifndef PCL_FILTERS_STATISTICALOUTLIERREMOVAL_H_
pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 > impl_
The PCL filter implementation used.
void config_callback(pcl_ros::StatisticalOutlierRemovalConfig &config, uint32_t level)
Dynamic reconfigure callback.
Filter represents the base filter class. Some generic 3D operations that are applicable to all filter...
bool child_init(ros::NodeHandle &nh, bool &has_service)
Child initialization routine.
sensor_msgs::PointCloud2 PointCloud2
boost::mutex mutex_
Internal mutex.
StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. For more information check:
void filter(const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output)
Call the actual filter.
boost::shared_ptr< dynamic_reconfigure::Server< pcl_ros::StatisticalOutlierRemovalConfig > > srv_
Pointer to a dynamic reconfigure service.
void moveFromPCL(pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
void toPCL(const ros::Time &stamp, pcl::uint64_t &pcl_stamp)