37 #ifndef JSK_PCL_ROS_UTILS_POLYGON_POINTS_SAMPLER_H_ 38 #define JSK_PCL_ROS_UTILS_POLYGON_POINTS_SAMPLER_H_ 43 #include <jsk_pcl_ros_utils/PolygonPointsSamplerConfig.h> 44 #include <dynamic_reconfigure/server.h> 50 #include <jsk_recognition_msgs/PolygonArray.h> 51 #include <jsk_recognition_msgs/ModelCoefficientsArray.h> 58 typedef PolygonPointsSamplerConfig
Config;
61 jsk_recognition_msgs::PolygonArray,
62 jsk_recognition_msgs::ModelCoefficientsArray >
SyncPolicy;
70 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
71 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg);
74 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
75 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg);
virtual void unsubscribe()
virtual void configCallback(Config &config, uint32_t level)
virtual void sample(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg)
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
boost::shared_ptr< PolygonPointsSampler > Ptr
PolygonPointsSamplerConfig Config
virtual bool isValidMessage(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
message_filters::sync_policies::ExactTime< jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray > SyncPolicy
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_