Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041 #ifndef DRAW_RECTS_H__
00042 #define DRAW_RECTS_H__
00043
00044 #include <sstream>
00045
00046 #include <boost/shared_ptr.hpp>
00047 #include <boost/thread.hpp>
00048
00049 #include <opencv2/opencv.hpp>
00050
00051 #include <cv_bridge/cv_bridge.h>
00052 #include <dynamic_reconfigure/server.h>
00053 #include <jsk_topic_tools/connection_based_nodelet.h>
00054 #include <message_filters/pass_through.h>
00055 #include <message_filters/subscriber.h>
00056 #include <message_filters/synchronizer.h>
00057 #include <message_filters/sync_policies/exact_time.h>
00058 #include <message_filters/sync_policies/approximate_time.h>
00059 #include <sensor_msgs/image_encodings.h>
00060
00061 #include <jsk_perception/DrawRectsConfig.h>
00062 #include <jsk_recognition_msgs/ClassificationResult.h>
00063 #include <jsk_recognition_msgs/RectArray.h>
00064 #include <sensor_msgs/Image.h>
00065
00066
00067 namespace jsk_perception
00068 {
00069 class DrawRects : public jsk_topic_tools::ConnectionBasedNodelet
00070 {
00071 public:
00072 typedef DrawRectsConfig Config;
00073 typedef message_filters::sync_policies::ExactTime<
00074 sensor_msgs::Image,
00075 jsk_recognition_msgs::RectArray,
00076 jsk_recognition_msgs::ClassificationResult> SyncPolicy;
00077 typedef message_filters::sync_policies::ApproximateTime<
00078 sensor_msgs::Image,
00079 jsk_recognition_msgs::RectArray,
00080 jsk_recognition_msgs::ClassificationResult> AsyncPolicy;
00081
00082 DrawRects(){}
00083 protected:
00084 virtual void onInit();
00085 virtual void subscribe();
00086 virtual void unsubscribe();
00087 virtual void configCallback(Config& config, uint32_t level);
00088 virtual void onMessage(
00089 const sensor_msgs::Image::ConstPtr& image,
00090 const jsk_recognition_msgs::RectArray::ConstPtr& rects,
00091 const jsk_recognition_msgs::ClassificationResult::ConstPtr& classes);
00092 virtual void fillEmptyClasses(
00093 const jsk_recognition_msgs::RectArray::ConstPtr& rects);
00094 virtual void drawRect(
00095 cv::Mat& img, const jsk_recognition_msgs::Rect& rect, const cv::Scalar& color);
00096 virtual void drawLabel(
00097 cv::Mat& img, const jsk_recognition_msgs::Rect& rect,
00098 const cv::Scalar& color, const std::string& label);
00099 virtual void randomColor(const int& label_num, const int& index, cv::Scalar& color);
00100 virtual bool isDarkColor(const cv::Scalar& color) {
00101 return color[2] * 0.299 + color[1] * 0.587 + color[0] * 0.114 <= 186.0;
00102 }
00103
00104 boost::mutex mutex_;
00105 boost::shared_ptr<dynamic_reconfigure::Server<Config> > srv_;
00106 boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > sync_;
00107 boost::shared_ptr<message_filters::Synchronizer<AsyncPolicy> > async_;
00108 ros::Publisher pub_image_;
00109 message_filters::PassThrough<jsk_recognition_msgs::ClassificationResult> null_class_;
00110 message_filters::Subscriber<sensor_msgs::Image> sub_image_;
00111 message_filters::Subscriber<jsk_recognition_msgs::RectArray> sub_rects_;
00112 message_filters::Subscriber<jsk_recognition_msgs::ClassificationResult> sub_class_;
00113
00114 bool use_async_;
00115 bool use_classification_result_;
00116 bool show_proba_;
00117 int queue_size_;
00118 int rect_boldness_;
00119 double label_size_;
00120 int label_boldness_;
00121 int label_font_;
00122 double label_margin_factor_;
00123 double resolution_factor_;
00124 int interpolation_method_;
00125 };
00126 }
00127
00128
00129 #endif // DRAW_RECTS_H__