snake_segmentation.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
37 #include <boost/assign.hpp>
39 #include <opencv2/opencv.hpp>
40 #if CV_MAJOR_VERSION < 3
41 #include <opencv2/legacy/legacy.hpp>
42 #endif
43 #include <cv_bridge/cv_bridge.h>
45 
46 namespace jsk_perception
47 {
49  {
50  DiagnosticNodelet::onInit();
51  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
52  dynamic_reconfigure::Server<Config>::CallbackType f =
53  boost::bind (
54  &SnakeSegmentation::configCallback, this, _1, _2);
55  srv_->setCallback (f);
56 
57  pub_debug_ = advertise<sensor_msgs::Image>(*pnh_, "debug", 1);
59  }
60 
61  void SnakeSegmentation::configCallback (Config &config, uint32_t level)
62  {
63  boost::mutex::scoped_lock lock(mutex_);
64  alpha_ = config.alpha;
65  beta_ = config.beta;
66  gamma_ = config.gamma;
67  max_iterations_ = config.max_iterations;
68  epsilon_ = config.epsilon;
69  if (config.window_size % 2 == 1) {
70  window_size_ = config.window_size;
71  }
72  else {
73  config.window_size = window_size_;
74  }
75  }
76 
77 
78 
80  {
81  sub_ = pnh_->subscribe("input", 1, &SnakeSegmentation::segment, this);
82  ros::V_string names = boost::assign::list_of("~input");
84  }
85 
87  {
88  sub_.shutdown();
89  }
90 
92  const sensor_msgs::Image::ConstPtr& image_msg)
93  {
94 #if CV_MAJOR_VERSION >= 3
95  ROS_ERROR("cvSnakeImage is not supported in OpenCV3");
96 #else
97  vital_checker_->poke();
98  boost::mutex::scoped_lock lock(mutex_);
99  cv::Mat input = cv_bridge::toCvCopy(
100  image_msg, sensor_msgs::image_encodings::MONO8)->image;
101  // snake is only supported in legacy format
102  IplImage ipl_input = input;
103  float alpha = alpha_;
104  float beta = beta_;
105  float gamma = gamma_;
106  CvTermCriteria criteria;
107  criteria.type = CV_TERMCRIT_ITER;
108  criteria.max_iter = max_iterations_;
109  criteria.epsilon = epsilon_;
110  int coeffUsage = CV_VALUE;
111  CvSize win = cv::Size(window_size_, window_size_);
112  int calcGradient = 1;
113  std::vector<CvPoint> points;
114  // all the points on edge of border of image
115  const int resolution = 20;
116  for (size_t i = 0; i < resolution; i++) {
117  double r = (double)i/resolution;
118  points.push_back(cvPoint(0, r * image_msg->height));
119  }
120  for (size_t i = 0; i < resolution; i++) {
121  double r = (double)i/resolution;
122  points.push_back(cvPoint(image_msg->width * r, image_msg->height));
123  }
124  for (size_t i = 0; i < resolution; i++) {
125  double r = (double)i/resolution;
126  points.push_back(cvPoint(image_msg->width, image_msg->height * (1 - r)));
127  }
128  for (size_t i = 0; i < resolution; i++) {
129  double r = (double)i/resolution;
130  points.push_back(cvPoint(image_msg->width * (1 - r), 0));
131  }
132  cvSnakeImage(&ipl_input, &(points[0]), points.size(), &alpha, &beta, &gamma,
133  coeffUsage, win, criteria, calcGradient);
134  cv::Mat debug_image;
135  cv::cvtColor(input, debug_image, CV_GRAY2BGR);
136  for (int i = 1; i < points.size(); i++) {
137  cv::line(debug_image, points[i - 1], points[i], cv::Scalar(0, 100, 0), 2);
138  cv::circle(debug_image, points[i], 2, cv::Scalar(100, 0, 0), 1);
139  }
140 
142  image_msg->header,
144  debug_image).toImageMsg());
145 #endif
146  }
147 }
148 
f
void publish(const boost::shared_ptr< M > &message) const
virtual void segment(const sensor_msgs::Image::ConstPtr &image_msg)
input
std::vector< std::string > V_string
boost::shared_ptr< ros::NodeHandle > pnh_
bool warnNoRemap(const std::vector< std::string > names)
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
jsk_topic_tools::VitalChecker::Ptr vital_checker_
mutex_t * lock
PLUGINLIB_EXPORT_CLASS(jsk_perception::SnakeSegmentation, nodelet::Nodelet)
win
virtual void configCallback(Config &config, uint32_t level)
r
#define ROS_ERROR(...)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
sensor_msgs::ImagePtr toImageMsg() const


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Mon May 3 2021 03:03:27