Compare commits
15 Commits
41a31f1c18
...
master
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
4a640cf7db | ||
| 12a02f382a | |||
| 3eb2d39942 | |||
| c0ee469118 | |||
| a133dea09a | |||
| 15be04d1f7 | |||
|
|
7770503779 | ||
|
|
5cf1a30ea0 | ||
|
|
7f6e2f4e6e | ||
|
|
0b1f5ff47f | ||
|
|
e1eb8b2590 | ||
|
|
b24542e97c | ||
|
|
de94ff2242 | ||
|
|
d5df7ce7da | ||
|
|
ef257b7df0 |
3
.gitignore
vendored
3
.gitignore
vendored
@@ -1,6 +1,9 @@
|
|||||||
cmake-build-debug
|
cmake-build-debug
|
||||||
build
|
build
|
||||||
.idea
|
.idea
|
||||||
|
.xmake
|
||||||
|
.vscode/.cache
|
||||||
|
.vscode/compile_commands.json
|
||||||
Mark
|
Mark
|
||||||
armor_box_photo
|
armor_box_photo
|
||||||
tools/TrainCNN/.idea
|
tools/TrainCNN/.idea
|
||||||
|
|||||||
8
.vscode/settings.json
vendored
Normal file
8
.vscode/settings.json
vendored
Normal file
@@ -0,0 +1,8 @@
|
|||||||
|
{
|
||||||
|
"clangd.arguments": [
|
||||||
|
"--compile-commands-dir=${workspaceFolder}/build",
|
||||||
|
"--completion-style=detailed",
|
||||||
|
"--query-driver=/usr/bin/clang",
|
||||||
|
"--header-insertion=never"
|
||||||
|
],
|
||||||
|
}
|
||||||
@@ -8,6 +8,8 @@ SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DPATH=\"\\\"${PROJECT_SOURCE_DIR}\\\"\"
|
|||||||
SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -D${CMAKE_SYSTEM_NAME}")
|
SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -D${CMAKE_SYSTEM_NAME}")
|
||||||
SET(BIN_NAME "run")
|
SET(BIN_NAME "run")
|
||||||
|
|
||||||
|
SET(CMAKE_EXPORT_COMPILE_COMMANDS ON)
|
||||||
|
|
||||||
|
|
||||||
FIND_FILE(CONFIG_FOUND "config.h" "others/include/config")
|
FIND_FILE(CONFIG_FOUND "config.h" "others/include/config")
|
||||||
if (CONFIG_FOUND)
|
if (CONFIG_FOUND)
|
||||||
@@ -24,7 +26,7 @@ IF(CCACHE_FOUND)
|
|||||||
ENDIF()
|
ENDIF()
|
||||||
|
|
||||||
FIND_PACKAGE(Eigen3 REQUIRED)
|
FIND_PACKAGE(Eigen3 REQUIRED)
|
||||||
FIND_PACKAGE(OpenCV 3 REQUIRED)
|
FIND_PACKAGE(OpenCV 4 REQUIRED)
|
||||||
FIND_PACKAGE(Threads)
|
FIND_PACKAGE(Threads)
|
||||||
|
|
||||||
LINK_DIRECTORIES(${PROJECT_SOURCE_DIR}/others)
|
LINK_DIRECTORIES(${PROJECT_SOURCE_DIR}/others)
|
||||||
|
|||||||
21
LICENSE
Normal file
21
LICENSE
Normal file
@@ -0,0 +1,21 @@
|
|||||||
|
MIT License
|
||||||
|
|
||||||
|
Copyright (c) 2019 xinyang
|
||||||
|
|
||||||
|
Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||||
|
of this software and associated documentation files (the "Software"), to deal
|
||||||
|
in the Software without restriction, including without limitation the rights
|
||||||
|
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||||
|
copies of the Software, and to permit persons to whom the Software is
|
||||||
|
furnished to do so, subject to the following conditions:
|
||||||
|
|
||||||
|
The above copyright notice and this permission notice shall be included in all
|
||||||
|
copies or substantial portions of the Software.
|
||||||
|
|
||||||
|
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||||
|
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||||
|
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||||
|
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||||
|
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||||
|
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||||
|
SOFTWARE.
|
||||||
12
README.md
12
README.md
@@ -13,6 +13,12 @@
|
|||||||
|
|
||||||
**如有BUG或者想交流的朋友欢迎积极联系我们**
|
**如有BUG或者想交流的朋友欢迎积极联系我们**
|
||||||
|
|
||||||
|
**分享部分比赛时摄像头录制的视频:**
|
||||||
|
|
||||||
|
链接: https://pan.baidu.com/s/1LwxEpeYYblX3cSzb59MTVg 提取码: 84ju 复制这段内容后打开百度网盘手机App,操作更方便哦
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
运行效果:自瞄帧率120(摄像头最大帧率),识别距离根据环境不同大约8米左右(5mm焦距镜头)。
|
运行效果:自瞄帧率120(摄像头最大帧率),识别距离根据环境不同大约8米左右(5mm焦距镜头)。
|
||||||
|
|
||||||

|

|
||||||
@@ -24,6 +30,8 @@
|
|||||||
| ---------------------------------------------------- | -------------------------------------------- | ------------------------------------------------------------ | ---------------------------------------------------------- |
|
| ---------------------------------------------------- | -------------------------------------------- | ------------------------------------------------------------ | ---------------------------------------------------------- |
|
||||||
| IntelNUC<br />MindVision工业相机×1<br />USB转TTL×1 | Ubuntu18.04<br />Ubuntu16.04<br />Windows10 | OpenCV3.4.5<br />OpenCV_contrib3.4.5<br />Eigen3<br />MindVision相机驱动 | Ubuntu18/16 : cmake3+gcc7+g++7 <br />Win10 : cmake3+VS2019 |
|
| IntelNUC<br />MindVision工业相机×1<br />USB转TTL×1 | Ubuntu18.04<br />Ubuntu16.04<br />Windows10 | OpenCV3.4.5<br />OpenCV_contrib3.4.5<br />Eigen3<br />MindVision相机驱动 | Ubuntu18/16 : cmake3+gcc7+g++7 <br />Win10 : cmake3+VS2019 |
|
||||||
|
|
||||||
|
MindVision相机型号:MV-UBS31GC
|
||||||
|
|
||||||
**关于Windows环境下的运行支持,仅保证程序可以编译运行。对与部分辅助功能,如生成自启动脚本则不支持。**
|
**关于Windows环境下的运行支持,仅保证程序可以编译运行。对与部分辅助功能,如生成自启动脚本则不支持。**
|
||||||
|
|
||||||
**实际装载在步兵和哨兵上的运行环境为Ubuntu18.04。**
|
**实际装载在步兵和哨兵上的运行环境为Ubuntu18.04。**
|
||||||
@@ -60,6 +68,8 @@ sudo ./run
|
|||||||
|
|
||||||
```./run --help```可以查看所有命令行参数及其作用。所有调试选项都集成到了命令行参数中。
|
```./run --help```可以查看所有命令行参数及其作用。所有调试选项都集成到了命令行参数中。
|
||||||
|
|
||||||
|
**不使用任何参数直接运行将没有任何图像显示。**
|
||||||
|
|
||||||
需要调参的部分:主要需要根据车辆情况而调参的参数存放在others/include/config/setconfig.h中
|
需要调参的部分:主要需要根据车辆情况而调参的参数存放在others/include/config/setconfig.h中
|
||||||
|
|
||||||
### 3.工作条件
|
### 3.工作条件
|
||||||
@@ -118,7 +128,7 @@ sudo ./run
|
|||||||
### 1.自瞄装甲板识别方式
|
### 1.自瞄装甲板识别方式
|
||||||
|
|
||||||
首先对图像进行通道拆分以及二值化操作,再进行开闭运算,通过边缘提取和条件限制得出可能为灯条的部分。再对所有可能的灯条进行两两匹配,根据形状大小特性进行筛选,得出可能为装甲板的候选区。然后把所有候选区交给分类器判断,得出真实的装甲板及其数字id。最后根据优先级选取最终击打目标以及后续处理。
|
首先对图像进行通道拆分以及二值化操作,再进行开闭运算,通过边缘提取和条件限制得出可能为灯条的部分。再对所有可能的灯条进行两两匹配,根据形状大小特性进行筛选,得出可能为装甲板的候选区。然后把所有候选区交给分类器判断,得出真实的装甲板及其数字id。最后根据优先级选取最终击打目标以及后续处理。
|
||||||
|

|
||||||
### 2.能量机关识别方式
|
### 2.能量机关识别方式
|
||||||
|
|
||||||
首先对图像进行二值化操作,然后进行一定腐蚀和膨胀,通过边缘提取和条件限制得出待击打叶片(锤子形)。在待击打叶片范围内进一步用类似方法寻找目标装甲板和流动条,在二者连线上寻找中心的“R”。根据目标装甲板坐标和中心坐标计算极坐标系下的目标角度,进而预测待击打点的坐标(小符为装甲板本身,大符需要旋转)。最后将待击打点坐标和图像中心的差值转换为yaw和pitch轴角度,增加一环PID后发送给云台主控板。
|
首先对图像进行二值化操作,然后进行一定腐蚀和膨胀,通过边缘提取和条件限制得出待击打叶片(锤子形)。在待击打叶片范围内进一步用类似方法寻找目标装甲板和流动条,在二者连线上寻找中心的“R”。根据目标装甲板坐标和中心坐标计算极坐标系下的目标角度,进而预测待击打点的坐标(小符为装甲板本身,大符需要旋转)。最后将待击打点坐标和图像中心的差值转换为yaw和pitch轴角度,增加一环PID后发送给云台主控板。
|
||||||
|
|||||||
@@ -9,7 +9,7 @@
|
|||||||
#include <systime.h>
|
#include <systime.h>
|
||||||
#include <constants.h>
|
#include <constants.h>
|
||||||
#include <opencv2/core.hpp>
|
#include <opencv2/core.hpp>
|
||||||
#include <opencv2/tracking.hpp>
|
#include <opencv2/tracking/tracking.hpp>
|
||||||
#include <serial.h>
|
#include <serial.h>
|
||||||
#include <armor_finder/classifier/classifier.h>
|
#include <armor_finder/classifier/classifier.h>
|
||||||
#include <additions.h>
|
#include <additions.h>
|
||||||
@@ -20,8 +20,8 @@
|
|||||||
#define BOX_RED ENEMY_RED
|
#define BOX_RED ENEMY_RED
|
||||||
#define BOX_BLUE ENEMY_BLUE
|
#define BOX_BLUE ENEMY_BLUE
|
||||||
|
|
||||||
#define IMAGE_CENTER_X (320)
|
#define IMAGE_CENTER_X (640)
|
||||||
#define IMAGE_CENTER_Y (240-20)
|
#define IMAGE_CENTER_Y (512-20)
|
||||||
|
|
||||||
#define DISTANCE_HEIGHT_5MM (10700.0) // 单位: cm*pixel
|
#define DISTANCE_HEIGHT_5MM (10700.0) // 单位: cm*pixel
|
||||||
#define DISTANCE_HEIGHT DISTANCE_HEIGHT_5MM
|
#define DISTANCE_HEIGHT DISTANCE_HEIGHT_5MM
|
||||||
@@ -120,6 +120,10 @@ private:
|
|||||||
vector<systime> time_seq; // 一个周期内的时间采样点
|
vector<systime> time_seq; // 一个周期内的时间采样点
|
||||||
vector<float> angle_seq; // 一个周期内的角度采样点
|
vector<float> angle_seq; // 一个周期内的角度采样点
|
||||||
|
|
||||||
|
float yaw_rotation, pitch_rotation;//云台yaw轴和pitch轴应该转到的角度
|
||||||
|
float last_yaw, last_pitch;//PID中微分项
|
||||||
|
float sum_yaw, sum_pitch;//yaw和pitch的累计误差,即PID中积分项
|
||||||
|
|
||||||
bool findLightBlobs(const cv::Mat &src, LightBlobs &light_blobs);
|
bool findLightBlobs(const cv::Mat &src, LightBlobs &light_blobs);
|
||||||
bool findArmorBox(const cv::Mat &src, ArmorBox &box);
|
bool findArmorBox(const cv::Mat &src, ArmorBox &box);
|
||||||
bool matchArmorBoxes(const cv::Mat &src, const LightBlobs &light_blobs, ArmorBoxes &armor_boxes);
|
bool matchArmorBoxes(const cv::Mat &src, const LightBlobs &light_blobs, ArmorBoxes &armor_boxes);
|
||||||
|
|||||||
@@ -67,7 +67,7 @@ void ArmorFinder::run(cv::Mat &src) {
|
|||||||
if ((target_box.rect & cv::Rect2d(0, 0, 640, 480)) == target_box.rect) { // 判断装甲板区域是否脱离图像区域
|
if ((target_box.rect & cv::Rect2d(0, 0, 640, 480)) == target_box.rect) { // 判断装甲板区域是否脱离图像区域
|
||||||
if (!classifier) { /* 如果分类器不可用 */
|
if (!classifier) { /* 如果分类器不可用 */
|
||||||
cv::Mat roi = src(target_box.rect).clone(), roi_gray; /* 就使用装甲区域亮点数判断是否跟丢 */
|
cv::Mat roi = src(target_box.rect).clone(), roi_gray; /* 就使用装甲区域亮点数判断是否跟丢 */
|
||||||
cv::cvtColor(roi, roi_gray, CV_RGB2GRAY);
|
cv::cvtColor(roi, roi_gray, cv::COLOR_RGB2GRAY);
|
||||||
cv::threshold(roi_gray, roi_gray, 180, 255, cv::THRESH_BINARY);
|
cv::threshold(roi_gray, roi_gray, 180, 255, cv::THRESH_BINARY);
|
||||||
contour_area = cv::countNonZero(roi_gray);
|
contour_area = cv::countNonZero(roi_gray);
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -156,6 +156,7 @@ bool ArmorFinder::findArmorBox(const cv::Mat &src, ArmorBox &box) {
|
|||||||
for (auto &one_box : armor_boxes) {
|
for (auto &one_box : armor_boxes) {
|
||||||
if (one_box.id != 0) {
|
if (one_box.id != 0) {
|
||||||
box = one_box;
|
box = one_box;
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (save_labelled_boxes) {
|
if (save_labelled_boxes) {
|
||||||
|
|||||||
@@ -83,11 +83,11 @@ bool ArmorFinder::findLightBlobs(const cv::Mat &src, LightBlobs &light_blobs) {
|
|||||||
}else{
|
}else{
|
||||||
light_threshold = 200;
|
light_threshold = 200;
|
||||||
}
|
}
|
||||||
cv::threshold(color_channel, src_bin_light, light_threshold, 255, CV_THRESH_BINARY); // 二值化对应通道
|
cv::threshold(color_channel, src_bin_light, light_threshold, 255, cv::THRESH_BINARY); // 二值化对应通道
|
||||||
if (src_bin_light.empty()) return false;
|
if (src_bin_light.empty()) return false;
|
||||||
imagePreProcess(src_bin_light); // 开闭运算
|
imagePreProcess(src_bin_light); // 开闭运算
|
||||||
|
|
||||||
cv::threshold(color_channel, src_bin_dim, 140, 255, CV_THRESH_BINARY); // 二值化对应通道
|
cv::threshold(color_channel, src_bin_dim, 140, 255, cv::THRESH_BINARY); // 二值化对应通道
|
||||||
if (src_bin_dim.empty()) return false;
|
if (src_bin_dim.empty()) return false;
|
||||||
imagePreProcess(src_bin_dim); // 开闭运算
|
imagePreProcess(src_bin_dim); // 开闭运算
|
||||||
|
|
||||||
@@ -100,8 +100,8 @@ bool ArmorFinder::findLightBlobs(const cv::Mat &src, LightBlobs &light_blobs) {
|
|||||||
std::vector<std::vector<cv::Point>> light_contours_light, light_contours_dim;
|
std::vector<std::vector<cv::Point>> light_contours_light, light_contours_dim;
|
||||||
LightBlobs light_blobs_light, light_blobs_dim;
|
LightBlobs light_blobs_light, light_blobs_dim;
|
||||||
std::vector<cv::Vec4i> hierarchy_light, hierarchy_dim;
|
std::vector<cv::Vec4i> hierarchy_light, hierarchy_dim;
|
||||||
cv::findContours(src_bin_light, light_contours_light, hierarchy_light, CV_RETR_CCOMP, CV_CHAIN_APPROX_NONE);
|
cv::findContours(src_bin_light, light_contours_light, hierarchy_light, cv::RETR_CCOMP, cv::CHAIN_APPROX_NONE);
|
||||||
cv::findContours(src_bin_dim, light_contours_dim, hierarchy_dim, CV_RETR_CCOMP, CV_CHAIN_APPROX_NONE);
|
cv::findContours(src_bin_dim, light_contours_dim, hierarchy_dim, cv::RETR_CCOMP, cv::CHAIN_APPROX_NONE);
|
||||||
for (int i = 0; i < light_contours_light.size(); i++) {
|
for (int i = 0; i < light_contours_light.size(); i++) {
|
||||||
if (hierarchy_light[i][2] == -1) {
|
if (hierarchy_light[i][2] == -1) {
|
||||||
cv::RotatedRect rect = cv::minAreaRect(light_contours_light[i]);
|
cv::RotatedRect rect = cv::minAreaRect(light_contours_light[i]);
|
||||||
|
|||||||
@@ -22,6 +22,8 @@ static bool sendTarget(Serial &serial, double x, double y, double z, uint16_t sh
|
|||||||
fps += 1;
|
fps += 1;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#define MINMAX(value, min, max) value = ((value) < (min)) ? (min) : ((value) > (max) ? (max) : (value))
|
||||||
|
|
||||||
x_tmp = static_cast<short>(x * (32768 - 1) / 100);
|
x_tmp = static_cast<short>(x * (32768 - 1) / 100);
|
||||||
y_tmp = static_cast<short>(y * (32768 - 1) / 100);
|
y_tmp = static_cast<short>(y * (32768 - 1) / 100);
|
||||||
z_tmp = static_cast<short>(z * (32768 - 1) / 1000);
|
z_tmp = static_cast<short>(z * (32768 - 1) / 1000);
|
||||||
@@ -49,6 +51,24 @@ bool ArmorFinder::sendBoxPosition(uint16_t shoot_delay) {
|
|||||||
auto rect = target_box.rect;
|
auto rect = target_box.rect;
|
||||||
double dx = rect.x + rect.width / 2 - IMAGE_CENTER_X;
|
double dx = rect.x + rect.width / 2 - IMAGE_CENTER_X;
|
||||||
double dy = rect.y + rect.height / 2 - IMAGE_CENTER_Y;
|
double dy = rect.y + rect.height / 2 - IMAGE_CENTER_Y;
|
||||||
|
|
||||||
|
// PID
|
||||||
|
sum_yaw += dx;
|
||||||
|
sum_pitch += dy;
|
||||||
|
float yaw_I_component = YAW_AIM_KI * sum_yaw;
|
||||||
|
float pitch_I_component = PITCH_AIM_KI * sum_pitch;
|
||||||
|
|
||||||
|
double tmp_yaw = dx;
|
||||||
|
double tmp_pitch = dy;
|
||||||
|
dx = YAW_AIM_KP * dx + YAW_AIM_KI * sum_yaw +
|
||||||
|
YAW_AIM_KD * (dx - last_yaw);
|
||||||
|
dy = PITCH_AIM_KP * dy + PITCH_AIM_KI * sum_pitch +
|
||||||
|
PITCH_AIM_KD * (dy - last_pitch);
|
||||||
|
|
||||||
|
last_yaw = tmp_yaw;
|
||||||
|
last_pitch = tmp_pitch;
|
||||||
|
//
|
||||||
|
|
||||||
double yaw = atan(dx / FOCUS_PIXAL) * 180 / PI;
|
double yaw = atan(dx / FOCUS_PIXAL) * 180 / PI;
|
||||||
double pitch = atan(dy / FOCUS_PIXAL) * 180 / PI;
|
double pitch = atan(dy / FOCUS_PIXAL) * 180 / PI;
|
||||||
double dist = DISTANCE_HEIGHT / rect.height;
|
double dist = DISTANCE_HEIGHT / rect.height;
|
||||||
|
|||||||
@@ -8,13 +8,13 @@
|
|||||||
#include <show_images/show_images.h>
|
#include <show_images/show_images.h>
|
||||||
|
|
||||||
bool ArmorFinder::stateTrackingTarget(cv::Mat &src) {
|
bool ArmorFinder::stateTrackingTarget(cv::Mat &src) {
|
||||||
auto pos = target_box.rect;
|
cv::Rect pos(target_box.rect);
|
||||||
if(!tracker->update(src, pos)){ // 使用KCFTracker进行追踪
|
if(!tracker->update(src, pos)){ // 使用KCFTracker进行追踪
|
||||||
target_box = ArmorBox();
|
target_box = ArmorBox();
|
||||||
LOGW("Track fail!");
|
LOGW("Track fail!");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
if((pos & cv::Rect2d(0, 0, 640, 480)) != pos){
|
if((cv::Rect2d(pos) & cv::Rect2d(0, 0, 640, 480)) != cv::Rect2d(pos)){
|
||||||
target_box = ArmorBox();
|
target_box = ArmorBox();
|
||||||
LOGW("Track out range!");
|
LOGW("Track out range!");
|
||||||
return false;
|
return false;
|
||||||
@@ -52,7 +52,7 @@ bool ArmorFinder::stateTrackingTarget(cv::Mat &src) {
|
|||||||
}
|
}
|
||||||
}else{ // 分类器不可用,使用常规方法判断
|
}else{ // 分类器不可用,使用常规方法判断
|
||||||
cv::Mat roi_gray;
|
cv::Mat roi_gray;
|
||||||
cv::cvtColor(roi, roi_gray, CV_RGB2GRAY);
|
cv::cvtColor(roi, roi_gray, cv::COLOR_RGB2GRAY);
|
||||||
cv::threshold(roi_gray, roi_gray, 180, 255, cv::THRESH_BINARY);
|
cv::threshold(roi_gray, roi_gray, 180, 255, cv::THRESH_BINARY);
|
||||||
contour_area = cv::countNonZero(roi_gray);
|
contour_area = cv::countNonZero(roi_gray);
|
||||||
if(abs(cv::countNonZero(roi_gray) - contour_area) > contour_area * 0.3){
|
if(abs(cv::countNonZero(roi_gray) - contour_area) > contour_area * 0.3){
|
||||||
|
|||||||
@@ -21,12 +21,12 @@ int Energy::findFans(const cv::Mat &src) {
|
|||||||
static Mat src_bin;
|
static Mat src_bin;
|
||||||
src_bin = src.clone();
|
src_bin = src.clone();
|
||||||
if (src.type() == CV_8UC3) {
|
if (src.type() == CV_8UC3) {
|
||||||
cvtColor(src_bin, src_bin, CV_BGR2GRAY);//若读取三通道视频文件,需转换为单通道
|
cvtColor(src_bin, src_bin, cv::COLOR_BGR2GRAY);//若读取三通道视频文件,需转换为单通道
|
||||||
}
|
}
|
||||||
std::vector<vector<Point> > fan_contours;
|
std::vector<vector<Point> > fan_contours;
|
||||||
FanStruct(src_bin);//图像膨胀,防止图像断开并更方便寻找
|
FanStruct(src_bin);//图像膨胀,防止图像断开并更方便寻找
|
||||||
if (show_process)imshow("fan struct", src_bin);
|
if (show_process)imshow("fan struct", src_bin);
|
||||||
findContours(src_bin, fan_contours, CV_RETR_EXTERNAL, CV_CHAIN_APPROX_NONE);
|
findContours(src_bin, fan_contours, cv::RETR_EXTERNAL, cv::CHAIN_APPROX_NONE);
|
||||||
|
|
||||||
for (auto &fan_contour : fan_contours) {
|
for (auto &fan_contour : fan_contours) {
|
||||||
if (!isValidFanContour(src_bin, fan_contour)) {
|
if (!isValidFanContour(src_bin, fan_contour)) {
|
||||||
@@ -54,16 +54,16 @@ int Energy::findArmors(const cv::Mat &src) {
|
|||||||
static Mat src_bin;
|
static Mat src_bin;
|
||||||
src_bin = src.clone();
|
src_bin = src.clone();
|
||||||
if (src.type() == CV_8UC3) {
|
if (src.type() == CV_8UC3) {
|
||||||
cvtColor(src_bin, src_bin, CV_BGR2GRAY);//若读取三通道视频文件,需转换为单通道
|
cvtColor(src_bin, src_bin, cv::COLOR_BGR2GRAY);//若读取三通道视频文件,需转换为单通道
|
||||||
}
|
}
|
||||||
std::vector<vector<Point> > armor_contours;
|
std::vector<vector<Point> > armor_contours;
|
||||||
std::vector<vector<Point> > armor_contours_external;//用总轮廓减去外轮廓,只保留内轮廓,除去流动条的影响。
|
std::vector<vector<Point> > armor_contours_external;//用总轮廓减去外轮廓,只保留内轮廓,除去流动条的影响。
|
||||||
|
|
||||||
ArmorStruct(src_bin);//图像膨胀,防止图像断开并更方便寻找
|
ArmorStruct(src_bin);//图像膨胀,防止图像断开并更方便寻找
|
||||||
findContours(src_bin, armor_contours, CV_RETR_LIST, CV_CHAIN_APPROX_NONE);
|
findContours(src_bin, armor_contours, cv::RETR_LIST, cv::CHAIN_APPROX_NONE);
|
||||||
if (show_process)imshow("armor struct", src_bin);
|
if (show_process)imshow("armor struct", src_bin);
|
||||||
|
|
||||||
findContours(src_bin, armor_contours_external, CV_RETR_EXTERNAL, CV_CHAIN_APPROX_NONE);
|
findContours(src_bin, armor_contours_external, cv::RETR_EXTERNAL, cv::CHAIN_APPROX_NONE);
|
||||||
for (int i = 0; i < armor_contours_external.size(); i++)//去除外轮廓
|
for (int i = 0; i < armor_contours_external.size(); i++)//去除外轮廓
|
||||||
{
|
{
|
||||||
unsigned long external_contour_size = armor_contours_external[i].size();
|
unsigned long external_contour_size = armor_contours_external[i].size();
|
||||||
@@ -103,12 +103,12 @@ bool Energy::findCenterR(const cv::Mat &src) {
|
|||||||
static Mat src_bin;
|
static Mat src_bin;
|
||||||
src_bin = src.clone();
|
src_bin = src.clone();
|
||||||
if (src.type() == CV_8UC3) {
|
if (src.type() == CV_8UC3) {
|
||||||
cvtColor(src_bin, src_bin, CV_BGR2GRAY);
|
cvtColor(src_bin, src_bin, cv::COLOR_BGR2GRAY);
|
||||||
}
|
}
|
||||||
std::vector<vector<Point> > center_R_contours;
|
std::vector<vector<Point> > center_R_contours;
|
||||||
CenterRStruct(src_bin);
|
CenterRStruct(src_bin);
|
||||||
if (show_process)imshow("R struct", src_bin);
|
if (show_process)imshow("R struct", src_bin);
|
||||||
findContours(src_bin, center_R_contours, CV_RETR_EXTERNAL, CV_CHAIN_APPROX_NONE);
|
findContours(src_bin, center_R_contours, cv::RETR_EXTERNAL, cv::CHAIN_APPROX_NONE);
|
||||||
for (auto ¢er_R_contour : center_R_contours) {
|
for (auto ¢er_R_contour : center_R_contours) {
|
||||||
if (!isValidCenterRContour(center_R_contour)) {
|
if (!isValidCenterRContour(center_R_contour)) {
|
||||||
continue;
|
continue;
|
||||||
@@ -139,13 +139,13 @@ bool Energy::findFlowStripFan(const cv::Mat &src) {
|
|||||||
src_bin = src.clone();
|
src_bin = src.clone();
|
||||||
src_copy = src.clone();
|
src_copy = src.clone();
|
||||||
if (src.type() == CV_8UC3) {
|
if (src.type() == CV_8UC3) {
|
||||||
cvtColor(src_bin, src_bin, CV_BGR2GRAY);//若读取三通道视频文件,需转换为单通道
|
cvtColor(src_bin, src_bin, cv::COLOR_BGR2GRAY);//若读取三通道视频文件,需转换为单通道
|
||||||
}
|
}
|
||||||
std::vector<vector<Point> > flow_strip_fan_contours;
|
std::vector<vector<Point> > flow_strip_fan_contours;
|
||||||
FlowStripFanStruct(src_bin);//图像膨胀,防止图像断开并更方便寻找
|
FlowStripFanStruct(src_bin);//图像膨胀,防止图像断开并更方便寻找
|
||||||
if (show_process)imshow("flow strip fan struct", src_bin);
|
if (show_process)imshow("flow strip fan struct", src_bin);
|
||||||
|
|
||||||
findContours(src_bin, flow_strip_fan_contours, CV_RETR_EXTERNAL, CV_CHAIN_APPROX_NONE);
|
findContours(src_bin, flow_strip_fan_contours, cv::RETR_EXTERNAL, cv::CHAIN_APPROX_NONE);
|
||||||
std::vector<cv::RotatedRect> candidate_flow_strip_fans;
|
std::vector<cv::RotatedRect> candidate_flow_strip_fans;
|
||||||
|
|
||||||
for (auto &flow_strip_fan_contour : flow_strip_fan_contours) {
|
for (auto &flow_strip_fan_contour : flow_strip_fan_contours) {
|
||||||
@@ -175,7 +175,7 @@ bool Energy::findFlowStrip(const cv::Mat &src) {
|
|||||||
|
|
||||||
if (src_bin.type() == CV_8UC1) // 黑白图像
|
if (src_bin.type() == CV_8UC1) // 黑白图像
|
||||||
{
|
{
|
||||||
cvtColor(src_bin, src_bin, COLOR_GRAY2RGB);
|
cvtColor(src_bin, src_bin, cv::COLOR_GRAY2RGB);
|
||||||
|
|
||||||
}
|
}
|
||||||
std::vector<cv::RotatedRect> candidate_target_armors = target_armors;
|
std::vector<cv::RotatedRect> candidate_target_armors = target_armors;
|
||||||
@@ -189,13 +189,13 @@ bool Energy::findFlowStrip(const cv::Mat &src) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
cvtColor(src_bin, src_bin, CV_BGR2GRAY);//若读取三通道视频文件,需转换为单通道
|
cvtColor(src_bin, src_bin, cv::COLOR_BGR2GRAY);//若读取三通道视频文件,需转换为单通道
|
||||||
|
|
||||||
FlowStripStruct(src_bin);//图像膨胀,防止图像断开并更方便寻找
|
FlowStripStruct(src_bin);//图像膨胀,防止图像断开并更方便寻找
|
||||||
if (show_process)imshow("flow strip struct", src_bin);
|
if (show_process)imshow("flow strip struct", src_bin);
|
||||||
|
|
||||||
std::vector<vector<Point> > flow_strip_contours;
|
std::vector<vector<Point> > flow_strip_contours;
|
||||||
findContours(src_bin, flow_strip_contours, CV_RETR_EXTERNAL, CV_CHAIN_APPROX_NONE);
|
findContours(src_bin, flow_strip_contours, cv::RETR_EXTERNAL, cv::CHAIN_APPROX_NONE);
|
||||||
|
|
||||||
for (auto candidate_flow_strip_fan: flow_strip_fans) {
|
for (auto candidate_flow_strip_fan: flow_strip_fans) {
|
||||||
for (auto &flow_strip_contour : flow_strip_contours) {
|
for (auto &flow_strip_contour : flow_strip_contours) {
|
||||||
@@ -261,7 +261,7 @@ bool Energy::findFlowStripWeak(const cv::Mat &src) {
|
|||||||
|
|
||||||
if (src_bin.type() == CV_8UC1) // 黑白图像
|
if (src_bin.type() == CV_8UC1) // 黑白图像
|
||||||
{
|
{
|
||||||
cvtColor(src_bin, src_bin, COLOR_GRAY2RGB);
|
cvtColor(src_bin, src_bin, cv::COLOR_GRAY2RGB);
|
||||||
|
|
||||||
}
|
}
|
||||||
std::vector<cv::RotatedRect> candidate_armors = armors;
|
std::vector<cv::RotatedRect> candidate_armors = armors;
|
||||||
@@ -275,13 +275,13 @@ bool Energy::findFlowStripWeak(const cv::Mat &src) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
cvtColor(src_bin, src_bin, CV_BGR2GRAY);//若读取三通道视频文件,需转换为单通道
|
cvtColor(src_bin, src_bin, cv::COLOR_BGR2GRAY);//若读取三通道视频文件,需转换为单通道
|
||||||
|
|
||||||
FlowStripStruct(src_bin);//图像膨胀,防止图像断开并更方便寻找
|
FlowStripStruct(src_bin);//图像膨胀,防止图像断开并更方便寻找
|
||||||
if (show_process)imshow("weak struct", src_bin);
|
if (show_process)imshow("weak struct", src_bin);
|
||||||
|
|
||||||
std::vector<vector<Point> > flow_strip_contours;
|
std::vector<vector<Point> > flow_strip_contours;
|
||||||
findContours(src_bin, flow_strip_contours, CV_RETR_EXTERNAL, CV_CHAIN_APPROX_NONE);
|
findContours(src_bin, flow_strip_contours, cv::RETR_EXTERNAL, cv::CHAIN_APPROX_NONE);
|
||||||
|
|
||||||
for (auto &flow_strip_contour : flow_strip_contours) {
|
for (auto &flow_strip_contour : flow_strip_contours) {
|
||||||
if (!isValidFlowStripContour(flow_strip_contour)) {
|
if (!isValidFlowStripContour(flow_strip_contour)) {
|
||||||
@@ -336,5 +336,3 @@ bool Energy::findCenterROI(const cv::Mat &src) {
|
|||||||
return true;
|
return true;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -5,17 +5,17 @@ resolution :
|
|||||||
image_size :
|
image_size :
|
||||||
{
|
{
|
||||||
iIndex = 1;
|
iIndex = 1;
|
||||||
acDescription = "640X480 ROI";
|
acDescription = "1280X1024 ROI";
|
||||||
uBinSumMode = 0;
|
uBinSumMode = 0;
|
||||||
uBinAverageMode = 0;
|
uBinAverageMode = 0;
|
||||||
uSkipMode = 0;
|
uSkipMode = 0;
|
||||||
uResampleMask = 0;
|
uResampleMask = 0;
|
||||||
iHOffsetFOV = 56;
|
iHOffsetFOV = 56;
|
||||||
iVOffsetFOV = 0;
|
iVOffsetFOV = 0;
|
||||||
iWidthFOV = 640;
|
iWidthFOV = 1280;
|
||||||
iHeightFOV = 480;
|
iHeightFOV = 1024;
|
||||||
iWidth = 640;
|
iWidth = 1280;
|
||||||
iHeight = 480;
|
iHeight = 1024;
|
||||||
iWidthZoomHd = 0;
|
iWidthZoomHd = 0;
|
||||||
iHeightZoomHd = 0;
|
iHeightZoomHd = 0;
|
||||||
iWidthZoomSw = 0;
|
iWidthZoomSw = 0;
|
||||||
|
|||||||
File diff suppressed because it is too large
Load Diff
@@ -6,7 +6,7 @@
|
|||||||
#define _CAMERA_WRAPPER_H_
|
#define _CAMERA_WRAPPER_H_
|
||||||
|
|
||||||
#include <additions.h>
|
#include <additions.h>
|
||||||
#include <opencv2/core/core.hpp>
|
#include <opencv2/core.hpp>
|
||||||
#include <camera/wrapper_head.h>
|
#include <camera/wrapper_head.h>
|
||||||
|
|
||||||
#ifdef Windows
|
#ifdef Windows
|
||||||
@@ -19,9 +19,9 @@ class CameraWrapper: public WrapperHead {
|
|||||||
friend void cameraCallback(CameraHandle hCamera, BYTE *pFrameBuffer, tSdkFrameHead* pFrameHead,PVOID pContext);
|
friend void cameraCallback(CameraHandle hCamera, BYTE *pFrameBuffer, tSdkFrameHead* pFrameHead,PVOID pContext);
|
||||||
private:
|
private:
|
||||||
const std::string name;
|
const std::string name;
|
||||||
int mode;
|
//int mode;
|
||||||
|
|
||||||
bool init_done;
|
//bool init_done;
|
||||||
|
|
||||||
unsigned char* rgb_buffer;
|
unsigned char* rgb_buffer;
|
||||||
int camera_cnts;
|
int camera_cnts;
|
||||||
@@ -33,7 +33,7 @@ private:
|
|||||||
tSdkCameraCapbility tCapability;
|
tSdkCameraCapbility tCapability;
|
||||||
tSdkFrameHead frame_info;
|
tSdkFrameHead frame_info;
|
||||||
BYTE *pby_buffer;
|
BYTE *pby_buffer;
|
||||||
IplImage* iplImage;
|
cv::Mat image_header;
|
||||||
int channel;
|
int channel;
|
||||||
|
|
||||||
RoundQueue<cv::Mat, 2> src_queue;
|
RoundQueue<cv::Mat, 2> src_queue;
|
||||||
@@ -41,6 +41,9 @@ public:
|
|||||||
int gain;
|
int gain;
|
||||||
int exposure;
|
int exposure;
|
||||||
|
|
||||||
|
int mode;
|
||||||
|
bool init_done;
|
||||||
|
|
||||||
CameraWrapper(int exposure, int gain, int camera_mode=1, const std::string &n="NULL");
|
CameraWrapper(int exposure, int gain, int camera_mode=1, const std::string &n="NULL");
|
||||||
~CameraWrapper() final;
|
~CameraWrapper() final;
|
||||||
|
|
||||||
|
|||||||
@@ -4,6 +4,7 @@
|
|||||||
#ifndef _SETCONFIG_H_
|
#ifndef _SETCONFIG_H_
|
||||||
#define _SETCONFIG_H_
|
#define _SETCONFIG_H_
|
||||||
|
|
||||||
|
#define WITH_CONFIG
|
||||||
|
|
||||||
#ifdef WITH_CONFIG
|
#ifdef WITH_CONFIG
|
||||||
#include <config/config.h>
|
#include <config/config.h>
|
||||||
@@ -49,13 +50,13 @@
|
|||||||
#define YAW_AIM_KI (0.01)
|
#define YAW_AIM_KI (0.01)
|
||||||
#endif
|
#endif
|
||||||
#ifndef PITCH_AIM_KD
|
#ifndef PITCH_AIM_KD
|
||||||
#define PITCH_AIM_KD (0.4)
|
#define PITCH_AIM_KD (0)
|
||||||
#endif
|
#endif
|
||||||
#ifndef PITCH_AIM_KP
|
#ifndef PITCH_AIM_KP
|
||||||
#define PITCH_AIM_KP (0.75)
|
#define PITCH_AIM_KP (0)
|
||||||
#endif
|
#endif
|
||||||
#ifndef PITCH_AIM_KI
|
#ifndef PITCH_AIM_KI
|
||||||
#define PITCH_AIM_KI (0.01)
|
#define PITCH_AIM_KI (0)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef RED_COMPENSATE_YAW
|
#ifndef RED_COMPENSATE_YAW
|
||||||
|
|||||||
@@ -19,6 +19,6 @@
|
|||||||
|
|
||||||
#define FOCUS_PIXAL_8MM (1488)
|
#define FOCUS_PIXAL_8MM (1488)
|
||||||
#define FOCUS_PIXAL_5MM (917)
|
#define FOCUS_PIXAL_5MM (917)
|
||||||
#define FOCUS_PIXAL FOCUS_PIXAL_5MM
|
#define FOCUS_PIXAL FOCUS_PIXAL_8MM
|
||||||
|
|
||||||
#endif /* _CONSTANTS_H */
|
#endif /* _CONSTANTS_H */
|
||||||
|
|||||||
@@ -32,6 +32,7 @@
|
|||||||
|
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <systime.h>
|
#include <systime.h>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
/************** Define the control code *************/
|
/************** Define the control code *************/
|
||||||
#define START_CTR "\033[0"
|
#define START_CTR "\033[0"
|
||||||
|
|||||||
@@ -36,9 +36,9 @@ void uartReceive(Serial *pSerial) {
|
|||||||
pSerial->ReadData((uint8_t *) buffer, sizeof(mcu_data)+1);
|
pSerial->ReadData((uint8_t *) buffer, sizeof(mcu_data)+1);
|
||||||
if (buffer[sizeof(mcu_data)] == '\n') {
|
if (buffer[sizeof(mcu_data)] == '\n') {
|
||||||
memcpy(&mcu_data, buffer, sizeof(mcu_data));
|
memcpy(&mcu_data, buffer, sizeof(mcu_data));
|
||||||
// LOGM("Get, state:%c, mark:%d!", mcu_data.state, (int) mcu_data.mark);
|
LOGM("Get, state:%c, mark:%d!", mcu_data.state, (int) mcu_data.mark);
|
||||||
// LOGM("Get yaw: %f, pitch: %f!", mcu_data.curr_yaw, mcu_data.curr_pitch);
|
LOGM("Get yaw: %f, pitch: %f!", mcu_data.curr_yaw, mcu_data.curr_pitch);
|
||||||
// LOGM("Get delta x: %d, delta y: %d!", mcu_data.delta_x, mcu_data.delta_y);
|
LOGM("Get delta x: %d, delta y: %d!", mcu_data.delta_x, mcu_data.delta_y);
|
||||||
// static int t = time(nullptr);
|
// static int t = time(nullptr);
|
||||||
// static int cnt = 0;
|
// static int cnt = 0;
|
||||||
// if(time(nullptr) > t){
|
// if(time(nullptr) > t){
|
||||||
@@ -77,8 +77,12 @@ bool checkReconnect(bool is_camera_connect) {
|
|||||||
if (!is_camera_connect) {
|
if (!is_camera_connect) {
|
||||||
int curr_gain = ((CameraWrapper* )video)->gain;
|
int curr_gain = ((CameraWrapper* )video)->gain;
|
||||||
int curr_exposure = ((CameraWrapper* )video)->exposure;
|
int curr_exposure = ((CameraWrapper* )video)->exposure;
|
||||||
|
int curr_mode = ((CameraWrapper* )video)->mode; // 获取原始模式
|
||||||
|
|
||||||
delete video;
|
delete video;
|
||||||
video = new CameraWrapper(curr_exposure, curr_gain, 0/*, "armor"*/);
|
std::this_thread::sleep_for(std::chrono::milliseconds(500)); // 等待硬件释放
|
||||||
|
video = new CameraWrapper(curr_exposure, curr_gain, curr_mode/*, "armor"*/);
|
||||||
|
//video = new CameraWrapper(curr_exposure, curr_gain, 0/*, "armor"*/);
|
||||||
is_camera_connect = video->init();
|
is_camera_connect = video->init();
|
||||||
}
|
}
|
||||||
return is_camera_connect;
|
return is_camera_connect;
|
||||||
@@ -103,14 +107,14 @@ void extract(cv::Mat &src) {//图像预处理,将视频切成640×480的大小
|
|||||||
if (src.empty()) return;
|
if (src.empty()) return;
|
||||||
float length = static_cast<float>(src.cols);
|
float length = static_cast<float>(src.cols);
|
||||||
float width = static_cast<float>(src.rows);
|
float width = static_cast<float>(src.rows);
|
||||||
if (length / width > 640.0 / 480.0) {
|
if (length / width > 1280.0 / 1024.0) {
|
||||||
length *= 480.0 / width;
|
length *= 1024 / width;
|
||||||
resize(src, src, cv::Size(length, 480));
|
resize(src, src, cv::Size(length, 1024));
|
||||||
src = src(Rect((length - 640) / 2, 0, 640, 480));
|
src = src(Rect((length - 1280) / 2, 0, 1280, 1024));
|
||||||
} else {
|
} else {
|
||||||
width *= 640.0 / length;
|
width *= 1280.0 / length;
|
||||||
resize(src, src, cv::Size(640, width));
|
resize(src, src, cv::Size(1280, width));
|
||||||
src = src(Rect(0, (width - 480) / 2, 640, 480));
|
src = src(Rect(0, (width - 1024) / 2, 1280, 1024));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -17,7 +17,6 @@ CameraWrapper::CameraWrapper(int exposure, int gain, int camera_mode, const std:
|
|||||||
mode(camera_mode),
|
mode(camera_mode),
|
||||||
camera_cnts(2),
|
camera_cnts(2),
|
||||||
camera_status(-1),
|
camera_status(-1),
|
||||||
iplImage(nullptr),
|
|
||||||
rgb_buffer(nullptr),
|
rgb_buffer(nullptr),
|
||||||
channel(3),
|
channel(3),
|
||||||
gain(gain),
|
gain(gain),
|
||||||
@@ -27,9 +26,11 @@ CameraWrapper::CameraWrapper(int exposure, int gain, int camera_mode, const std:
|
|||||||
void cameraCallback(CameraHandle hCamera, BYTE *pFrameBuffer, tSdkFrameHead* pFrameHead,PVOID pContext){
|
void cameraCallback(CameraHandle hCamera, BYTE *pFrameBuffer, tSdkFrameHead* pFrameHead,PVOID pContext){
|
||||||
CameraWrapper *c = (CameraWrapper*)pContext;
|
CameraWrapper *c = (CameraWrapper*)pContext;
|
||||||
CameraImageProcess(hCamera, pFrameBuffer, c->rgb_buffer, pFrameHead);
|
CameraImageProcess(hCamera, pFrameBuffer, c->rgb_buffer, pFrameHead);
|
||||||
auto iplImage = cvCreateImageHeader(cvSize(pFrameHead->iWidth, pFrameHead->iHeight), IPL_DEPTH_8U, c->channel);
|
// 使用 cv::Mat 替代 IplImage
|
||||||
cvSetData(iplImage, c->rgb_buffer, pFrameHead->iWidth * c->channel); //此处只是设置指针,无图像块数据拷贝,不需担心转换效率
|
cv::Mat img(pFrameHead->iHeight, pFrameHead->iWidth,
|
||||||
c->src_queue.push(cv::cvarrToMat(iplImage).clone());
|
c->channel == 3 ? CV_8UC3 : CV_8UC1,
|
||||||
|
c->rgb_buffer, pFrameHead->iWidth * c->channel);
|
||||||
|
c->src_queue.push(img.clone());
|
||||||
}
|
}
|
||||||
|
|
||||||
bool CameraWrapper::init() {
|
bool CameraWrapper::init() {
|
||||||
@@ -37,6 +38,7 @@ bool CameraWrapper::init() {
|
|||||||
int camera_enumerate_device_status = CameraEnumerateDevice(camera_enum_list, &camera_cnts);
|
int camera_enumerate_device_status = CameraEnumerateDevice(camera_enum_list, &camera_cnts);
|
||||||
if (camera_enumerate_device_status != CAMERA_STATUS_SUCCESS) {
|
if (camera_enumerate_device_status != CAMERA_STATUS_SUCCESS) {
|
||||||
LOGE("CameraEnumerateDevice fail with %d!", camera_enumerate_device_status);
|
LOGE("CameraEnumerateDevice fail with %d!", camera_enumerate_device_status);
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
if (camera_cnts == 0) {
|
if (camera_cnts == 0) {
|
||||||
LOGE("No camera device detected!");
|
LOGE("No camera device detected!");
|
||||||
@@ -134,15 +136,9 @@ bool CameraWrapper::read(cv::Mat &src) {
|
|||||||
|
|
||||||
bool CameraWrapper::readRaw(cv::Mat &src) {
|
bool CameraWrapper::readRaw(cv::Mat &src) {
|
||||||
if (CameraGetImageBuffer(h_camera, &frame_info, &pby_buffer, 500) == CAMERA_STATUS_SUCCESS) {
|
if (CameraGetImageBuffer(h_camera, &frame_info, &pby_buffer, 500) == CAMERA_STATUS_SUCCESS) {
|
||||||
if (iplImage) {
|
// 使用 cv::Mat 替代 IplImage
|
||||||
cvReleaseImageHeader(&iplImage);
|
cv::Mat img(frame_info.iHeight, frame_info.iWidth, CV_8UC1, pby_buffer, frame_info.iWidth);
|
||||||
}
|
src = img.clone();
|
||||||
|
|
||||||
iplImage = cvCreateImageHeader(cvSize(frame_info.iWidth, frame_info.iHeight), IPL_DEPTH_8U, 1);
|
|
||||||
|
|
||||||
cvSetData(iplImage, pby_buffer, frame_info.iWidth); //此处只是设置指针,无图像块数据拷贝,不需担心转换效率
|
|
||||||
|
|
||||||
src = cv::cvarrToMat(iplImage).clone();
|
|
||||||
|
|
||||||
//在成功调用CameraGetImageBuffer后,必须调用CameraReleaseImageBuffer来释放获得的buffer。
|
//在成功调用CameraGetImageBuffer后,必须调用CameraReleaseImageBuffer来释放获得的buffer。
|
||||||
//否则再次调用CameraGetImageBuffer时,程序将被挂起一直阻塞,直到其他线程中调用CameraReleaseImageBuffer来释放了buffer
|
//否则再次调用CameraGetImageBuffer时,程序将被挂起一直阻塞,直到其他线程中调用CameraReleaseImageBuffer来释放了buffer
|
||||||
@@ -156,16 +152,13 @@ bool CameraWrapper::readRaw(cv::Mat &src) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
bool CameraWrapper::readProcessed(cv::Mat &src) {
|
bool CameraWrapper::readProcessed(cv::Mat &src) {
|
||||||
// cerr << "Get-1" << endl;
|
|
||||||
if (CameraGetImageBuffer(h_camera, &frame_info, &pby_buffer, 500) == CAMERA_STATUS_SUCCESS) {
|
if (CameraGetImageBuffer(h_camera, &frame_info, &pby_buffer, 500) == CAMERA_STATUS_SUCCESS) {
|
||||||
CameraImageProcess(h_camera, pby_buffer, rgb_buffer,
|
CameraImageProcess(h_camera, pby_buffer, rgb_buffer,
|
||||||
&frame_info); // this function is super slow, better not to use it.
|
&frame_info); // this function is super slow, better not to use it.
|
||||||
if (iplImage) {
|
// 使用 cv::Mat 替代 IplImage
|
||||||
cvReleaseImageHeader(&iplImage);
|
int mat_type = (channel == 3) ? CV_8UC3 : CV_8UC1;
|
||||||
}
|
cv::Mat img(frame_info.iHeight, frame_info.iWidth, mat_type, rgb_buffer, frame_info.iWidth * channel);
|
||||||
iplImage = cvCreateImageHeader(cvSize(frame_info.iWidth, frame_info.iHeight), IPL_DEPTH_8U, channel);
|
src = img.clone();
|
||||||
cvSetData(iplImage, rgb_buffer, frame_info.iWidth * channel); //此处只是设置指针,无图像块数据拷贝,不需担心转换效率
|
|
||||||
src = cv::cvarrToMat(iplImage).clone();
|
|
||||||
//在成功调用CameraGetImageBuffer后,必须调用CameraReleaseImageBuffer来释放获得的buffer。
|
//在成功调用CameraGetImageBuffer后,必须调用CameraReleaseImageBuffer来释放获得的buffer。
|
||||||
//否则再次调用CameraGetImageBuffer时,程序将被挂起一直阻塞,直到其他线程中调用CameraReleaseImageBuffer来释放了buffer
|
//否则再次调用CameraGetImageBuffer时,程序将被挂起一直阻塞,直到其他线程中调用CameraReleaseImageBuffer来释放了buffer
|
||||||
CameraReleaseImageBuffer(h_camera, pby_buffer);
|
CameraReleaseImageBuffer(h_camera, pby_buffer);
|
||||||
|
|||||||
@@ -6,19 +6,20 @@
|
|||||||
#include <log.h>
|
#include <log.h>
|
||||||
#include <cstring>
|
#include <cstring>
|
||||||
#include <map>
|
#include <map>
|
||||||
|
#include <string>
|
||||||
|
|
||||||
bool show_armor_box = false;
|
bool show_armor_box = true;
|
||||||
bool show_armor_boxes = false;
|
bool show_armor_boxes = false;
|
||||||
bool show_light_blobs = false;
|
bool show_light_blobs = false;
|
||||||
bool show_origin = false;
|
bool show_origin = false;
|
||||||
bool run_with_camera = false;
|
bool run_with_camera = true;
|
||||||
bool save_video = false;
|
bool save_video = false;
|
||||||
bool wait_uart = false;
|
bool wait_uart = false;
|
||||||
bool save_labelled_boxes = false;
|
bool save_labelled_boxes = false;
|
||||||
bool show_process = false;
|
bool show_process = false;
|
||||||
bool show_energy = false;
|
bool show_energy = false;
|
||||||
bool save_mark = false;
|
bool save_mark = false;
|
||||||
bool show_info = false;
|
bool show_info = true;
|
||||||
bool run_by_frame = false;
|
bool run_by_frame = false;
|
||||||
|
|
||||||
// 使用map保存所有选项及其描述和操作,加快查找速度。
|
// 使用map保存所有选项及其描述和操作,加快查找速度。
|
||||||
|
|||||||
@@ -181,7 +181,7 @@ bool Serial::ReadData(unsigned char *buffer, unsigned int length) {
|
|||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
string get_uart_dev_name() {
|
string get_uart_dev_name() {
|
||||||
FILE *ls = popen("ls /dev/ttyUSB* --color=never", "r");
|
FILE *ls = popen("ls /dev/ttyCH341USB* --color=never", "r");
|
||||||
char name[20] = {0};
|
char name[20] = {0};
|
||||||
fscanf(ls, "%s", name);
|
fscanf(ls, "%s", name);
|
||||||
return name;
|
return name;
|
||||||
|
|||||||
3
tools/tty-permission.sh
Normal file
3
tools/tty-permission.sh
Normal file
@@ -0,0 +1,3 @@
|
|||||||
|
#!/bin/sh
|
||||||
|
|
||||||
|
sudo touch /etc/udev/rules.d/70-ttyusb.rules
|
||||||
Reference in New Issue
Block a user