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