Go to the documentation of this file.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 #ifndef JSK_PCL_ROS_BILATERAL_FILTER_H_
00038 #define JSK_PCL_ROS_BILATERAL_FILTER_H_
00039
00040 #include <pcl_ros/publisher.h>
00041 #include <jsk_topic_tools/connection_based_nodelet.h>
00042 #include "jsk_recognition_utils/pcl_conversion_util.h"
00043 #include <jsk_pcl_ros/BilateralFilterConfig.h>
00044 #include <dynamic_reconfigure/server.h>
00045
00046 namespace jsk_pcl_ros
00047 {
00049
00050
00051
00053 inline void
00054 PointXYZRGBtoXYZI (pcl::PointXYZRGB& in,
00055 pcl::PointXYZI& out)
00056 {
00057 out.x = in.x; out.y = in.y; out.z = in.z;
00058 out.intensity = 0.299f * static_cast <float> (in.r) + 0.587f * static_cast
00059 <float> (in.g) + 0.114f * static_cast <float> (in.b);
00060 }
00061
00062 inline void
00063 PointCloudXYZRGBtoXYZI (pcl::PointCloud<pcl::PointXYZRGB>& in,
00064 pcl::PointCloud<pcl::PointXYZI>& out)
00065 {
00066 out.width = in.width;
00067 out.height = in.height;
00068 for (size_t i = 0; i < in.points.size (); i++)
00069 {
00070 pcl::PointXYZI p;
00071 PointXYZRGBtoXYZI (in.points[i], p);
00072 out.points.push_back (p);
00073 }
00074 }
00075
00076
00077 class BilateralFilter: public jsk_topic_tools::ConnectionBasedNodelet
00078 {
00079 public:
00080 typedef boost::shared_ptr<BilateralFilter> Ptr;
00081 typedef pcl::PointXYZRGB PointT;
00082 typedef BilateralFilterConfig Config;
00083 protected:
00085
00087 virtual void onInit();
00088
00089 virtual void filter(const sensor_msgs::PointCloud2::ConstPtr& msg);
00090
00091 virtual void subscribe();
00092 virtual void unsubscribe();
00093
00094 virtual void configCallback(Config &config, uint32_t level);
00095
00097
00099 boost::mutex mutex_;
00100 ros::Subscriber sub_;
00101 ros::Publisher pub_;
00102 boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00103
00105
00107 double sigma_s_;
00108 double sigma_r_;
00109
00110 private:
00111
00112
00113 };
00114 }
00115
00116
00117 #endif