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
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 <pal_vision_segmentation/histogram.h>
00061
00062
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
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 cv::Mat backProject;
00095 pal_vision_util::backProject(image_rect, target_hist, threshold, backProject);
00096
00097 cv::Mat mask, tmp1;
00098
00099 if(dilate_iterations == 0 && erode_iterations == 0)
00100 mask = backProject;
00101
00102 if(dilate_iterations > 0)
00103 {
00104 cv::dilate(backProject, erode_iterations == 0 ? mask: tmp1,
00105 cv::Mat::ones(dilate_size, dilate_size, CV_8UC1),
00106 cv::Point(-1, -1), dilate_iterations);
00107 }
00108
00109 if(erode_iterations > 0)
00110 {
00111 cv::erode(dilate_iterations == 0 ? backProject : tmp1, mask,
00112 cv::Mat::ones(erode_size, erode_size, CV_8UC1),
00113 cv::Point(-1, -1), erode_iterations);
00114 }
00115
00116 ros::Time now = msg->header.stamp;
00117
00118 if(mask_pub.getNumSubscribers() > 0)
00119 {
00120 cv_bridge::CvImage mask_msg;
00121 mask_msg.header = msg->header;
00122 mask_msg.header.stamp = now;
00123 mask_msg.encoding = sensor_msgs::image_encodings::TYPE_8UC1;
00124 mask_msg.image = mask;
00125 mask_pub.publish(mask_msg.toImageMsg());
00126 }
00127
00128 if(image_pub.getNumSubscribers() > 0)
00129 {
00130 cv::Mat masked;
00131 image_rect.copyTo(masked, mask);
00132 cv_bridge::CvImage masked_msg;
00133 masked_msg.header = msg->header;
00134 masked_msg.encoding = sensor_msgs::image_encodings::BGR8;
00135 masked_msg.image = masked;
00136 masked_msg.header.stamp = now;
00137 image_pub.publish(*masked_msg.toImageMsg());
00138 }
00139
00140
00141 if(debug_pub.getNumSubscribers() > 0)
00142 {
00143 cv_bridge::CvImage debug_msg;
00144 debug_msg.header = msg->header;
00145 debug_msg.encoding = sensor_msgs::image_encodings::TYPE_8UC1;
00146 debug_msg.image = backProject;
00147 debug_pub.publish(*debug_msg.toImageMsg());
00148 }
00149 }
00150 }
00151
00152 void reconf_callback(pal_vision_segmentation::HistogramSegmentConfig &config, uint32_t level)
00153 {
00154 threshold = config.threshold;
00155 dilate_iterations = config.dilate_iterations;
00156 dilate_size = config.dilate_size;
00157 erode_iterations = config.erode_iterations;
00158 erode_size = config.erode_size;
00159 }
00160
00161 void computeHistogramFromFile(const std::string& template_path, cv::MatND& hist)
00162 {
00163 if ( !boost::filesystem::is_directory(template_path) )
00164 {
00165 if ( !boost::filesystem::is_regular_file(template_path) )
00166 throw std::runtime_error("The given path is not a file: " + template_path);
00167
00168 cv::Mat raw_template = cv::imread(template_path);
00169 pal_vision_util::calcHSVHist(raw_template, hist);
00170 cv::normalize(hist, hist, 0, 255, cv::NORM_MINMAX, -1, cv::Mat());
00171 cv::threshold(hist, hist, 128, 255, cv::THRESH_BINARY);
00172 }
00173 else
00174 {
00175 boost::filesystem::directory_iterator end_iter;
00176 std::vector<cv::Mat> images;
00177 for( boost::filesystem::directory_iterator dir_iter(template_path) ; dir_iter != end_iter ; ++dir_iter)
00178 {
00179 if ( boost::filesystem::is_regular_file(dir_iter->status()) )
00180 {
00181 std::string fullPathFileName = dir_iter->path().string();
00182 cv::Mat raw_template = cv::imread(fullPathFileName);
00183 if ( !raw_template.empty() )
00184 images.push_back(raw_template);
00185 }
00186 }
00187 if ( !images.empty() )
00188 {
00189
00190 std::vector<cv::MatND> hists;
00191
00192 pal_vision_util::calcHSVHist(images, hists);
00193
00194
00195
00196 for (int h = 0; h < hists[0].rows; ++h)
00197 for (int s = 0; s < hists[0].cols; ++s)
00198 {
00199 int i = 0;
00200 bool found = false;
00201 while ( i < hists.size() && !found )
00202 {
00203 if ( hists[i].at<float>(h, s) > threshold )
00204 {
00205 hists[0].at<float>(h, s) = 255;
00206 found = true;
00207 }
00208 ++i;
00209 }
00210 if ( !found )
00211 hists[0].at<float>(h, s) = 0;
00212 }
00213 hist = hists[0].clone();
00214 }
00215 else
00216 throw std::runtime_error("No images found in the given path: " + template_path);
00217 }
00218 }
00219
00220 int main(int argc, char *argv[] )
00221 {
00222 ros::init(argc, argv, "histogram_segmentation");
00223 ros::NodeHandle nh("~");
00224 nh.param<int>("threshold", threshold, 254);
00225 nh.param<int>("dilate_iterations", dilate_iterations, 9);
00226 nh.param<int>("dilate_size", dilate_size, 7);
00227 nh.param<int>("erode_iterations", erode_iterations, 0);
00228 nh.param<int>("erode_size", erode_size, 3);
00229
00230 if(argc < 2)
00231 {
00232 ROS_ERROR("Histogram segmentation needs a template to search for. Please provide it as a command line argument.");
00233 return -1;
00234 }
00235
00236 std::string template_path(argv[1]);
00237 ROS_INFO_STREAM("Computing histogram from: " << template_path);
00238
00239 computeHistogramFromFile( template_path, target_hist );
00240
00241 image_transport::ImageTransport it(nh);
00242 image_transport::Subscriber rect_sub = it.subscribe("/image", 1, &imageCb);
00243 image_pub = it.advertise("image_masked", 1);
00244 mask_pub = it.advertise("mask", 1);
00245 debug_pub = it.advertise("debug",1);
00246
00247 dynamic_reconfigure::Server<pal_vision_segmentation::HistogramSegmentConfig> server;
00248 dynamic_reconfigure::Server<pal_vision_segmentation::HistogramSegmentConfig>::CallbackType f;
00249 f = boost::bind(&reconf_callback, _1, _2);
00250 server.setCallback(f);
00251
00252 ros::spin();
00253 }