37 #ifndef JSK_PCL_ROS_UTILS_POLYGON_FLIPPER_H_ 38 #define JSK_PCL_ROS_UTILS_POLYGON_FLIPPER_H_ 41 #include <jsk_recognition_msgs/PolygonArray.h> 42 #include <jsk_recognition_msgs/ModelCoefficientsArray.h> 43 #include <jsk_recognition_msgs/ClusterPointIndices.h> 60 jsk_recognition_msgs::PolygonArray,
61 jsk_recognition_msgs::ClusterPointIndices,
62 jsk_recognition_msgs::ModelCoefficientsArray >
SyncPolicy;
70 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg);
72 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
73 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg,
74 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg);
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void unsubscribe()
virtual void flip(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg)
ros::Publisher pub_polygons_
std::string sensor_frame_
ros::Publisher pub_indices_
virtual void fillEmptyIndices(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg)
message_filters::sync_policies::ExactTime< jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::ModelCoefficientsArray > SyncPolicy
message_filters::PassThrough< jsk_recognition_msgs::ClusterPointIndices > sub_indices_null_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
tf::TransformListener * tf_listener_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
ros::Publisher pub_coefficients_
boost::shared_ptr< PolygonFlipper > Ptr