36 #ifndef JSK_PERCEPTION_FILTER_MASK_IMAGE_WITH_SIZE_H_ 37 #define JSK_PERCEPTION_FILTER_MASK_IMAGE_WITH_SIZE_H_ 39 #include <dynamic_reconfigure/server.h> 45 #include <sensor_msgs/Image.h> 47 #include "jsk_perception/FilterMaskImageWithSizeConfig.h" 59 typedef jsk_perception::FilterMaskImageWithSizeConfig
Config;
65 virtual void filter(
const sensor_msgs::Image::ConstPtr& input_msg);
66 virtual void filter(
const sensor_msgs::Image::ConstPtr& input_msg,
67 const sensor_msgs::Image::ConstPtr& reference_msg);
90 #endif // JSK_PERCEPTION_FILTER_MASK_IMAGE_WITH_RELATIVE_SIZE_H_ virtual void configCallback(Config &config, uint32_t level)
jsk_perception::FilterMaskImageWithSizeConfig Config
boost::shared_ptr< message_filters::Synchronizer< ApproxSyncPolicy > > async_
double max_relative_size_
virtual void unsubscribe()
message_filters::Subscriber< sensor_msgs::Image > sub_reference_
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image > ApproxSyncPolicy
double min_relative_size_
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image > SyncPolicy
message_filters::Subscriber< sensor_msgs::Image > sub_input_
FilterMaskImageWithSize()
virtual void filter(const sensor_msgs::Image::ConstPtr &input_msg)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_