Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
jsk_perception::SingleChannelHistogram Class Reference

#include <single_channel_histogram.h>

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

List of all members.

Public Types

typedef
SingleChannelHistogramConfig 
Config
typedef
message_filters::sync_policies::ApproximateTime
< sensor_msgs::Image,
sensor_msgs::Image > 
SyncPolicy

Public Member Functions

 SingleChannelHistogram ()

Protected Member Functions

virtual void compute (const sensor_msgs::Image::ConstPtr &msg)
virtual void compute (const sensor_msgs::Image::ConstPtr &msg, const sensor_msgs::Image::ConstPtr &mask_msg)
virtual void configCallback (Config &config, uint32_t level)
virtual void onInit ()
virtual void subscribe ()
virtual void unsubscribe ()

Protected Attributes

int hist_size_
float max_value_
float min_value_
boost::mutex mutex_
ros::Publisher pub_
boost::shared_ptr
< dynamic_reconfigure::Server
< Config > > 
srv_
ros::Subscriber sub_
message_filters::Subscriber
< sensor_msgs::Image > 
sub_image_
message_filters::Subscriber
< sensor_msgs::Image > 
sub_mask_
boost::shared_ptr
< message_filters::Synchronizer
< SyncPolicy > > 
sync_
bool use_mask_

Detailed Description

Definition at line 54 of file single_channel_histogram.h.


Member Typedef Documentation

typedef SingleChannelHistogramConfig jsk_perception::SingleChannelHistogram::Config

Definition at line 60 of file single_channel_histogram.h.

Definition at line 59 of file single_channel_histogram.h.


Constructor & Destructor Documentation

Definition at line 61 of file single_channel_histogram.h.


Member Function Documentation

void jsk_perception::SingleChannelHistogram::compute ( const sensor_msgs::Image::ConstPtr &  msg) [protected, virtual]

Definition at line 109 of file single_channel_histogram.cpp.

void jsk_perception::SingleChannelHistogram::compute ( const sensor_msgs::Image::ConstPtr &  msg,
const sensor_msgs::Image::ConstPtr &  mask_msg 
) [protected, virtual]

Definition at line 84 of file single_channel_histogram.cpp.

void jsk_perception::SingleChannelHistogram::configCallback ( Config config,
uint32_t  level 
) [protected, virtual]

Definition at line 115 of file single_channel_histogram.cpp.

void jsk_perception::SingleChannelHistogram::onInit ( ) [protected, virtual]

Reimplemented from jsk_topic_tools::DiagnosticNodelet.

Definition at line 42 of file single_channel_histogram.cpp.


Member Data Documentation

Definition at line 81 of file single_channel_histogram.h.

Definition at line 83 of file single_channel_histogram.h.

Definition at line 82 of file single_channel_histogram.h.

Definition at line 80 of file single_channel_histogram.h.

Definition at line 79 of file single_channel_histogram.h.

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_perception::SingleChannelHistogram::srv_ [protected]

Definition at line 76 of file single_channel_histogram.h.

Definition at line 78 of file single_channel_histogram.h.

Definition at line 74 of file single_channel_histogram.h.

Definition at line 75 of file single_channel_histogram.h.

Definition at line 73 of file single_channel_histogram.h.

Definition at line 77 of file single_channel_histogram.h.


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


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Wed Sep 16 2015 04:36:16