$search
00001 00002 /* 00003 * Software License Agreement (Modified BSD License) 00004 * 00005 * Copyright (c) 2012, PAL Robotics, S.L. 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/or other materials provided 00017 * with the distribution. 00018 * * Neither the name of PAL Robotics, S.L. nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 */ 00035 00043 #include <ros/ros.h> 00044 #include <opencv2/core/core.hpp> 00045 #include <opencv2/imgproc/imgproc.hpp> 00046 #include <opencv2/highgui/highgui.hpp> 00047 00048 #include <image_transport/image_transport.h> 00049 #include <cv_bridge/cv_bridge.h> 00050 #include <sensor_msgs/image_encodings.h> 00051 00052 #include <dynamic_reconfigure/server.h> 00053 #include <pal_vision_segmentation/TemplateSegmentConfig.h> 00054 #include <pal_vision_segmentation/image_processing.h> 00055 00056 /***Variables used in callbacks***/ 00057 image_transport::Publisher mask_pub; 00058 int window_width; 00059 int window_height; 00060 int coeffs_to_cancel; 00061 cv::Mat image_rect; 00062 image_transport::Publisher image_pub; 00063 image_transport::Publisher debug_pub; 00064 cv::Mat target_template; 00065 cv::Mat raw_template; 00066 int offset_x, offset_y; 00067 /***end of callback section***/ 00068 00069 void imageCb(const sensor_msgs::ImageConstPtr& msg) 00070 { 00071 if(image_pub.getNumSubscribers() > 0 || 00072 mask_pub.getNumSubscribers() > 0 || 00073 debug_pub.getNumSubscribers() > 0) 00074 { 00075 cv_bridge::CvImagePtr cv_ptr; 00076 try 00077 { 00078 cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8); 00079 } 00080 catch (cv_bridge::Exception& e) 00081 { 00082 ROS_ERROR("cv_bridge exception: %s", e.what()); 00083 return; 00084 } 00085 00086 image_rect = cv_ptr->image; 00087 00088 double ticksBefore = cv::getTickCount(); 00089 00090 cv::Mat matched; 00091 cv::Mat dct_d; 00092 pal_vision_util::dctNormalization(image_rect, dct_d, coeffs_to_cancel); 00093 cv::matchTemplate(dct_d, target_template, matched, CV_TM_CCORR_NORMED); 00094 00095 double min_val, max_val; 00096 cv::Point max_loc, min_loc; 00097 cv::minMaxLoc(matched, &min_val, &max_val, &min_loc, &max_loc, cv::Mat()); 00098 00099 cv::Mat mask; 00100 mask = cv::Mat::zeros(image_rect.rows, image_rect.cols, CV_8UC1); 00101 00102 const int start_col = (max_loc.x + offset_x - window_width/2 < 0) ? 00103 0 : (max_loc.x + offset_x - window_width/2); 00104 const int start_row = (max_loc.y + offset_y - window_height/2 < 0) ? 00105 0 : (max_loc.y + offset_y - window_height/2); 00106 const int end_col = (window_width/2 + max_loc.x + offset_x > mask.rows) ? 00107 mask.rows : (window_width/2 + offset_x + max_loc.x); 00108 const int end_row = (window_height/2 + max_loc.y + offset_y > mask.cols) ? 00109 mask.cols : (window_height/2 + max_loc.y + offset_y); 00110 for(int i=start_row; i<end_row; ++i) 00111 for(int j=start_col; j<end_col; ++j) 00112 mask.at<uchar>(i,j) = 255; 00113 00114 if(mask_pub.getNumSubscribers() > 0) 00115 { 00116 cv_bridge::CvImage mask_msg; 00117 mask_msg.header = msg->header; 00118 mask_msg.encoding = sensor_msgs::image_encodings::TYPE_8UC1; 00119 mask_msg.image = mask; 00120 mask_pub.publish(mask_msg.toImageMsg()); 00121 } 00122 00123 if(image_pub.getNumSubscribers() > 0) 00124 { 00125 cv::Mat masked; 00126 image_rect.copyTo(masked, mask); 00127 cv_bridge::CvImage masked_msg; 00128 masked_msg.header = msg->header; 00129 masked_msg.encoding = sensor_msgs::image_encodings::BGR8; 00130 masked_msg.image = masked; 00131 masked_msg.header.stamp = ros::Time::now(); 00132 image_pub.publish(*masked_msg.toImageMsg()); 00133 } 00134 00135 //DEBUG 00136 if(debug_pub.getNumSubscribers() > 0) 00137 { 00138 cv::rectangle(dct_d, cv::Rect(start_col, start_row, window_width, window_height), cv::Scalar(255,0,0), 2); 00139 cv::circle(dct_d, cv::Point(max_loc.x + offset_x, max_loc.y + offset_y), 5, cv::Scalar(255,0,0), 1); 00140 cv_bridge::CvImage debug_msg; 00141 debug_msg.header = msg->header; 00142 debug_msg.encoding = sensor_msgs::image_encodings::TYPE_8UC3; 00143 debug_msg.image = dct_d; 00144 debug_pub.publish(*debug_msg.toImageMsg()); 00145 } 00146 00147 ROS_INFO("imageCb runtime: %f ms", 00148 1000*(cv::getTickCount() - ticksBefore)/cv::getTickFrequency()); 00149 } 00150 } 00151 00152 void reconf_callback(pal_vision_segmentation::TemplateSegmentConfig &config, uint32_t level) 00153 { 00154 window_width = config.window_width; 00155 window_height = config.window_height; 00156 coeffs_to_cancel = config.coeffs_to_cancel; 00157 00158 pal_vision_util::dctNormalization(raw_template, target_template, coeffs_to_cancel); 00159 } 00160 00161 int main(int argc, char *argv[] ) 00162 { 00163 ros::init(argc, argv, "template_segmentation"); 00164 ros::NodeHandle nh("template_segmentation"); 00165 nh.param<int>("window_width", window_width, 10); 00166 nh.param<int>("window_height", window_height, 10); 00167 nh.param<int>("coeffs_to_cancel", coeffs_to_cancel, 2); 00168 00169 if(argc < 2) 00170 { 00171 ROS_ERROR("Template segmentation needs a template to match. Please provide it as a command line argument."); 00172 return -1; 00173 } 00174 00175 std::string template_path(argv[1]); 00176 ROS_INFO("%s", template_path.c_str()); 00177 raw_template = cv::imread(template_path); 00178 pal_vision_util::dctNormalization(raw_template, target_template, coeffs_to_cancel); 00179 00180 offset_x = (target_template.rows-1)/2; 00181 offset_y = (target_template.cols-1)/2; 00182 00183 image_transport::ImageTransport it(nh); 00184 image_transport::Subscriber rect_sub = it.subscribe("/image", 1, &imageCb); 00185 image_pub = it.advertise("image_masked", 1); 00186 mask_pub = it.advertise("mask", 1); 00187 debug_pub = it.advertise("debug",1); 00188 00189 dynamic_reconfigure::Server<pal_vision_segmentation::TemplateSegmentConfig> server; 00190 dynamic_reconfigure::Server<pal_vision_segmentation::TemplateSegmentConfig>::CallbackType f; 00191 f = boost::bind(&reconf_callback, _1, _2); 00192 server.setCallback(f); 00193 00194 ros::spin(); 00195 } 00196