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
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/FindContoursConfig.h"
00054 #include "opencv_apps/Contour.h"
00055 #include "opencv_apps/ContourArray.h"
00056 #include "opencv_apps/ContourArrayStamped.h"
00057
00058 namespace opencv_apps
00059 {
00060 class FindContoursNodelet : 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 msg_pub_;
00066
00067 boost::shared_ptr<image_transport::ImageTransport> it_;
00068
00069 typedef opencv_apps::FindContoursConfig 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 low_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 low_threshold_ = config_.canny_low_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 , void* )
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
00114 try
00115 {
00116
00117 cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
00118
00119
00120 opencv_apps::ContourArrayStamped contours_msg;
00121 contours_msg.header = msg->header;
00122
00123
00124 cv::Mat src_gray;
00125
00127 if (frame.channels() > 1)
00128 {
00129 cv::cvtColor(frame, src_gray, cv::COLOR_RGB2GRAY);
00130 }
00131 else
00132 {
00133 src_gray = frame;
00134 }
00135 cv::GaussianBlur(src_gray, src_gray, cv::Size(3, 3), 0, 0, cv::BORDER_DEFAULT);
00136
00138 if (debug_view_)
00139 {
00140 cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
00141 }
00142
00143 cv::Mat canny_output;
00144 int max_thresh = 255;
00145 std::vector<std::vector<cv::Point> > contours;
00146 std::vector<cv::Vec4i> hierarchy;
00147 cv::RNG rng(12345);
00148
00150 cv::blur(src_gray, canny_output, cv::Size(3, 3));
00151
00153 cv::Canny(canny_output, canny_output, low_threshold_, low_threshold_ * 2, 3);
00154
00156 cv::findContours(canny_output, contours, hierarchy, CV_RETR_TREE, CV_CHAIN_APPROX_SIMPLE, cv::Point(0, 0));
00157
00159 cv::Mat drawing = cv::Mat::zeros(canny_output.size(), CV_8UC3);
00160 for (size_t i = 0; i < contours.size(); i++)
00161 {
00162 cv::Scalar color = cv::Scalar(rng.uniform(0, 255), rng.uniform(0, 255), rng.uniform(0, 255));
00163 cv::drawContours(drawing, contours, (int)i, color, 2, 8, hierarchy, 0, cv::Point());
00164
00165 opencv_apps::Contour contour_msg;
00166 for (const cv::Point& j : contours[i])
00167 {
00168 opencv_apps::Point2D point_msg;
00169 point_msg.x = j.x;
00170 point_msg.y = j.y;
00171 contour_msg.points.push_back(point_msg);
00172 }
00173 contours_msg.contours.push_back(contour_msg);
00174 }
00175
00177 if (debug_view_)
00178 {
00179 if (need_config_update_)
00180 {
00181 config_.canny_low_threshold = low_threshold_;
00182 reconfigure_server_->updateConfig(config_);
00183 need_config_update_ = false;
00184 }
00185 cv::createTrackbar("Canny thresh:", window_name_, &low_threshold_, max_thresh, trackbarCallback);
00186
00187 cv::imshow(window_name_, drawing);
00188 int c = cv::waitKey(1);
00189 }
00190
00191
00192 sensor_msgs::Image::Ptr out_img =
00193 cv_bridge::CvImage(msg->header, sensor_msgs::image_encodings::BGR8, drawing).toImageMsg();
00194 img_pub_.publish(out_img);
00195 msg_pub_.publish(contours_msg);
00196 }
00197 catch (cv::Exception& e)
00198 {
00199 NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00200 }
00201
00202 prev_stamp_ = msg->header.stamp;
00203 }
00204
00205 void subscribe()
00206 {
00207 NODELET_DEBUG("Subscribing to image topic.");
00208 if (config_.use_camera_info)
00209 cam_sub_ = it_->subscribeCamera("image", queue_size_, &FindContoursNodelet::imageCallbackWithInfo, this);
00210 else
00211 img_sub_ = it_->subscribe("image", queue_size_, &FindContoursNodelet::imageCallback, this);
00212 }
00213
00214 void unsubscribe()
00215 {
00216 NODELET_DEBUG("Unsubscribing from image topic.");
00217 img_sub_.shutdown();
00218 cam_sub_.shutdown();
00219 }
00220
00221 public:
00222 virtual void onInit()
00223 {
00224 Nodelet::onInit();
00225 it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00226
00227 pnh_->param("queue_size", queue_size_, 3);
00228 pnh_->param("debug_view", debug_view_, false);
00229 if (debug_view_)
00230 {
00231 always_subscribe_ = true;
00232 }
00233 prev_stamp_ = ros::Time(0, 0);
00234
00235 window_name_ = "Demo code to find contours in an image";
00236 low_threshold_ = 100;
00237
00238 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00239 dynamic_reconfigure::Server<Config>::CallbackType f =
00240 boost::bind(&FindContoursNodelet::reconfigureCallback, this, _1, _2);
00241 reconfigure_server_->setCallback(f);
00242
00243 img_pub_ = advertiseImage(*pnh_, "image", 1);
00244 msg_pub_ = advertise<opencv_apps::ContourArrayStamped>(*pnh_, "contours", 1);
00245
00246 onInitPostProcess();
00247 }
00248 };
00249 bool FindContoursNodelet::need_config_update_ = false;
00250 }
00251
00252 namespace find_contours
00253 {
00254 class FindContoursNodelet : public opencv_apps::FindContoursNodelet
00255 {
00256 public:
00257 virtual void onInit()
00258 {
00259 ROS_WARN("DeprecationWarning: Nodelet find_contours/find_contours is deprecated, "
00260 "and renamed to opencv_apps/find_contours.");
00261 opencv_apps::FindContoursNodelet::onInit();
00262 }
00263 };
00264 }
00265
00266 #include <pluginlib/class_list_macros.h>
00267 PLUGINLIB_EXPORT_CLASS(opencv_apps::FindContoursNodelet, nodelet::Nodelet);
00268 PLUGINLIB_EXPORT_CLASS(find_contours::FindContoursNodelet, nodelet::Nodelet);