Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jsk_perception::DrawRects Class Reference

#include <draw_rects.h>

Inheritance diagram for jsk_perception::DrawRects:
Inheritance graph
[legend]

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 ()
 
virtual ~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_
 

Detailed Description

Definition at line 101 of file draw_rects.h.

Member Typedef Documentation

◆ AsyncPolicy

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, jsk_recognition_msgs::RectArray, jsk_recognition_msgs::ClassificationResult> jsk_perception::DrawRects::AsyncPolicy

Definition at line 144 of file draw_rects.h.

◆ Config

typedef DrawRectsConfig jsk_perception::DrawRects::Config

Definition at line 136 of file draw_rects.h.

◆ SyncPolicy

typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, jsk_recognition_msgs::RectArray, jsk_recognition_msgs::ClassificationResult> jsk_perception::DrawRects::SyncPolicy

Definition at line 140 of file draw_rects.h.

Constructor & Destructor Documentation

◆ DrawRects()

jsk_perception::DrawRects::DrawRects ( )
inline

Definition at line 146 of file draw_rects.h.

◆ ~DrawRects()

jsk_perception::DrawRects::~DrawRects ( )
virtual

Definition at line 96 of file draw_rects.cpp.

Member Function Documentation

◆ configCallback()

void jsk_perception::DrawRects::configCallback ( Config config,
uint32_t  level 
)
protectedvirtual

Definition at line 144 of file draw_rects.cpp.

◆ drawLabel()

void jsk_perception::DrawRects::drawLabel ( cv::Mat &  img,
const jsk_recognition_msgs::Rect &  rect,
const cv::Scalar &  color,
const std::string label 
)
protectedvirtual

Definition at line 241 of file draw_rects.cpp.

◆ drawRect()

void jsk_perception::DrawRects::drawRect ( cv::Mat &  img,
const jsk_recognition_msgs::Rect &  rect,
const cv::Scalar &  color 
)
protectedvirtual

Definition at line 231 of file draw_rects.cpp.

◆ fillEmptyClasses()

void jsk_perception::DrawRects::fillEmptyClasses ( const jsk_recognition_msgs::RectArray::ConstPtr &  rects)
protectedvirtual

Definition at line 178 of file draw_rects.cpp.

◆ isDarkColor()

virtual bool jsk_perception::DrawRects::isDarkColor ( const cv::Scalar &  color)
inlineprotectedvirtual

Definition at line 165 of file draw_rects.h.

◆ onInit()

void jsk_perception::DrawRects::onInit ( )
protectedvirtual

Definition at line 82 of file draw_rects.cpp.

◆ 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

Definition at line 187 of file draw_rects.cpp.

◆ randomColor()

void jsk_perception::DrawRects::randomColor ( const int &  label_num,
const int &  index,
cv::Scalar &  color 
)
protectedvirtual

Definition at line 270 of file draw_rects.cpp.

◆ subscribe()

void jsk_perception::DrawRects::subscribe ( )
protectedvirtual

Definition at line 108 of file draw_rects.cpp.

◆ unsubscribe()

void jsk_perception::DrawRects::unsubscribe ( )
protectedvirtual

Definition at line 136 of file draw_rects.cpp.

Member Data Documentation

◆ async_

boost::shared_ptr<message_filters::Synchronizer<AsyncPolicy> > jsk_perception::DrawRects::async_
protected

Definition at line 172 of file draw_rects.h.

◆ interpolation_method_

int jsk_perception::DrawRects::interpolation_method_
protected

Definition at line 189 of file draw_rects.h.

◆ label_boldness_

int jsk_perception::DrawRects::label_boldness_
protected

Definition at line 185 of file draw_rects.h.

◆ label_font_

int jsk_perception::DrawRects::label_font_
protected

Definition at line 186 of file draw_rects.h.

◆ label_margin_factor_

double jsk_perception::DrawRects::label_margin_factor_
protected

Definition at line 187 of file draw_rects.h.

◆ label_size_

double jsk_perception::DrawRects::label_size_
protected

Definition at line 184 of file draw_rects.h.

◆ mutex_

boost::mutex jsk_perception::DrawRects::mutex_
protected

Definition at line 169 of file draw_rects.h.

◆ null_class_

message_filters::PassThrough<jsk_recognition_msgs::ClassificationResult> jsk_perception::DrawRects::null_class_
protected

Definition at line 174 of file draw_rects.h.

◆ pub_image_

ros::Publisher jsk_perception::DrawRects::pub_image_
protected

Definition at line 173 of file draw_rects.h.

◆ queue_size_

int jsk_perception::DrawRects::queue_size_
protected

Definition at line 182 of file draw_rects.h.

◆ rect_boldness_

int jsk_perception::DrawRects::rect_boldness_
protected

Definition at line 183 of file draw_rects.h.

◆ resolution_factor_

double jsk_perception::DrawRects::resolution_factor_
protected

Definition at line 188 of file draw_rects.h.

◆ show_proba_

bool jsk_perception::DrawRects::show_proba_
protected

Definition at line 181 of file draw_rects.h.

◆ srv_

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_perception::DrawRects::srv_
protected

Definition at line 170 of file draw_rects.h.

◆ sub_class_

message_filters::Subscriber<jsk_recognition_msgs::ClassificationResult> jsk_perception::DrawRects::sub_class_
protected

Definition at line 177 of file draw_rects.h.

◆ sub_image_

message_filters::Subscriber<sensor_msgs::Image> jsk_perception::DrawRects::sub_image_
protected

Definition at line 175 of file draw_rects.h.

◆ sub_rects_

message_filters::Subscriber<jsk_recognition_msgs::RectArray> jsk_perception::DrawRects::sub_rects_
protected

Definition at line 176 of file draw_rects.h.

◆ sync_

boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_perception::DrawRects::sync_
protected

Definition at line 171 of file draw_rects.h.

◆ use_async_

bool jsk_perception::DrawRects::use_async_
protected

Definition at line 179 of file draw_rects.h.

◆ use_classification_result_

bool jsk_perception::DrawRects::use_classification_result_
protected

Definition at line 180 of file draw_rects.h.


The documentation for this class was generated from the following files:


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Fri May 16 2025 03:11:17