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

#include <morphological_operator.h>

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

Public Member Functions

 MorphologicalImageOperator (const std::string &name, const int &operation)
 
- Public Member Functions inherited from jsk_perception::MorphologicalImageOperatorNodelet
 MorphologicalImageOperatorNodelet (const std::string &name)
 

Protected Member Functions

virtual void apply (const cv::Mat &input, cv::Mat &output, const cv::Mat &element)
 
- Protected Member Functions inherited from jsk_perception::MorphologicalImageOperatorNodelet
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 operation_
 
- Protected Attributes inherited from jsk_perception::MorphologicalImageOperatorNodelet
int iterations_
 
int method_
 
boost::mutex mutex_
 
ros::Publisher pub_
 
int size_
 
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
 
ros::Subscriber sub_
 

Additional Inherited Members

- Public Types inherited from jsk_perception::MorphologicalImageOperatorNodelet
typedef jsk_perception::MorphologicalMaskImageOperatorConfig Config
 

Detailed Description

Definition at line 107 of file morphological_operator.h.

Constructor & Destructor Documentation

◆ MorphologicalImageOperator()

jsk_perception::MorphologicalImageOperator::MorphologicalImageOperator ( const std::string name,
const int &  operation 
)
inline

Definition at line 110 of file morphological_operator.h.

Member Function Documentation

◆ apply()

void jsk_perception::MorphologicalImageOperator::apply ( const cv::Mat &  input,
cv::Mat &  output,
const cv::Mat &  element 
)
protectedvirtual

Member Data Documentation

◆ operation_

int jsk_perception::MorphologicalImageOperator::operation_
protected

Definition at line 115 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 Fri May 16 2025 03:11:17