33 image_transport::ImageTransport
it_;
65 boost_classifier.load(
"/home/pedrobatista/workingcopy/lar3/perception/pedestrians/PedestrianDetect/trained_boost_15Kf_2000w_19Ks_m8_M64_boot3.xml");
81 void imageCb (
const sensor_msgs::ImageConstPtr & msg)
87 cv_ptr = cv_bridge::toCvCopy (msg,
"rgb8");
92 catch (cv_bridge::Exception & e)
94 ROS_ERROR (
"cv_bridge exception: %s", e.what ());
105 resize(Img, Img, win , 0, 0, INTER_LINEAR);
109 Size win; win.width=640; win.height=480;
110 resize(Img, Img, win , 0, 0, INTER_LINEAR);
117 cvtColor (Img, Img, CV_BGR2RGB, 0);
128 for (uint n=0; n<
PedRect.size(); n++)
131 double FR = (double)Img.rows / (
double)
PedRect[n].Scale.height, FC=(double)Img.cols / (
double)
PedRect[n].Scale.width;
143 rectangle(Img,
rectangles[n],Scalar(0,255,0), 2, 8, 0);
158 ROS_INFO (
"Image nr %d\n",
ImgCount++);
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 ();
189 int main (
int argc,
char **argv)
192 ros::init (argc, argv,
"image_converter");
vector< PedRoi > PedRoiVec
void GetRandParams(int seed, int NrFtrs, FtrVecParams2 &RandParams, Rect region)
void GetChnFtrsOverImagePyramid(Mat Image, CvRect ®ion, vector< float > &features, int nOctUp, Size minSize, int nPerOct, FtrVecParams2 Params, PedRoiVec &PedRect, CvBoost &boost_classifier)
int main(int argc, char **argv)
void imageCb(const sensor_msgs::ImageConstPtr &msg)
vector< Rect > rectangles
image_transport::ImageTransport it_
image_transport::Publisher image_pub_
image_transport::Subscriber image_sub_
vector< FtrParams2 > FtrVecParams2
cv_bridge::CvImagePtr cv_ptr