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 #define _MAIN_C_
00028 #include "peddetect.h"
00029
00030 class PedestrianDetect
00031 {
00032 ros::NodeHandle nh_;
00033 image_transport::ImageTransport it_;
00034 image_transport::Subscriber image_sub_;
00035 image_transport::Publisher image_pub_;
00036 int ImgCount;
00037 cv_bridge::CvImagePtr cv_ptr;
00038 DVector features;
00039 CvRect region;
00040 Size minSize;
00041 FtrVecParams2 randparams;
00042 long long int Pedcount, nPedcount;
00043 PedRoiVec PedRect;
00044 PedRoiVec PedRect_Post;
00045 CvBoost boost_classifier;
00046 vector<Rect> rectangles;
00047
00048
00049 public:
00050
00051 PedestrianDetect ():
00052 it_ (nh_)
00053 {
00054
00055 ImgCount = 0;
00056 image_pub_ = it_.advertise ("Image_Out", 1);
00057 image_sub_ =
00058
00059 it_.subscribe ("snr/scam/wide/left/image_color", 1, &PedestrianDetect::imageCb, this);
00060
00061 region.x = 0; region.y = 0; region.width = DWWIDTH; region.height = DWHEIGHT;
00062 minSize.width=DWWIDTH; minSize.height=DWHEIGHT;
00063
00064 GetRandParams(SEED,NRFEATURE2, randparams, region);
00065 boost_classifier.load("/home/pedrobatista/workingcopy/lar3/perception/pedestrians/PedestrianDetect/trained_boost_15Kf_2000w_19Ks_m8_M64_boot3.xml");
00066
00067 Pedcount=0;
00068 nPedcount=0;
00069
00070
00071
00072 }
00073
00074 ~PedestrianDetect ()
00075 {
00076
00077
00078
00079 }
00080
00081 void imageCb (const sensor_msgs::ImageConstPtr & msg)
00082 {
00083
00084 try
00085 {
00086
00087 cv_ptr = cv_bridge::toCvCopy (msg, "rgb8");
00088
00089 cv_ptr->image.convertTo (cv_ptr->image, CV_8UC1);
00090
00091 }
00092 catch (cv_bridge::Exception & e)
00093 {
00094 ROS_ERROR ("cv_bridge exception: %s", e.what ());
00095 return;
00096 }
00097 Mat Img = cv_ptr->image;
00098
00099 if (Img.rows == 0)
00100 return;
00101
00102 if (Img.rows<162)
00103 {
00104 Size win; win.width=DWWIDTH; win.height=DWHEIGHT;
00105 resize(Img, Img, win , 0, 0, INTER_LINEAR);
00106 }
00107 else
00108 {
00109 Size win; win.width=640; win.height=480;
00110 resize(Img, Img, win , 0, 0, INTER_LINEAR);
00111 }
00112
00113
00114
00116
00117 cvtColor (Img, Img, CV_BGR2RGB, 0);
00118
00119 features.clear ();
00120 PedRect.clear();
00121 rectangles.clear();
00122 PedRect_Post.clear();
00123
00124
00125 GetChnFtrsOverImagePyramid(Img , region , features ,NOCTUP, minSize, SCALEPOCT , randparams,PedRect, boost_classifier);
00126
00127
00128 for (uint n=0; n<PedRect.size(); n++)
00129 {
00130
00131 double FR = (double)Img.rows / (double)PedRect[n].Scale.height, FC=(double)Img.cols / (double)PedRect[n].Scale.width;
00132 cv::Rect BB(Point((double)PedRect[n].x*FC,(double)PedRect[n].y*FR),Point((double)PedRect[n].x*FC+(double)DWWIDTH*FC,(double)PedRect[n].y*FR+(double)DWHEIGHT*FR));
00133
00134 rectangles.push_back(BB);
00135
00136 }
00137
00138
00139 if (rectangles.size()!=0) groupRectangles(rectangles, 1, 0.2);
00140
00141 for (uint n=0; n<rectangles.size();n++)
00142 {
00143 rectangle(Img,rectangles[n],Scalar(0,255,0), 2, 8, 0);
00144
00145
00146 }
00147
00148
00149
00150
00151
00152
00153
00154 Pedcount+=PedRect.size();
00155 nPedcount+=features.size()/NRFEATURE-PedRect.size();
00156 cout<<"Ped: "<<Pedcount<<" nPed: "<<nPedcount<<endl;
00157
00158 ROS_INFO ("Image nr %d\n", ImgCount++);
00159
00160
00161
00163
00164
00165
00166
00167
00168
00169
00170
00171 cv_ptr->image = Img;
00172
00173
00174
00175 sensor_msgs::ImagePtr msg_out = cv_ptr->toImageMsg ();
00176 msg_out->encoding = "rgb8";
00177 msg_out->header.frame_id = "Image_Out";
00178 msg_out->header.stamp = ros::Time::now ();
00179
00180
00181 image_pub_.publish (msg_out);
00182
00183
00184
00185 }
00186
00187 };
00188
00189 int main (int argc, char **argv)
00190 {
00191
00192 ros::init (argc, argv, "image_converter");
00193 PedestrianDetect ic;
00194 ros::spin ();
00195 return 0;
00196
00197 }