#include <tabletop_color_difference_likelihood.h>
|
| typedef TabletopColorDifferenceLikelihoodConfig | Config |
| |
◆ Config
◆ TabletopColorDifferenceLikelihood()
| jsk_perception::TabletopColorDifferenceLikelihood::TabletopColorDifferenceLikelihood |
( |
| ) |
|
|
inline |
◆ computePixelDistance()
| virtual unsigned char jsk_perception::TabletopColorDifferenceLikelihood::computePixelDistance |
( |
const unsigned char |
from, |
|
|
const unsigned char |
to |
|
) |
| const |
|
inlineprotectedvirtual |
◆ computePixelHistogramDistance()
| virtual unsigned char jsk_perception::TabletopColorDifferenceLikelihood::computePixelHistogramDistance |
( |
const unsigned char |
from, |
|
|
const std::vector< jsk_recognition_msgs::HistogramWithRangeBin > & |
bins |
|
) |
| |
|
inlineprotectedvirtual |
◆ configCallback()
| void jsk_perception::TabletopColorDifferenceLikelihood::configCallback |
( |
Config & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
protectedvirtual |
◆ debugPolygonImage()
◆ imageCallback()
| void jsk_perception::TabletopColorDifferenceLikelihood::imageCallback |
( |
const sensor_msgs::Image::ConstPtr & |
msg | ) |
|
|
protectedvirtual |
◆ infoCallback()
| void jsk_perception::TabletopColorDifferenceLikelihood::infoCallback |
( |
const sensor_msgs::CameraInfo::ConstPtr & |
msg | ) |
|
|
protectedvirtual |
◆ onInit()
| void jsk_perception::TabletopColorDifferenceLikelihood::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ polygonCallback()
| void jsk_perception::TabletopColorDifferenceLikelihood::polygonCallback |
( |
const jsk_recognition_msgs::PolygonArray::ConstPtr & |
msg | ) |
|
|
protectedvirtual |
◆ subscribe()
| void jsk_perception::TabletopColorDifferenceLikelihood::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ unsubscribe()
| void jsk_perception::TabletopColorDifferenceLikelihood::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
◆ bin_size_
| int jsk_perception::TabletopColorDifferenceLikelihood::bin_size_ |
|
protected |
◆ cyclic_value_
| bool jsk_perception::TabletopColorDifferenceLikelihood::cyclic_value_ |
|
protected |
◆ histogram_top_n_ratio_
| double jsk_perception::TabletopColorDifferenceLikelihood::histogram_top_n_ratio_ |
|
protected |
◆ latest_info_msg_
| sensor_msgs::CameraInfo::ConstPtr jsk_perception::TabletopColorDifferenceLikelihood::latest_info_msg_ |
|
protected |
◆ latest_polygon_msg_
| jsk_recognition_msgs::PolygonArray::ConstPtr jsk_perception::TabletopColorDifferenceLikelihood::latest_polygon_msg_ |
|
protected |
◆ mutex_
| boost::mutex jsk_perception::TabletopColorDifferenceLikelihood::mutex_ |
|
protected |
◆ pixel_max_value_
| int jsk_perception::TabletopColorDifferenceLikelihood::pixel_max_value_ |
|
protected |
◆ pixel_min_value_
| int jsk_perception::TabletopColorDifferenceLikelihood::pixel_min_value_ |
|
protected |
◆ pub_
| ros::Publisher jsk_perception::TabletopColorDifferenceLikelihood::pub_ |
|
protected |
◆ pub_debug_histogram_image_
| ros::Publisher jsk_perception::TabletopColorDifferenceLikelihood::pub_debug_histogram_image_ |
|
protected |
◆ pub_debug_polygon_
| ros::Publisher jsk_perception::TabletopColorDifferenceLikelihood::pub_debug_polygon_ |
|
protected |
◆ srv_
◆ sub_image_
◆ sub_info_
| ros::Subscriber jsk_perception::TabletopColorDifferenceLikelihood::sub_info_ |
|
protected |
◆ sub_polygons_
| ros::Subscriber jsk_perception::TabletopColorDifferenceLikelihood::sub_polygons_ |
|
protected |
◆ tf_filter_
◆ tf_listener_
◆ tf_queue_size_
| int jsk_perception::TabletopColorDifferenceLikelihood::tf_queue_size_ |
|
protected |
The documentation for this class was generated from the following files: