37 #ifndef JSK_PCL_ROS_UTILS_CLUSTER_POINT_INDICES_TO_POINT_INDICES_H_ 38 #define JSK_PCL_ROS_UTILS_CLUSTER_POINT_INDICES_TO_POINT_INDICES_H_ 41 #include <dynamic_reconfigure/server.h> 42 #include <jsk_pcl_ros_utils/ClusterPointIndicesToPointIndicesConfig.h> 43 #include <jsk_recognition_msgs/ClusterPointIndices.h> 51 typedef jsk_pcl_ros_utils::ClusterPointIndicesToPointIndicesConfig
Config;
57 virtual void convert(
const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& cluster_indices_msg);
71 #endif // JSK_PCL_ROS_UTILS_CLUSTER_POINT_INDICES_TO_POINT_INDICES_H_
ClusterPointIndicesToPointIndices()
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void convert(const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &cluster_indices_msg)
jsk_pcl_ros_utils::ClusterPointIndicesToPointIndicesConfig Config
virtual void unsubscribe()
virtual void configCallback(Config &config, uint32_t level)