37 #ifndef JSK_PCL_ROS_UTILS_POLYGON_ARRAY_LIKELIHOOD_FILTER_H_ 38 #define JSK_PCL_ROS_UTILS_POLYGON_ARRAY_LIKELIHOOD_FILTER_H_ 44 #include <dynamic_reconfigure/server.h> 45 #include <jsk_pcl_ros_utils/PolygonArrayLikelihoodFilterConfig.h> 46 #include <jsk_recognition_msgs/PolygonArray.h> 47 #include <jsk_recognition_msgs/ModelCoefficientsArray.h> 56 typedef PolygonArrayLikelihoodFilterConfig
Config;
58 jsk_recognition_msgs::PolygonArray,
59 jsk_recognition_msgs::ModelCoefficientsArray>
68 const jsk_recognition_msgs::PolygonArray::ConstPtr&
polygons);
70 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons,
71 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr&
coefficients);
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
virtual void filter(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons)
ros::Subscriber sub_polygons_alone_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
PolygonArrayLikelihoodFilterConfig Config
ros::Publisher pub_polygons_
message_filters::sync_policies::ExactTime< jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray > SyncPolicy
virtual void configCallback(Config &config, uint32_t level)
ros::Publisher pub_coefficients_
virtual void unsubscribe()
PolygonArrayLikelihoodFilter()
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_