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 find_contours {
00059 class FindContoursNodelet : public opencv_apps::Nodelet
00060 {
00061 image_transport::Publisher img_pub_;
00062 image_transport::Subscriber img_sub_;
00063 image_transport::CameraSubscriber cam_sub_;
00064 ros::Publisher msg_pub_;
00065
00066 boost::shared_ptr<image_transport::ImageTransport> it_;
00067
00068 typedef find_contours::FindContoursConfig Config;
00069 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00070 Config config_;
00071 boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00072
00073 bool debug_view_;
00074 ros::Time prev_stamp_;
00075
00076 int low_threshold_;
00077
00078 std::string window_name_;
00079 static bool need_config_update_;
00080
00081 void reconfigureCallback(Config &new_config, uint32_t level)
00082 {
00083 config_ = new_config;
00084 low_threshold_ = config_.canny_low_threshold;
00085 }
00086
00087 const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
00088 {
00089 if (frame.empty())
00090 return image_frame;
00091 return frame;
00092 }
00093
00094 void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00095 {
00096 do_work(msg, cam_info->header.frame_id);
00097 }
00098
00099 void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00100 {
00101 do_work(msg, msg->header.frame_id);
00102 }
00103
00104 static void trackbarCallback( int, void* )
00105 {
00106 need_config_update_ = true;
00107 }
00108
00109 void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg)
00110 {
00111
00112 try
00113 {
00114
00115 cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
00116
00117
00118 opencv_apps::ContourArrayStamped contours_msg;
00119 contours_msg.header = msg->header;
00120
00121
00122 cv::Mat src_gray;
00123
00125 if ( frame.channels() > 1 ) {
00126 cv::cvtColor( frame, src_gray, cv::COLOR_RGB2GRAY );
00127 } else {
00128 src_gray = frame;
00129 }
00130 cv::GaussianBlur( src_gray, src_gray, cv::Size(3,3), 0, 0, cv::BORDER_DEFAULT );
00131
00133 if( debug_view_) {
00134 cv::namedWindow( window_name_, cv::WINDOW_AUTOSIZE );
00135 }
00136
00137 cv::Mat canny_output;
00138 int max_thresh = 255;
00139 std::vector<std::vector<cv::Point> > contours;
00140 std::vector<cv::Vec4i> hierarchy;
00141 cv::RNG rng(12345);
00142
00144 cv::blur( src_gray, canny_output, cv::Size(3,3) );
00145
00147 cv::Canny( canny_output, canny_output, low_threshold_, low_threshold_*2, 3 );
00148
00150 cv::findContours( canny_output, contours, hierarchy, CV_RETR_TREE, CV_CHAIN_APPROX_SIMPLE, cv::Point(0, 0) );
00151
00153 cv::Mat drawing = cv::Mat::zeros( canny_output.size(), CV_8UC3 );
00154 for( size_t i = 0; i< contours.size(); i++ )
00155 {
00156 cv::Scalar color = cv::Scalar( rng.uniform(0, 255), rng.uniform(0,255), rng.uniform(0,255) );
00157 cv::drawContours( drawing, contours, (int)i, color, 2, 8, hierarchy, 0, cv::Point() );
00158
00159 opencv_apps::Contour contour_msg;
00160 for ( size_t j = 0; j < contours[i].size(); j++ ) {
00161 opencv_apps::Point2D point_msg;
00162 point_msg.x = contours[i][j].x;
00163 point_msg.y = contours[i][j].y;
00164 contour_msg.points.push_back(point_msg);
00165 }
00166 contours_msg.contours.push_back(contour_msg);
00167 }
00168
00170 if( debug_view_) {
00171 if (need_config_update_) {
00172 config_.canny_low_threshold = low_threshold_;
00173 reconfigure_server_->updateConfig(config_);
00174 need_config_update_ = false;
00175 }
00176 cv::createTrackbar( "Canny thresh:", window_name_, &low_threshold_, max_thresh, trackbarCallback);
00177
00178 cv::imshow( window_name_, drawing );
00179 int c = cv::waitKey(1);
00180 }
00181
00182
00183 sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, sensor_msgs::image_encodings::BGR8, drawing).toImageMsg();
00184 img_pub_.publish(out_img);
00185 msg_pub_.publish(contours_msg);
00186 }
00187 catch (cv::Exception &e)
00188 {
00189 NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00190 }
00191
00192 prev_stamp_ = msg->header.stamp;
00193 }
00194
00195 void subscribe()
00196 {
00197 NODELET_DEBUG("Subscribing to image topic.");
00198 if (config_.use_camera_info)
00199 cam_sub_ = it_->subscribeCamera("image", 3, &FindContoursNodelet::imageCallbackWithInfo, this);
00200 else
00201 img_sub_ = it_->subscribe("image", 3, &FindContoursNodelet::imageCallback, this);
00202 }
00203
00204 void unsubscribe()
00205 {
00206 NODELET_DEBUG("Unsubscribing from image topic.");
00207 img_sub_.shutdown();
00208 cam_sub_.shutdown();
00209 }
00210
00211 public:
00212 virtual void onInit()
00213 {
00214 Nodelet::onInit();
00215 it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00216
00217 pnh_->param("debug_view", debug_view_, false);
00218 if (debug_view_) {
00219 always_subscribe_ = true;
00220 }
00221 prev_stamp_ = ros::Time(0, 0);
00222
00223 window_name_ = "Demo code to find contours in an image";
00224 low_threshold_ = 100;
00225
00226 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00227 dynamic_reconfigure::Server<Config>::CallbackType f =
00228 boost::bind(&FindContoursNodelet::reconfigureCallback, this, _1, _2);
00229 reconfigure_server_->setCallback(f);
00230
00231 img_pub_ = advertiseImage(*pnh_, "image", 1);
00232 msg_pub_ = advertise<opencv_apps::ContourArrayStamped>(*pnh_, "contours", 1);
00233
00234 onInitPostProcess();
00235 }
00236 };
00237 bool FindContoursNodelet::need_config_update_ = false;
00238 }
00239
00240 #include <pluginlib/class_list_macros.h>
00241 PLUGINLIB_EXPORT_CLASS(find_contours::FindContoursNodelet, nodelet::Nodelet);