40 #include <pcl/filters/bilateral.h> 41 #include <pcl/filters/fast_bilateral.h> 42 #include <pcl/filters/fast_bilateral_omp.h> 48 ConnectionBasedNodelet::onInit();
49 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
50 typename dynamic_reconfigure::Server<Config>::CallbackType
f =
52 srv_->setCallback (f);
54 pub_ = advertise<sensor_msgs::PointCloud2>(*
pnh_,
"output", 1);
72 pcl::PointCloud<PointT>::Ptr
cloud (
new pcl::PointCloud<PointT>);
73 pcl::PointCloud<PointT>::Ptr
74 output (
new pcl::PointCloud<PointT>);
76 pcl::FastBilateralFilter<PointT> bilateral;
78 bilateral.setInputCloud(cloud);
81 bilateral.filter(*output);
82 sensor_msgs::PointCloud2 ros_output;
84 ros_output.header = msg->header;
virtual void configCallback(Config &config, uint32_t level)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::BilateralFilter, nodelet::Nodelet)
void publish(const boost::shared_ptr< M > &message) const
BilateralFilterConfig Config
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
virtual void filter(const sensor_msgs::PointCloud2::ConstPtr &msg)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
void output(int index, double value)
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
virtual void unsubscribe()