37 #ifndef JSK_PCL_ROS_BILATERAL_FILTER_H_ 38 #define JSK_PCL_ROS_BILATERAL_FILTER_H_ 43 #include <jsk_pcl_ros/BilateralFilterConfig.h> 44 #include <dynamic_reconfigure/server.h> 57 out.x = in.x; out.y = in.y; out.z = in.z;
58 out.intensity = 0.299f * static_cast <
float> (in.r) + 0.587
f * static_cast
59 <
float> (in.g) + 0.114f * static_cast <
float> (in.b);
64 pcl::PointCloud<pcl::PointXYZI>& out)
67 out.height = in.height;
68 for (
size_t i = 0; i < in.points.size (); i++)
72 out.points.push_back (p);
82 typedef BilateralFilterConfig
Config;
89 virtual void filter(
const sensor_msgs::PointCloud2::ConstPtr&
msg);
virtual void configCallback(Config &config, uint32_t level)
BilateralFilterConfig Config
boost::shared_ptr< BilateralFilter > Ptr
virtual void filter(const sensor_msgs::PointCloud2::ConstPtr &msg)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
boost::mutex mutex
global mutex.
void PointCloudXYZRGBtoXYZI(pcl::PointCloud< pcl::PointXYZRGB > &in, pcl::PointCloud< pcl::PointXYZI > &out)
void PointXYZRGBtoXYZI(pcl::PointXYZRGB &in, pcl::PointXYZI &out)
virtual void unsubscribe()