37 #include <boost/assign.hpp> 
   38 #include <jsk_topic_tools/log_utils.h> 
   39 #include <opencv2/opencv.hpp> 
   40 #if CV_MAJOR_VERSION < 3 
   41 #include <opencv2/legacy/legacy.hpp> 
   50     DiagnosticNodelet::onInit();
 
   51     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
 
   52     dynamic_reconfigure::Server<Config>::CallbackType 
f =
 
   55     srv_->setCallback (f);
 
   57     pub_debug_ = advertise<sensor_msgs::Image>(*pnh_, 
"debug", 1);
 
   69     if (
config.window_size % 2 == 1) {
 
   83     jsk_topic_tools::warnNoRemap(names);
 
   92     const sensor_msgs::Image::ConstPtr& image_msg)
 
   94 #if CV_MAJOR_VERSION >= 3 
   95     ROS_ERROR(
"cvSnakeImage is not supported in OpenCV3");
 
   97     vital_checker_->poke();
 
  102     IplImage ipl_input = 
input;
 
  106     CvTermCriteria criteria;
 
  107     criteria.type = CV_TERMCRIT_ITER;
 
  110     int coeffUsage = CV_VALUE;
 
  112     int calcGradient = 1;
 
  113     std::vector<CvPoint> points;
 
  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));
 
  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));
 
  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)));
 
  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));
 
  132     cvSnakeImage(&ipl_input, &(points[0]), points.size(), &alpha, &beta, &gamma,
 
  133                  coeffUsage, win, criteria, calcGradient);
 
  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);