client_train.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 
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  vector<DVector> WindowFtrs;
43 
44 public:
45 
47  it_ (nh_)
48  {
49 
50  ImgCount = 1;
51  image_pub_ = it_.advertise ("Image_Out", 1);
52  image_sub_ = it_.subscribe ("Image_In", 1, &ImageConverter::imageCb,this);
53  region.x = 0; region.y = 0; region.width = 64; region.height = 128;
54  minSize.width=region.width; minSize.height=region.height;
56 
57 // for (uint n = 0; n<randparams.size();n++)
58 // {
59 // cout<<randparams[n].width<<" x "<<randparams[n].height<<" x: "<<randparams[n].x<<" y: "<<randparams[n].y<<endl;
60 // }
61 
62  }
63 
65  {
66 
67  }
68 
69  void imageCb (const sensor_msgs::ImageConstPtr & msg)
70  {
71 
72  try
73  {
74 
75  cv_ptr = cv_bridge::toCvCopy (msg, "rgb8");
76 
77  cv_ptr->image.convertTo (cv_ptr->image, CV_8UC1);
78 
79  }
80  catch (cv_bridge::Exception & e)
81  {
82  ROS_ERROR ("cv_bridge exception: %s", e.what ());
83  return;
84  }
85  Mat Img = cv_ptr->image;
86 
87  if (Img.rows == 0)
88  return;
89 
90 
91 
92  Size win; win.width=64; win.height=128;
93  resize(Img, Img, win , 0, 0, INTER_LINEAR);
94 
96 
97 
98  cvtColor (Img, Img, CV_BGR2RGB, 0);
99 
100  features.clear ();
101  WindowFtrs.clear();
102 
103 
105 
106 // cout<<features.size()<<endl;
107 
108  fstream outfile;
109 
110  outfile.open ("/home/pedrobatista/workingcopy/lar3/perception/pedestrians/PedestrianDetect/train_625cf.csv", fstream::in | fstream::out | fstream::app);
111 
112  outfile<<"1,";
113 
114  for (int i=0;i<NRFEATURE;i++)
115  {
116  if (i != NRFEATURE-1)
117  outfile<<features[i]<<",";
118  else
119  outfile<<features[i];
120  }
121 
122  outfile<<endl;
123 
124  outfile.close();
125 
126  ROS_INFO ("Image nr %d\n", ImgCount++);
127 
129 
130 
131  cv_ptr->image = Img;
132 
133 
134 
135  sensor_msgs::ImagePtr msg_out = cv_ptr->toImageMsg ();
136  msg_out->encoding = "rgb8";
137  msg_out->header.frame_id = "Image_Out";
138  msg_out->header.stamp = ros::Time::now ();
139 
140 
141  image_pub_.publish (msg_out);
142 
143 
144 
145  }
146 
147 };
148 
149 int main (int argc, char **argv)
150 {
151  fstream outfile("/home/pedrobatista/workingcopy/lar3/perception/pedestrians/PedestrianDetect/train_625cf.csv");
152  ros::init (argc, argv, "image_converter");
153  ImageConverter ic;
154  ros::spin ();
155  return 0;
156 }
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_
image_transport::Subscriber image_sub_
vector< FtrParams2 > FtrVecParams2
Definition: peddetect.h:92
int main(int argc, char **argv)


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