36 #ifndef JSK_PCL_ROS_COLOR_HISTOGRAM_H_ 37 #define JSK_PCL_ROS_COLOR_HISTOGRAM_H_ 45 #include <jsk_recognition_msgs/ColorHistogram.h> 46 #include <jsk_recognition_msgs/ColorHistogramArray.h> 47 #include <sensor_msgs/PointCloud2.h> 48 #include <jsk_recognition_msgs/ClusterPointIndices.h> 50 #include <dynamic_reconfigure/server.h> 51 #include <jsk_pcl_ros/ColorHistogramMatcherConfig.h> 62 typedef ColorHistogramMatcherConfig
Config;
72 const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
73 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices);
75 const sensor_msgs::PointCloud2::ConstPtr& input_cloud);
77 const jsk_recognition_msgs::ColorHistogram::ConstPtr& input_histogram);
78 virtual void computeHistogram(
const pcl::PointCloud<pcl::PointXYZHSV>& cloud,
79 std::vector<float>& output,
82 const std::vector<float>& b);
virtual void feature(const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &input_indices)
ros::Publisher all_histogram_pub_
double color_min_coefficient_
virtual void reference(const sensor_msgs::PointCloud2::ConstPtr &input_cloud)
ros::Publisher reference_histogram_pub_
ros::Publisher coefficient_points_pub_
ros::Publisher result_pub_
ColorHistogramMatcherConfig Config
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual double bhattacharyyaCoefficient(const std::vector< float > &a, const std::vector< float > &b)
double color_max_coefficient_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
ros::Subscriber reference_histogram_sub_
bool publish_colored_cloud_
virtual void unsubscribe()
boost::mutex mutex
global mutex.
virtual void configCallback(Config &config, uint32_t level)
virtual void referenceHistogram(const jsk_recognition_msgs::ColorHistogram::ConstPtr &input_histogram)
std::vector< float > reference_histogram_
virtual void computeHistogram(const pcl::PointCloud< pcl::PointXYZHSV > &cloud, std::vector< float > &output, const ComparePolicy policy)
ros::Subscriber reference_sub_
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > SyncPolicy
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_