添加注释

This commit is contained in:
xinyang
2019-08-15 15:57:27 +08:00
parent ae059cb572
commit d650907319
4 changed files with 34 additions and 84 deletions

View File

@@ -8,7 +8,7 @@
ArmorBox::ArmorBox(const cv::Rect &pos, const LightBlobs &blobs, uint8_t color, int i) :
rect(pos), light_blobs(blobs), box_color(color), id(i) {};
// 获取装甲板中心点
cv::Point2f ArmorBox::getCenter() const {
return cv::Point2f(
rect.x + rect.width / 2,
@@ -16,7 +16,7 @@ cv::Point2f ArmorBox::getCenter() const {
);
}
// 获取两个灯条中心点的间距
double ArmorBox::getBlobsDistance() const {
if (light_blobs.size() == 2) {
auto &x = light_blobs[0].rect.center;
@@ -27,6 +27,7 @@ double ArmorBox::getBlobsDistance() const {
}
}
// 获取灯条长度和间距的比例
double ArmorBox::lengthDistanceRatio() const {
if (light_blobs.size() == 2) {
return max(light_blobs[0].length, light_blobs[1].length)
@@ -36,6 +37,7 @@ double ArmorBox::lengthDistanceRatio() const {
}
}
// 计算装甲板到摄像头的距离
double ArmorBox::getBoxDistance() const {
if (light_blobs.size() == 2) {
return DISTANCE_HEIGHT / 2 / max(light_blobs[0].length, light_blobs[1].length);
@@ -44,8 +46,8 @@ double ArmorBox::getBoxDistance() const {
}
}
// 判断装甲板的正对还是侧对(已弃用,误差过大)
ArmorBox::BoxOrientation ArmorBox::getOrientation() const {
// cout << lengthDistanceRatio() << endl;
if (light_blobs.size() != 2) {
return UNKNOWN;
}
@@ -78,7 +80,7 @@ ArmorBox::BoxOrientation ArmorBox::getOrientation() const {
return UNKNOWN;
}
}
// 装甲板的优先级比较
bool ArmorBox::operator<(const ArmorBox &box) const {
if (id != box.id) {
if (box_color == BOX_BLUE) {

View File

@@ -11,7 +11,7 @@
#include <log.h>
// 判断两个灯条的角度差
static bool angelJudge(const LightBlob &light_blob_i, const LightBlob &light_blob_j) {
float angle_i = light_blob_i.rect.size.width > light_blob_i.rect.size.height ? light_blob_i.rect.angle :
light_blob_i.rect.angle - 90;
@@ -19,19 +19,19 @@ static bool angelJudge(const LightBlob &light_blob_i, const LightBlob &light_blo
light_blob_j.rect.angle - 90;
return abs(angle_i - angle_j) < 20;
}
// 判断两个灯条的高度差
static bool heightJudge(const LightBlob &light_blob_i, const LightBlob &light_blob_j) {
cv::Point2f centers = light_blob_i.rect.center - light_blob_j.rect.center;
return abs(centers.y) < 30;
}
// 判断两个灯条的间距
static bool lengthJudge(const LightBlob &light_blob_i, const LightBlob &light_blob_j) {
double side_length;
cv::Point2f centers = light_blob_i.rect.center - light_blob_j.rect.center;
side_length = sqrt(centers.ddot(centers));
return (side_length / light_blob_i.length < 10 && side_length / light_blob_i.length > 0.5);
}
// 判断两个灯条的长度比
static bool lengthRatioJudge(const LightBlob &light_blob_i, const LightBlob &light_blob_j) {
return (light_blob_i.length / light_blob_j.length < 2.5
&& light_blob_i.length / light_blob_j.length > 0.4);
@@ -52,7 +52,7 @@ static bool CuoWeiDuJudge(const LightBlob &light_blob_i, const LightBlob &light_
light_blob_j.rect.center.y - light_blob_i.rect.center.y);
return abs(orientation.dot(p2p)) < 25;
}
// 判断装甲板方向
static bool boxAngleJudge(const LightBlob &light_blob_i, const LightBlob &light_blob_j) {
float angle_i = light_blob_i.rect.size.width > light_blob_i.rect.size.height ? light_blob_i.rect.angle :
light_blob_i.rect.angle - 90;
@@ -64,7 +64,7 @@ static bool boxAngleJudge(const LightBlob &light_blob_i, const LightBlob &light_
}
return (-120.0 < angle && angle < -60.0) || (60.0 < angle && angle < 120.0);
}
// 判断两个灯条是否可以匹配
static bool isCoupleLight(const LightBlob &light_blob_i, const LightBlob &light_blob_j, uint8_t enemy_color) {
return light_blob_i.blob_color == enemy_color &&
light_blob_j.blob_color == enemy_color &&
@@ -76,13 +76,7 @@ static bool isCoupleLight(const LightBlob &light_blob_i, const LightBlob &light_
CuoWeiDuJudge(light_blob_i, light_blob_j);
}
static double centerDistance(const cv::Rect2d &box) {
double dx = box.x - box.width / 2 - 320;
double dy = box.y - box.height / 2 - 240;
return dx * dx + dy * dy;
}
// 匹配所有灯条,得出装甲板候选区
bool ArmorFinder::matchArmorBoxes(const cv::Mat &src, const LightBlobs &light_blobs, ArmorBoxes &armor_boxes) {
armor_boxes.clear();
for (int i = 0; i < light_blobs.size() - 1; ++i) {
@@ -113,32 +107,34 @@ bool ArmorFinder::matchArmorBoxes(const cv::Mat &src, const LightBlobs &light_bl
}
return !armor_boxes.empty();
}
// 在给定的图像上寻找装甲板
bool ArmorFinder::findArmorBox(const cv::Mat &src, ArmorBox &box) {
LightBlobs light_blobs; // 存储所有可能的灯条
ArmorBoxes armor_boxes; // 装甲板候选区
box.rect = cv::Rect2d(0, 0, 0, 0);
box.id = -1;
// 寻找所有可能的灯条
CNT_TIME("blob", {
if (!findLightBlobs(src, light_blobs)) {
return false;
}
});
if (show_light_blobs && src.size() == cv::Size(640, 480)) {
if (show_light_blobs && state==SEARCHING_STATE) {
showLightBlobs("light_blobs", src, light_blobs);
cv::waitKey(1);
}
// 对灯条进行匹配得出装甲板候选区
CNT_TIME("boxes", {
if (!matchArmorBoxes(src, light_blobs, armor_boxes)) {
return false;
}
});
if (show_armor_boxes && src.size() == cv::Size(640, 480)) {
if (show_armor_boxes && state==SEARCHING_STATE) {
showArmorBoxes("boxes", src, armor_boxes);
cv::waitKey(1);
}
// 如果分类器可用,则使用分类器对装甲板候选区进行筛选
if (classifier) {
CNT_TIME("classify: %d", {
for (auto &armor_box : armor_boxes) {
@@ -148,6 +144,7 @@ bool ArmorFinder::findArmorBox(const cv::Mat &src, ArmorBox &box) {
armor_box.id = c;
}
}, armor_boxes.size());
// 按照优先级对装甲板进行排序
sort(armor_boxes.begin(), armor_boxes.end(), [&](const ArmorBox &a, const ArmorBox &b) {
if (last_box.rect != cv::Rect2d()) {
return getPointLength(a.getCenter() - last_box.getCenter()) <
@@ -174,10 +171,10 @@ bool ArmorFinder::findArmorBox(const cv::Mat &src, ArmorBox &box) {
if (box.rect == cv::Rect2d(0, 0, 0, 0)) {
return false;
}
if (show_armor_boxes && src.size() == cv::Size(640, 480)) {
if (show_armor_boxes && state==SEARCHING_STATE) {
showArmorBoxesClass("class", src, armor_boxes);
}
} else {
} else { // 如果分类器不可用,则直接选取候选区中的第一个区域作为目标(往往会误识别)
box = armor_boxes[0];
}
return true;

View File

@@ -6,25 +6,24 @@
#include <options.h>
#include <opencv2/highgui.hpp>
// 旋转矩形的长宽比
static double lw_rate(const cv::RotatedRect &rect) {
return rect.size.height > rect.size.width ?
rect.size.height / rect.size.width :
rect.size.width / rect.size.height;
}
// 轮廓面积和其最小外接矩形面积之比
static double areaRatio(const std::vector<cv::Point> &contour, const cv::RotatedRect &rect) {
return cv::contourArea(contour) / rect.size.area();
}
// 判断轮廓是否为一个灯条
static bool isValidLightBlob(const std::vector<cv::Point> &contour, const cv::RotatedRect &rect) {
return (1.2 < lw_rate(rect) && lw_rate(rect) < 10) &&
// (rect.size.area() < 3000) &&
((rect.size.area() < 50 && areaRatio(contour, rect) > 0.4) ||
(rect.size.area() >= 50 && areaRatio(contour, rect) > 0.6));
}
// 此函数可以有性能优化.
// 判断灯条颜色(此函数可以有性能优化).
static uint8_t get_blob_color(const cv::Mat &src, const cv::RotatedRect &blobPos) {
auto region = blobPos.boundingRect();
region.x -= fmax(3, region.width * 0.1);
@@ -46,60 +45,12 @@ static uint8_t get_blob_color(const cv::Mat &src, const cv::RotatedRect &blobPos
return BLOB_BLUE;
}
}
static float linePointX(const cv::Point2f &p1, const cv::Point2f &p2, int y) {
return (p2.x - p1.x) / (p2.y - p1.y) * (y - p1.y) + p1.x;
}
/// Todo:性能优化后的函数(还有点问题)
static double get_blob_color_opt(const cv::Mat &src, cv::RotatedRect blobPos) {
int blue_cnt = 0, red_cnt = 0;
blobPos.size.height *= 1.05;
blobPos.size.width *= 1.1;
cv::Point2f corners[4];
blobPos.points(corners);
sort(corners, &corners[4], [](cv::Point2f p1, cv::Point2f p2) {
return p1.y < p2.y;
});
for (int r = corners[0].y; r < corners[1].y; r++) {
auto start = min(linePointX(corners[0], corners[1], r), linePointX(corners[0], corners[2], r)) - 1;
auto end = max(linePointX(corners[0], corners[1], r), linePointX(corners[0], corners[2], r)) + 1;
if (start < 0 || end > 640) return 0;
for (int c = start; c < end; c++) {
red_cnt += src.at<cv::Vec3b>(r, c)[2];
blue_cnt += src.at<cv::Vec3b>(r, c)[0];
}
}
for (int r = corners[1].y; r < corners[2].y; r++) {
auto start = min(linePointX(corners[0], corners[2], r), linePointX(corners[1], corners[3], r)) - 1;
auto end = max(linePointX(corners[0], corners[2], r), linePointX(corners[1], corners[3], r)) + 1;
if (start < 0 || end > 640) return 0;
for (int c = start; c < end; c++) {
red_cnt += src.at<cv::Vec3b>(r, c)[2];
blue_cnt += src.at<cv::Vec3b>(r, c)[0];
}
}
for (int r = corners[2].y; r < corners[3].y; r++) {
auto start = min(linePointX(corners[1], corners[3], r), linePointX(corners[2], corners[3], r)) - 1;
auto end = max(linePointX(corners[1], corners[3], r), linePointX(corners[2], corners[3], r)) + 1;
if (start < 0 || end > 640) return 0;
for (int c = start; c < end; c++) {
red_cnt += src.at<cv::Vec3b>(r, c)[2];
blue_cnt += src.at<cv::Vec3b>(r, c)[0];
}
}
if (red_cnt > blue_cnt) {
return BLOB_RED;
} else {
return BLOB_BLUE;
}
}
// 判断两个灯条区域是同一个灯条
static bool isSameBlob(LightBlob blob1, LightBlob blob2) {
auto dist = blob1.rect.center - blob2.rect.center;
return (dist.x * dist.x + dist.y * dist.y) < 9;
}
// 开闭运算
static void imagePreProcess(cv::Mat &src) {
static cv::Mat kernel_erode = getStructuringElement(cv::MORPH_RECT, cv::Size(3, 5));
erode(src, src, kernel_erode);
@@ -112,12 +63,8 @@ static void imagePreProcess(cv::Mat &src) {
static cv::Mat kernel_erode2 = getStructuringElement(cv::MORPH_RECT, cv::Size(3, 5));
erode(src, src, kernel_erode2);
// float alpha = 1.5;
// int beta = 0;
// src.convertTo(src, -1, alpha, beta);
}
// 在给定图像上寻找所有可能的灯条
bool ArmorFinder::findLightBlobs(const cv::Mat &src, LightBlobs &light_blobs) {
cv::Mat color_channel;
cv::Mat src_bin_light, src_bin_dim;
@@ -148,7 +95,8 @@ bool ArmorFinder::findLightBlobs(const cv::Mat &src, LightBlobs &light_blobs) {
imshow("bin_light", src_bin_light);
imshow("bin_dim", src_bin_dim);
}
// 使用两个不同的二值化阈值同时进行灯条提取,减少环境光照对二值化这个操作的影响。
// 同时剔除重复的灯条,剔除冗余计算,即对两次找出来的灯条取交集。
std::vector<std::vector<cv::Point>> light_contours_light, light_contours_dim;
LightBlobs light_blobs_light, light_blobs_dim;
std::vector<cv::Vec4i> hierarchy_light, hierarchy_dim;

View File

@@ -1,3 +1,6 @@
// 本文件定义了在不同步兵车辆上运行时需要根据车辆情况而发生变化的参数
// 以下所有参数都给定了默认值如果想要修改推荐在该文件目录下新建文件config.h并在config.h中写定自定义参数
#ifndef _SETCONFIG_H_
#define _SETCONFIG_H_