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
00030
00031
00032 class ImageConverter
00033 {
00034 ros::NodeHandle nh_;
00035 image_transport::ImageTransport it_;
00036 image_transport::Subscriber image_sub_;
00037 image_transport::Publisher image_pub_;
00038 int ImgCount;
00039 cv_bridge::CvImagePtr cv_ptr;
00040 DVector features;
00041 CvRect region;
00042 Size minSize;
00043 FtrVecParams randparams;
00044 vector<DVector> WindowFtrs;
00045 CvBoost boost;
00046 int nPedcount;
00047 int Pedcount;
00048
00049
00050 public:
00051
00052 ImageConverter ():
00053 it_ (nh_)
00054 {
00055
00056 ImgCount = 1;
00057 image_pub_ = it_.advertise ("Image_Out", 1);
00058 image_sub_ =
00059 it_.subscribe ("Image_In", 1, &ImageConverter::imageCb, this);
00060
00061 region.x = 0; region.y = 0; region.width = DWWIDTH; region.height = DWHEIGHT;
00062 minSize.width=region.width; minSize.height=region.height;
00063
00064 GetRandParams(SEED,NRFEATURE, randparams, region);
00065 boost.load("/home/pedrobatista/workingcopy/lar3/perception/pedestrians/PedestrianDetect/trained_boost_8030samples-1000ftrs.xml");
00066 nPedcount = 0;
00067 Pedcount=0;
00068
00069
00070
00071 }
00072
00073 ~ImageConverter ()
00074 {
00075
00076
00077
00078 }
00079
00080 void imageCb (const sensor_msgs::ImageConstPtr & msg)
00081 {
00082
00083 try
00084 {
00085
00086 cv_ptr = cv_bridge::toCvCopy (msg, "rgb8");
00087
00088 cv_ptr->image.convertTo (cv_ptr->image, CV_8UC1);
00089
00090 }
00091 catch (cv_bridge::Exception & e)
00092 {
00093 ROS_ERROR ("cv_bridge exception: %s", e.what ());
00094 return;
00095 }
00096 Mat Img = cv_ptr->image;
00097
00098 if (Img.rows == 0)
00099 return;
00100
00101 if (Img.rows<162)
00102 {
00103 Size win; win.width=DWWIDTH; win.height=DWHEIGHT;
00104
00105 resize(Img, Img, win , 0, 0, INTER_LINEAR);
00106 }
00107
00108
00109
00111
00112
00113 cvtColor (Img, Img, CV_BGR2RGB, 0);
00114
00115 features.clear ();
00116 WindowFtrs.clear();
00117
00118 GetChnFtrsOverImagePyramid(Img , region , features, WindowFtrs ,0, minSize, 8 , randparams);
00119
00120
00121 Mat Test;
00122
00123 for(uint n=0;n<WindowFtrs.size();n++)
00124 {
00125
00126 Test=Mat::zeros(1,NRFEATURE,CV_32FC1);
00127
00128 for(uint i=0; i<NRFEATURE; i++)
00129 {
00130
00131 Test.at<float>(0,i)=WindowFtrs[n][i];
00132
00133 }
00134 float x = boost.predict(Test,Mat(),Range::all(),false,false);
00135 if (x==1) nPedcount++;
00136 if (x==2) Pedcount++;
00137
00138 }
00139 cout<<"No Ped: "<<nPedcount<<" Ped: "<<Pedcount<<endl;
00140
00141
00142
00143 ROS_INFO ("Image nr %d\n", ImgCount++);
00144
00145
00146
00148
00149
00150 cv_ptr->image = Img;
00151
00152
00153
00154 sensor_msgs::ImagePtr msg_out = cv_ptr->toImageMsg ();
00155 msg_out->encoding = "rgb8";
00156 msg_out->header.frame_id = "Image_Out";
00157 msg_out->header.stamp = ros::Time::now ();
00158
00159
00160 image_pub_.publish (msg_out);
00161
00162
00163
00164 }
00165
00166 };
00167
00168 int main (int argc, char **argv)
00169 {
00170 ros::init (argc, argv, "image_converter");
00171 ImageConverter ic;
00172 ros::spin ();
00173 return 0;
00174 }