client_train_neg.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 class ImageConverter
30 {
31  ros::NodeHandle nh_;
32  image_transport::ImageTransport it_;
33  image_transport::Subscriber image_sub_;
34  image_transport::Publisher image_pub_;
35  int ImgCount;
36  cv_bridge::CvImagePtr cv_ptr;
38  CvRect region;
39  Size minSize;
41  vector<DVector> WindowFtrs;
42  RNG rng;
43 
44 public:
45 
47  it_ (nh_)
48  {
49 
50  ImgCount = 1;
51  image_pub_ = it_.advertise ("Image_Out", 1);
52  image_sub_ =
53  it_.subscribe ("Image_In", 1, &ImageConverter::imageCb, this);
54 
55  region.x = 0; region.y = 0; region.width = 64; region.height = 128;
56  minSize.width=region.width; minSize.height=region.height;
57 
59  rng(123);
60 
61  }
62 
64  {
65 
66  }
67 
68  void imageCb (const sensor_msgs::ImageConstPtr & msg)
69  {
70 
71  try
72  {
73 
74  cv_ptr = cv_bridge::toCvCopy (msg, "rgb8");
75 
76  cv_ptr->image.convertTo (cv_ptr->image, CV_8UC1);
77 
78  }
79  catch (cv_bridge::Exception & e)
80  {
81  ROS_ERROR ("cv_bridge exception: %s", e.what ());
82  return;
83  }
84  Mat Img = cv_ptr->image;
85 
86  if (Img.rows == 0)
87  return;
88 
89  Size win; win.width=640; win.height=480;
90  resize(Img, Img, win , 0, 0, INTER_LINEAR);
91 
92  region.x = 0; region.y = 0; region.width = DWWIDTH; region.height = DWHEIGHT;
93 
95 
96  cvtColor (Img, Img, CV_BGR2RGB, 0);
97 
98  features.clear ();
99  WindowFtrs.clear();
100 
102 
103  fstream outfile;
104  outfile.open ("/home/pedrobatista/workingcopy/lar3/perception/pedestrians/PedestrianDetect/train_10000.csv", fstream::in | fstream::out | fstream::app);
105 
106  int a=rng.uniform(0,WindowFtrs.size());
107  int b=rng.uniform(0,WindowFtrs.size());
108  int c=rng.uniform(0,WindowFtrs.size());
109  int d=rng.uniform(0,WindowFtrs.size());
110 
111  outfile<<"2,";
112 
113  for (int i=0;i<NRFEATURE;i++)
114  {
115  if (i != NRFEATURE-1)
116  outfile<<WindowFtrs[a][i]<<",";
117  else
118  outfile<<WindowFtrs[a][i];
119  }
120 
121  outfile<<endl;
122  outfile<<"2,";
123  for (int i=0;i<NRFEATURE;i++)
124  {
125  if (i != NRFEATURE-1)
126  outfile<<WindowFtrs[b][i]<<",";
127  else
128  outfile<<WindowFtrs[b][i];
129  }
130 
131 
132  outfile<<endl;
133  outfile<<"2,";
134  for (int i=0;i<NRFEATURE;i++)
135  {
136  if (i != NRFEATURE-1)
137  outfile<<WindowFtrs[c][i]<<",";
138  else
139  outfile<<WindowFtrs[c][i];
140  }
141 
142  outfile<<endl;
143  outfile<<"2,";
144 
145  for (int i=0;i<NRFEATURE;i++)
146  {
147  if (i != NRFEATURE-1)
148  outfile<<WindowFtrs[d][i]<<",";
149  else
150  outfile<<WindowFtrs[d][i];
151  }
152 
153  outfile<<endl;
154 // cout<<WindowFtrs.size()<<" "<<features.size()<<endl;
155 
156  outfile.close();
157  ROS_INFO ("Image nr %d\n", ImgCount++);
158 
159 
160 
161 
162 
164 
165 
166  cv_ptr->image = Img;
167 
168 
169 
170  sensor_msgs::ImagePtr msg_out = cv_ptr->toImageMsg ();
171  msg_out->encoding = "rgb8";
172  msg_out->header.frame_id = "Image_Out";
173  msg_out->header.stamp = ros::Time::now ();
174 
175 
176  image_pub_.publish (msg_out);
177 
178 
179 
180  }
181 
182 };
183 
184 int main (int argc, char **argv)
185 {
186  fstream outfile("/home/pedrobatista/workingcopy/lar3/perception/pedestrians/PedestrianDetect/train_10000.csv");
187  ros::init (argc, argv, "image_converter");
188  ImageConverter ic;
189  ros::spin ();
190  return 0;
191 }
#define DWHEIGHT
Definition: peddetect.h:51
int main(int argc, char **argv)
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
#define NRFEATURE2
Definition: peddetect.h:50
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_
vector< FtrParams2 > FtrVecParams2
Definition: peddetect.h:92


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