general_contours_nodelet.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2014, Kei Okada.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Kei Okada nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 // https://github.com/Itseez/opencv/blob/2.4/samples/cpp/tutorial_code/ShapeDescriptors/generalContours_demo2.cpp
00042 #include <ros/ros.h>
00043 #include "opencv_apps/nodelet.h"
00044 #include <image_transport/image_transport.h>
00045 #include <sensor_msgs/image_encodings.h>
00046 #include <cv_bridge/cv_bridge.h>
00047 #include <sensor_msgs/image_encodings.h>
00048 
00049 #include <opencv2/highgui/highgui.hpp>
00050 #include <opencv2/imgproc/imgproc.hpp>
00051 
00052 #include <dynamic_reconfigure/server.h>
00053 #include "opencv_apps/GeneralContoursConfig.h"
00054 #include "opencv_apps/RotatedRect.h"
00055 #include "opencv_apps/RotatedRectArray.h"
00056 #include "opencv_apps/RotatedRectArrayStamped.h"
00057 
00058 namespace opencv_apps
00059 {
00060 class GeneralContoursNodelet : public opencv_apps::Nodelet
00061 {
00062   image_transport::Publisher img_pub_;
00063   image_transport::Subscriber img_sub_;
00064   image_transport::CameraSubscriber cam_sub_;
00065   ros::Publisher rects_pub_, ellipses_pub_;
00066 
00067   boost::shared_ptr<image_transport::ImageTransport> it_;
00068 
00069   typedef opencv_apps::GeneralContoursConfig Config;
00070   typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00071   Config config_;
00072   boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00073 
00074   int queue_size_;
00075   bool debug_view_;
00076   ros::Time prev_stamp_;
00077 
00078   int threshold_;
00079 
00080   std::string window_name_;
00081   static bool need_config_update_;
00082 
00083   void reconfigureCallback(Config& new_config, uint32_t level)
00084   {
00085     config_ = new_config;
00086     threshold_ = config_.threshold;
00087   }
00088 
00089   const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame)
00090   {
00091     if (frame.empty())
00092       return image_frame;
00093     return frame;
00094   }
00095 
00096   void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00097   {
00098     doWork(msg, cam_info->header.frame_id);
00099   }
00100 
00101   void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00102   {
00103     doWork(msg, msg->header.frame_id);
00104   }
00105 
00106   static void trackbarCallback(int /*unused*/, void* /*unused*/)
00107   {
00108     need_config_update_ = true;
00109   }
00110 
00111   void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg)
00112   {
00113     // Work on the image.
00114     try
00115     {
00116       // Convert the image into something opencv can handle.
00117       cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
00118 
00119       // Messages
00120       opencv_apps::RotatedRectArrayStamped rects_msg, ellipses_msg;
00121       rects_msg.header = msg->header;
00122       ellipses_msg.header = msg->header;
00123 
00124       // Do the work
00125       cv::Mat src_gray;
00126 
00128       if (frame.channels() > 1)
00129       {
00130         cv::cvtColor(frame, src_gray, cv::COLOR_RGB2GRAY);
00131       }
00132       else
00133       {
00134         src_gray = frame;
00135       }
00136       cv::blur(src_gray, src_gray, cv::Size(3, 3));
00137 
00139       if (debug_view_)
00140       {
00141         cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
00142       }
00143 
00144       cv::Mat threshold_output;
00145       int max_thresh = 255;
00146       std::vector<std::vector<cv::Point> > contours;
00147       std::vector<cv::Vec4i> hierarchy;
00148       cv::RNG rng(12345);
00149 
00151       cv::threshold(src_gray, threshold_output, threshold_, 255, cv::THRESH_BINARY);
00152 
00154       cv::findContours(threshold_output, contours, hierarchy, CV_RETR_TREE, CV_CHAIN_APPROX_SIMPLE, cv::Point(0, 0));
00155 
00157       std::vector<cv::RotatedRect> min_rect(contours.size());
00158       std::vector<cv::RotatedRect> min_ellipse(contours.size());
00159 
00160       for (size_t i = 0; i < contours.size(); i++)
00161       {
00162         min_rect[i] = cv::minAreaRect(cv::Mat(contours[i]));
00163         if (contours[i].size() > 5)
00164         {
00165           min_ellipse[i] = cv::fitEllipse(cv::Mat(contours[i]));
00166         }
00167       }
00168 
00170       cv::Mat drawing = cv::Mat::zeros(threshold_output.size(), CV_8UC3);
00171       for (size_t i = 0; i < contours.size(); i++)
00172       {
00173         cv::Scalar color = cv::Scalar(rng.uniform(0, 255), rng.uniform(0, 255), rng.uniform(0, 255));
00174         // contour
00175         cv::drawContours(drawing, contours, (int)i, color, 1, 8, std::vector<cv::Vec4i>(), 0, cv::Point());
00176         // ellipse
00177         cv::ellipse(drawing, min_ellipse[i], color, 2, 8);
00178         // rotated rectangle
00179         cv::Point2f rect_points[4];
00180         min_rect[i].points(rect_points);
00181         for (int j = 0; j < 4; j++)
00182           cv::line(drawing, rect_points[j], rect_points[(j + 1) % 4], color, 1, 8);
00183 
00184         opencv_apps::RotatedRect rect_msg;
00185         opencv_apps::Point2D rect_center;
00186         opencv_apps::Size rect_size;
00187         rect_center.x = min_rect[i].center.x;
00188         rect_center.y = min_rect[i].center.y;
00189         rect_size.width = min_rect[i].size.width;
00190         rect_size.height = min_rect[i].size.height;
00191         rect_msg.center = rect_center;
00192         rect_msg.size = rect_size;
00193         rect_msg.angle = min_rect[i].angle;
00194         opencv_apps::RotatedRect ellipse_msg;
00195         opencv_apps::Point2D ellipse_center;
00196         opencv_apps::Size ellipse_size;
00197         ellipse_center.x = min_ellipse[i].center.x;
00198         ellipse_center.y = min_ellipse[i].center.y;
00199         ellipse_size.width = min_ellipse[i].size.width;
00200         ellipse_size.height = min_ellipse[i].size.height;
00201         ellipse_msg.center = ellipse_center;
00202         ellipse_msg.size = ellipse_size;
00203         ellipse_msg.angle = min_ellipse[i].angle;
00204 
00205         rects_msg.rects.push_back(rect_msg);
00206         ellipses_msg.rects.push_back(ellipse_msg);
00207       }
00208 
00210       if (debug_view_)
00211       {
00212         if (need_config_update_)
00213         {
00214           config_.threshold = threshold_;
00215           reconfigure_server_->updateConfig(config_);
00216           need_config_update_ = false;
00217         }
00218         cv::createTrackbar("Threshold:", window_name_, &threshold_, max_thresh, trackbarCallback);
00219 
00220         cv::imshow(window_name_, drawing);
00221         int c = cv::waitKey(1);
00222       }
00223 
00224       // Publish the image.
00225       sensor_msgs::Image::Ptr out_img =
00226           cv_bridge::CvImage(msg->header, sensor_msgs::image_encodings::BGR8, drawing).toImageMsg();
00227       img_pub_.publish(out_img);
00228       rects_pub_.publish(rects_msg);
00229       ellipses_pub_.publish(ellipses_msg);
00230     }
00231     catch (cv::Exception& e)
00232     {
00233       NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00234     }
00235 
00236     prev_stamp_ = msg->header.stamp;
00237   }
00238 
00239   void subscribe()  // NOLINT(modernize-use-override)
00240   {
00241     NODELET_DEBUG("Subscribing to image topic.");
00242     if (config_.use_camera_info)
00243       cam_sub_ = it_->subscribeCamera("image", queue_size_, &GeneralContoursNodelet::imageCallbackWithInfo, this);
00244     else
00245       img_sub_ = it_->subscribe("image", queue_size_, &GeneralContoursNodelet::imageCallback, this);
00246   }
00247 
00248   void unsubscribe()  // NOLINT(modernize-use-override)
00249   {
00250     NODELET_DEBUG("Unsubscribing from image topic.");
00251     img_sub_.shutdown();
00252     cam_sub_.shutdown();
00253   }
00254 
00255 public:
00256   virtual void onInit()  // NOLINT(modernize-use-override)
00257   {
00258     Nodelet::onInit();
00259     it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00260 
00261     pnh_->param("queue_size", queue_size_, 3);
00262     pnh_->param("debug_view", debug_view_, false);
00263     if (debug_view_)
00264     {
00265       always_subscribe_ = true;
00266     }
00267     prev_stamp_ = ros::Time(0, 0);
00268 
00269     window_name_ = "Contours";
00270     threshold_ = 100;
00271 
00272     reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00273     dynamic_reconfigure::Server<Config>::CallbackType f =
00274         boost::bind(&GeneralContoursNodelet::reconfigureCallback, this, _1, _2);
00275     reconfigure_server_->setCallback(f);
00276 
00277     img_pub_ = advertiseImage(*pnh_, "image", 1);
00278     rects_pub_ = advertise<opencv_apps::RotatedRectArrayStamped>(*pnh_, "rectangles", 1);
00279     ellipses_pub_ = advertise<opencv_apps::RotatedRectArrayStamped>(*pnh_, "ellipses", 1);
00280 
00281     onInitPostProcess();
00282   }
00283 };
00284 bool GeneralContoursNodelet::need_config_update_ = false;
00285 }  // namespace opencv_apps
00286 
00287 namespace general_contours
00288 {
00289 class GeneralContoursNodelet : public opencv_apps::GeneralContoursNodelet
00290 {
00291 public:
00292   virtual void onInit()  // NOLINT(modernize-use-override)
00293   {
00294     ROS_WARN("DeprecationWarning: Nodelet general_contours/general_contours is deprecated, "
00295              "and renamed to opencv_apps/general_contours.");
00296     opencv_apps::GeneralContoursNodelet::onInit();
00297   }
00298 };
00299 }  // namespace general_contours
00300 
00301 #include <pluginlib/class_list_macros.h>
00302 PLUGINLIB_EXPORT_CLASS(opencv_apps::GeneralContoursNodelet, nodelet::Nodelet);
00303 PLUGINLIB_EXPORT_CLASS(general_contours::GeneralContoursNodelet, nodelet::Nodelet);


opencv_apps
Author(s): Kei Okada
autogenerated on Mon Apr 22 2019 02:18:26