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 <vector>
00040 #include <cmath>
00041 #include <iostream>
00042 #include <signal.h>
00043 #include <Eigen/Dense>
00044
00045 #define PI 3.1415926
00046 #include "linefinder.h"
00047 #include "edgedetector.h"
00048 #include "lines.h"
00049 #include "road_representation.h"
00050 #include "watershedSegmentation.h"
00051
00052
00053 namespace enc = sensor_msgs::image_encodings;
00054 using namespace Eigen;
00055
00056
00057 static const char WINDOW1[] = "Image Processed";
00058 static const char WINDOW0[] = "Image Raw";
00059
00060 int CountUpperThresh;
00061
00062 void printPts(Point *p,uint size);
00063
00064
00065 image_transport::Publisher pub;
00066
00067
00068 static VectorXi Count_ref(20);
00069 static Eigen::MatrixXd Rep_ref(2, 20);
00070 int OutMsg,frame,frame_lost;
00071 Scalar stddev_old;
00072
00076 int videolanematching( int& MaxLaneNum , int &ExpLaneNum , VectorXi &Enable , MatrixXd &Line , int& TrackThreshold, int &CountUpperThresh)
00077 {
00078 ROS_INFO("Enter -- videolanematching");
00079
00080
00081 MatrixXd List(MaxLaneNum,ExpLaneNum);
00082 List.setOnes();
00083
00084
00085
00086
00087
00088 for (int i = 0 ; i<MaxLaneNum ; i++)
00089 {
00090 for (int j = 0 ; j<ExpLaneNum ; j++)
00091 {
00092 if ( (Count_ref(i)>0) && (Enable(j)==1) )
00093 {
00094 List(i,j) = abs(Line(0,j) - Rep_ref(0,i)) + abs(Line(1,j) - Rep_ref(1,i)) * 200.;
00095 }
00096 }
00097 }
00098
00099
00100 VectorXd Match_dis(MaxLaneNum);
00101 Match_dis.setOnes();
00102
00103 Eigen::MatrixXi Match_list(2,MaxLaneNum);
00104 Match_list.setZero();
00105
00106 int rowInd=-1;
00107 int colInd=-1;
00108
00109 for (int i = 0 ; i<ExpLaneNum ; i++)
00110 {
00111 if (i>0)
00112 {
00113 List.row(rowInd).setOnes();
00114 List.col(colInd).setOnes();
00115 }
00116
00117
00118
00119
00120
00121 MatrixXi::Index min_i, min_j;
00122 double minOfM = List.minCoeff(&min_i,&min_j);
00123
00124 Match_dis(i) = minOfM;
00125 rowInd = min_i;
00126 colInd = min_j;
00127
00128 Match_list(0,i) = min_i;
00129 Match_list(1,i) = min_j;
00130
00131
00132 }
00133
00134
00135
00136
00137
00138
00139 VectorXi Ones(Count_ref.size());
00140 Ones.setOnes();
00141
00142 Count_ref = Count_ref - Ones;
00143
00144 for (int i = 0 ; i<ExpLaneNum ; i++)
00145 {
00146 if (Match_dis(i)>TrackThreshold)
00147 {
00148
00149 int NewInd = 0;
00150 do{
00151 NewInd++;
00152 } while ( Count_ref(NewInd) > 0 );
00153
00154 Rep_ref.col(NewInd) = Line.col( Match_list(1,i) );
00155 Count_ref( NewInd ) = Count_ref( NewInd ) + 2;
00156 }
00157 else
00158 {
00159
00160 Rep_ref.col( Match_list(0,i) ) = Line.col( Match_list(1,i) );
00161 Count_ref(Match_list(0,i)) = Count_ref(Match_list(0,i)) + 2;
00162 }
00163 }
00164
00165 for (int i = 0;i<Count_ref.size(); i++)
00166 {
00167 if (Count_ref(i) < 0)
00168 Count_ref(i) = 0;
00169
00170 if (Count_ref(i) > CountUpperThresh)
00171 Count_ref(i) = CountUpperThresh;
00172 }
00173
00174 ROS_INFO("Exit -- videolanematching");
00175 return 1;
00176 }
00177
00178
00182 VectorXi videodetectcolorandtype(MatrixXi twoLines_0b , cv::Mat image ,MatrixXi li)
00183 {
00184 ROS_INFO(" Enter -- videodetectcolorandtype");
00185
00186 int INVALID_COLOR = 0;
00187 int WHITE_COLOR = 1;
00188 int YELLOW_COLOR = 2;
00189
00190 int INVALID_MARKING = 0;
00191 int BROKEN_MARKING = 1;
00192 int SOLID_MARKING = 2;
00193
00194 int INVALID_COLOR_OR_TYPE = 1;
00195 int YELLOW_BROKEN = 2;
00196 int YELLOW_SOLID = 3;
00197 int WHITE_BROKEN = 4;
00198 int WHITE_SOLID = 5;
00199
00200 VectorXi colorAndTypeIdx(2);
00201 colorAndTypeIdx.setZero();
00202
00203 VectorXi lineColorIdx(2);
00204 lineColorIdx.setZero();
00205
00206 VectorXi solidBrokenIdx(2);
00207 solidBrokenIdx.setZero();
00208
00209 int HALF_OFFSET = 10;
00210
00211 int rH = image.rows;
00212 int cW = image.cols;
00213
00214 VectorXi leftC( rH );
00215 VectorXi rightC( rH );
00216 VectorXi Rs( rH );
00217
00218 Rs.setZero();
00219 leftC.setZero();
00220 rightC.setZero();
00221
00222 bool line_within_image;
00223
00224 int whiteCount;
00225 int yelowCount;
00226 int grayCount;
00227 int SumOfGotAlLeastOneWhitePixelInTheRow;
00228 int SumOfGotAlLeastOneYellowPixelInTheRow;
00229
00230 bool gotAlLeastOneWhitePixelInTheRow;
00231 bool gotAlLeastOneYellowPixelInTheRow;
00232
00233 int yellowVsTotal;
00234 int whiteVsTotal;
00235
00236 int linearPixelRatio;
00237 int pointNotLine = 0;
00238 int len;
00239
00240
00241 cvtColor(image , image ,CV_BGR2YCrCb,CV_8U);
00242 vector<cv::Mat> channels;
00243
00244
00245 split(image, channels);
00246
00247 MatrixXi twoLines_1b( twoLines_0b.rows() , twoLines_0b.cols() );
00248 MatrixXi ones( twoLines_0b.rows() , twoLines_0b.cols() );
00249 ones.setOnes();
00250
00251 twoLines_1b.row(0).swap(twoLines_0b.row(1));
00252 twoLines_1b.row(1).swap(twoLines_0b.row(0));
00253 twoLines_1b.row(2).swap(twoLines_0b.row(3));
00254 twoLines_1b.row(3).swap(twoLines_0b.row(2));
00255
00256 twoLines_1b = twoLines_1b + ones;
00257
00258
00259
00260 for(uint lineIdx=0 ; lineIdx<2 ; lineIdx++)
00261 {
00262 VectorXi r1c1r2c2(4);
00263 r1c1r2c2 = twoLines_1b.col(lineIdx);
00264
00265
00266 for (uint i=0; i<4 ; i++)
00267 {
00268 if (r1c1r2c2(i) > rH)
00269 r1c1r2c2(i) = rH;
00270
00271 if (r1c1r2c2(i) > cW)
00272 r1c1r2c2(i) = cW;
00273 }
00274
00275 int r1 = r1c1r2c2(0);
00276 int c1 = r1c1r2c2(1);
00277 int r2 = r1c1r2c2(2);
00278 int c2 = r1c1r2c2(3);
00279
00280
00281
00282
00283 if (r1>r2)
00284 {
00285 int tmp;
00286 tmp=r2;
00287 r2 = r1;
00288 r1 = tmp;
00289
00290 tmp = c2;
00291 c2 = c1;
00292 c1 = tmp;
00293 }
00294
00295 if ( (r1==r2) && (c1==c2) )
00296 {
00297 pointNotLine = 1;
00298 }
00299 else
00300 {
00301 pointNotLine = 0;
00302 }
00303
00304
00305 if ( (r1>0 && r1<=rH) && (c1>0 && c1<=cW) && (r2>0 && r2<=rH) && (c2>0 && c2<=cW) && pointNotLine == 0 )
00306 {
00307 line_within_image = true;
00308 }
00309 else
00310 {
00311 line_within_image = false;
00312 }
00313
00314
00315 if (line_within_image == true)
00316 {
00317 len = r2-r1+1;
00318
00319 int i = 0;
00320 for (int p=r1; p<r2 ; p++)
00321 {
00322 Rs(i) = p;
00323 i++;
00324 }
00325 double quotient = (c2 - c1)/(len - 1);
00326
00327 for (int i=0; i<len ; i++)
00328 {
00329 leftC(i) = (c1 - HALF_OFFSET) + (i-1)*quotient;
00330 rightC(i) = leftC(i) + 2*HALF_OFFSET;
00331
00332 if (leftC(i)<1)
00333 {
00334 leftC(i) = 1;
00335
00336 if (rightC(i) < 1)
00337 {
00338 rightC(i) = 1;
00339 }
00340 }
00341
00342 if (rightC(1) > cW)
00343 {
00344 rightC(i) = cW;
00345 }
00346 }
00347
00348 whiteCount = 0;
00349 yelowCount = 0;
00350 grayCount = 0;
00351
00352 SumOfGotAlLeastOneWhitePixelInTheRow = 0;
00353 SumOfGotAlLeastOneYellowPixelInTheRow = 0;
00354
00355 for (int i = 0; i < len ; i++)
00356 {
00357 gotAlLeastOneWhitePixelInTheRow = false;
00358 gotAlLeastOneYellowPixelInTheRow = false;
00359
00360 for (int cv = leftC(i); cv<rightC(i) ; cv++)
00361 {
00362 if ( (int)channels[0].at<uchar>(Rs(i) , cv) >= 175)
00363 {
00364 whiteCount++;
00365 gotAlLeastOneWhitePixelInTheRow = true;
00366 }
00367 else if ( ((int)channels[2].at<uchar>(Rs(i),cv) >= 90) && ((int)channels[2].at<uchar>(Rs(i),cv) <= 127) )
00368 {
00369 yelowCount++;
00370 gotAlLeastOneYellowPixelInTheRow = true;
00371 }
00372 else
00373 {
00374 grayCount++;
00375 }
00376 }
00377
00378 if (gotAlLeastOneWhitePixelInTheRow == true)
00379 SumOfGotAlLeastOneWhitePixelInTheRow ++;
00380
00381 if (gotAlLeastOneYellowPixelInTheRow == true)
00382 SumOfGotAlLeastOneYellowPixelInTheRow ++;
00383 }
00384
00385 yellowVsTotal = yelowCount/(grayCount + yelowCount + whiteCount);
00386 whiteVsTotal = whiteCount/(grayCount + yelowCount + whiteCount);
00387
00388
00389 if (yellowVsTotal > whiteVsTotal)
00390 {
00391 lineColorIdx(lineIdx) = YELLOW_COLOR;
00392 linearPixelRatio = SumOfGotAlLeastOneYellowPixelInTheRow/len;
00393 }
00394 else
00395 {
00396 lineColorIdx(lineIdx) = WHITE_COLOR;
00397 linearPixelRatio = SumOfGotAlLeastOneWhitePixelInTheRow/len;
00398 }
00399
00400
00401
00402 if (linearPixelRatio > 0.8)
00403 {
00404 solidBrokenIdx(lineIdx) = SOLID_MARKING;
00405 }
00406 else
00407 {
00408 solidBrokenIdx(lineIdx) = BROKEN_MARKING;
00409 }
00410
00411 if ( (lineColorIdx(lineIdx) == YELLOW_COLOR) && (solidBrokenIdx(lineIdx) == BROKEN_MARKING) )
00412 {
00413 colorAndTypeIdx(lineIdx) = YELLOW_BROKEN;
00414 }
00415 else if ( (lineColorIdx(lineIdx) == YELLOW_COLOR) && (solidBrokenIdx(lineIdx) == SOLID_MARKING) )
00416 {
00417 colorAndTypeIdx(lineIdx) = YELLOW_SOLID;
00418 }
00419 else if ( (lineColorIdx(lineIdx) == WHITE_COLOR) && (solidBrokenIdx(lineIdx) == BROKEN_MARKING) )
00420 {
00421 colorAndTypeIdx(lineIdx) = WHITE_BROKEN;
00422 }
00423 else if ( (lineColorIdx(lineIdx) == WHITE_COLOR) && (solidBrokenIdx(lineIdx) == SOLID_MARKING) )
00424 {
00425 colorAndTypeIdx(lineIdx) = WHITE_SOLID;
00426 }
00427 }
00428 else
00429 {
00430 lineColorIdx(lineIdx) = INVALID_COLOR;
00431 solidBrokenIdx(lineIdx) = INVALID_MARKING;
00432 colorAndTypeIdx(lineIdx) = INVALID_COLOR_OR_TYPE;
00433 }
00434 }
00435
00436 ROS_INFO(" Exit -- videodetectcolorandtype --");
00437 return colorAndTypeIdx;
00438 }
00439
00440
00444 int videodeparturewarning(MatrixXi Pts, cv::Mat Imlow ,MatrixXi &TwoLanes, int &TwoValidLanes,int &NumNormalDriving , int &MaxLaneNum)
00445 {
00446 ROS_INFO("Enter -- videodeparturewarning");
00447
00448 VectorXi Left_pts(4);
00449 Left_pts.setZero();
00450
00451 VectorXi Right_pts(4);
00452 Right_pts.setZero();
00453
00454 VectorXi TmpLeftPts(4);
00455 TmpLeftPts.setZero();
00456
00457 VectorXi TmpRightPts(4);
00458 TmpRightPts.setZero();
00459
00460 int RawMsg;
00461 int Left_dis = 111111111;
00462 int Right_dis = 111111111;
00463 int Dis_inf = Imlow.cols;
00464 int ColNum = -1;
00465 int Halfwidth = Dis_inf * 0.5;
00466 int centerDis = -1;
00467
00468 MatrixXi Pts_local;
00469 MatrixXi Pts_tmp(Pts.rows(),Pts.cols());
00470 Pts_tmp.col(0).swap(Pts.col(1));
00471 Pts_tmp.col(1).swap(Pts.col(0));
00472 Pts_tmp.col(2).swap(Pts.col(3));
00473 Pts_tmp.col(3).swap(Pts.col(2));
00474
00475
00476 Pts_local = Pts_tmp.transpose();
00477
00478 for (int i=0 ; i<MaxLaneNum ; i++)
00479 {
00480
00481 if ( Pts_local(0,i) >= Pts_local(2,i) )
00482 {
00483 ColNum = Pts_local(1,i);
00484 }
00485 else
00486 {
00487 ColNum = Pts_local(3,i);
00488 }
00489
00490 if (Count_ref(i) >= 5)
00491 {
00492 centerDis = abs(Halfwidth - ColNum);
00493 }
00494 else
00495 {
00496 centerDis = Dis_inf;
00497 }
00498
00499
00500 if ((Halfwidth - ColNum) >= 0)
00501 {
00502 if (centerDis < Left_dis)
00503 {
00504 Left_dis = centerDis;
00505 Left_pts = Pts_local.col(i);
00506 }
00507 }
00508 else
00509 {
00510 if (centerDis < Right_dis)
00511 {
00512 Right_dis = centerDis;
00513 Right_pts = Pts_local.col(i);
00514 }
00515 }
00516 }
00517
00518
00519 if (Left_dis <= Dis_inf)
00520 {
00521 TmpLeftPts = Left_pts;
00522 }
00523 else
00524 {
00525 TmpLeftPts.setZero();
00526 }
00527
00528 if (Right_dis <= Dis_inf)
00529 {
00530 TmpRightPts = Right_pts;
00531 }
00532 else
00533 {
00534 TmpRightPts.setZero();
00535 }
00536
00537 TwoLanes << TmpLeftPts,TmpRightPts;
00538
00539 int Check1 = 0;
00540 int Check2 = 0;
00541
00542 if ( (TwoLanes.row(0)!=TwoLanes.row(2)) | (TwoLanes.row(1)!=TwoLanes.row(3)) )
00543 {
00544 Check1 = 1;
00545 }
00546
00547 if ((abs(TwoLanes.row(0).sum() - TwoLanes.row(2).sum()) + abs(TwoLanes.row(1).sum() - TwoLanes.row(3).sum())) >=10 )
00548 {
00549 Check2 = 1;
00550 }
00551 if ( (Left_dis <= Dis_inf) && (Right_dis <= Dis_inf) && (TwoLanes(0,0)>=0) && (TwoLanes(0,1)>=0) & (Check1==1) & (Check2==1) )
00552 {
00553 TwoValidLanes = 1;
00554 }
00555
00556 int Diswarn = Dis_inf * 0.4;
00557
00558
00559
00560
00561
00562
00563 if (Left_dis <= Diswarn && Left_dis <= Right_dis)
00564 {
00565 RawMsg = 2;
00566 ROS_ERROR("WARNING -- Left lane departure");
00567 }
00568 else if (Right_dis <= Diswarn && Left_dis > Right_dis)
00569 {
00570 RawMsg = 0;
00571 ROS_ERROR("WARNING -- Right lane departure");
00572 }
00573 else
00574 {
00575 RawMsg = 1;
00576 }
00577
00578
00579
00580
00581
00582 if (RawMsg == 1)
00583 NumNormalDriving++;
00584
00585 if (RawMsg == 1 || NumNormalDriving >= 4)
00586 OutMsg = RawMsg;
00587
00588 if (RawMsg != 1)
00589 NumNormalDriving = 0;
00590
00591 MatrixXi TwoLanes_tmp(TwoLanes.rows(), TwoLanes.cols());
00592 TwoLanes_tmp = TwoLanes;
00593 TwoLanes.row(0).swap(TwoLanes_tmp.row(1));
00594 TwoLanes.row(1).swap(TwoLanes_tmp.row(0));
00595 TwoLanes.row(2).swap(TwoLanes_tmp.row(3));
00596 TwoLanes.row(3).swap(TwoLanes_tmp.row(2));
00597
00598 ROS_INFO("Exit -- videodeparturewarning");
00599 return 1;
00600 }
00601
00605 int framedivider(Mat image)
00606 {
00607 ROS_INFO("ENTER -- frmedivider");
00608 int rows;
00609
00610
00611 WatershedSegmenter segmenter;
00612
00613
00614 Mat markers( image.rows , image.cols , CV_8U , Scalar(0) );
00615 int height = 20;
00616
00617
00618 Point pt1 = Point(0 , 0);
00619 Point pt2 = Point(image.cols-1 , height);
00620 Point pt3 = Point(0, image.rows-1-height);
00621 Point pt4 = Point(image.cols-1, image.rows-1);
00622
00623 rectangle(markers, pt1, pt2, cvScalar(255) );
00624 rectangle(markers, pt3, pt4, cvScalar(128) );
00625
00626 cout<<"-> Error"<<endl;
00627 imshow("markers",markers);
00628
00629
00630 segmenter.setMarkers(markers);
00631
00632 segmenter.process(image);
00633
00634
00635 namedWindow("Segmentation");
00636 imshow("Segmentation",segmenter.getSegmentation());
00637
00638
00639 namedWindow("Watersheds");
00640 imshow("Watersheds",segmenter.getWatersheds());
00641
00642 std::vector<int> y;
00643 y.clear();
00644
00645 Mat Watersheds = segmenter.getWatersheds();
00646
00647 for (int col=0 ; col<image.cols ; col++)
00648 {
00649 for (int row=0 ; row<image.rows ; row++)
00650 {
00651 if ( (int)Watersheds.at<uchar>(row , col) <= 5 )
00652 {
00653 y.push_back(row);
00654
00655 }
00656 }
00657 }
00658
00659
00660 cout<<"size y ="<<y.size()<<endl;
00661 cout<<"mean(y) ="<<mean(y)<<endl;
00662 return (int)mean(y)[0];
00663
00664
00665
00666 }
00667
00671 int imageCallback(const sensor_msgs::ImageConstPtr& original_image)
00672 {
00673
00674
00675 cv_bridge::CvImagePtr cv_ptr;
00676 cv::Mat im_gray;
00677 cv::Mat YCbCr;
00678 Mat subImg;
00679
00680 cv::Mat original_subImg;
00681 cv::Mat cv_clone;
00682 Mat cv_clone_gray;
00683 Mat top_img;
00684 Mat bgr_image;
00685
00686 try
00687 {
00688
00689
00690 cv_ptr = cv_bridge::toCvCopy(original_image, enc::BGR8);
00691 cv_clone = cv_ptr->image.clone();
00692 }
00693 catch (cv_bridge::Exception& e)
00694 {
00695
00696 ROS_ERROR("tutorialROSOpenCV::main.cpp::cv_bridge exception: %s", e.what());
00697 return 0;
00698 }
00699
00701 int NumRows = 120;
00702 int MaxLaneNum = 20;
00703 int ExpLaneNum = 2;
00704
00705 int TrackThreshold = 75;
00706 int frameFound = 5;
00707 int frameLost = 20;
00708
00709 cv::Point anchor;
00710 VectorXi colorAndTypeIdx;
00711
00712 MatrixXi TwoLanes1(4,2);
00713
00714 VectorXd Theta;
00715 VectorXd Rho;
00717 VectorXi size(3);
00718 size << NumRows - 20 , NumRows + 20, NumRows;
00719
00720 NumRows = framedivider(cv_clone);
00721 cout<<"NumRows ="<<NumRows<<endl;
00722
00723 Rect ROI_1(0, NumRows,cv_clone.cols,cv_clone.rows-NumRows);
00724
00725 Mat upperImg = cv_clone(Range(0,NumRows),Range(0,cv_clone.cols));
00726
00727 subImg = cv_clone(Range(NumRows,cv_clone.rows),Range(0,cv_clone.cols));
00728 original_subImg = cv_clone(ROI_1);
00729 bgr_image = cv_clone(ROI_1);
00730
00731 cv::cvtColor(subImg,subImg,CV_RGB2GRAY,CV_8U);
00732 cv::cvtColor(original_subImg,original_subImg,CV_RGB2GRAY,CV_8U);
00733 cvtColor(upperImg,upperImg,CV_RGB2GRAY,CV_8U);
00735
00736 cv::Mat kernel(1,3,CV_32F,cv::Scalar(0));
00737
00738 kernel.at<float>(0,0)= -1;
00739 kernel.at<float>(0,1)= 0;
00740 kernel.at<float>(0,2)= 1;
00741 cv::Mat Edge;
00742
00743
00744 cv::filter2D(subImg,Edge,subImg.depth(),kernel);
00745 cv::threshold(Edge,Edge,100,255,cv::THRESH_OTSU);
00746
00747 cv::namedWindow("Edge");
00748 cv::imshow("Edge",Edge);
00749
00751
00753
00754 LineFinder ld;
00755
00756
00757 ld.setLineLengthAndGap(10,170);
00758 ld.setMinVote(30);
00759
00760
00761 cv::Mat image(Edge.rows,Edge.cols,CV_8U,cv::Scalar(0));
00762
00763
00764 vector<cv::Vec4i> li= ld.findLines(Edge);
00765
00766
00767 if (li.size() == 0)
00768 {
00769
00770 ROS_ERROR("Nenhuma linha encontrada");
00771 frame_lost++;
00772 return 0;
00773 }
00774 else if (li.size() ==1 )
00775 {
00776 ROS_ERROR("So uma linha encontrada");
00777 frame_lost++;
00778 return 0;
00779 }
00780
00781
00782 MatrixXi Pts;
00783
00784 Lines lines;
00785 lines.end_points=li;
00786 lines.calculatePolarCoodinates();
00787
00788 MatrixXd Line(2,li.size());
00789 Line.setZero();
00790 VectorXi Enable(ExpLaneNum);
00791 Enable.setOnes();
00792
00793
00794
00795 for (uint i=0 ; i<li.size() ; i++)
00796 {
00797 Line(0,i) = lines.rhos[i];
00798 Line(1,i) = lines.thetas[i];
00799 }
00800
00801 ld.drawDetectedLines(image);
00802
00803
00804
00805 namedWindow("Original");
00806 imshow("Original",cv_ptr->image);
00807
00808 cv::namedWindow("Detected Lines with HoughP");
00809 cv::imshow("Detected Lines with HoughP",image);
00810
00811
00812
00813
00814
00815
00816
00817
00818 MatrixXi TwoLanes(4,2);
00819 TwoLanes.setZero();
00820 int CountUpperThresh = frameFound+frameLost;
00821
00822
00823
00824
00825
00826
00827
00828
00829
00830
00831
00832
00833
00834
00835
00836
00837 videolanematching(MaxLaneNum, ExpLaneNum, Enable, Line,TrackThreshold, CountUpperThresh);
00838
00839
00840
00841
00842
00843 int TwoValidLanes = 0;
00844 int NumNormalDriving = 0;
00845
00846
00847 Pts = lines.extremePoints( subImg.rows , subImg.cols );
00848
00849
00850
00851
00852
00853
00854
00855
00856
00857
00858 videodeparturewarning(Pts , subImg ,TwoLanes,TwoValidLanes,NumNormalDriving,MaxLaneNum);
00859
00860
00861
00862
00863
00864
00866
00867 colorAndTypeIdx = videodetectcolorandtype(TwoLanes , bgr_image , Pts);
00868
00869
00870
00871
00872
00873
00874
00875
00876
00877 if (TwoValidLanes == 1)
00878 {
00879 ostringstream str_right;
00880 ostringstream str_left;
00881 ostringstream str_warning;
00882 cv::Mat poly_img(cv_clone.rows,cv_clone.cols,CV_8U,cv::Scalar(0));
00883
00884
00885 switch ( colorAndTypeIdx(0) )
00886 {
00887 case 0:
00888 str_right << "INVALID_COLOR_OR_TYPE";
00889 break;
00890
00891 case 1:
00892 str_right << "YELLOW_BROKEN";
00893 break;
00894
00895 case 2:
00896 str_right << "YELLOW_SOLID";
00897 break;
00898
00899 case 3:
00900 str_right << "WHITE_BROKEN";
00901 break;
00902
00903 case 4:
00904 str_right <<"WHITE_SOLID";
00905 break;
00906 }
00907
00908
00909
00910
00911
00912 switch ( colorAndTypeIdx(1) )
00913 {
00914 case 0:
00915 str_left << "INVALID_COLOR_OR_TYPE";
00916 break;
00917
00918 case 1:
00919 str_left << "YELLOW_BROKEN";
00920 break;
00921
00922 case 2:
00923 str_left << "YELLOW_SOLID";
00924 break;
00925
00926 case 3:
00927 str_left << "WHITE_BROKEN";
00928 break;
00929
00930 case 4:
00931 str_left << "WHITE_SOLID";
00932 break;
00933 }
00934
00935
00936
00937
00938
00939 switch (OutMsg)
00940 {
00941 case 0:
00942 str_warning << "Right lane departure";
00943 break;
00944
00945 case 2:
00946 str_warning << "Left lane departure";
00947 break;
00948
00949 case 1:
00950 str_warning << "";
00951 break;
00952
00953 }
00954
00955
00956
00957
00958 VectorXi Tempr(2);
00959 VectorXi Templ(2);
00960 Tempr.setZero();
00961 Templ.setZero();
00962
00963
00964 MatrixXi offset(4,2);
00965 int off = cv_clone.rows - subImg.rows;
00966 offset<<0, 0,
00967 off, off,
00968 0 , 0,
00969 off, off;
00970
00971 TwoLanes1 = TwoLanes + offset;
00972
00973
00974 if ( TwoLanes(3,0) >= 230 )
00975 {
00976 Templ(0) = TwoLanes1(2, 0);
00977 Templ(1) = TwoLanes1(3, 0);
00978 }
00979 else
00980 {
00981 Templ(0) = 0;
00982 Templ(1) = cv_clone.rows;
00983 }
00984
00985 if (TwoLanes(3,1) >= 230)
00986 {
00987 Tempr(0) = TwoLanes1(2, 1);
00988 Tempr(1) = TwoLanes1(3, 1);
00989 }
00990 else
00991 {
00992 Tempr(0) = 359;
00993 Tempr(1) = cv_clone.rows;
00994 }
00996
00998 int npts = 6;
00999 int npt[] = { 6 };
01000
01001 Point Pts_poly[1][npts];
01002 Pts_poly[0][0] = cv::Point( TwoLanes1(0,0) , TwoLanes1(1,0) );
01003 Pts_poly[0][1] = cv::Point( TwoLanes1(2,0) , TwoLanes1(3,0) );
01004 Pts_poly[0][2] = cv::Point( Templ(0) , Templ(1) );
01005 Pts_poly[0][3] = cv::Point( Tempr(0) , Tempr(1) );
01006 Pts_poly[0][4] = cv::Point( TwoLanes1(2,1),TwoLanes1(3,1) );
01007 Pts_poly[0][5] = cv::Point( TwoLanes1(0,1),TwoLanes1(1,1) );
01008
01009 const Point *ppt[1]={ Pts_poly[0] };
01010
01011 fillPoly( cv_clone, ppt, npt, 1, Scalar( 200, 200, 200 ),8);
01012
01013 cv::namedWindow("Polygon road - 2");
01014 cv::imshow("Polygon road - 2",cv_clone);
01015 }
01016
01017 frame++;
01018 int total = frame + frame_lost;
01019 double percentage = (frame_lost * 100) / total;
01020 cout<<"Numero de frames perdidos = "<<frame_lost<<endl<<"Numero de frames analisados = "<<total<<endl;
01021 cout<<"Percentagem de frames perdidos = "<<percentage<<" %"<<endl;
01022
01023 cv::waitKey(10);
01024 return 1;
01025
01026 }
01027
01031 void printPts(Point *p,uint size)
01032 {
01033
01034 for(uint i=0;i<size;i++)
01035 cout<<p[i]<<endl;
01036 }
01037
01041 void sighandler(int sig)
01042 {
01043 ROS_ERROR("Signal %d caught...",sig);
01044 cout<<"Shuting down road_recognition"<<endl;
01045 exit(0);
01046 }
01047
01051 int main(int argc, char **argv)
01052 {
01053 ros::init(argc, argv, "lane_processor");
01054
01055
01056 Rep_ref.setZero();
01057 Count_ref.setZero();
01058 OutMsg = -1;
01059 frame = 0;
01060 frame_lost = 0;
01061
01062 ros::NodeHandle nh;
01063
01064 image_transport::ImageTransport it(nh);
01065
01066 cv::namedWindow(WINDOW0, CV_WINDOW_AUTOSIZE);
01067 cv::namedWindow(WINDOW1, CV_WINDOW_AUTOSIZE);
01068
01069 signal(SIGINT, &sighandler);
01070
01071 image_transport::Subscriber sub = it.subscribe("snr/cam/0/image_color", 1, imageCallback);
01072
01073
01074 cv::destroyWindow(WINDOW0);
01075 cv::destroyWindow(WINDOW1);
01076
01077 pub = it.advertise("image_processed", 1);
01078
01079 ros::spin();
01080 ROS_INFO("tutorialROSOpenCV::main.cpp::No error.");
01081
01082 }