#include <draw_rects.h>
|
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 () |
|
Definition at line 101 of file draw_rects.h.
◆ AsyncPolicy
◆ Config
◆ SyncPolicy
◆ DrawRects()
jsk_perception::DrawRects::DrawRects |
( |
| ) |
|
|
inline |
◆ ~DrawRects()
jsk_perception::DrawRects::~DrawRects |
( |
| ) |
|
|
virtual |
◆ configCallback()
void jsk_perception::DrawRects::configCallback |
( |
Config & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
protectedvirtual |
◆ drawLabel()
void jsk_perception::DrawRects::drawLabel |
( |
cv::Mat & |
img, |
|
|
const jsk_recognition_msgs::Rect & |
rect, |
|
|
const cv::Scalar & |
color, |
|
|
const std::string & |
label |
|
) |
| |
|
protectedvirtual |
◆ drawRect()
void jsk_perception::DrawRects::drawRect |
( |
cv::Mat & |
img, |
|
|
const jsk_recognition_msgs::Rect & |
rect, |
|
|
const cv::Scalar & |
color |
|
) |
| |
|
protectedvirtual |
◆ fillEmptyClasses()
void jsk_perception::DrawRects::fillEmptyClasses |
( |
const jsk_recognition_msgs::RectArray::ConstPtr & |
rects | ) |
|
|
protectedvirtual |
◆ isDarkColor()
virtual bool jsk_perception::DrawRects::isDarkColor |
( |
const cv::Scalar & |
color | ) |
|
|
inlineprotectedvirtual |
◆ onInit()
void jsk_perception::DrawRects::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ onMessage()
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 |
|
) |
| |
|
protectedvirtual |
◆ randomColor()
void jsk_perception::DrawRects::randomColor |
( |
const int & |
label_num, |
|
|
const int & |
index, |
|
|
cv::Scalar & |
color |
|
) |
| |
|
protectedvirtual |
◆ subscribe()
void jsk_perception::DrawRects::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ unsubscribe()
void jsk_perception::DrawRects::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
◆ async_
◆ interpolation_method_
int jsk_perception::DrawRects::interpolation_method_ |
|
protected |
◆ label_boldness_
int jsk_perception::DrawRects::label_boldness_ |
|
protected |
◆ label_font_
int jsk_perception::DrawRects::label_font_ |
|
protected |
◆ label_margin_factor_
double jsk_perception::DrawRects::label_margin_factor_ |
|
protected |
◆ label_size_
double jsk_perception::DrawRects::label_size_ |
|
protected |
◆ mutex_
boost::mutex jsk_perception::DrawRects::mutex_ |
|
protected |
◆ null_class_
◆ pub_image_
◆ queue_size_
int jsk_perception::DrawRects::queue_size_ |
|
protected |
◆ rect_boldness_
int jsk_perception::DrawRects::rect_boldness_ |
|
protected |
◆ resolution_factor_
double jsk_perception::DrawRects::resolution_factor_ |
|
protected |
◆ show_proba_
bool jsk_perception::DrawRects::show_proba_ |
|
protected |
◆ srv_
◆ sub_class_
◆ sub_image_
◆ sub_rects_
◆ sync_
◆ use_async_
bool jsk_perception::DrawRects::use_async_ |
|
protected |
◆ use_classification_result_
bool jsk_perception::DrawRects::use_classification_result_ |
|
protected |
The documentation for this class was generated from the following files: