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
00033 #include <ros/ros.h>
00034 #include <image_transport/image_transport.h>
00035 #include <cv_bridge/cv_bridge.h>
00036 #include <sensor_msgs/image_encodings.h>
00037 #include <opencv2/imgproc/imgproc.hpp>
00038 #include <opencv2/highgui/highgui.hpp>
00039 #include <stdio.h>
00040 #include <stdlib.h>
00041 #include <signal.h>
00042 #include "ProcessImage.h"
00043
00044 #include "main.hh"
00045 #include "cmdline.h"
00046 #include "LaneDetector.hh"
00047 #include <stdio.h>
00048 #include <fstream>
00049 #include <sstream>
00050 #include <iostream>
00051 #include <iomanip>
00052 #include <ctime>
00053
00054
00055 namespace enc = sensor_msgs::image_encodings;
00056
00057
00058 #define MSG(fmt, ...) \
00059 (fprintf(stdout, "%s:%d msg " fmt "\n", __FILE__, __LINE__, ##__VA_ARGS__) ? 0 : 0)
00060
00061
00062 #define ERROR(fmt, ...) \
00063 (fprintf(stderr, "%s:%d error " fmt "\n", __FILE__, __LINE__, ##__VA_ARGS__) ? -1 : -1)
00064 using namespace std;
00065 using namespace cv;
00066
00067
00068 Procecess pross;
00069
00073 void sighandler(int sig)
00074 {
00075 ROS_ERROR("Signal %d caught...",sig);
00076 cout<<"Shuting down road_recognition"<<endl;
00077 exit(0);
00078 }
00079
00080
00081 namespace LaneDetector
00082 {
00086 void imageCallback(const sensor_msgs::ImageConstPtr& original_image)
00087 {
00088
00089 cv_bridge::CvImagePtr cv_ptr;
00090
00091 try
00092 {
00093 cv_ptr = cv_bridge::toCvCopy(original_image, enc::BGR8);
00094 }catch (cv_bridge::Exception& e)
00095 {
00096 ROS_ERROR("Caltech::main.cpp::cv_bridge exception:%s",e.what());
00097 exit(0);
00098 }
00099
00100
00101
00102 clock_t elapsed = 0;
00103
00104 pross.ProcessImage( cv_ptr->image, NULL, 0,&elapsed);
00105 double elapsedTime = static_cast<double>(elapsed) / CLOCKS_PER_SEC;
00106 MSG("Total time %f secs for 1 image = %f Hz", elapsedTime,
00107 1. / elapsedTime);
00108 cv::waitKey(10);
00109 }
00110 }
00116 int main(int argc, char** argv)
00117 {
00118
00119 ros::init(argc, argv, "caltech_lane");
00120
00121 pross.Load_config( argc , argv );
00122
00123 ros::NodeHandle nh;
00124 signal(SIGINT, &sighandler);
00125
00126
00127
00128
00129
00130 image_transport::ImageTransport it(nh);
00131 image_transport::Subscriber sub = it.subscribe("image", 1, imageCallback);
00132
00133
00134 ros::Time start_time = ros::Time::now();
00135 while (ros::ok() && (ros::Time::now() - start_time).toSec() < 50)
00136 {
00137 ros::spinOnce();
00138 }
00139 ROS_INFO("Caltech::main.cpp::No error.");
00140 }