road_recognition.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
33 #include <ros/ros.h> //Includes all the headers necessary to use the most common public pieces of the ROS system.
34 #include <image_transport/image_transport.h> //Use image_transport for publishing and subscribing to images in ROS
35 #include <cv_bridge/cv_bridge.h> //Use cv_bridge to convert between ROS and OpenCV Image formats
36 #include <sensor_msgs/image_encodings.h> //Include some useful constants for image encoding. Refer to: http://www.ros.org/doc/api/sensor_msgs/html/namespacesensor__msgs_1_1image__encodings.html for more info.
37 #include <opencv2/imgproc/imgproc.hpp> //Include headers for OpenCV Image processing
38 #include <opencv2/highgui/highgui.hpp> //Include headers for OpenCV GUI handling
39 
40 //Store all constants for image encodings in the enc namespace to be used later.
41 namespace enc = sensor_msgs::image_encodings;
42 
43 //Declare a string with the name of the window that we will create using OpenCV where processed images will be displayed.
44 static const char WINDOW1[] = "Image Processed";
45 static const char WINDOW0[] = "Image Raw";
46 
47 //Use method of ImageTransport to create image publisher
48 image_transport::Publisher pub;
49 // image_transport::Publisher pub_raw;
50 
54 void imageCallback(const sensor_msgs::ImageConstPtr& original_image)
55 {
56  int x=0 , y=0;
57  //Convert from the ROS image message to a CvImage suitable for working with OpenCV for processing
58  cv_bridge::CvImagePtr cv_ptr;
59  cv_bridge::CvImagePtr cv_ptr_clone;
60 
61  try
62  {
63 // Always copy, returning a mutable CvImage
64 // OpenCV expects color images to use BGR channel order.
65 
66  cv_ptr = cv_bridge::toCvCopy(original_image, enc::BGR8);
67  cv_ptr_clone = cv_bridge::toCvCopy(original_image, enc::BGR8);
68  cv::Mat cv_clone=cv_ptr->image.clone();
69 
70  }
71  catch (cv_bridge::Exception& e)
72  {
73 // if there is an error during conversion, display it
74  ROS_ERROR("tutorialROSOpenCV::main.cpp::cv_bridge exception: %s", e.what());
75  return;
76  }
77 
78 
79  /*Process the image */
80  /* para todas as linhas */
81 
82  for(int i = 0; i<cv_ptr->image.rows; i++)
83  {
84  /* Para todas as colunas */
85  for(int j = 0; j<cv_ptr->image.cols; j++)
86  {
87  if (cv_ptr->image.at<cv::Vec3b>(i,j)[0]>100 && cv_ptr->image.at<cv::Vec3b>(i,j)[1]>120 && cv_ptr->image.at<cv::Vec3b>(i,j)[2]>110 && cv_ptr->image.at<cv::Vec3b>(i,j)[0]<255 && cv_ptr->image.at<cv::Vec3b>(i,j)[1]<255 && cv_ptr->image.at<cv::Vec3b>(i,j)[2]<255)
88  {
89  if (cv_ptr->image.at<cv::Vec3b>(i,j)[0]>120 && cv_ptr->image.at<cv::Vec3b>(i,j)[1]>190 && cv_ptr->image.at<cv::Vec3b>(i,j)[2]>120 && cv_ptr->image.at<cv::Vec3b>(i,j)[0]<160 && cv_ptr->image.at<cv::Vec3b>(i,j)[1]<255 && cv_ptr->image.at<cv::Vec3b>(i,j)[2]<150)
90  {
91  cv_ptr_clone->image.at<cv::Vec3b>(i,j)[0] = 255;
92  cv_ptr_clone->image.at<cv::Vec3b>(i,j)[1] = 255;
93  cv_ptr_clone->image.at<cv::Vec3b>(i,j)[2] = 255;
94  }
95  else
96  {
97  cv_ptr_clone->image.at<cv::Vec3b>(i,j)[0] = 0;
98  cv_ptr_clone->image.at<cv::Vec3b>(i,j)[1] = 0;
99  cv_ptr_clone->image.at<cv::Vec3b>(i,j)[2] = 0;
100  }
101  }
102  else
103  {
104  cv_ptr_clone->image.at<cv::Vec3b>(i,j)[0] = 255;
105  cv_ptr_clone->image.at<cv::Vec3b>(i,j)[1] = 255;
106  cv_ptr_clone->image.at<cv::Vec3b>(i,j)[2] = 255;
107  }
108  }
109  }
110 
111  /* Criar um vector com as varias camadas da imagem */
112  std::vector<cv::Mat> channels;
113 
114  /* separar a imagem em camadas */
115  cv::split(cv_ptr_clone->image, channels);
116 
117  /* Separar a img nos varios canais */
118  cv::Mat imageB = channels[0];
119  cv::Mat imageG = channels[1];
120  cv::Mat imageR = channels[2];
121 
122  /* Iniciar o check = 0 */
123  int check = 0;
124 
125 // ROS_INFO("valor das colunas %d",imageR.at<uchar>(100 , 100));
126 // ROS_INFO("O valor das condicoes do if \n %d \n %d",cv_ptr->image.at<uchar>(cv_ptr->image.rows , cv_ptr->image.cols/2) , cv_ptr->image.at<uchar>(cv_ptr->image.rows - 2, cv_ptr->image.cols / 2));
127 // ROS_INFO("O valor das condicoes do if da camada red \n %d\n %d",imageR.at<uchar>(imageR.rows , imageR.cols/2),imageR.at<uchar>(imageR.rows - 2, imageR.cols / 2));
128 // ROS_INFO("Numero de colunas da img %s e linhas %s",cv_ptr->image.cols,cv_ptr->image.rows);
129 
130 // if (imageR.at<uchar>(imageR.rows , imageR.cols/2) == 0 && imageR.at<uchar>(imageR.rows - 2, imageR.cols / 2) == 0)
131  if ( (imageR.at<uchar>(imageR.rows-1 , imageR.cols/2) <= 2) && (imageR.at<uchar>(imageR.rows - 2, imageR.cols / 2) <= 2) )
132  {
133 // ROS_INFO("Entrou dentro do if");
134 
135  for (int i=1 ; i<imageR.rows-10 ; i++)
136  {
137  if ( imageR.at<uchar>(i , 1) && imageR.at<uchar>(i+1 , 1) && imageR.at<uchar>(i+4 , 1) && imageR.at<uchar>(i+5 , 1)==255 && imageR.at<uchar>(i+10 , 1)==255)
138  {
139  x=i;
140  }
141 
142  if ( imageR.at<uchar>(i , cv_ptr->image.cols) && imageR.at<uchar>(i+2 , cv_ptr->image.cols) && imageR.at<uchar>(i+4 , cv_ptr->image.cols)==255 && imageR.at<uchar>(i+10 , cv_ptr->image.cols)==255)
143  {
144  y=i;
145  }
146  }
147 // ROS_INFO("Saiu do for ");
148 // ROS_INFO("x=%d - y=%d",x,y);
149  if(x>=160 || y>=160)
150  {
151  if(x==y || x==y+2)
152  {
153 // cv::imshow("SIGNAL", arrow3);
154  ROS_ERROR("Right");
155  check=1;
156  }
157  else if (x<y)
158  {
159 // cv::imshow("SIGNAL", arrow4);
160  ROS_ERROR("Left");
161  check=1;
162  }
163  else if (x>y)
164  {
165 // cv::imshow("SIGNAL", arrow2);
166  ROS_ERROR("Right");
167  check=1;
168  }
169  }
170 
171  if (check==0)
172  {
173 // cv::imshow("SIGNAL", arrow5);
174  ROS_ERROR("UP");
175  }
176  }
177  else
178  {
179 // ROS_ERROR("Cross");
180  }
181 
182 // cv_bridge::CvImage cv_ptr_clone(cv_ptr->header,cv_ptr->encoding,copy);
183 
184  /* Criar uma janela para publicar as imagens */
185  cv::imshow(WINDOW1, cv_ptr_clone->image);
186  cv::imshow(WINDOW0, cv_ptr->image);
187  cv::waitKey(3);
188 
189  //Convert the CvImage to a ROS image message and publish it on the "camera/image_processed" topic.
190 // pub.publish(cv_ptr->toImageMsg());
191  pub.publish(cv_ptr_clone->toImageMsg());
192 }
193 
197 int main(int argc, char **argv)
198 {
199  ros::init(argc, argv, "image_processor");
200 
201  ros::NodeHandle nh;
202  //Create an ImageTransport instance, initializing it with our NodeHandle.
203  image_transport::ImageTransport it(nh);
204  //OpenCV HighGUI call to create a display window on start-up.
205  cv::namedWindow(WINDOW0, CV_WINDOW_AUTOSIZE);
206  cv::namedWindow(WINDOW1, CV_WINDOW_AUTOSIZE);
207 
208  image_transport::Subscriber sub = it.subscribe("image", 1, imageCallback);
209  //OpenCV HighGUI call to destroy a display window on shut-down.
210  cv::destroyWindow(WINDOW0);
211  cv::destroyWindow(WINDOW1);
212 
213 // pub_raw = it.advertise("image_raw", 1);
214  pub = it.advertise("image_processed", 1);
215 
216  ros::spin();
217  ROS_INFO("tutorialROSOpenCV::main.cpp::No error.");
218 }
static const char WINDOW1[]
static const char WINDOW0[]
int main(int argc, char **argv)
image_transport::Publisher pub
void imageCallback(const sensor_msgs::ImageConstPtr &original_image)


road_recognition
Author(s): Ricardo Morais
autogenerated on Mon Mar 2 2015 01:32:51