37 #include <boost/assign.hpp> 
   38 #include <boost/tuple/tuple.hpp> 
   39 #include <jsk_topic_tools/log_utils.h> 
   41 #include <opencv2/opencv.hpp> 
   44 #if ( CV_MAJOR_VERSION >= 4) 
   45 #include <opencv2/imgproc/imgproc_c.h> 
   52     DiagnosticNodelet::onInit();
 
   53     pub_ = advertise<sensor_msgs::Image>(*pnh_, 
"output", 1);
 
   61     jsk_topic_tools::warnNoRemap(names);
 
   70     const sensor_msgs::Image::ConstPtr& mask_msg)
 
   72     vital_checker_->poke();
 
   75     cv::Mat mask = cv_ptr->image;
 
   77     std::vector<std::vector<cv::Point> > contours;
 
   78     cv::findContours(mask, contours, CV_RETR_EXTERNAL, CV_CHAIN_APPROX_NONE);
 
   80     boost::tuple<int, double> max_area;
 
   81     std::vector<std::vector<cv::Point> >hull(contours.size());
 
   83     for (
size_t i = 0; 
i < contours.size(); 
i++) {
 
   85       double area = cv::contourArea(contours[
i]);
 
   86       if (
area > max_area.get<1>()) {
 
   87         max_area = boost::make_tuple<int, double>(
i, 
area);
 
   89       cv::convexHull(cv::Mat(contours[i]), hull[i], 
false);
 
   92     cv::Mat convex_hull_mask = cv::Mat::zeros(mask_msg->height, mask_msg->width, CV_8UC1);
 
   93     cv::drawContours(convex_hull_mask, hull, max_area.get<0>(), cv::Scalar(255), CV_FILLED);