36 #ifndef JSK_PERCEPTION_CONSENSUS_TRACKING_H_ 37 #define JSK_PERCEPTION_CONSENSUS_TRACKING_H_ 39 #include <geometry_msgs/PolygonStamped.h> 40 #include <libcmt/CMT.h> 46 #include <sensor_msgs/Image.h> 68 const geometry_msgs::PolygonStamped::ConstPtr& poly_msg);
89 #endif // JSK_PERCEPTION_CONSENSUS_TRACKING_H_ message_filters::sync_policies::ExactTime< sensor_msgs::Image, geometry_msgs::PolygonStamped > ExactSyncPolicy
message_filters::Subscriber< sensor_msgs::Image > sub_image_to_init_
ros::Publisher pub_mask_image_
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, geometry_msgs::PolygonStamped > ApproximateSyncPolicy
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
ros::Publisher pub_debug_image_
void setInitialWindow(const sensor_msgs::Image::ConstPtr &img_msg, const geometry_msgs::PolygonStamped::ConstPtr &poly_msg)
boost::shared_ptr< message_filters::Synchronizer< ExactSyncPolicy > > sync_
message_filters::Subscriber< geometry_msgs::PolygonStamped > sub_polygon_to_init_
ros::Subscriber sub_image_
virtual void getTrackingResult(const sensor_msgs::Image::ConstPtr &image_msg)
virtual void unsubscribe()