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 #include "jsk_perception/morphological_operator.h"
00038 #include <cv_bridge/cv_bridge.h>
00039 #include <opencv2/opencv.hpp>
00040 #include <sensor_msgs/image_encodings.h>
00041
00042 namespace jsk_perception
00043 {
00044
00045 void MorphologicalImageOperatorNodelet::onInit()
00046 {
00047 DiagnosticNodelet::onInit();
00048 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00049 dynamic_reconfigure::Server<Config>::CallbackType f =
00050 boost::bind (
00051 &MorphologicalImageOperatorNodelet::configCallback, this, _1, _2);
00052 srv_->setCallback (f);
00053
00054 pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
00055 }
00056
00057 void MorphologicalImageOperatorNodelet::subscribe()
00058 {
00059 sub_ = pnh_->subscribe(
00060 "input", 1, &MorphologicalImageOperatorNodelet::imageCallback, this);
00061 }
00062
00063 void MorphologicalImageOperatorNodelet::unsubscribe()
00064 {
00065 sub_.shutdown();
00066 }
00067
00068 void MorphologicalImageOperatorNodelet::configCallback(
00069 Config &config, uint32_t level)
00070 {
00071 boost::mutex::scoped_lock lock(mutex_);
00072 method_ = config.method;
00073 size_ = config.size;
00074 iterations_ = config.iterations;
00075 }
00076
00077 void MorphologicalImageOperatorNodelet::imageCallback(
00078 const sensor_msgs::Image::ConstPtr& image_msg)
00079 {
00080 boost::mutex::scoped_lock lock(mutex_);
00081 cv::Mat image = cv_bridge::toCvShare(image_msg, sensor_msgs::image_encodings::MONO8)->image;
00082 int type;
00083 if (method_ == 0) {
00084 type = cv::MORPH_RECT;
00085 }
00086 else if (method_ == 1) {
00087 type = cv::MORPH_CROSS;
00088 }
00089 else if (method_ == 2) {
00090 type = cv::MORPH_ELLIPSE;
00091 }
00092 cv::Mat output_image;
00093
00094 cv::Mat element = cv::getStructuringElement(
00095 type,
00096 cv::Size(2 * size_ + 1, 2 * size_+1),
00097 cv::Point(size_, size_));
00098 apply(image, output_image, element);
00099 pub_.publish(
00100 cv_bridge::CvImage(image_msg->header,
00101 sensor_msgs::image_encodings::MONO8,
00102 output_image).toImageMsg());
00103 }
00104
00105 void MorphologicalImageOperator::apply(
00106 const cv::Mat& input, cv::Mat& output, const cv::Mat& element)
00107 {
00108 cv::morphologyEx(input, output, operation_, element,
00109 cv::Point(-1,-1), iterations_);
00110 }
00111 }
00112
00113 #include <pluginlib/class_list_macros.h>
00114 PLUGINLIB_EXPORT_CLASS (jsk_perception::Dilate, nodelet::Nodelet);
00115 PLUGINLIB_EXPORT_CLASS (jsk_perception::Erode, nodelet::Nodelet);
00116 PLUGINLIB_EXPORT_CLASS (jsk_perception::Opening, nodelet::Nodelet);
00117 PLUGINLIB_EXPORT_CLASS (jsk_perception::Closing, nodelet::Nodelet);
00118 PLUGINLIB_EXPORT_CLASS (jsk_perception::MorphologicalGradient, nodelet::Nodelet);
00119 PLUGINLIB_EXPORT_CLASS (jsk_perception::TopHat, nodelet::Nodelet);
00120 PLUGINLIB_EXPORT_CLASS (jsk_perception::BlackHat, nodelet::Nodelet);