#include <draw_rects.h>
Public Types | |
typedef message_filters::sync_policies::ApproximateTime < sensor_msgs::Image, jsk_recognition_msgs::RectArray, jsk_recognition_msgs::ClassificationResult > | AsyncPolicy |
typedef DrawRectsConfig | Config |
typedef message_filters::sync_policies::ExactTime < sensor_msgs::Image, jsk_recognition_msgs::RectArray, jsk_recognition_msgs::ClassificationResult > | SyncPolicy |
Public Member Functions | |
DrawRects () | |
Protected Member Functions | |
virtual void | configCallback (Config &config, uint32_t level) |
virtual void | drawLabel (cv::Mat &img, const jsk_recognition_msgs::Rect &rect, const cv::Scalar &color, const std::string &label) |
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) |
virtual bool | isDarkColor (const cv::Scalar &color) |
virtual void | onInit () |
virtual void | onMessage (const sensor_msgs::Image::ConstPtr &image, const jsk_recognition_msgs::RectArray::ConstPtr &rects, const jsk_recognition_msgs::ClassificationResult::ConstPtr &classes) |
virtual void | randomColor (const int &label_num, const int &index, cv::Scalar &color) |
virtual void | subscribe () |
virtual void | unsubscribe () |
Protected Attributes | |
boost::shared_ptr < message_filters::Synchronizer < AsyncPolicy > > | async_ |
int | interpolation_method_ |
int | label_boldness_ |
int | label_font_ |
double | label_margin_factor_ |
double | label_size_ |
boost::mutex | mutex_ |
message_filters::PassThrough < jsk_recognition_msgs::ClassificationResult > | null_class_ |
ros::Publisher | pub_image_ |
int | queue_size_ |
int | rect_boldness_ |
double | resolution_factor_ |
bool | show_proba_ |
boost::shared_ptr < dynamic_reconfigure::Server < Config > > | srv_ |
message_filters::Subscriber < jsk_recognition_msgs::ClassificationResult > | sub_class_ |
message_filters::Subscriber < sensor_msgs::Image > | sub_image_ |
message_filters::Subscriber < jsk_recognition_msgs::RectArray > | sub_rects_ |
boost::shared_ptr < message_filters::Synchronizer < SyncPolicy > > | sync_ |
bool | use_async_ |
bool | use_classification_result_ |
Definition at line 69 of file draw_rects.h.
typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, jsk_recognition_msgs::RectArray, jsk_recognition_msgs::ClassificationResult> jsk_perception::DrawRects::AsyncPolicy |
Definition at line 80 of file draw_rects.h.
typedef DrawRectsConfig jsk_perception::DrawRects::Config |
Definition at line 72 of file draw_rects.h.
typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, jsk_recognition_msgs::RectArray, jsk_recognition_msgs::ClassificationResult> jsk_perception::DrawRects::SyncPolicy |
Definition at line 76 of file draw_rects.h.
jsk_perception::DrawRects::DrawRects | ( | ) | [inline] |
Definition at line 82 of file draw_rects.h.
void jsk_perception::DrawRects::configCallback | ( | Config & | config, |
uint32_t | level | ||
) | [protected, virtual] |
Definition at line 97 of file draw_rects.cpp.
void jsk_perception::DrawRects::drawLabel | ( | cv::Mat & | img, |
const jsk_recognition_msgs::Rect & | rect, | ||
const cv::Scalar & | color, | ||
const std::string & | label | ||
) | [protected, virtual] |
Definition at line 194 of file draw_rects.cpp.
void jsk_perception::DrawRects::drawRect | ( | cv::Mat & | img, |
const jsk_recognition_msgs::Rect & | rect, | ||
const cv::Scalar & | color | ||
) | [protected, virtual] |
Definition at line 184 of file draw_rects.cpp.
void jsk_perception::DrawRects::fillEmptyClasses | ( | const jsk_recognition_msgs::RectArray::ConstPtr & | rects | ) | [protected, virtual] |
Definition at line 131 of file draw_rects.cpp.
virtual bool jsk_perception::DrawRects::isDarkColor | ( | const cv::Scalar & | color | ) | [inline, protected, virtual] |
Definition at line 100 of file draw_rects.h.
void jsk_perception::DrawRects::onInit | ( | ) | [protected, virtual] |
Definition at line 47 of file draw_rects.cpp.
void jsk_perception::DrawRects::onMessage | ( | const sensor_msgs::Image::ConstPtr & | image, |
const jsk_recognition_msgs::RectArray::ConstPtr & | rects, | ||
const jsk_recognition_msgs::ClassificationResult::ConstPtr & | classes | ||
) | [protected, virtual] |
Definition at line 140 of file draw_rects.cpp.
void jsk_perception::DrawRects::randomColor | ( | const int & | label_num, |
const int & | index, | ||
cv::Scalar & | color | ||
) | [protected, virtual] |
Definition at line 223 of file draw_rects.cpp.
void jsk_perception::DrawRects::subscribe | ( | ) | [protected, virtual] |
Definition at line 61 of file draw_rects.cpp.
void jsk_perception::DrawRects::unsubscribe | ( | ) | [protected, virtual] |
Definition at line 89 of file draw_rects.cpp.
boost::shared_ptr<message_filters::Synchronizer<AsyncPolicy> > jsk_perception::DrawRects::async_ [protected] |
Definition at line 107 of file draw_rects.h.
int jsk_perception::DrawRects::interpolation_method_ [protected] |
Definition at line 124 of file draw_rects.h.
int jsk_perception::DrawRects::label_boldness_ [protected] |
Definition at line 120 of file draw_rects.h.
int jsk_perception::DrawRects::label_font_ [protected] |
Definition at line 121 of file draw_rects.h.
double jsk_perception::DrawRects::label_margin_factor_ [protected] |
Definition at line 122 of file draw_rects.h.
double jsk_perception::DrawRects::label_size_ [protected] |
Definition at line 119 of file draw_rects.h.
boost::mutex jsk_perception::DrawRects::mutex_ [protected] |
Definition at line 104 of file draw_rects.h.
message_filters::PassThrough<jsk_recognition_msgs::ClassificationResult> jsk_perception::DrawRects::null_class_ [protected] |
Definition at line 109 of file draw_rects.h.
ros::Publisher jsk_perception::DrawRects::pub_image_ [protected] |
Definition at line 108 of file draw_rects.h.
int jsk_perception::DrawRects::queue_size_ [protected] |
Definition at line 117 of file draw_rects.h.
int jsk_perception::DrawRects::rect_boldness_ [protected] |
Definition at line 118 of file draw_rects.h.
double jsk_perception::DrawRects::resolution_factor_ [protected] |
Definition at line 123 of file draw_rects.h.
bool jsk_perception::DrawRects::show_proba_ [protected] |
Definition at line 116 of file draw_rects.h.
boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_perception::DrawRects::srv_ [protected] |
Definition at line 105 of file draw_rects.h.
message_filters::Subscriber<jsk_recognition_msgs::ClassificationResult> jsk_perception::DrawRects::sub_class_ [protected] |
Definition at line 112 of file draw_rects.h.
message_filters::Subscriber<sensor_msgs::Image> jsk_perception::DrawRects::sub_image_ [protected] |
Definition at line 110 of file draw_rects.h.
message_filters::Subscriber<jsk_recognition_msgs::RectArray> jsk_perception::DrawRects::sub_rects_ [protected] |
Definition at line 111 of file draw_rects.h.
boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_perception::DrawRects::sync_ [protected] |
Definition at line 106 of file draw_rects.h.
bool jsk_perception::DrawRects::use_async_ [protected] |
Definition at line 114 of file draw_rects.h.
bool jsk_perception::DrawRects::use_classification_result_ [protected] |
Definition at line 115 of file draw_rects.h.