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

#include <morphological_operator.h>

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

List of all members.

Public Types

typedef
jsk_perception::MorphologicalMaskImageOperatorConfig 
Config

Public Member Functions

 MorphologicalImageOperatorNodelet (const std::string &name)

Protected Member Functions

virtual void apply (const cv::Mat &input, cv::Mat &output, const cv::Mat &element)=0
virtual void configCallback (Config &config, uint32_t level)
virtual void imageCallback (const sensor_msgs::Image::ConstPtr &image_msg)
virtual void onInit ()
virtual void subscribe ()
virtual void unsubscribe ()

Protected Attributes

int iterations_
int method_
boost::mutex mutex_
ros::Publisher pub_
int size_
boost::shared_ptr
< dynamic_reconfigure::Server
< Config > > 
srv_
ros::Subscriber sub_

Detailed Description

Definition at line 49 of file morphological_operator.h.


Member Typedef Documentation

typedef jsk_perception::MorphologicalMaskImageOperatorConfig jsk_perception::MorphologicalImageOperatorNodelet::Config

Definition at line 53 of file morphological_operator.h.


Constructor & Destructor Documentation

Definition at line 54 of file morphological_operator.h.


Member Function Documentation

virtual void jsk_perception::MorphologicalImageOperatorNodelet::apply ( const cv::Mat &  input,
cv::Mat &  output,
const cv::Mat &  element 
) [protected, pure virtual]
void jsk_perception::MorphologicalImageOperatorNodelet::configCallback ( Config config,
uint32_t  level 
) [protected, virtual]

Definition at line 68 of file morphological_operator.cpp.

void jsk_perception::MorphologicalImageOperatorNodelet::imageCallback ( const sensor_msgs::Image::ConstPtr &  image_msg) [protected, virtual]

Definition at line 77 of file morphological_operator.cpp.

Reimplemented from jsk_topic_tools::DiagnosticNodelet.

Definition at line 45 of file morphological_operator.cpp.


Member Data Documentation

Definition at line 70 of file morphological_operator.h.

Definition at line 68 of file morphological_operator.h.

Definition at line 64 of file morphological_operator.h.

Definition at line 66 of file morphological_operator.h.

Definition at line 69 of file morphological_operator.h.

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

Definition at line 67 of file morphological_operator.h.

Definition at line 65 of file morphological_operator.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