29 #include <opencv2/highgui/highgui.hpp>
30 #include <opencv2/opencv.hpp>
31 #include <image_transport/image_transport.h>
32 #include <opencv/cvwimage.h>
33 #include <opencv/highgui.h>
39 image_transport::ImageTransport
it_;
72 string classifier_file;
73 nh_.param<
string>(
"classifier",classifier_file,string(
"not_found"));
91 void imageCb (
const sensor_msgs::ImageConstPtr & msg)
95 cv_ptr = cv_bridge::toCvCopy (msg,
"rgb8");
100 catch (cv_bridge::Exception & e)
102 ROS_ERROR (
"cv_bridge exception: %s", e.what ());
124 double secs =ros::Time::now().toSec();
127 cvtColor (Img, Img, CV_BGR2RGB, 0);
135 cout <<
"a imagem contem peoes?" <<
PedRect.size() << endl;
138 cout <<
"sim" << endl;
140 else {cout <<
"nao" << endl;}
200 cout <<
"duracao: " << ros::Time::now().toSec() -secs << endl;
209 int main (
int argc,
char **argv)
212 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