$search
00001 /* 00002 * Software License Agreement (Modified BSD License) 00003 * 00004 * Copyright (c) 2012, PAL Robotics, S.L. 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 PAL Robotics, S.L. 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 00045 #include <boost/filesystem.hpp> 00046 00047 #include <ros/ros.h> 00048 #include <opencv2/core/core.hpp> 00049 #include <opencv2/imgproc/imgproc.hpp> 00050 #include <opencv2/highgui/highgui.hpp> 00051 #include <opencv2/video/video.hpp> 00052 00053 #include <image_transport/image_transport.h> 00054 #include <cv_bridge/cv_bridge.h> 00055 #include <sensor_msgs/image_encodings.h> 00056 00057 #include <dynamic_reconfigure/server.h> 00058 #include <pal_vision_segmentation/HistogramSegmentConfig.h> 00059 #include <pal_vision_segmentation/image_processing.h> 00060 #include "histogram.h" 00061 00062 /***Variables used in callbacks***/ 00063 image_transport::Publisher mask_pub; 00064 int threshold; 00065 int dilate_iterations; 00066 int dilate_size; 00067 int erode_iterations; 00068 int erode_size; 00069 cv::Mat image_rect; 00070 image_transport::Publisher image_pub; 00071 image_transport::Publisher debug_pub; 00072 cv::MatND target_hist; 00073 /***end of callback section***/ 00074 00075 void imageCb(const sensor_msgs::ImageConstPtr& msg) 00076 { 00077 if(image_pub.getNumSubscribers() > 0 || 00078 mask_pub.getNumSubscribers() > 0 || 00079 debug_pub.getNumSubscribers() > 0) 00080 { 00081 cv_bridge::CvImagePtr cv_ptr; 00082 try 00083 { 00084 cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8); 00085 } 00086 catch (cv_bridge::Exception& e) 00087 { 00088 ROS_ERROR("cv_bridge exception: %s", e.what()); 00089 return; 00090 } 00091 00092 image_rect = cv_ptr->image; 00093 00094 //double ticksBefore = cv::getTickCount(); 00095 00096 cv::Mat backProject; 00097 cv::Mat hsv; 00098 cv::cvtColor(image_rect, hsv, CV_BGR2HSV); 00099 // Quantize the hue to 30 levels 00100 // and the saturation to 32 levels 00101 // hue varies from 0 to 179, see cvtColor 00102 float hranges[] = { 0, 180 }; 00103 // saturation varies from 0 (black-gray-white) to 00104 // 255 (pure spectrum color) 00105 float sranges[] = { 0, 256 }; 00106 const float* ranges[] = { hranges, sranges }; 00107 // we compute the histogram from the 0-th and 1-st channels 00108 int channels[] = {0, 1}; 00109 00110 //back-projection takes every pixel in hsv and checks in what bin of target_hist belongs to. Then, the value of 00111 //the bin is stored in backProject in the same coordinates as the pixel 00112 cv::calcBackProject(&hsv, 1, channels, target_hist, backProject, ranges, 1, true); 00113 00114 //normalization is not necessary as the histogram target_hist was already normalized 00115 //cv::normalize(backProject, backProject, 0, 255, cv::NORM_MINMAX, -1, cv::Mat()); 00116 cv::threshold(backProject, backProject, threshold, 255, CV_THRESH_BINARY); 00117 00118 cv::Mat mask, tmp1; 00119 00120 if(dilate_iterations == 0 && erode_iterations == 0) 00121 mask = backProject; 00122 00123 if(dilate_iterations > 0) 00124 { 00125 cv::dilate(backProject, erode_iterations == 0 ? mask: tmp1, 00126 cv::Mat::ones(dilate_size, dilate_size, CV_8UC1), 00127 cv::Point(-1, -1), dilate_iterations); 00128 } 00129 00130 if(erode_iterations > 0) 00131 { 00132 cv::erode(dilate_iterations == 0 ? backProject : tmp1, mask, 00133 cv::Mat::ones(erode_size, erode_size, CV_8UC1), 00134 cv::Point(-1, -1), erode_iterations); 00135 } 00136 00137 ros::Time now = msg->header.stamp; //ros::Time::now(); 00138 00139 if(mask_pub.getNumSubscribers() > 0) 00140 { 00141 cv_bridge::CvImage mask_msg; 00142 mask_msg.header = msg->header; 00143 mask_msg.header.stamp = now; //ros::Time::now(); 00144 mask_msg.encoding = sensor_msgs::image_encodings::TYPE_8UC1; 00145 mask_msg.image = mask; 00146 mask_pub.publish(mask_msg.toImageMsg()); 00147 } 00148 00149 if(image_pub.getNumSubscribers() > 0) 00150 { 00151 cv::Mat masked; 00152 image_rect.copyTo(masked, mask); 00153 cv_bridge::CvImage masked_msg; 00154 masked_msg.header = msg->header; 00155 masked_msg.encoding = sensor_msgs::image_encodings::BGR8; 00156 masked_msg.image = masked; 00157 masked_msg.header.stamp = now; //ros::Time::now(); 00158 image_pub.publish(*masked_msg.toImageMsg()); 00159 } 00160 00161 //DEBUG 00162 if(debug_pub.getNumSubscribers() > 0) 00163 { 00164 cv_bridge::CvImage debug_msg; 00165 debug_msg.header = msg->header; 00166 debug_msg.encoding = sensor_msgs::image_encodings::TYPE_8UC1; 00167 debug_msg.image = backProject; 00168 debug_pub.publish(*debug_msg.toImageMsg()); 00169 } 00170 00171 // ROS_INFO("imageCb runtime: %f ms", 00172 // 1000*(cv::getTickCount() - ticksBefore)/cv::getTickFrequency()); 00173 } 00174 } 00175 00176 void reconf_callback(pal_vision_segmentation::HistogramSegmentConfig &config, uint32_t level) 00177 { 00178 threshold = config.threshold; 00179 dilate_iterations = config.dilate_iterations; 00180 dilate_size = config.dilate_size; 00181 erode_iterations = config.erode_iterations; 00182 erode_size = config.erode_size; 00183 } 00184 00185 void computeHistogramFromFile(const std::string& template_path, cv::MatND& hist) 00186 { 00187 if ( !boost::filesystem::is_directory(template_path) ) //if the given path is not a folder 00188 { 00189 if ( !boost::filesystem::is_regular_file(template_path) ) 00190 throw std::runtime_error("The given path is not a file: " + template_path); 00191 00192 cv::Mat raw_template = cv::imread(template_path); 00193 pal_vision_util::calcHSVHist(raw_template, hist); 00194 cv::normalize(hist, hist, 0, 255, cv::NORM_MINMAX, -1, cv::Mat()); 00195 } 00196 else //otherwise, it should be a folder 00197 { 00198 boost::filesystem::directory_iterator end_iter; 00199 std::vector<cv::Mat> images; 00200 for( boost::filesystem::directory_iterator dir_iter(template_path) ; dir_iter != end_iter ; ++dir_iter) 00201 { 00202 if ( boost::filesystem::is_regular_file(dir_iter->status()) ) 00203 { 00204 std::string fullPathFileName = dir_iter->path().string(); 00205 cv::Mat raw_template = cv::imread(fullPathFileName); 00206 if ( !raw_template.empty() ) 00207 images.push_back(raw_template); 00208 } 00209 } 00210 if ( !images.empty() ) 00211 { 00212 //pal_vision_util::calcHSVHist(images, hist); 00213 std::vector<cv::MatND> hists; 00214 //compute a separate histogram for each image 00215 pal_vision_util::calcHSVHist(images, hists); 00216 00217 //create a new histogram where every bin takes the maximum value if any of the histogram's bin value is 00218 //larger than the threshold 00219 for (int h = 0; h < hists[0].rows; ++h) 00220 for (int s = 0; s < hists[0].cols; ++s) 00221 { 00222 int i = 0; 00223 bool found = false; 00224 while ( i < hists.size() && !found ) 00225 { 00226 if ( hists[i].at<float>(h, s) > threshold ) 00227 { 00228 hists[0].at<float>(h, s) = 255; 00229 found = true; 00230 } 00231 ++i; 00232 } 00233 if ( !found ) 00234 hists[0].at<float>(h, s) = 0; 00235 } 00236 hist = hists[0].clone(); 00237 } 00238 else 00239 throw std::runtime_error("No images found in the given path: " + template_path); 00240 } 00241 00242 // cv::imshow("histogram", pal_vision_util::histogramImage(hist)); 00243 // cv::waitKey(0); 00244 } 00245 00246 int main(int argc, char *argv[] ) 00247 { 00248 ros::init(argc, argv, "histogram_segmentation"); //initialize with a default name 00249 ros::NodeHandle nh("~"); //use node name as sufix of the namespace 00250 nh.param<int>("threshold", threshold, 254); 00251 nh.param<int>("dilate_iterations", dilate_iterations, 9); 00252 nh.param<int>("dilate_size", dilate_size, 7); 00253 nh.param<int>("erode_iterations", erode_iterations, 0); 00254 nh.param<int>("erode_size", erode_size, 3); 00255 00256 if(argc < 2) 00257 { 00258 ROS_ERROR("Histogram segmentation needs a template to search for. Please provide it as a command line argument."); 00259 return -1; 00260 } 00261 00262 std::string template_path(argv[1]); 00263 ROS_INFO_STREAM("Computing histogram from: " << template_path); 00264 00265 computeHistogramFromFile( template_path, target_hist ); 00266 00267 image_transport::ImageTransport it(nh); 00268 image_transport::Subscriber rect_sub = it.subscribe("/image", 1, &imageCb); 00269 image_pub = it.advertise("image_masked", 1); 00270 mask_pub = it.advertise("mask", 1); 00271 debug_pub = it.advertise("debug",1); 00272 00273 dynamic_reconfigure::Server<pal_vision_segmentation::HistogramSegmentConfig> server; 00274 dynamic_reconfigure::Server<pal_vision_segmentation::HistogramSegmentConfig>::CallbackType f; 00275 f = boost::bind(&reconf_callback, _1, _2); 00276 server.setCallback(f); 00277 00278 ros::spin(); 00279 }