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 #include "peddetect.h"
00028
00029
00030 class ImageConverter
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 vector<DVector> WindowFtrs;
00043
00044 public:
00045
00046 ImageConverter ():
00047 it_ (nh_)
00048 {
00049
00050 ImgCount = 1;
00051 image_pub_ = it_.advertise ("Image_Out", 1);
00052 image_sub_ = it_.subscribe ("Image_In", 1, &ImageConverter::imageCb,this);
00053 region.x = 0; region.y = 0; region.width = 64; region.height = 128;
00054 minSize.width=region.width; minSize.height=region.height;
00055 GetRandParams(SEED, NRFEATURE2, randparams, region);
00056
00057
00058
00059
00060
00061
00062 }
00063
00064 ~ImageConverter ()
00065 {
00066
00067 }
00068
00069 void imageCb (const sensor_msgs::ImageConstPtr & msg)
00070 {
00071
00072 try
00073 {
00074
00075 cv_ptr = cv_bridge::toCvCopy (msg, "rgb8");
00076
00077 cv_ptr->image.convertTo (cv_ptr->image, CV_8UC1);
00078
00079 }
00080 catch (cv_bridge::Exception & e)
00081 {
00082 ROS_ERROR ("cv_bridge exception: %s", e.what ());
00083 return;
00084 }
00085 Mat Img = cv_ptr->image;
00086
00087 if (Img.rows == 0)
00088 return;
00089
00090
00091
00092 Size win; win.width=64; win.height=128;
00093 resize(Img, Img, win , 0, 0, INTER_LINEAR);
00094
00096
00097
00098 cvtColor (Img, Img, CV_BGR2RGB, 0);
00099
00100 features.clear ();
00101 WindowFtrs.clear();
00102
00103
00104 GetChnFtrsOverImagePyramid(Img , region , features, WindowFtrs ,0, minSize, 8 , randparams);
00105
00106
00107
00108 fstream outfile;
00109
00110 outfile.open ("/home/pedrobatista/workingcopy/lar3/perception/pedestrians/PedestrianDetect/train_625cf.csv", fstream::in | fstream::out | fstream::app);
00111
00112 outfile<<"1,";
00113
00114 for (int i=0;i<NRFEATURE;i++)
00115 {
00116 if (i != NRFEATURE-1)
00117 outfile<<features[i]<<",";
00118 else
00119 outfile<<features[i];
00120 }
00121
00122 outfile<<endl;
00123
00124 outfile.close();
00125
00126 ROS_INFO ("Image nr %d\n", ImgCount++);
00127
00129
00130
00131 cv_ptr->image = Img;
00132
00133
00134
00135 sensor_msgs::ImagePtr msg_out = cv_ptr->toImageMsg ();
00136 msg_out->encoding = "rgb8";
00137 msg_out->header.frame_id = "Image_Out";
00138 msg_out->header.stamp = ros::Time::now ();
00139
00140
00141 image_pub_.publish (msg_out);
00142
00143
00144
00145 }
00146
00147 };
00148
00149 int main (int argc, char **argv)
00150 {
00151 fstream outfile("/home/pedrobatista/workingcopy/lar3/perception/pedestrians/PedestrianDetect/train_625cf.csv");
00152 ros::init (argc, argv, "image_converter");
00153 ImageConverter ic;
00154 ros::spin ();
00155 return 0;
00156 }