Go to the documentation of this file.
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>
53 #include <jsk_topic_tools/connection_based_nodelet.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>
69 class DrawRects :
public jsk_topic_tools::ConnectionBasedNodelet
72 typedef DrawRectsConfig
Config;
75 jsk_recognition_msgs::RectArray,
76 jsk_recognition_msgs::ClassificationResult>
SyncPolicy;
79 jsk_recognition_msgs::RectArray,
80 jsk_recognition_msgs::ClassificationResult>
AsyncPolicy;
90 const sensor_msgs::Image::ConstPtr& image,
91 const jsk_recognition_msgs::RectArray::ConstPtr& rects,
92 const jsk_recognition_msgs::ClassificationResult::ConstPtr& classes);
94 const jsk_recognition_msgs::RectArray::ConstPtr& rects);
96 cv::Mat& img,
const jsk_recognition_msgs::Rect& rect,
const cv::Scalar& color);
98 cv::Mat& img,
const jsk_recognition_msgs::Rect& rect,
99 const cv::Scalar& color,
const std::string& label);
100 virtual void randomColor(
const int& label_num,
const int& index, cv::Scalar& color);
102 return color[2] * 0.299 + color[1] * 0.587 + color[0] * 0.114 <= 186.0;
130 #endif // DRAW_RECTS_H__
message_filters::PassThrough< jsk_recognition_msgs::ClassificationResult > null_class_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
message_filters::Subscriber< sensor_msgs::Image > sub_image_
virtual void unsubscribe()
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::sync_policies::ApproximateTime< sensor_msgs::Image, jsk_recognition_msgs::RectArray, jsk_recognition_msgs::ClassificationResult > AsyncPolicy
int interpolation_method_
boost::shared_ptr< message_filters::Synchronizer< AsyncPolicy > > async_
message_filters::sync_policies::ExactTime< sensor_msgs::Image, jsk_recognition_msgs::RectArray, jsk_recognition_msgs::ClassificationResult > SyncPolicy
bool use_classification_result_
virtual void drawLabel(cv::Mat &img, const jsk_recognition_msgs::Rect &rect, const cv::Scalar &color, const std::string &label)
ros::Publisher pub_image_
virtual bool isDarkColor(const cv::Scalar &color)
double resolution_factor_
virtual void drawRect(cv::Mat &img, const jsk_recognition_msgs::Rect &rect, const cv::Scalar &color)
virtual void fillEmptyClasses(const jsk_recognition_msgs::RectArray::ConstPtr &rects)
double label_margin_factor_
virtual void configCallback(Config &config, uint32_t level)
virtual void randomColor(const int &label_num, const int &index, cv::Scalar &color)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
message_filters::Subscriber< jsk_recognition_msgs::ClassificationResult > sub_class_
message_filters::Subscriber< jsk_recognition_msgs::RectArray > sub_rects_
jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Fri May 16 2025 03:11:16