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
00048 #include <opencv2/highgui/highgui.hpp>
00049 #include <opencv2/imgproc/imgproc.hpp>
00050
00051 #include <dynamic_reconfigure/server.h>
00052 #include "opencv_apps/ContourMomentsConfig.h"
00053 #include "opencv_apps/Moment.h"
00054 #include "opencv_apps/MomentArray.h"
00055 #include "opencv_apps/MomentArrayStamped.h"
00056
00057 namespace opencv_apps
00058 {
00059
00060
00061 bool compareContourAreas(const std::vector<cv::Point>& contour1, const std::vector<cv::Point>& contour2)
00062 {
00063 double i = fabs(contourArea(cv::Mat(contour1)));
00064 double j = fabs(contourArea(cv::Mat(contour2)));
00065 return (i > j);
00066 }
00067
00068 class ContourMomentsNodelet : public opencv_apps::Nodelet
00069 {
00070 image_transport::Publisher img_pub_;
00071 image_transport::Subscriber img_sub_;
00072 image_transport::CameraSubscriber cam_sub_;
00073 ros::Publisher msg_pub_;
00074
00075 boost::shared_ptr<image_transport::ImageTransport> it_;
00076
00077 typedef opencv_apps::ContourMomentsConfig Config;
00078 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00079 Config config_;
00080 boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00081
00082 int queue_size_;
00083 bool debug_view_;
00084 ros::Time prev_stamp_;
00085
00086 int low_threshold_;
00087
00088 std::string window_name_;
00089 static bool need_config_update_;
00090
00091 void reconfigureCallback(Config& new_config, uint32_t level)
00092 {
00093 config_ = new_config;
00094 low_threshold_ = config_.canny_low_threshold;
00095 }
00096
00097 const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame)
00098 {
00099 if (frame.empty())
00100 return image_frame;
00101 return frame;
00102 }
00103
00104 void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00105 {
00106 doWork(msg, cam_info->header.frame_id);
00107 }
00108
00109 void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00110 {
00111 doWork(msg, msg->header.frame_id);
00112 }
00113
00114 static void trackbarCallback(int , void* )
00115 {
00116 need_config_update_ = true;
00117 }
00118
00119 void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg)
00120 {
00121
00122 try
00123 {
00124
00125 cv::Mat frame = cv_bridge::toCvShare(msg, msg->encoding)->image;
00126
00127
00128 opencv_apps::MomentArrayStamped moments_msg;
00129 moments_msg.header = msg->header;
00130
00131
00132 cv::Mat src_gray;
00134 if (frame.channels() > 1)
00135 {
00136 cv::cvtColor(frame, src_gray, cv::COLOR_BGR2GRAY);
00137 }
00138 else
00139 {
00140 src_gray = frame;
00141 }
00142 cv::blur(src_gray, src_gray, cv::Size(3, 3));
00143
00145 if (debug_view_)
00146 {
00147 cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
00148 }
00149
00150 cv::Mat canny_output;
00151 std::vector<std::vector<cv::Point> > contours;
00152 std::vector<cv::Vec4i> hierarchy;
00153 cv::RNG rng(12345);
00154
00156 cv::Canny(src_gray, canny_output, low_threshold_, low_threshold_ * 2, 3);
00158 cv::findContours(canny_output, contours, hierarchy, CV_RETR_TREE, CV_CHAIN_APPROX_SIMPLE, cv::Point(0, 0));
00159
00161 cv::Mat drawing;
00162 if (debug_view_)
00163 {
00164 drawing = cv::Mat::zeros(canny_output.size(), CV_8UC3);
00165 }
00166
00168 NODELET_INFO("\t Info: Area and Contour Length");
00169
00170
00171 std::sort(contours.begin(), contours.end(), compareContourAreas);
00172
00173 std::vector<cv::Moments> mu(contours.size());
00174 std::vector<cv::Point2f> mc(contours.size());
00175 for (size_t i = 0; i < contours.size(); i++)
00176 {
00178 for (size_t i = 0; i < contours.size(); i++)
00179 {
00180 mu[i] = moments(contours[i], false);
00181 }
00182
00184 for (size_t i = 0; i < contours.size(); i++)
00185 {
00186 mc[i] = cv::Point2f(static_cast<float>(mu[i].m10 / mu[i].m00), static_cast<float>(mu[i].m01 / mu[i].m00));
00187 }
00188
00189 if (debug_view_)
00190 {
00191 cv::Scalar color = cv::Scalar(rng.uniform(0, 255), rng.uniform(0, 255), rng.uniform(0, 255));
00192 cv::drawContours(drawing, contours, (int)i, color, 2, 8, hierarchy, 0, cv::Point());
00193 cv::circle(drawing, mc[i], 4, color, -1, 8, 0);
00194 }
00195 NODELET_INFO(" * Contour[%d] - Area (M_00) = %.2f - Area OpenCV: %.2f - Length: %.2f - Center (%.2f, %.2f)",
00196 (int)i, mu[i].m00, cv::contourArea(contours[i]), cv::arcLength(contours[i], true), mc[i].x,
00197 mc[i].y);
00198
00199 opencv_apps::Moment moment_msg;
00200 moment_msg.m00 = mu[i].m00;
00201 moment_msg.m10 = mu[i].m10;
00202 moment_msg.m01 = mu[i].m01;
00203 moment_msg.m20 = mu[i].m20;
00204 moment_msg.m11 = mu[i].m11;
00205 moment_msg.m02 = mu[i].m02;
00206 moment_msg.m30 = mu[i].m30;
00207 moment_msg.m21 = mu[i].m21;
00208 moment_msg.m12 = mu[i].m12;
00209 moment_msg.m03 = mu[i].m03;
00210 moment_msg.mu20 = mu[i].mu20;
00211 moment_msg.mu11 = mu[i].mu11;
00212 moment_msg.mu02 = mu[i].mu02;
00213 moment_msg.mu30 = mu[i].mu30;
00214 moment_msg.mu21 = mu[i].mu21;
00215 moment_msg.mu12 = mu[i].mu12;
00216 moment_msg.mu03 = mu[i].mu03;
00217 moment_msg.nu20 = mu[i].nu20;
00218 moment_msg.nu11 = mu[i].nu11;
00219 moment_msg.nu02 = mu[i].nu02;
00220 moment_msg.nu30 = mu[i].nu30;
00221 moment_msg.nu21 = mu[i].nu21;
00222 moment_msg.nu12 = mu[i].nu12;
00223 moment_msg.nu03 = mu[i].nu03;
00224 opencv_apps::Point2D center_msg;
00225 center_msg.x = mc[i].x;
00226 center_msg.y = mc[i].y;
00227 moment_msg.center = center_msg;
00228 moment_msg.area = cv::contourArea(contours[i]);
00229 moment_msg.length = cv::arcLength(contours[i], true);
00230 moments_msg.moments.push_back(moment_msg);
00231 }
00232
00233 if (debug_view_)
00234 {
00235 cv::imshow(window_name_, drawing);
00236 int c = cv::waitKey(1);
00237 }
00238
00239
00240 sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, "bgr8", drawing).toImageMsg();
00241 img_pub_.publish(out_img);
00242 msg_pub_.publish(moments_msg);
00243 }
00244 catch (cv::Exception& e)
00245 {
00246 NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00247 }
00248
00249 prev_stamp_ = msg->header.stamp;
00250 }
00251
00252 void subscribe()
00253 {
00254 NODELET_DEBUG("Subscribing to image topic.");
00255 if (config_.use_camera_info)
00256 cam_sub_ = it_->subscribeCamera("image", queue_size_, &ContourMomentsNodelet::imageCallbackWithInfo, this);
00257 else
00258 img_sub_ = it_->subscribe("image", queue_size_, &ContourMomentsNodelet::imageCallback, this);
00259 }
00260
00261 void unsubscribe()
00262 {
00263 NODELET_DEBUG("Unsubscribing from image topic.");
00264 img_sub_.shutdown();
00265 cam_sub_.shutdown();
00266 }
00267
00268 public:
00269 virtual void onInit()
00270 {
00271 Nodelet::onInit();
00272 it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00273
00274 pnh_->param("queue_size", queue_size_, 3);
00275 pnh_->param("debug_view", debug_view_, false);
00276 if (debug_view_)
00277 {
00278 always_subscribe_ = true;
00279 }
00280 prev_stamp_ = ros::Time(0, 0);
00281
00282 window_name_ = "Contours";
00283 low_threshold_ = 100;
00284
00285 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00286 dynamic_reconfigure::Server<Config>::CallbackType f =
00287 boost::bind(&ContourMomentsNodelet::reconfigureCallback, this, _1, _2);
00288 reconfigure_server_->setCallback(f);
00289
00290 img_pub_ = advertiseImage(*pnh_, "image", 1);
00291 msg_pub_ = advertise<opencv_apps::MomentArrayStamped>(*pnh_, "moments", 1);
00292 onInitPostProcess();
00293 }
00294 };
00295 bool ContourMomentsNodelet::need_config_update_ = false;
00296 }
00297
00298 namespace contour_moments
00299 {
00300 class ContourMomentsNodelet : public opencv_apps::ContourMomentsNodelet
00301 {
00302 public:
00303 virtual void onInit()
00304 {
00305 ROS_WARN("DeprecationWarning: Nodelet contour_moments/contour_moments is deprecated, "
00306 "and renamed to opencv_apps/contour_moments.");
00307 opencv_apps::ContourMomentsNodelet::onInit();
00308 }
00309 };
00310 }
00311
00312 #include <pluginlib/class_list_macros.h>
00313 PLUGINLIB_EXPORT_CLASS(opencv_apps::ContourMomentsNodelet, nodelet::Nodelet);
00314 PLUGINLIB_EXPORT_CLASS(contour_moments::ContourMomentsNodelet, nodelet::Nodelet);