clientimg_deprecated.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  #include "peddetect.h"
28 
29 // 1 - NoPed
30 // 2 - Ped
31 
32 class ImageConverter
33 {
34  ros::NodeHandle nh_;
35  image_transport::ImageTransport it_;
36  image_transport::Subscriber image_sub_;
37  image_transport::Publisher image_pub_;
38  int ImgCount;
39  cv_bridge::CvImagePtr cv_ptr;
41  CvRect region;
42  Size minSize;
43  FtrVecParams randparams;
44  vector<DVector> WindowFtrs;
45  CvBoost boost;
46  int nPedcount;
47  int Pedcount;
48 
49 
50 public:
51 
53  it_ (nh_)
54  {
55 
56  ImgCount = 1;
57  image_pub_ = it_.advertise ("Image_Out", 1);
58  image_sub_ =
59  it_.subscribe ("Image_In", 1, &ImageConverter::imageCb, this);
60 
61  region.x = 0; region.y = 0; region.width = DWWIDTH; region.height = DWHEIGHT;
62  minSize.width=region.width; minSize.height=region.height;
63 
65  boost.load("/home/pedrobatista/workingcopy/lar3/perception/pedestrians/PedestrianDetect/trained_boost_8030samples-1000ftrs.xml");
66  nPedcount = 0;
67  Pedcount=0;
68 
69 
70 
71  }
72 
74  {
75 
76 
77 
78  }
79 
80  void imageCb (const sensor_msgs::ImageConstPtr & msg)
81  {
82 
83  try
84  {
85 
86  cv_ptr = cv_bridge::toCvCopy (msg, "rgb8");
87 
88  cv_ptr->image.convertTo (cv_ptr->image, CV_8UC1);
89 
90  }
91  catch (cv_bridge::Exception & e)
92  {
93  ROS_ERROR ("cv_bridge exception: %s", e.what ());
94  return;
95  }
96  Mat Img = cv_ptr->image;
97 
98  if (Img.rows == 0)
99  return;
100 
101  if (Img.rows<162)
102  {
103  Size win; win.width=DWWIDTH; win.height=DWHEIGHT;
104 
105  resize(Img, Img, win , 0, 0, INTER_LINEAR);
106  }
107 
108 
109 
111 
112 
113  cvtColor (Img, Img, CV_BGR2RGB, 0);
114 
115  features.clear ();
116  WindowFtrs.clear();
117 
119 
120 
121  Mat Test;
122 
123  for(uint n=0;n<WindowFtrs.size();n++)
124  {
125 
126  Test=Mat::zeros(1,NRFEATURE,CV_32FC1);
127 
128  for(uint i=0; i<NRFEATURE; i++)
129  {
130 
131  Test.at<float>(0,i)=WindowFtrs[n][i];
132 
133  }
134  float x = boost.predict(Test,Mat(),Range::all(),false,false);
135  if (x==1) nPedcount++;
136  if (x==2) Pedcount++;
137 
138  }
139  cout<<"No Ped: "<<nPedcount<<" Ped: "<<Pedcount<<endl;
140 //
141 // Pedcount=0; nPedcount=0;
142 
143  ROS_INFO ("Image nr %d\n", ImgCount++);
144 // cout<<endl<<features.size()<<endl;
145 // cout<<endl<<Img.rows<<" x "<<Img.cols<<endl;
146 
148 
149 
150  cv_ptr->image = Img;
151 
152 
153 
154  sensor_msgs::ImagePtr msg_out = cv_ptr->toImageMsg ();
155  msg_out->encoding = "rgb8";
156  msg_out->header.frame_id = "Image_Out";
157  msg_out->header.stamp = ros::Time::now ();
158 
159 
160  image_pub_.publish (msg_out);
161 
162 
163 
164  }
165 
166 };
167 
168 int main (int argc, char **argv)
169 {
170  ros::init (argc, argv, "image_converter");
171  ImageConverter ic;
172  ros::spin ();
173  return 0;
174 }
#define DWHEIGHT
Definition: peddetect.h:51
void GetRandParams(int seed, int NrFtrs, FtrVecParams2 &RandParams, Rect region)
Definition: pedfuncs.cpp:216
ros::NodeHandle nh_
#define NRFEATURE
Definition: peddetect.h:49
vector< DVector > WindowFtrs
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
FtrVecParams2 randparams
image_transport::Publisher image_pub_
vector< float > DVector
Definition: peddetect.h:93
cv_bridge::CvImagePtr cv_ptr
void imageCb(const sensor_msgs::ImageConstPtr &msg)
#define SEED
Definition: peddetect.h:53
image_transport::ImageTransport it_
#define DWWIDTH
Definition: peddetect.h:52
image_transport::Subscriber image_sub_
int main(int argc, char **argv)


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