snake_segmentation.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #include "jsk_perception/snake_segmentation.h"
00037 #include <opencv2/opencv.hpp>
00038 #if CV_MAJOR_VERSION < 3
00039 #include <opencv2/legacy/legacy.hpp>
00040 #endif
00041 #include <cv_bridge/cv_bridge.h>
00042 #include <sensor_msgs/image_encodings.h>
00043 
00044 namespace jsk_perception
00045 {
00046   void SnakeSegmentation::onInit()
00047   {
00048     DiagnosticNodelet::onInit();
00049     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00050     dynamic_reconfigure::Server<Config>::CallbackType f =
00051       boost::bind (
00052         &SnakeSegmentation::configCallback, this, _1, _2);
00053     srv_->setCallback (f);
00054 
00055     pub_debug_ = advertise<sensor_msgs::Image>(*pnh_, "debug", 1);
00056   }
00057 
00058   void SnakeSegmentation::configCallback (Config &config, uint32_t level)
00059   {
00060     boost::mutex::scoped_lock lock(mutex_);
00061     alpha_ = config.alpha;
00062     beta_ = config.beta;
00063     gamma_ = config.gamma;
00064     max_iterations_ = config.max_iterations;
00065     epsilon_ = config.epsilon;
00066     if (config.window_size % 2 == 1) {
00067       window_size_ = config.window_size;
00068     }
00069     else {
00070       config.window_size = window_size_;
00071     }
00072   }
00073 
00074 
00075   
00076   void SnakeSegmentation::subscribe()
00077   {
00078     sub_ = pnh_->subscribe("input", 1, &SnakeSegmentation::segment, this);
00079   }
00080 
00081   void SnakeSegmentation::unsubscribe()
00082   {
00083     sub_.shutdown();
00084   }
00085 
00086   void SnakeSegmentation::segment(
00087     const sensor_msgs::Image::ConstPtr& image_msg)
00088   {
00089 #if CV_MAJOR_VERSION >= 3
00090     JSK_ROS_ERROR("cvSnakeImage is not supported in OpenCV3");
00091 #else
00092     vital_checker_->poke();
00093     boost::mutex::scoped_lock lock(mutex_);
00094     cv::Mat input = cv_bridge::toCvCopy(
00095       image_msg, sensor_msgs::image_encodings::MONO8)->image;
00096     // snake is only supported in legacy format
00097     IplImage ipl_input = input;
00098     float alpha = alpha_;
00099     float beta = beta_;
00100     float gamma = gamma_;
00101     CvTermCriteria criteria;
00102     criteria.type = CV_TERMCRIT_ITER;
00103     criteria.max_iter = max_iterations_;
00104     criteria.epsilon = epsilon_;
00105     int coeffUsage = CV_VALUE;
00106     CvSize win = cv::Size(window_size_, window_size_);
00107     int calcGradient = 1;
00108     std::vector<CvPoint> points;
00109     // all the points on  edge of  border of image
00110     const int resolution = 20;
00111     for (size_t i = 0; i < resolution; i++) {
00112       double r = (double)i/resolution;
00113       points.push_back(cvPoint(0, r * image_msg->height));
00114     }
00115     for (size_t i = 0; i < resolution; i++) {
00116       double r = (double)i/resolution;
00117       points.push_back(cvPoint(image_msg->width * r, image_msg->height));
00118     }
00119     for (size_t i = 0; i < resolution; i++) {
00120       double r = (double)i/resolution;
00121       points.push_back(cvPoint(image_msg->width, image_msg->height * (1 - r)));
00122     }
00123     for (size_t i = 0; i < resolution; i++) {
00124       double r = (double)i/resolution;
00125       points.push_back(cvPoint(image_msg->width * (1 - r), 0));
00126     }
00127     cvSnakeImage(&ipl_input, &(points[0]), points.size(), &alpha, &beta, &gamma,
00128                  coeffUsage, win, criteria, calcGradient);
00129     cv::Mat debug_image;
00130     cv::cvtColor(input, debug_image, CV_GRAY2BGR);
00131     for (int i = 1; i < points.size(); i++) {
00132       cv::line(debug_image, points[i - 1], points[i], cv::Scalar(0, 100, 0), 2);
00133       cv::circle(debug_image, points[i], 2, cv::Scalar(100, 0, 0), 1);
00134     }
00135 
00136     pub_debug_.publish(cv_bridge::CvImage(
00137                          image_msg->header,
00138                          sensor_msgs::image_encodings::BGR8,
00139                          debug_image).toImageMsg());
00140 #endif
00141   }
00142 }
00143 
00144 #include <pluginlib/class_list_macros.h>
00145 PLUGINLIB_EXPORT_CLASS (jsk_perception::SnakeSegmentation, nodelet::Nodelet);


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Wed Sep 16 2015 04:36:15