40 #ifndef JSK_PCL_ROS_COLOR_HISTOGRAM_H__ 41 #define JSK_PCL_ROS_COLOR_HISTOGRAM_H__ 43 #include <dynamic_reconfigure/server.h> 45 #include <jsk_recognition_msgs/ColorHistogram.h> 46 #include <jsk_recognition_msgs/ColorHistogramArray.h> 47 #include <jsk_recognition_msgs/ClusterPointIndices.h> 53 #include <sensor_msgs/PointCloud2.h> 55 #include <jsk_pcl_ros/ColorHistogramConfig.h> 74 const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
75 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_indices);
93 #endif // JSK_PCL_ROS_COLOR_HISTOGRAM_H__ virtual void configCallback(Config &config, uint32_t level)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
ColorHistogramConfig Config
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > SyncPolicy
ros::Publisher pub_histogram_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
virtual void feature(const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &input_indices)
boost::mutex mutex
global mutex.
jsk_recognition_utils::HistogramPolicy histogram_policy_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void unsubscribe()