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/convex_hull_mask_image.h"
00037 #include <boost/assign.hpp>
00038 #include <boost/tuple/tuple.hpp>
00039 #include <jsk_topic_tools/log_utils.h>
00040 #include <jsk_recognition_utils/cv_utils.h>
00041 #include <opencv2/opencv.hpp>
00042 #include <sensor_msgs/image_encodings.h>
00043 #include <cv_bridge/cv_bridge.h>
00044
00045 namespace jsk_perception
00046 {
00047 void ConvexHullMaskImage::onInit()
00048 {
00049 DiagnosticNodelet::onInit();
00050 pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
00051 onInitPostProcess();
00052 }
00053
00054 void ConvexHullMaskImage::subscribe()
00055 {
00056 sub_ = pnh_->subscribe("input", 1, &ConvexHullMaskImage::rectify, this);
00057 ros::V_string names = boost::assign::list_of("~input");
00058 jsk_topic_tools::warnNoRemap(names);
00059 }
00060
00061 void ConvexHullMaskImage::unsubscribe()
00062 {
00063 sub_.shutdown();
00064 }
00065
00066 void ConvexHullMaskImage::rectify(
00067 const sensor_msgs::Image::ConstPtr& mask_msg)
00068 {
00069 vital_checker_->poke();
00070 cv_bridge::CvImagePtr cv_ptr = cv_bridge::toCvCopy(
00071 mask_msg, sensor_msgs::image_encodings::MONO8);
00072 cv::Mat mask = cv_ptr->image;
00073
00074 std::vector<std::vector<cv::Point> > contours;
00075 cv::findContours(mask, contours, CV_RETR_EXTERNAL, CV_CHAIN_APPROX_NONE);
00076
00077 boost::tuple<int, double> max_area;
00078 std::vector<std::vector<cv::Point> >hull(contours.size());
00079
00080 for (size_t i = 0; i < contours.size(); i++) {
00081
00082 double area = cv::contourArea(contours[i]);
00083 if (area > max_area.get<1>()) {
00084 max_area = boost::make_tuple<int, double>(i, area);
00085 }
00086 cv::convexHull(cv::Mat(contours[i]), hull[i], false);
00087 }
00088
00089 cv::Mat convex_hull_mask = cv::Mat::zeros(mask_msg->height, mask_msg->width, CV_8UC1);
00090 cv::drawContours(convex_hull_mask, hull, max_area.get<0>(), cv::Scalar(255), CV_FILLED);
00091
00092 pub_.publish(cv_bridge::CvImage(
00093 mask_msg->header,
00094 sensor_msgs::image_encodings::MONO8,
00095 convex_hull_mask).toImageMsg());
00096 }
00097
00098 }
00099
00100 #include <pluginlib/class_list_macros.h>
00101 PLUGINLIB_EXPORT_CLASS(jsk_perception::ConvexHullMaskImage, nodelet::Nodelet);