37 #ifndef JSK_PCL_ROS_UTILS_POLYGON_ARRAY_WRAPPER_H_ 38 #define JSK_PCL_ROS_UTILS_POLYGON_ARRAY_WRAPPER_H_ 44 #include <geometry_msgs/PolygonStamped.h> 45 #include <jsk_recognition_msgs/PolygonArray.h> 46 #include <jsk_recognition_msgs/ModelCoefficientsArray.h> 55 geometry_msgs::PolygonStamped, pcl_msgs::ModelCoefficients>
SyncPolicy;
61 virtual void wrap(
const geometry_msgs::PolygonStamped::ConstPtr& polygon,
62 const pcl_msgs::ModelCoefficients::ConstPtr& coefficients);
ros::Publisher pub_polygon_array_
ros::Publisher pub_coefficients_array_
message_filters::sync_policies::ExactTime< geometry_msgs::PolygonStamped, pcl_msgs::ModelCoefficients > SyncPolicy
virtual void unsubscribe()
virtual void wrap(const geometry_msgs::PolygonStamped::ConstPtr &polygon, const pcl_msgs::ModelCoefficients::ConstPtr &coefficients)
message_filters::Subscriber< pcl_msgs::ModelCoefficients > sub_coefficients_
message_filters::Subscriber< geometry_msgs::PolygonStamped > sub_polygon_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_