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
00040
00041 namespace enc = sensor_msgs::image_encodings;
00042
00043
00044 static const char WINDOW1[] = "Image Processed";
00045 static const char WINDOW0[] = "Image Raw";
00046
00047
00048 image_transport::Publisher pub;
00049
00050
00054 void imageCallback(const sensor_msgs::ImageConstPtr& original_image)
00055 {
00056 int x=0 , y=0;
00057
00058 cv_bridge::CvImagePtr cv_ptr;
00059 cv_bridge::CvImagePtr cv_ptr_clone;
00060
00061 try
00062 {
00063
00064
00065
00066 cv_ptr = cv_bridge::toCvCopy(original_image, enc::BGR8);
00067 cv_ptr_clone = cv_bridge::toCvCopy(original_image, enc::BGR8);
00068 cv::Mat cv_clone=cv_ptr->image.clone();
00069
00070 }
00071 catch (cv_bridge::Exception& e)
00072 {
00073
00074 ROS_ERROR("tutorialROSOpenCV::main.cpp::cv_bridge exception: %s", e.what());
00075 return;
00076 }
00077
00078
00079
00080
00081
00082 for(int i = 0; i<cv_ptr->image.rows; i++)
00083 {
00084
00085 for(int j = 0; j<cv_ptr->image.cols; j++)
00086 {
00087 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)
00088 {
00089 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)
00090 {
00091 cv_ptr_clone->image.at<cv::Vec3b>(i,j)[0] = 255;
00092 cv_ptr_clone->image.at<cv::Vec3b>(i,j)[1] = 255;
00093 cv_ptr_clone->image.at<cv::Vec3b>(i,j)[2] = 255;
00094 }
00095 else
00096 {
00097 cv_ptr_clone->image.at<cv::Vec3b>(i,j)[0] = 0;
00098 cv_ptr_clone->image.at<cv::Vec3b>(i,j)[1] = 0;
00099 cv_ptr_clone->image.at<cv::Vec3b>(i,j)[2] = 0;
00100 }
00101 }
00102 else
00103 {
00104 cv_ptr_clone->image.at<cv::Vec3b>(i,j)[0] = 255;
00105 cv_ptr_clone->image.at<cv::Vec3b>(i,j)[1] = 255;
00106 cv_ptr_clone->image.at<cv::Vec3b>(i,j)[2] = 255;
00107 }
00108 }
00109 }
00110
00111
00112 std::vector<cv::Mat> channels;
00113
00114
00115 cv::split(cv_ptr_clone->image, channels);
00116
00117
00118 cv::Mat imageB = channels[0];
00119 cv::Mat imageG = channels[1];
00120 cv::Mat imageR = channels[2];
00121
00122
00123 int check = 0;
00124
00125
00126
00127
00128
00129
00130
00131 if ( (imageR.at<uchar>(imageR.rows-1 , imageR.cols/2) <= 2) && (imageR.at<uchar>(imageR.rows - 2, imageR.cols / 2) <= 2) )
00132 {
00133
00134
00135 for (int i=1 ; i<imageR.rows-10 ; i++)
00136 {
00137 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)
00138 {
00139 x=i;
00140 }
00141
00142 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)
00143 {
00144 y=i;
00145 }
00146 }
00147
00148
00149 if(x>=160 || y>=160)
00150 {
00151 if(x==y || x==y+2)
00152 {
00153
00154 ROS_ERROR("Right");
00155 check=1;
00156 }
00157 else if (x<y)
00158 {
00159
00160 ROS_ERROR("Left");
00161 check=1;
00162 }
00163 else if (x>y)
00164 {
00165
00166 ROS_ERROR("Right");
00167 check=1;
00168 }
00169 }
00170
00171 if (check==0)
00172 {
00173
00174 ROS_ERROR("UP");
00175 }
00176 }
00177 else
00178 {
00179
00180 }
00181
00182
00183
00184
00185 cv::imshow(WINDOW1, cv_ptr_clone->image);
00186 cv::imshow(WINDOW0, cv_ptr->image);
00187 cv::waitKey(3);
00188
00189
00190
00191 pub.publish(cv_ptr_clone->toImageMsg());
00192 }
00193
00197 int main(int argc, char **argv)
00198 {
00199 ros::init(argc, argv, "image_processor");
00200
00201 ros::NodeHandle nh;
00202
00203 image_transport::ImageTransport it(nh);
00204
00205 cv::namedWindow(WINDOW0, CV_WINDOW_AUTOSIZE);
00206 cv::namedWindow(WINDOW1, CV_WINDOW_AUTOSIZE);
00207
00208 image_transport::Subscriber sub = it.subscribe("image", 1, imageCallback);
00209
00210 cv::destroyWindow(WINDOW0);
00211 cv::destroyWindow(WINDOW1);
00212
00213
00214 pub = it.advertise("image_processed", 1);
00215
00216 ros::spin();
00217 ROS_INFO("tutorialROSOpenCV::main.cpp::No error.");
00218 }