#include <color_histogram.h>
|
| void | configCallback (Config &new_config, uint32_t level) |
| |
| virtual void | convertHistogramToMsg (const cv::Mat &hist, int size, jsk_recognition_msgs::ColorHistogram &msg) |
| |
| virtual void | extract (const sensor_msgs::Image::ConstPtr &image, const geometry_msgs::PolygonStamped::ConstPtr &rectangle) |
| |
| virtual void | extractMask (const sensor_msgs::Image::ConstPtr &image, const sensor_msgs::Image::ConstPtr &mask_image) |
| |
| virtual void | onInit () |
| |
| virtual void | processBGR (const cv::Mat &bgr_image, const cv::Mat &mask, const std_msgs::Header &header) |
| |
| virtual void | processBGR (const cv::Mat &bgr_image, const std_msgs::Header &header) |
| |
| virtual void | processHSI (const cv::Mat &bgr_image, const cv::Mat &mask, const std_msgs::Header &header) |
| |
| virtual void | processHSI (const cv::Mat &bgr_image, const std_msgs::Header &header) |
| |
| virtual void | subscribe () |
| |
| virtual void | unsubscribe () |
| |
Definition at line 88 of file color_histogram.h.
◆ Config
◆ MaskSyncPolicy
◆ SyncPolicy
◆ ColorHistogram()
| jsk_perception::ColorHistogram::ColorHistogram |
( |
| ) |
|
|
inline |
◆ ~ColorHistogram()
| jsk_perception::ColorHistogram::~ColorHistogram |
( |
| ) |
|
|
virtual |
◆ configCallback()
| void jsk_perception::ColorHistogram::configCallback |
( |
Config & |
new_config, |
|
|
uint32_t |
level |
|
) |
| |
|
protected |
◆ convertHistogramToMsg()
| void jsk_perception::ColorHistogram::convertHistogramToMsg |
( |
const cv::Mat & |
hist, |
|
|
int |
size, |
|
|
jsk_recognition_msgs::ColorHistogram & |
msg |
|
) |
| |
|
protectedvirtual |
◆ extract()
| void jsk_perception::ColorHistogram::extract |
( |
const sensor_msgs::Image::ConstPtr & |
image, |
|
|
const geometry_msgs::PolygonStamped::ConstPtr & |
rectangle |
|
) |
| |
|
protectedvirtual |
◆ extractMask()
| void jsk_perception::ColorHistogram::extractMask |
( |
const sensor_msgs::Image::ConstPtr & |
image, |
|
|
const sensor_msgs::Image::ConstPtr & |
mask_image |
|
) |
| |
|
protectedvirtual |
◆ onInit()
| void jsk_perception::ColorHistogram::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ processBGR() [1/2]
| void jsk_perception::ColorHistogram::processBGR |
( |
const cv::Mat & |
bgr_image, |
|
|
const cv::Mat & |
mask, |
|
|
const std_msgs::Header & |
header |
|
) |
| |
|
protectedvirtual |
◆ processBGR() [2/2]
| void jsk_perception::ColorHistogram::processBGR |
( |
const cv::Mat & |
bgr_image, |
|
|
const std_msgs::Header & |
header |
|
) |
| |
|
protectedvirtual |
◆ processHSI() [1/2]
| void jsk_perception::ColorHistogram::processHSI |
( |
const cv::Mat & |
bgr_image, |
|
|
const cv::Mat & |
mask, |
|
|
const std_msgs::Header & |
header |
|
) |
| |
|
protectedvirtual |
◆ processHSI() [2/2]
| void jsk_perception::ColorHistogram::processHSI |
( |
const cv::Mat & |
bgr_image, |
|
|
const std_msgs::Header & |
header |
|
) |
| |
|
protectedvirtual |
◆ subscribe()
| void jsk_perception::ColorHistogram::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ unsubscribe()
| void jsk_perception::ColorHistogram::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
◆ b_hist_pub_
◆ b_hist_size_
| int jsk_perception::ColorHistogram::b_hist_size_ |
|
protected |
◆ g_hist_pub_
◆ g_hist_size_
| int jsk_perception::ColorHistogram::g_hist_size_ |
|
protected |
◆ h_hist_pub_
◆ h_hist_size_
| int jsk_perception::ColorHistogram::h_hist_size_ |
|
protected |
◆ i_hist_pub_
◆ i_hist_size_
| int jsk_perception::ColorHistogram::i_hist_size_ |
|
protected |
◆ image_mask_sub_
◆ image_pub_
◆ image_sub_
◆ it_
◆ mask_sync_
◆ mutex_
| boost::mutex jsk_perception::ColorHistogram::mutex_ |
|
protected |
◆ nh_
◆ r_hist_pub_
◆ r_hist_size_
| int jsk_perception::ColorHistogram::r_hist_size_ |
|
protected |
◆ rectangle_sub_
◆ s_hist_pub_
◆ s_hist_size_
| int jsk_perception::ColorHistogram::s_hist_size_ |
|
protected |
◆ srv_
◆ sync_
◆ use_mask_
| bool jsk_perception::ColorHistogram::use_mask_ |
|
protected |
The documentation for this class was generated from the following files: