37 #ifndef JSK_PERCEPTION_RECT_ARRAY_ACTUAL_SIZE_FILTER_H_ 38 #define JSK_PERCEPTION_RECT_ARRAY_ACTUAL_SIZE_FILTER_H_ 41 #include <sensor_msgs/Image.h> 42 #include <sensor_msgs/CameraInfo.h> 43 #include <jsk_recognition_msgs/RectArray.h> 44 #include <jsk_perception/RectArrayActualSizeFilterConfig.h> 45 #include <dynamic_reconfigure/server.h> 50 #include <opencv2/opencv.hpp> 58 typedef RectArrayActualSizeFilterConfig
Config;
60 jsk_recognition_msgs::RectArray,
64 jsk_recognition_msgs::RectArray,
73 virtual void filter(
const jsk_recognition_msgs::RectArray::ConstPtr& rect_array_msg,
74 const sensor_msgs::Image::ConstPtr& depth_image_msg,
75 const sensor_msgs::CameraInfo::ConstPtr&
info_msg);
77 virtual double averageDistance(
const int center_x,
const int center_y,
const cv::Mat&
img)
const;
boost::shared_ptr< RectArrayActualSizeFilter > Ptr
virtual double averageDistance(const int center_x, const int center_y, const cv::Mat &img) const
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
message_filters::Subscriber< sensor_msgs::Image > sub_image_
message_filters::sync_policies::ApproximateTime< jsk_recognition_msgs::RectArray, sensor_msgs::Image, sensor_msgs::CameraInfo > ApproxSyncPolicy
boost::shared_ptr< message_filters::Synchronizer< ApproxSyncPolicy > > async_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_
virtual void configCallback(Config &config, uint32_t level)
message_filters::Subscriber< jsk_recognition_msgs::RectArray > sub_rect_array_
message_filters::sync_policies::ExactTime< jsk_recognition_msgs::RectArray, sensor_msgs::Image, sensor_msgs::CameraInfo > SyncPolicy
RectArrayActualSizeFilter()
virtual void filter(const jsk_recognition_msgs::RectArray::ConstPtr &rect_array_msg, const sensor_msgs::Image::ConstPtr &depth_image_msg, const sensor_msgs::CameraInfo::ConstPtr &info_msg)
virtual void unsubscribe()
RectArrayActualSizeFilterConfig Config
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_