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 #include "peddetect.h"
00028 
00029 class ImageConverter
00030 {
00031   ros::NodeHandle nh_;
00032   image_transport::ImageTransport it_;
00033   image_transport::Subscriber image_sub_;
00034   image_transport::Publisher image_pub_;
00035 
00036   Mat xsobel, ysobel, GrayImg, xsobeldiv, div, integralim, GradMag,
00037     IntegralChns;
00038 
00039   MatVector BinVect, LUVchannels;
00040 
00041   d10Vector features;
00042 
00043   int ImgCount;
00044   cv_bridge::CvImagePtr cv_ptr;
00045 
00046 public:
00047 
00048 ImageConverter ():
00049   it_ (nh_)
00050   {
00051 
00052     ImgCount = 0;
00053     image_pub_ = it_.advertise ("Image_Out", 1);
00054     image_sub_ =
00055       it_.subscribe ("Image_In", 1, &ImageConverter::imageCb, this);
00056 
00057   }
00058 
00059   ~ImageConverter ()
00060   {
00061 
00062   }
00063 
00064   void imageCb (const sensor_msgs::ImageConstPtr & msg)
00065   {
00066 
00067 
00068 
00069 
00070     try
00071     {
00072 
00073       cv_ptr = cv_bridge::toCvCopy (msg, "rgb8");
00074 
00075       cv_ptr->image.convertTo (cv_ptr->image, CV_8UC1);
00076 
00077     }
00078     catch (cv_bridge::Exception & e)
00079     {
00080       ROS_ERROR ("cv_bridge exception: %s", e.what ());
00081       return;
00082     }
00083     Mat Img = cv_ptr->image;
00084 
00085     if (Img.rows == 0)
00086       return;
00087     
00088     
00089 
00090     Mat MergedChannels (Img.rows, Img.cols, CV_64FC (CHANNELNR));
00091 
00093 
00094 
00095     cvtColor (Img, Img, CV_BGR2RGB, 0);
00096 
00097     cvtColor (Img, GrayImg, CV_RGB2GRAY, 0);
00098 
00099     features.clear ();
00100 
00101     Sobel (GrayImg, xsobel, CV_64FC1, 1, 0, 3, 1, 0, BORDER_DEFAULT);
00102     Sobel (GrayImg, ysobel, CV_64FC1, 0, 1, 3, 1, 0, BORDER_DEFAULT);
00103 
00104     GradMag = GradientMagnitude (xsobel, ysobel);
00105 
00106     BinVect = OrientedGradientsDiagram (GradMag, xsobel, ysobel);
00107 
00108     LUVchannels = LUVcolourchannels (Img);
00109 
00110     Mat ToBeMergedChannels[] =
00111       { GradMag, BinVect[0], BinVect[1], BinVect[2], BinVect[3], BinVect[4],
00112       BinVect[5], LUVchannels[0], LUVchannels[1], LUVchannels[2]
00113     };
00114 
00115 
00116     merge (ToBeMergedChannels, CHANNELNR, MergedChannels);
00117 
00118     integral (GradMag, integralim, CV_64F);
00119 
00120     integral (MergedChannels, IntegralChns, CV_64FC (CHANNELNR));
00121 
00122 
00123     CvRect region;
00124     region.x = 0;
00125     region.y = 0;
00126     region.width = 15;
00127     region.height = 90;
00128 
00129     GetChnFtrsOverImage (IntegralChns, region, features);
00130     
00131     cout<<features.size()<<endl;
00132 
00133     cvtColor (Img, GrayImg, CV_RGB2GRAY, 0);
00135 
00136 
00137     cv_ptr->image = BinVect[0];
00138 
00139 
00140 
00141     sensor_msgs::ImagePtr msg_out = cv_ptr->toImageMsg ();
00142     msg_out->encoding = "64FC1";
00143     msg_out->header.frame_id = "Image_Out";
00144     msg_out->header.stamp = ros::Time::now ();
00145 
00146 
00147     image_pub_.publish (msg_out);
00148 
00149 
00150   }
00151 
00152 };
00153 
00154 int main (int argc, char **argv)
00155 {
00156   ros::init (argc, argv, "image_converter");
00157   ImageConverter ic;
00158   ros::spin ();
00159   return 0;
00160 }