37 #ifndef JSK_PERCEPTION_RECT_ARRAY_TO_DENSITY_IMAGE_H_ 38 #define JSK_PERCEPTION_RECT_ARRAY_TO_DENSITY_IMAGE_H_ 41 #include <sensor_msgs/Image.h> 42 #include <jsk_recognition_msgs/RectArray.h> 56 sensor_msgs::Image, jsk_recognition_msgs::RectArray >
SyncPolicy;
64 const sensor_msgs::Image::ConstPtr& image_msg,
65 const jsk_recognition_msgs::RectArray::ConstPtr& rects_msg);
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, jsk_recognition_msgs::RectArray > ApproximateSyncPolicy
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void convert(const sensor_msgs::Image::ConstPtr &image_msg, const jsk_recognition_msgs::RectArray::ConstPtr &rects_msg)
message_filters::Subscriber< sensor_msgs::Image > sub_image_
message_filters::sync_policies::ExactTime< sensor_msgs::Image, jsk_recognition_msgs::RectArray > SyncPolicy
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
RectArrayToDensityImage()
message_filters::Subscriber< jsk_recognition_msgs::RectArray > sub_rects_
virtual void unsubscribe()