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 #include "jsk_perception/snake_segmentation.h"
00037 #include <boost/assign.hpp>
00038 #include <jsk_topic_tools/log_utils.h>
00039 #include <opencv2/opencv.hpp>
00040 #if CV_MAJOR_VERSION < 3
00041 #include <opencv2/legacy/legacy.hpp>
00042 #endif
00043 #include <cv_bridge/cv_bridge.h>
00044 #include <sensor_msgs/image_encodings.h>
00045
00046 namespace jsk_perception
00047 {
00048 void SnakeSegmentation::onInit()
00049 {
00050 DiagnosticNodelet::onInit();
00051 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00052 dynamic_reconfigure::Server<Config>::CallbackType f =
00053 boost::bind (
00054 &SnakeSegmentation::configCallback, this, _1, _2);
00055 srv_->setCallback (f);
00056
00057 pub_debug_ = advertise<sensor_msgs::Image>(*pnh_, "debug", 1);
00058 onInitPostProcess();
00059 }
00060
00061 void SnakeSegmentation::configCallback (Config &config, uint32_t level)
00062 {
00063 boost::mutex::scoped_lock lock(mutex_);
00064 alpha_ = config.alpha;
00065 beta_ = config.beta;
00066 gamma_ = config.gamma;
00067 max_iterations_ = config.max_iterations;
00068 epsilon_ = config.epsilon;
00069 if (config.window_size % 2 == 1) {
00070 window_size_ = config.window_size;
00071 }
00072 else {
00073 config.window_size = window_size_;
00074 }
00075 }
00076
00077
00078
00079 void SnakeSegmentation::subscribe()
00080 {
00081 sub_ = pnh_->subscribe("input", 1, &SnakeSegmentation::segment, this);
00082 ros::V_string names = boost::assign::list_of("~input");
00083 jsk_topic_tools::warnNoRemap(names);
00084 }
00085
00086 void SnakeSegmentation::unsubscribe()
00087 {
00088 sub_.shutdown();
00089 }
00090
00091 void SnakeSegmentation::segment(
00092 const sensor_msgs::Image::ConstPtr& image_msg)
00093 {
00094 #if CV_MAJOR_VERSION >= 3
00095 ROS_ERROR("cvSnakeImage is not supported in OpenCV3");
00096 #else
00097 vital_checker_->poke();
00098 boost::mutex::scoped_lock lock(mutex_);
00099 cv::Mat input = cv_bridge::toCvCopy(
00100 image_msg, sensor_msgs::image_encodings::MONO8)->image;
00101
00102 IplImage ipl_input = input;
00103 float alpha = alpha_;
00104 float beta = beta_;
00105 float gamma = gamma_;
00106 CvTermCriteria criteria;
00107 criteria.type = CV_TERMCRIT_ITER;
00108 criteria.max_iter = max_iterations_;
00109 criteria.epsilon = epsilon_;
00110 int coeffUsage = CV_VALUE;
00111 CvSize win = cv::Size(window_size_, window_size_);
00112 int calcGradient = 1;
00113 std::vector<CvPoint> points;
00114
00115 const int resolution = 20;
00116 for (size_t i = 0; i < resolution; i++) {
00117 double r = (double)i/resolution;
00118 points.push_back(cvPoint(0, r * image_msg->height));
00119 }
00120 for (size_t i = 0; i < resolution; i++) {
00121 double r = (double)i/resolution;
00122 points.push_back(cvPoint(image_msg->width * r, image_msg->height));
00123 }
00124 for (size_t i = 0; i < resolution; i++) {
00125 double r = (double)i/resolution;
00126 points.push_back(cvPoint(image_msg->width, image_msg->height * (1 - r)));
00127 }
00128 for (size_t i = 0; i < resolution; i++) {
00129 double r = (double)i/resolution;
00130 points.push_back(cvPoint(image_msg->width * (1 - r), 0));
00131 }
00132 cvSnakeImage(&ipl_input, &(points[0]), points.size(), &alpha, &beta, &gamma,
00133 coeffUsage, win, criteria, calcGradient);
00134 cv::Mat debug_image;
00135 cv::cvtColor(input, debug_image, CV_GRAY2BGR);
00136 for (int i = 1; i < points.size(); i++) {
00137 cv::line(debug_image, points[i - 1], points[i], cv::Scalar(0, 100, 0), 2);
00138 cv::circle(debug_image, points[i], 2, cv::Scalar(100, 0, 0), 1);
00139 }
00140
00141 pub_debug_.publish(cv_bridge::CvImage(
00142 image_msg->header,
00143 sensor_msgs::image_encodings::BGR8,
00144 debug_image).toImageMsg());
00145 #endif
00146 }
00147 }
00148
00149 #include <pluginlib/class_list_macros.h>
00150 PLUGINLIB_EXPORT_CLASS (jsk_perception::SnakeSegmentation, nodelet::Nodelet);