clientimg_detect.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
27  #define _MAIN_C_
28  #include "peddetect.h"
29 
31 {
32  ros::NodeHandle nh_;
33  image_transport::ImageTransport it_;
34  image_transport::Subscriber image_sub_;
35  image_transport::Publisher image_pub_;
36  int ImgCount;
37  cv_bridge::CvImagePtr cv_ptr;
39  CvRect region;
40  Size minSize;
42  long long int Pedcount, nPedcount;
46  vector<Rect> rectangles;
47 
48 
49 public:
50 
52  it_ (nh_)
53  {
54 
55  ImgCount = 0;
56  image_pub_ = it_.advertise ("Image_Out", 1);
57  image_sub_ =
58 // it_.subscribe ("Image_In", 1, &PedestrianDetect:imageCb, this);
59  it_.subscribe ("snr/scam/wide/left/image_color", 1, &PedestrianDetect::imageCb, this);
60 
61  region.x = 0; region.y = 0; region.width = DWWIDTH; region.height = DWHEIGHT;
62  minSize.width=DWWIDTH; minSize.height=DWHEIGHT;
63 
65  boost_classifier.load("/home/pedrobatista/workingcopy/lar3/perception/pedestrians/PedestrianDetect/trained_boost_15Kf_2000w_19Ks_m8_M64_boot3.xml");
66 
67  Pedcount=0;
68  nPedcount=0;
69 
70 
71 
72  }
73 
75  {
76 
77 
78 
79  }
80 
81  void imageCb (const sensor_msgs::ImageConstPtr & msg)
82  {
83 
84  try
85  {
86 
87  cv_ptr = cv_bridge::toCvCopy (msg, "rgb8");
88 
89  cv_ptr->image.convertTo (cv_ptr->image, CV_8UC1);
90 
91  }
92  catch (cv_bridge::Exception & e)
93  {
94  ROS_ERROR ("cv_bridge exception: %s", e.what ());
95  return;
96  }
97  Mat Img = cv_ptr->image;
98 
99  if (Img.rows == 0)
100  return;
101 
102  if (Img.rows<162)
103  {
104  Size win; win.width=DWWIDTH; win.height=DWHEIGHT;
105  resize(Img, Img, win , 0, 0, INTER_LINEAR);
106  }
107  else
108  {
109  Size win; win.width=640; win.height=480;
110  resize(Img, Img, win , 0, 0, INTER_LINEAR);
111  }
112 
113 
114 
116 
117  cvtColor (Img, Img, CV_BGR2RGB, 0);
118 
119  features.clear ();
120  PedRect.clear();
121  rectangles.clear();
122  PedRect_Post.clear();
123 
124 
126 
127 
128  for (uint n=0; n<PedRect.size(); n++)
129  {
130 
131  double FR = (double)Img.rows / (double)PedRect[n].Scale.height, FC=(double)Img.cols / (double)PedRect[n].Scale.width;
132  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));
133 
134  rectangles.push_back(BB);
135 
136  }
137 
138 
139  if (rectangles.size()!=0) groupRectangles(rectangles, 1, 0.2);
140 
141  for (uint n=0; n<rectangles.size();n++)
142  {
143  rectangle(Img,rectangles[n],Scalar(0,255,0), 2, 8, 0);
144 // cout<<"width: "<<rectangles[n].width<<" height: "<<rectangles[n].height<<" x: "<<rectangles[n].x<<" y: "<<rectangles[n].y<<endl;
145 
146  }
147 //
148 // PostProcess(Img, rectangles, randparams, boost_classifier, PedRect_Post);
149 
150 // // Pedcount+=rectangles.size();
151 //
152 // // cout<<"Ped: "<<Pedcount<<" "<<PedRect.size()<<endl;
153 
154  Pedcount+=PedRect.size();
155  nPedcount+=features.size()/NRFEATURE-PedRect.size();
156  cout<<"Ped: "<<Pedcount<<" nPed: "<<nPedcount<<endl;
157 
158  ROS_INFO ("Image nr %d\n", ImgCount++);
159 // cout<<endl<<features.size()<<endl;
160 // cout<<endl<<Img.rows<<" x "<<Img.cols<<endl;
161 
163 
164 // cvtColor (Img, Img, CV_RGB2BGR, 0);
165 
166 
167 // std::ostringstream oss;
168 // oss<<ImgCount;
169 // imwrite( "/home/pedrobatista/workingcopy/lar3/perception/pedestrians/PedestrianDetect/Results/BagGaf_boot2/Frame"+oss.str()+".jpg", Img );
170 
171  cv_ptr->image = Img;
172 
173 
174 
175  sensor_msgs::ImagePtr msg_out = cv_ptr->toImageMsg ();
176  msg_out->encoding = "rgb8";
177  msg_out->header.frame_id = "Image_Out";
178  msg_out->header.stamp = ros::Time::now ();
179 
180 
181  image_pub_.publish (msg_out);
182 
183 
184 
185  }
186 
187 };
188 
189 int main (int argc, char **argv)
190 {
191 // fstream outfile("/home/pedrobatista/workingcopy/lar3/perception/pedestrians/PedestrianDetect/train_seed1234_MIN8_MAX64.csv");
192  ros::init (argc, argv, "image_converter");
193  PedestrianDetect ic;
194  ros::spin ();
195  return 0;
196 
197 }
vector< PedRoi > PedRoiVec
Definition: peddetect.h:87
#define DWHEIGHT
Definition: peddetect.h:51
void GetRandParams(int seed, int NrFtrs, FtrVecParams2 &RandParams, Rect region)
Definition: pedfuncs.cpp:216
#define NRFEATURE
Definition: peddetect.h:49
void GetChnFtrsOverImagePyramid(Mat Image, CvRect &region, vector< float > &features, int nOctUp, Size minSize, int nPerOct, FtrVecParams2 Params, PedRoiVec &PedRect, CvBoost &boost_classifier)
Definition: pedfuncs.cpp:273
#define NRFEATURE2
Definition: peddetect.h:50
int main(int argc, char **argv)
void imageCb(const sensor_msgs::ImageConstPtr &msg)
FtrVecParams2 randparams
vector< Rect > rectangles
#define NOCTUP
Definition: peddetect.h:58
vector< float > DVector
Definition: peddetect.h:93
#define SCALEPOCT
Definition: peddetect.h:59
long long int nPedcount
long long int Pedcount
#define SEED
Definition: peddetect.h:53
#define DWWIDTH
Definition: peddetect.h:52
image_transport::ImageTransport it_
image_transport::Publisher image_pub_
image_transport::Subscriber image_sub_
vector< FtrParams2 > FtrVecParams2
Definition: peddetect.h:92
ros::NodeHandle nh_
cv_bridge::CvImagePtr cv_ptr


pedestrian_detect
Author(s): Pedro Batista
autogenerated on Mon Mar 2 2015 01:32:33