00001 #include "textile_count_alg_node.h"
00002 #include <std_msgs/Int32.h>
00003
00004 using namespace cv;
00005
00006 TextileCountAlgNode::TextileCountAlgNode(void) :
00007 algorithm_base::IriBaseAlgorithm<TextileCountAlgorithm>()
00008 {
00009
00010
00011 rubbish_threshold_ = 0.01;
00012
00013
00014 output_img_publisher_ = public_node_handle_.advertise<sensor_msgs::Image>("output_img", 1);
00015 objects_found_publisher_ = public_node_handle_.advertise<std_msgs::Int32>("num_objects_found", 100);
00016
00017 input_raw_image_subscriber_ = this->public_node_handle_.subscribe("input_raw_image", 1, &TextileCountAlgNode::input_raw_image_callback, this);
00018
00019
00020
00021
00022
00023
00024
00025
00026 }
00027
00028 TextileCountAlgNode::~TextileCountAlgNode(void)
00029 {
00030
00031 }
00032
00033 void TextileCountAlgNode::mainNodeThread(void)
00034 {
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045 }
00046
00047
00048 void TextileCountAlgNode::input_raw_image_callback(const sensor_msgs::Image::ConstPtr& msg)
00049 {
00050 cv_bridge::CvImagePtr cv_ptr;
00051
00052 try
00053 {
00054 cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
00055 }
00056 catch (cv_bridge::Exception& e)
00057 {
00058 ROS_ERROR("cv_bridge exception: %s", e.what());
00059 return;
00060 }
00061
00062
00063
00064
00065 int pix_black = 0;
00066 for (int rr = 0; rr < cv_ptr->image.rows; rr++) {
00067 for (int cc = 0; cc < cv_ptr->image.cols; cc++) {
00068 if( cv_ptr->image.at<cv::Vec3b>(rr,cc)[0] == 0
00069 && cv_ptr->image.at<cv::Vec3b>(rr,cc)[1] == 0
00070 && cv_ptr->image.at<cv::Vec3b>(rr,cc)[2] == 0){
00071 pix_black++;
00072 }
00073 }
00074 }
00075 this->alg_.lock();
00076 double rubbish_th = rubbish_threshold_;
00077 this->alg_.unlock();
00078 double nonblack_proportion = 1 - ((double)pix_black)/((double)(cv_ptr->image.rows*cv_ptr->image.cols));
00079 if(nonblack_proportion < rubbish_th){
00080
00081 std_msgs::Int32 found;
00082 found.data = 0;
00083 objects_found_publisher_.publish(found);
00084 ROS_WARN("No objects found!");
00085 }else{
00086
00087 histCount(cv_ptr->image);
00088 }
00089
00090
00091
00092 this->output_img_publisher_.publish(cv_ptr->toImageMsg());
00093
00094
00095
00096
00097
00098
00099
00100
00101
00102 }
00103
00104 void TextileCountAlgNode::histCount(cv::Mat& image)
00105 {
00106 if( !image.data )
00107 { return; }
00108
00109
00110 GaussianBlur( image, image, Size( 3, 3 ), 0, 0 );
00111
00112
00113 Mat img_hsv, img_threshold;
00114 cvtColor(image, img_hsv, CV_BGR2HSV);
00115
00116 int width = image.cols;
00117 int height = image.rows;
00118
00119
00120 CV_Assert(img_hsv.depth() != sizeof(uchar));
00121 int channels = img_hsv.channels();
00122
00123 Mat segmented;
00124 for(int i = 0; i < height; ++i)
00125 {
00126 uchar *p1 = img_hsv.ptr<uchar>(i);
00127 for (int j = 0; j < width; ++j)
00128 {
00129
00130
00131 if ((p1[j*channels+1]>1)&&(p1[j*channels+2]>10))
00132 {
00133
00134 segmented.push_back(Vec3b(p1[j*channels],p1[j*channels+1],p1[j*channels+2]));
00135 }
00136 }
00137 }
00138
00139
00140
00141
00142 int hbins = 30, sbins = 43;
00143 int histSize[] = {hbins, sbins};
00144
00145 float hranges[] = { 0, 180 };
00146
00147
00148 float sranges[] = { 0, 256 };
00149 const float* ranges[] = { hranges, sranges };
00150 MatND hist;
00151 int channelsSeg[] = {0, 1};
00152
00153 calcHist( &segmented, 1, channelsSeg, Mat(),
00154 hist, 2, histSize, ranges,
00155 true,
00156 false );
00157
00158 double maxVal=0;
00159 minMaxLoc(hist, 0, &maxVal, 0, 0);
00160 int scale = 10;
00161 Mat histImg = Mat::zeros(sbins*scale, hbins*10, CV_8UC3);
00162 for( int h = 0; h < hbins; h++ )
00163 for( int s = 0; s < sbins; s++ )
00164 {
00165 float binVal = hist.at<float>(h, s);
00166 int intensity = cvRound(binVal*255/maxVal);
00167 if (intensity>20) intensity=255;
00168 else intensity = 0;
00169 rectangle( histImg, Point(h*scale, s*scale),
00170 Point( (h+1)*scale - 1, (s+1)*scale - 1),
00171 Scalar::all(intensity),
00172 CV_FILLED );
00173 }
00174
00175
00176
00177
00178
00179
00180
00181
00182
00183
00184
00185
00186 int thresh = 100;
00187 RNG rng(12345);
00188
00189 Mat canny_output;
00190 Mat src_gray;
00191 vector<vector<Point> > contours;
00192 vector<Vec4i> hierarchy;
00193 cvtColor( histImg, src_gray, CV_BGR2GRAY );
00195 Canny( src_gray, canny_output, thresh, thresh*2, 5 );
00197 findContours( canny_output, contours, hierarchy, CV_RETR_TREE, CV_CHAIN_APPROX_SIMPLE, Point(0, 0) );
00199 vector<Moments> mu(contours.size() );
00200 for(unsigned int i = 0; i < contours.size(); i++ )
00201 { mu[i] = moments( contours[i], false ); }
00203
00204 vector<Point2f> mc( contours.size() );
00205 for(unsigned int i = 0; i < contours.size(); i++ )
00206 { mc[i] = Point2f( mu[i].m10/mu[i].m00 , mu[i].m01/mu[i].m00 ); }
00208 Mat drawing = Mat::zeros( canny_output.size(), CV_8UC3 );
00209
00210
00211 int oldx=0, oldy=0;
00212
00213 int iTrobats=0;
00214 for(unsigned int i = 0; i< contours.size(); i++ )
00215 {
00216 if ((oldx!=(int)mc[i].x)&&(oldy!=(int)mc[i].y))
00217 {
00218 Scalar color = Scalar( rng.uniform(0, 255), rng.uniform(0,255), rng.uniform(0,255) );
00219
00220 circle( histImg, mc[i], 4, color, -1, 8, 0 );
00221 ++iTrobats;oldx=(int)mc[i].x;oldy=(int)mc[i].y;
00222
00223 }
00224 }
00225
00226
00227 std_msgs::Int32 found;
00228 found.data = iTrobats;
00229 objects_found_publisher_.publish(found);
00230
00231 ROS_INFO_STREAM("Objects found: " << found.data);
00232
00233 image=histImg;
00234 }
00235
00236
00237
00238
00239
00240
00241
00242
00243
00244
00245 void TextileCountAlgNode::node_config_update(Config &config, uint32_t level)
00246 {
00247 this->alg_.lock();
00248 ROS_INFO("Reconfig rubbish threshold: %f", config.rubbish_threshold);
00249 rubbish_threshold_ = config.rubbish_threshold;
00250
00251 this->alg_.unlock();
00252 }
00253
00254
00255 void TextileCountAlgNode::addNodeDiagnostics(void)
00256 {
00257 }
00258
00259
00260 int main(int argc,char *argv[])
00261 {
00262 return algorithm_base::main<TextileCountAlgNode>(argc, argv, "textile_count_alg_node");
00263 }