数字图像处理(DIP)实验4 目标颜色识别
数字图像处理课程相关文章 传送门
https://blog.csdn.net/qq_46164507/article/details/122503851
博文说明
本文所使用代码或多或少参考了以往博文的同类or相似文章的代码,并非纯原创
本文仅用于记录并提供一种代码思路,供大家参考
要求
代码
运行环境:Ubuntu16.04 LTS + OpenCV 3.0.4 + ROS-kinetic-full
代码语言:c++
#include <stdlib.h>
#include <iostream>
#include <algorithm>
#include <string>
#include <cv.h>
#include <highgui.h>
#include <opencv2/opencv.hpp>
#include <opencv2/core/core.hpp>
#include "ros/ros.h"
#include <boost/thread.hpp>
#include <geometry_msgs/Twist.h>
using namespace cv;
using namespace std;
Mat BlurforRGB(Mat input)
{
vector <Mat> bgr;
if (input.channels() > 1)
{
split(input, bgr);
}
for (int i = 0; i <= 2; ++i)
{
medianBlur(bgr[i], bgr[i], 3);
blur(bgr[i], bgr[i], Size(3, 3));
}
Mat output;
merge(bgr, output);
return output;
}
Mat RGB2HSV(Mat input)
{
int row = input.rows;
int col = input.cols;
Mat output;
output = input.clone();
for (int i = 0; i < row; ++i)
{
for (int j = 0; j < col; ++j)
{
Vec3b pix = input.at<Vec3b>(i, j);//012:BGR
float b = 1.0 * pix[0] / 255;
float g = 1.0 * pix[1] / 255;
float r = 1.0 * pix[2] / 255;
float maxrgb = max(r, max(g, b));
float minrgb = min(r, min(g, b));
float diff = maxrgb - minrgb;
float v = maxrgb;
float s = (diff / v);
float h;
if (maxrgb - minrgb < 1e-5)h = 0;
else if (maxrgb == r) h = 60 * (g - b) / diff;
else if (maxrgb == g) h = 60 * (b - r) / diff + 120;
else if (maxrgb == b) h = 60 * (r - g) / diff + 240;
if (h < 0)h += 360;
else if (h > 359)h -= 360;
output.at<Vec3b>(i, j)[0] = (int)(h * 180 / 360);
output.at<Vec3b>(i, j)[1] = (int)(s * 255);
output.at<Vec3b>(i, j)[2] = (int)(v * 255);
}
}
return output;
}
Mat RGB2HSI(Mat input)
{
int row = input.rows;
int col = input.cols;
Mat output;
output = input.clone();
for (int i = 0; i < row; ++i)
{
for (int j = 0; j < col; ++j)
{
int B = input.at<Vec3b>(i, j)[0];
int G = input.at<Vec3b>(i, j)[1];
int R = input.at<Vec3b>(i, j)[2];
int minRGB = min(min(R, G), B);
int I = (R + G + B) / 3;
int S = int(1 - 3 * minRGB / (R + G + B)) * 255;
int H = int(acos((R - G + R - B) / 2 / (sqrt((R - G) * (R - G) + (R - B) * (R - B))))) * 255;
output.at<Vec3b>(i, j)[0] = H;
output.at<Vec3b>(i, j)[1] = S;
output.at<Vec3b>(i, j)[2] = I;
}
}
return output;
}
int H_min = 35, H_max = 77, S_min = 43, S_max = 255, V_min = 46, V_max = 255;
Mat HSVThresholdPro(Mat input, int hmin, int hmax, int smin, int smax, int vmin, int vmax)
{
Mat output = input.clone();
int row = input.rows;
int col = input.cols;
for (int i = 0; i < row; ++i)
{
for (int j = 0; j < col; ++j)
{
int H = input.at<Vec3b>(i, j)[0];
int S = input.at<Vec3b>(i, j)[1];
int V = input.at<Vec3b>(i, j)[2];
if (H > hmin && H < hmax && S > smin && S < smax && V > vmin && V < vmax)
{
output.at<Vec3b>(i, j)[0] = 255;
output.at<Vec3b>(i, j)[1] = 255;
output.at<Vec3b>(i, j)[2] = 255;
}
else
{
output.at<Vec3b>(i, j)[0] = 0;
output.at<Vec3b>(i, j)[1] = 0;
output.at<Vec3b>(i, j)[2] = 0;
}
}
}
cvtColor(output, output, COLOR_BGR2GRAY);
return output;
}
int main(int argc,char **argv)
{
VideoCapture capture;
capture.open(1);
ROS_WARN("*****START*****");
ros::init(argc,argv,"ColorMove");//初始化 ROS 节点
ros::NodeHandle n;
ros::Publisher cmd_pub = n.advertise<geometry_msgs::Twist>("cmd_vel", 5);//定义速度发布器
geometry_msgs::Twist twist;
if(!capture.isOpened())
{
printf("the camera can't work normally");
return 0;
}
waitKey(100);
Mat srcImage;
int key = -1;
int Thresholds[5][6] = {0, 10, 43, 255, 46, 255,//红1
156, 180, 43, 255, 46, 255,//红2
26, 34, 43, 255, 46, 255,//黄
35, 77, 43, 255, 46, 255,//绿
100, 124, 43, 255, 46, 255};//蓝
while(key != 27)
{
int redN = -1;
capture.read(srcImage);
int rows = srcImage.rows;
int cols = srcImage.cols;
if(srcImage.empty())
{
break;
}
srcImage = BlurforRGB(srcImage);
imshow("src", srcImage);
Mat outputHSV = RGB2HSV(srcImage);
int maxcol_area = 0;
int maxcol_col = -1;Rect maxA;
for(int c = 0; c < 5; ++c)
{
Mat Threnew = HSVThresholdPro(outputHSV, Thresholds[c][0], Thresholds[c][1],
Thresholds[c][2], Thresholds[c][3], Thresholds[c][4], Thresholds[c][5]);
/*对阈值截取处理过的二值图寻找轮廓*/
Mat dst = Mat::zeros(Threnew.rows, Threnew.cols, CV_8UC3);
vector<vector<Point> > contours;
vector<Vec4i> hierarchy;
findContours(Threnew, contours, hierarchy,
RETR_CCOMP, CHAIN_APPROX_SIMPLE);
/*找到的轮廓的矩形边界*/
Mat rectImage = srcImage.clone();
int idx = 0;
for (; idx >= 0 && !contours.empty(); idx = hierarchy[idx][0])/*遍历轮廓*/
{
Rect A = boundingRect(contours[idx]);
rectangle(rectImage, A, Scalar(0, 0, 255), 2);
if (idx == 0)/*记录最大的矩形*/
{
maxA = A;
}
else if(A.area() > maxA.area())
{
maxA = A;
}
if (hierarchy[idx][0] <= 0)break;
}
rectangle(srcImage, maxA, Scalar(0, 0, 255), 3);
if(c == 0 || c==1)imshow("red", srcImage);
if(maxA.area() > rows * cols / 16)
{
if(maxA.area() > maxcol_area)
{
maxcol_area = maxA.area();
maxcol_col = c;
}
}
else
{
continue;
}
}
if(maxcol_area)
{
redN = maxcol_col;
}
else
{
redN = -1;//没有有效颜色
}
cout<<maxA.area()<<endl<<rows * cols / 4<<endl;
if( redN == 1)
{
//redN 图像程序输出的值
twist.linear.x = 0.3;//线速度
twist.linear.y = 0;
twist.linear.z = 0;
twist.angular.x = 0;
twist.angular.y = 0;
twist.angular.z = 0;//角速度
ROS_WARN("****red****");//调试使用,打印输出(可以看程序执行到哪里)
cmd_pub.publish(twist);//发布消息
cout<<"red";
}
else if(redN == 2)
{
//redN 图像程序输出的值
twist.linear.x = 0;//线速度
twist.linear.y = 0;
twist.linear.z = 0;
twist.angular.x = 0;
twist.angular.y = 0;
twist.angular.z = -0.7;//角速度
ROS_WARN("*****cmd");//调试使用,打印输出(可以看程序执行到哪里)
cmd_pub.publish(twist);//发布消息
cout<<"yellow";
}
else if(redN == 3)
{
//redN 图像程序输出的值
twist.linear.x = -0.3;//线速度
twist.linear.y = 0;
twist.linear.z = 0;
twist.angular.x = 0;
twist.angular.y = 0;
twist.angular.z = 0;//角速度
ROS_WARN("*****cmd");//调试使用,打印输出(可以看程序执行到哪里)
cmd_pub.publish(twist);//发布消息
cout<<"green";
}
else if(redN == 4)
{
//redN 图像程序输出的值
twist.linear.x = 0;//线速度
twist.linear.y = 0;
twist.linear.z = 0;
twist.angular.x = 0;
twist.angular.y = 0;
twist.angular.z = 0.7;//角速度
ROS_WARN("*****cmd");//调试使用,打印输出(可以看程序执行到哪里)
cmd_pub.publish(twist);//发布消息
cout<<"blue";
}
else
{
//redN 图像程序输出的值
twist.linear.x = 0;//线速度
twist.linear.y = 0;
twist.linear.z = 0;
twist.angular.x = 0;
twist.angular.y = 0;
twist.angular.z = 0;//角速度
ROS_WARN("*****cmd");//调试使用,打印输出(可以看程序执行到哪里)
cmd_pub.publish(twist);//发布消息
cout<<"Null";
}
ros::spinOnce();
key = waitKey(1);
}
return 0;
}
结果
略