37 #ifndef JSK_PCL_ROS_HEIGHTMAP_MORPHOLOGICAL_FILTERLING_H_ 38 #define JSK_PCL_ROS_HEIGHTMAP_MORPHOLOGICAL_FILTERLING_H_ 42 #include <opencv2/opencv.hpp> 43 #include <jsk_pcl_ros/HeightmapMorphologicalFilteringConfig.h> 44 #include <dynamic_reconfigure/server.h> 45 #include <jsk_recognition_msgs/HeightmapConfig.h> 46 #include <boost/accumulators/accumulators.hpp> 47 #include <boost/accumulators/statistics/mean.hpp> 48 #include <boost/accumulators/statistics/variance.hpp> 49 #include <boost/accumulators/statistics/count.hpp> 50 #include <boost/accumulators/statistics/stats.hpp> 58 typedef HeightmapMorphologicalFilteringConfig
Config;
59 typedef boost::accumulators::accumulator_set<
70 virtual void filter(
const sensor_msgs::Image::ConstPtr&
msg);
72 virtual void configTopicCallback(
const jsk_recognition_msgs::HeightmapConfig::ConstPtr& msg);
std::vector< OneDataStat::Ptr > stats
global variable to store stats.
virtual void filter(const sensor_msgs::Image::ConstPtr &msg)
virtual void configCallback(Config &config, uint32_t level)
virtual void configTopicCallback(const jsk_recognition_msgs::HeightmapConfig::ConstPtr &msg)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
double bilateral_sigma_color_
double bilateral_sigma_space_
ros::Publisher pub_config_
boost::shared_ptr< HeightmapMorphologicalFiltering > Ptr
boost::mutex mutex
global mutex.
std::string smooth_method_
HeightmapMorphologicalFiltering()
ros::Subscriber sub_config_
int bilateral_filter_size_
double count(const OneDataStat &d)
wrapper function for count method for boost::function
boost::accumulators::accumulator_set< float, boost::accumulators::stats< boost::accumulators::tag::variance, boost::accumulators::tag::count, boost::accumulators::tag::mean > > Accumulator
HeightmapMorphologicalFilteringConfig Config
virtual void unsubscribe()