41 #ifndef DRAW_RECTS_H__ 42 #define DRAW_RECTS_H__ 46 #include <boost/shared_ptr.hpp> 47 #include <boost/thread.hpp> 49 #include <opencv2/opencv.hpp> 52 #include <dynamic_reconfigure/server.h> 61 #include <jsk_perception/DrawRectsConfig.h> 62 #include <jsk_recognition_msgs/ClassificationResult.h> 63 #include <jsk_recognition_msgs/RectArray.h> 64 #include <sensor_msgs/Image.h> 75 jsk_recognition_msgs::RectArray,
79 jsk_recognition_msgs::RectArray,
89 const sensor_msgs::Image::ConstPtr& image,
90 const jsk_recognition_msgs::RectArray::ConstPtr& rects,
91 const jsk_recognition_msgs::ClassificationResult::ConstPtr& classes);
93 const jsk_recognition_msgs::RectArray::ConstPtr& rects);
95 cv::Mat&
img,
const jsk_recognition_msgs::Rect& rect,
const cv::Scalar& color);
97 cv::Mat& img,
const jsk_recognition_msgs::Rect& rect,
98 const cv::Scalar& color,
const std::string&
label);
99 virtual void randomColor(
const int& label_num,
const int&
index, cv::Scalar& color);
101 return color[2] * 0.299 + color[1] * 0.587 + color[0] * 0.114 <= 186.0;
129 #endif // DRAW_RECTS_H__ message_filters::sync_policies::ExactTime< sensor_msgs::Image, jsk_recognition_msgs::RectArray, jsk_recognition_msgs::ClassificationResult > SyncPolicy
bool use_classification_result_
double resolution_factor_
virtual void drawRect(cv::Mat &img, const jsk_recognition_msgs::Rect &rect, const cv::Scalar &color)
double label_margin_factor_
virtual void fillEmptyClasses(const jsk_recognition_msgs::RectArray::ConstPtr &rects)
virtual void configCallback(Config &config, uint32_t level)
message_filters::Subscriber< jsk_recognition_msgs::ClassificationResult > sub_class_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
message_filters::Subscriber< jsk_recognition_msgs::RectArray > sub_rects_
virtual void randomColor(const int &label_num, const int &index, cv::Scalar &color)
virtual void unsubscribe()
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void onMessage(const sensor_msgs::Image::ConstPtr &image, const jsk_recognition_msgs::RectArray::ConstPtr &rects, const jsk_recognition_msgs::ClassificationResult::ConstPtr &classes)
message_filters::Subscriber< sensor_msgs::Image > sub_image_
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, jsk_recognition_msgs::RectArray, jsk_recognition_msgs::ClassificationResult > AsyncPolicy
message_filters::PassThrough< jsk_recognition_msgs::ClassificationResult > null_class_
boost::shared_ptr< message_filters::Synchronizer< AsyncPolicy > > async_
ros::Publisher pub_image_
virtual bool isDarkColor(const cv::Scalar &color)
int interpolation_method_
virtual void drawLabel(cv::Mat &img, const jsk_recognition_msgs::Rect &rect, const cv::Scalar &color, const std::string &label)