Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef JSK_PERCEPTION_MORPHOLOGICAL_OPERATOR_H_
00038 #define JSK_PERCEPTION_MORPHOLOGICAL_OPERATOR_H_
00039
00040 #include <jsk_topic_tools/diagnostic_nodelet.h>
00041 #include <sensor_msgs/Image.h>
00042 #include <dynamic_reconfigure/server.h>
00043 #include <jsk_perception/MorphologicalMaskImageOperatorConfig.h>
00044 #include <opencv2/opencv.hpp>
00045
00046 namespace jsk_perception
00047 {
00048
00049 class MorphologicalImageOperatorNodelet:
00050 public jsk_topic_tools::DiagnosticNodelet
00051 {
00052 public:
00053 typedef jsk_perception::MorphologicalMaskImageOperatorConfig Config;
00054 MorphologicalImageOperatorNodelet(const std::string& name):
00055 DiagnosticNodelet(name) {}
00056 protected:
00057 virtual void onInit();
00058 virtual void subscribe();
00059 virtual void unsubscribe();
00060 virtual void configCallback(Config &config, uint32_t level);
00061 virtual void imageCallback(const sensor_msgs::Image::ConstPtr& image_msg);
00062 virtual void apply(const cv::Mat& input, cv::Mat& output, const cv::Mat& element) = 0;
00063
00064 boost::mutex mutex_;
00065 ros::Subscriber sub_;
00066 ros::Publisher pub_;
00067 boost::shared_ptr<dynamic_reconfigure::Server<Config> > srv_;
00068 int method_;
00069 int size_;
00070 int iterations_;
00071 private:
00072
00073 };
00074
00075 class MorphologicalImageOperator: public MorphologicalImageOperatorNodelet
00076 {
00077 public:
00078 MorphologicalImageOperator(const std::string& name, const int& operation):
00079 MorphologicalImageOperatorNodelet(name), operation_(operation) {}
00080 protected:
00081 virtual void apply(
00082 const cv::Mat& input, cv::Mat& output, const cv::Mat& element);
00083 int operation_;
00084 };
00085
00086 class Erode: public MorphologicalImageOperator
00087 {
00088 public:
00089 Erode(): MorphologicalImageOperator("Erode", cv::MORPH_ERODE) {}
00090 };
00091
00092 class Dilate: public MorphologicalImageOperator
00093 {
00094 public:
00095 Dilate(): MorphologicalImageOperator("Dilate", cv::MORPH_DILATE) {}
00096 };
00097
00098 class Opening: public MorphologicalImageOperator
00099 {
00100 public:
00101 Opening(): MorphologicalImageOperator("Opening", cv::MORPH_OPEN) {}
00102 };
00103
00104 class Closing: public MorphologicalImageOperator
00105 {
00106 public:
00107 Closing(): MorphologicalImageOperator("Closing", cv::MORPH_CLOSE) {}
00108 };
00109
00110 class MorphologicalGradient: public MorphologicalImageOperator
00111 {
00112 public:
00113 MorphologicalGradient():
00114 MorphologicalImageOperator("MorphologicalGradient", cv::MORPH_GRADIENT) {}
00115 };
00116
00117 class TopHat: public MorphologicalImageOperator
00118 {
00119 public:
00120 TopHat(): MorphologicalImageOperator("TopHat", cv::MORPH_TOPHAT) {}
00121 };
00122
00123 class BlackHat: public MorphologicalImageOperator
00124 {
00125 public:
00126 BlackHat(): MorphologicalImageOperator("BlackHat", cv::MORPH_BLACKHAT) {}
00127 };
00128 }
00129
00130 #endif