40 #ifndef JSK_PCL_ROS_COLOR_HISTOGRAM_CLASSIFIER_H__ 41 #define JSK_PCL_ROS_COLOR_HISTOGRAM_CLASSIFIER_H__ 43 #include <dynamic_reconfigure/server.h> 45 #include <jsk_recognition_msgs/ClusterPointIndices.h> 46 #include <jsk_recognition_msgs/ColorHistogram.h> 47 #include <jsk_recognition_msgs/ColorHistogramArray.h> 52 #include <jsk_pcl_ros/ColorHistogramClassifierConfig.h> 60 typedef ColorHistogramClassifierConfig
Config;
71 virtual void feature(
const jsk_recognition_msgs::ColorHistogram::ConstPtr& histogram);
72 virtual void features(
const jsk_recognition_msgs::ColorHistogramArray::ConstPtr& histograms);
93 #endif // JSK_PCL_ROS_COLOR_HISTOGRAM_CLASSIFIER_H__
virtual void configCallback(Config &config, uint32_t level)
ros::Subscriber sub_hist_
double detection_threshold_
std::vector< std::string > label_names_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual bool loadReference()
std::string classifier_name_
virtual void unsubscribe()
virtual void features(const jsk_recognition_msgs::ColorHistogramArray::ConstPtr &histograms)
jsk_recognition_msgs::ColorHistogram reference_histogram_
ColorHistogramClassifier()
ColorHistogramClassifierConfig Config
virtual void feature(const jsk_recognition_msgs::ColorHistogram::ConstPtr &histogram)
ros::Publisher pub_class_
jsk_recognition_utils::ComparePolicy compare_policy_
boost::mutex mutex
global mutex.
std::vector< std::vector< float > > reference_histograms_
ros::Subscriber sub_hists_
virtual void computeDistance(const std::vector< float > &histogram, std::vector< double > &distance)
double distance(const urdf::Pose &transform)