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/contour_finder.h"
00037 #include <boost/assign.hpp>
00038 #include <jsk_topic_tools/log_utils.h>
00039 #include <cv_bridge/cv_bridge.h>
00040 #include <sensor_msgs/image_encodings.h>
00041 #include <opencv2/opencv.hpp>
00042
00043
00044 namespace jsk_perception
00045 {
00046 void ContourFinder::onInit()
00047 {
00048 DiagnosticNodelet::onInit();
00049 pub_debug_image_ = advertise<sensor_msgs::Image>(*pnh_, "debug", 1);
00050 pub_convex_image_ = advertise<sensor_msgs::Image>(*pnh_, "output/convex", 1);
00051 onInitPostProcess();
00052 }
00053
00054 void ContourFinder::subscribe()
00055 {
00056 sub_ = pnh_->subscribe("input", 1, &ContourFinder::segment, this);
00057 ros::V_string names = boost::assign::list_of("~input");
00058 jsk_topic_tools::warnNoRemap(names);
00059 }
00060
00061 void ContourFinder::unsubscribe()
00062 {
00063 sub_.shutdown();
00064 }
00065
00066 void ContourFinder::segment(
00067 const sensor_msgs::Image::ConstPtr& image_msg)
00068 {
00069 std::vector<std::vector<cv::Point> > contours;
00070 std::vector<std::vector<cv::Point> > convex_contours(1);
00071 std::vector<cv::Vec4i> hierarchy;
00072 cv::RNG rng(12345);
00073 cv::Mat input = cv_bridge::toCvCopy(
00074 image_msg, sensor_msgs::image_encodings::MONO8)->image;
00075 cv::findContours(input, contours, hierarchy, CV_RETR_EXTERNAL, CV_CHAIN_APPROX_SIMPLE, cv::Point(0, 0));
00076 cv::Mat drawing = cv::Mat::zeros(input.size(), CV_8UC3);
00077 for( int i = 0; i< contours.size(); i++ )
00078 {
00079 cv::Scalar color = cv::Scalar( rng.uniform(0, 255), rng.uniform(0,255), rng.uniform(0,255) );
00080 cv::drawContours(drawing, contours, i, color, CV_FILLED, 8, hierarchy, 0, cv::Point());
00081 }
00082 pub_debug_image_.publish(cv_bridge::CvImage(
00083 image_msg->header,
00084 sensor_msgs::image_encodings::BGR8,
00085 drawing).toImageMsg());
00086
00087 std::vector<cv::Point> all_contours;
00088 for (size_t i = 0; i < contours.size(); i++) {
00089 for (size_t j = 0; j < contours[i].size(); j++) {
00090 all_contours.push_back(contours[i][j]);
00091 }
00092 }
00093
00094 cv::convexHull(cv::Mat(all_contours), convex_contours[0]);
00095 cv::Mat convex_image = cv::Mat::zeros(input.size(), CV_8UC1);
00096 cv::drawContours(convex_image, convex_contours, 0, cv::Scalar(255), CV_FILLED);
00097 pub_convex_image_.publish(
00098 cv_bridge::CvImage(
00099 image_msg->header,
00100 sensor_msgs::image_encodings::MONO8,
00101 convex_image).toImageMsg());
00102 }
00103 }
00104
00105 #include <pluginlib/class_list_macros.h>
00106 PLUGINLIB_EXPORT_CLASS (jsk_perception::ContourFinder, nodelet::Nodelet);
00107