对上交代码进行修改,主要将能量机关去掉,添加了同济的PnP位姿解算,但是同济有个四元数,获取IMU部分没有启用,可能导致精度不够。当前还存在反陀螺功能,修改为逻辑和弹道预测相结合,主要在时间关系上进行调整。
This commit is contained in:
15
.gitignore
vendored
Normal file
15
.gitignore
vendored
Normal file
@@ -0,0 +1,15 @@
|
||||
cmake-build-debug
|
||||
build
|
||||
.idea
|
||||
.xmake
|
||||
.vscode/.cache
|
||||
.vscode/compile_commands.json
|
||||
Mark
|
||||
armor_box_photo
|
||||
tools/TrainCNN/.idea
|
||||
tools/TrainCNN/model
|
||||
tools/TrainCNN/__pycache__
|
||||
others/include/config/config.h
|
||||
others/MV-UB31-Group0.config
|
||||
.DS_Store
|
||||
video
|
||||
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"
|
||||
],
|
||||
}
|
||||
61
CMakeLists.txt
Normal file
61
CMakeLists.txt
Normal file
@@ -0,0 +1,61 @@
|
||||
CMAKE_MINIMUM_REQUIRED(VERSION 3.5)
|
||||
|
||||
PROJECT(SJTU-RM-CV)
|
||||
SET(CMAKE_CXX_STANDARD 11)
|
||||
SET(CMAKE_BUILD_TYPE RELEASE)
|
||||
SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -O3")
|
||||
SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DPATH=\"\\\"${PROJECT_SOURCE_DIR}\\\"\"")
|
||||
SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -D${CMAKE_SYSTEM_NAME}")
|
||||
SET(BIN_NAME "run")
|
||||
|
||||
SET(CMAKE_EXPORT_COMPILE_COMMANDS ON)
|
||||
|
||||
|
||||
FIND_FILE(CONFIG_FOUND "config.h" "others/include/config")
|
||||
if (CONFIG_FOUND)
|
||||
MESSAGE("Found config.h")
|
||||
SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DWITH_CONFIG")
|
||||
endif()
|
||||
|
||||
|
||||
FIND_PROGRAM(CCACHE_FOUND ccache)
|
||||
IF(CCACHE_FOUND)
|
||||
SET_PROPERTY(GLOBAL PROPERTY RULE_LAUNCH_COMPILE ccache)
|
||||
SET_PROPERTY(GLOBAL PROPERTY RULE_LAUNCH_LINK ccache)
|
||||
MESSAGE("< Use ccache for compiler >")
|
||||
ENDIF()
|
||||
|
||||
FIND_PACKAGE(Eigen3 REQUIRED)
|
||||
FIND_PACKAGE(OpenCV 4 REQUIRED)
|
||||
FIND_PACKAGE(Threads)
|
||||
FIND_PACKAGE(yaml-cpp REQUIRED)
|
||||
|
||||
|
||||
LINK_DIRECTORIES(${PROJECT_SOURCE_DIR}/others)
|
||||
|
||||
INCLUDE_DIRECTORIES(${EIGEN3_INCLUDE_DIR})
|
||||
INCLUDE_DIRECTORIES(${PROJECT_SOURCE_DIR}/armor/include)
|
||||
INCLUDE_DIRECTORIES(${PROJECT_SOURCE_DIR}/others/include)
|
||||
|
||||
FILE(GLOB_RECURSE sourcefiles "others/src/*.cpp" "armor/src/*.cpp")
|
||||
ADD_EXECUTABLE(${BIN_NAME} main.cpp ${sourcefiles})
|
||||
|
||||
TARGET_LINK_LIBRARIES(${BIN_NAME} ${CMAKE_THREAD_LIBS_INIT})
|
||||
TARGET_LINK_LIBRARIES(${BIN_NAME} ${OpenCV_LIBS})
|
||||
TARGET_LINK_LIBRARIES(${BIN_NAME} yaml-cpp)
|
||||
|
||||
IF (CMAKE_SYSTEM_NAME MATCHES "Linux")
|
||||
MESSAGE(STATUS "current platform: Linux ")
|
||||
TARGET_LINK_LIBRARIES(${BIN_NAME} "${PROJECT_SOURCE_DIR}/others/libMVSDK.so")
|
||||
ELSEIF (CMAKE_SYSTEM_NAME MATCHES "Windows")
|
||||
MESSAGE(STATUS "current platform: Windows")
|
||||
TARGET_LINK_LIBRARIES(${BIN_NAME} "${PROJECT_SOURCE_DIR}/others/MVCAMSDK_X64.lib")
|
||||
ELSEIF (CMAKE_SYSTEM_NAME MATCHES "Darwin")
|
||||
MESSAGE(STATUS "current platform: Mac")
|
||||
TARGET_LINK_LIBRARIES(${BIN_NAME} "${PROJECT_SOURCE_DIR}/others/libmvsdk.dylib")
|
||||
ELSE ()
|
||||
MESSAGE(STATUS "Unsupport platform: ${CMAKE_SYSTEM_NAME}")
|
||||
ENDIF()
|
||||
|
||||
ADD_CUSTOM_TARGET(create-startup COMMAND "${PROJECT_SOURCE_DIR}/tools/create-startup.sh" "${PROJECT_SOURCE_DIR}" "${CMAKE_BINARY_DIR}")
|
||||
ADD_CUSTOM_TARGET(train-cnn COMMAND "gnome-terminal" "--" "bash" "-c" "${PROJECT_SOURCE_DIR}/tools/TrainCNN/backward.py")
|
||||
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.
|
||||
187
README.md
Normal file
187
README.md
Normal file
@@ -0,0 +1,187 @@
|
||||
# 上海交通大学 RoboMaster 2019赛季 视觉代码
|
||||
|
||||
本代码是上海交通大学RoboMaster2019赛季步兵车辆的视觉部分,分为三个模块:**装甲板识别**,**能量机关**,以及**封装的设备驱动和配置文件**。可以提取能量机关以外的模块并修改main函数直接作为哨兵识别代码。
|
||||
|
||||
本代码统一使用**640×480**大小的图像进行处理
|
||||
|
||||
| 作者 | 负责部分 | 微信号 |
|
||||
| ------ | -------------- | -------------------- |
|
||||
| 唐欣阳 | 自瞄装甲板识别 | xinyang_tang |
|
||||
| 卫志坤 | 自瞄装甲板识别 | |
|
||||
| 孙加桐 | 能量机关识别 | SJTxixiliadorabarryU |
|
||||
| 罗嘉鸣 | 能量机关识别 | |
|
||||
|
||||
**如有BUG或者想交流的朋友欢迎积极联系我们**
|
||||
|
||||
**分享部分比赛时摄像头录制的视频:**
|
||||
|
||||
链接: https://pan.baidu.com/s/1LwxEpeYYblX3cSzb59MTVg 提取码: 84ju 复制这段内容后打开百度网盘手机App,操作更方便哦
|
||||
|
||||
---
|
||||
|
||||
运行效果:自瞄帧率120(摄像头最大帧率),识别距离根据环境不同大约8米左右(5mm焦距镜头)。
|
||||
|
||||

|
||||

|
||||
|
||||
## 一、代码运行环境
|
||||
|
||||
| 硬件设备 | 操作系统 | 运行库 | ToolChain |
|
||||
| ---------------------------------------------------- | -------------------------------------------- | ------------------------------------------------------------ | ---------------------------------------------------------- |
|
||||
| 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环境下的运行支持,仅保证程序可以编译运行。对与部分辅助功能,如生成自启动脚本则不支持。**
|
||||
|
||||
**实际装载在步兵和哨兵上的运行环境为Ubuntu18.04。**
|
||||
|
||||
相机驱动下载地址:[相机驱动](https://www.mindvision.com.cn)
|
||||
|
||||
OpenCV下载地址:[OpenCV](https://github.com/opencv)
|
||||
|
||||
OpenCV安装教程 : [linux](https://docs.opencv.org/3.4.5/d7/d9f/tutorial_linux_install.html) [Windows](https://docs.opencv.org/3.4.5/d3/d52/tutorial_windows_install.html)
|
||||
|
||||
Eigen下载方法:
|
||||
* Ubuntu16/18: ```sudo apt install libeigen3-dev```
|
||||
* Windows10 : [Eigen下载地址](http://eigen.tuxfamily.org/)
|
||||
|
||||
## 二、程序编译运行以及调试方式
|
||||
|
||||
### 1.编译运行
|
||||
|
||||
* Ubuntu16/18(在项目文件夹下)
|
||||
|
||||
```shell
|
||||
mkdir build
|
||||
cd build
|
||||
cmake ..
|
||||
make -j8
|
||||
sudo ./run
|
||||
```
|
||||
|
||||
* Windows10
|
||||
|
||||
打开cmake-gui,选择项目文件夹和build文件夹,生成VS工程。在VS中编译项目。
|
||||
|
||||
### 2.调试方式
|
||||
|
||||
```./run --help```可以查看所有命令行参数及其作用。所有调试选项都集成到了命令行参数中。
|
||||
|
||||
**不使用任何参数直接运行将没有任何图像显示。**
|
||||
|
||||
需要调参的部分:主要需要根据车辆情况而调参的参数存放在others/include/config/setconfig.h中
|
||||
|
||||
### 3.工作条件
|
||||
|
||||
* 对于自瞄,由于使用了数字识别,务必保证光照充足,图像上数字清晰可见。光照不足时,调整摄像头曝光或增益数值,直到数字清晰可见。
|
||||
* 务必保证摄像头焦距正确,同时镜片干净无污物。
|
||||
|
||||
## 三、文件目录结构
|
||||
```
|
||||
.
|
||||
├── armor // 存放自瞄主要算法代码
|
||||
│ ├── include // 自瞄头文件
|
||||
│ └── src // 自瞄源码
|
||||
├── CMakeLists.txt // cmake工程文件
|
||||
├── energy // 存放能量机关主要算法代码
|
||||
│ ├── include // 能量机关头文件
|
||||
│ └── src // 能量机关源码
|
||||
├── main.cpp // 主函数
|
||||
├── others // 存放摄像头、串口、配置文件等
|
||||
│ ├── include // others头文件
|
||||
│ ├── libmvsdk.dylib // mac相机驱动链接库
|
||||
│ ├── libMVSDK.so // linux相机驱动链接库
|
||||
│ ├── MVCAMSDK_X64.dll // win10相机驱动链接库
|
||||
│ ├── MV-UB31-Group0.config // 相机配置文件
|
||||
│ └── src // others源码
|
||||
└── tools // 存放分类器训练代码及参数,自启动脚步等
|
||||
├── auto-pull.sh // 自动代码更新脚本
|
||||
├── create-startup.sh // 自启动文件创建脚本
|
||||
├── monitor.bat // win10进程守护脚本
|
||||
├── monitor.sh // linux进程守护脚本
|
||||
├── para // 分类器参数
|
||||
└── TrainCNN // 分类器训练源码
|
||||
```
|
||||
## 四、关键类解析
|
||||
|
||||
| 类名 | 主要成员 | 主要接口 | 类的作用 |
|
||||
| --------------- | ------------------------------------------------------------ | ---------------------- | ------------------------------------------------------- |
|
||||
| ArmorFinder | 过多,不做赘述 | void run(cv::Mat &src) | 将一帧图像中装甲板的detection以及数据发送封装为一个类 |
|
||||
| Energy | 过多,不做赘述 | void run(cv::Mat &src) | 将一帧图像中能量机关的detection以及数据发送封装为一个类 |
|
||||
| EnergyPartParam | 过多,不做赘述 | 无 | 能量机关所有参数的集合 |
|
||||
| LightBlob | 灯条位置<br />灯条颜色 | 无 | 灯条类定义 |
|
||||
| ArmorBox | 装甲板位置<br />装甲板的两个灯条<br />装甲板颜色<br />装甲板数字id | 无 | 装甲板类定义 |
|
||||
|
||||
## 五、程序运行基本流程
|
||||
|
||||
↗ 大能量机关 ↘
|
||||
|
||||
各项初始化→读取当前状态 → 小能量机关 → 回到读取状态
|
||||
|
||||
↓ ↘ 自瞄 ↗
|
||||
|
||||
数据接收线程
|
||||
|
||||
## 六、识别方式
|
||||
|
||||
### 1.自瞄装甲板识别方式
|
||||
|
||||
首先对图像进行通道拆分以及二值化操作,再进行开闭运算,通过边缘提取和条件限制得出可能为灯条的部分。再对所有可能的灯条进行两两匹配,根据形状大小特性进行筛选,得出可能为装甲板的候选区。然后把所有候选区交给分类器判断,得出真实的装甲板及其数字id。最后根据优先级选取最终击打目标以及后续处理。
|
||||

|
||||
### 2.能量机关识别方式
|
||||
|
||||
首先对图像进行二值化操作,然后进行一定腐蚀和膨胀,通过边缘提取和条件限制得出待击打叶片(锤子形)。在待击打叶片范围内进一步用类似方法寻找目标装甲板和流动条,在二者连线上寻找中心的“R”。根据目标装甲板坐标和中心坐标计算极坐标系下的目标角度,进而预测待击打点的坐标(小符为装甲板本身,大符需要旋转)。最后将待击打点坐标和图像中心的差值转换为yaw和pitch轴角度,增加一环PID后发送给云台主控板。
|
||||
|
||||
## 七、通信协议
|
||||
|
||||
### 1.通信方式
|
||||
|
||||
使用USB转TTL进行串口通信
|
||||
|
||||
### 2.数据接收结构体
|
||||
|
||||
```c++
|
||||
struct McuData {
|
||||
float curr_yaw; // 当前云台yaw角度
|
||||
float curr_pitch; // 当前云台pitch角
|
||||
uint8_t state; // 当前状态,自瞄-大符-小符
|
||||
uint8_t mark; // 云台角度标记位
|
||||
uint8_t anti_top; // 是否为反陀螺模式
|
||||
uint8_t enemy_color; // 敌方颜色
|
||||
int delta_x; // 能量机关x轴补偿量
|
||||
int delta_y; // 能量机关y轴补偿量
|
||||
};
|
||||
```
|
||||
|
||||
每个数据帧后使用字符```'\n'```作为帧尾标志
|
||||
|
||||
### 3.数据发送结构体
|
||||
|
||||
```c++
|
||||
struct SendData {
|
||||
char start_flag; // 帧头标志,字符's'
|
||||
int16_t yaw; // float类型的实际角度(以度为单位)/100*(32768-1)
|
||||
int16_t pitch; // float类型的实际角度(以度为单位)/100*(32768-1)
|
||||
uint16_t shoot_delay; // 反陀螺模式下的发射延迟
|
||||
char end_flag; // 帧尾标识,字符'e'
|
||||
};
|
||||
```
|
||||
|
||||
实际发送代码中没有使用这个结构体,而是使用uint8_t类型数组直接赋值代替
|
||||
|
||||
## 八、代码命名规范
|
||||
|
||||
函数名:使用首字母小写的驼峰命名法
|
||||
|
||||
类型名:使用首字母大写的驼峰命名法
|
||||
|
||||
变量名:使用下划线分割命名法
|
||||
|
||||
## 九、未来的优化方向
|
||||
* 基于灯条的候选区生成由于利用了灯条在其附近区域亮度是最高的这一先验知识,当摄像头曝光和增益较高,同时灯条旁边有其他较亮的物体(如反光、光晕过大等),该灯条将无法被识别。反应在算法上即体现在二值化这一步骤之上。所以本项目采用多二值化阈值同时进行灯条提取最后进行合并的办法,有一定改善,但没有解决本质问题。**所以第一个优化方向便是环境适应力更强的灯条提取或者候选区提取**。
|
||||
* 代码中使用CNN分类器对灯条候选区进行筛选以及数字识别,但分类器总是不能做到100%的正确率,同时许多明显为背景的候选区有时也会被误判成装甲板,导致误识别。**所以第二个优化方向是更低的误识别率(可以从候选区生成入手或者从分类器入手)**。
|
||||
* 由于陀螺这样的机械设计基本上是强队的标准配置,所以我们也首次尝试了从视觉层面对陀螺有一个专门的击打方式,但实际应用场景较少(当前仅针对原地旋转的陀螺),且对操作手不太友好(要求手动对准陀螺中心),所以没有取得很大的实战价值。**所以第三个优化方向便是一个有着自动击打动态陀螺的系统**。
|
||||
|
||||
---
|
||||
**觉得对你有帮助请点个STAR哦:)**
|
||||
155
armor/include/armor_finder/armor_finder.h
Normal file
155
armor/include/armor_finder/armor_finder.h
Normal file
@@ -0,0 +1,155 @@
|
||||
//
|
||||
// Created by xinyang on 19-3-27.
|
||||
//
|
||||
|
||||
#ifndef _ARMOR_FINDER_H_
|
||||
#define _ARMOR_FINDER_H_
|
||||
|
||||
#include <map>
|
||||
#include <systime.h>
|
||||
#include <constants.h>
|
||||
#include <opencv2/core.hpp>
|
||||
#include <opencv2/tracking/tracking.hpp>
|
||||
#include <serial.h>
|
||||
#include <armor_finder/classifier/solver.h>
|
||||
#include <additions.h>
|
||||
|
||||
#define BLOB_RED ENEMY_RED
|
||||
#define BLOB_BLUE ENEMY_BLUE
|
||||
|
||||
#define BOX_RED ENEMY_RED
|
||||
#define BOX_BLUE ENEMY_BLUE
|
||||
|
||||
#define IMAGE_CENTER_X (640)
|
||||
#define IMAGE_CENTER_Y (512-20)
|
||||
|
||||
#define DISTANCE_HEIGHT_5MM (10700.0) // 单位: cm*pixel
|
||||
#define DISTANCE_HEIGHT DISTANCE_HEIGHT_5MM
|
||||
|
||||
#define B1 1
|
||||
#define B2 2
|
||||
#define B3 3
|
||||
#define B4 4
|
||||
#define B5 5
|
||||
#define B7 6
|
||||
#define B8 7
|
||||
#define R1 8
|
||||
#define R2 9
|
||||
#define R3 10
|
||||
#define R4 11
|
||||
#define R5 12
|
||||
#define R7 13
|
||||
#define R8 14
|
||||
|
||||
extern std::map<int, string> id2name; //装甲板id到名称的map
|
||||
extern std::map<string, int> name2id; //装甲板名称到id的map
|
||||
extern std::map<string, int> prior_blue;
|
||||
extern std::map<string, int> prior_red;
|
||||
|
||||
|
||||
/******************* 灯条类定义 ***********************/
|
||||
class LightBlob {
|
||||
public:
|
||||
cv::RotatedRect rect; //灯条位置
|
||||
double area_ratio;
|
||||
double length; //灯条长度
|
||||
uint8_t blob_color; //灯条颜色
|
||||
|
||||
LightBlob(cv::RotatedRect &r, double ratio, uint8_t color) : rect(r), area_ratio(ratio), blob_color(color) {
|
||||
length = max(rect.size.height, rect.size.width);
|
||||
};
|
||||
LightBlob() = default;
|
||||
};
|
||||
|
||||
typedef std::vector<LightBlob> LightBlobs;
|
||||
|
||||
|
||||
|
||||
/******************* 装甲板类定义 **********************/
|
||||
class ArmorBox{
|
||||
public:
|
||||
typedef enum{
|
||||
FRONT, SIDE, UNKNOWN
|
||||
} BoxOrientation;
|
||||
|
||||
cv::Rect2d rect;
|
||||
LightBlobs light_blobs;
|
||||
uint8_t box_color;
|
||||
int id;
|
||||
std::vector<cv::Point2f> points; // 4 corner points for PnP
|
||||
|
||||
explicit ArmorBox(const cv::Rect &pos=cv::Rect2d(), const LightBlobs &blobs=LightBlobs(), uint8_t color=0, int i=0, const std::vector<cv::Point2f> &pts = {});
|
||||
|
||||
cv::Point2f getCenter() const; // 获取装甲板中心
|
||||
double getBlobsDistance() const; // 获取两个灯条中心间距
|
||||
double lengthDistanceRatio() const; // 获取灯条中心距和灯条长度的比值
|
||||
double getBoxDistance() const; // 获取装甲板到摄像头的距离
|
||||
BoxOrientation getOrientation() const; // 获取装甲板朝向(误差较大,已弃用)
|
||||
|
||||
bool operator<(const ArmorBox &box) const; // 装甲板优先级比较
|
||||
};
|
||||
|
||||
typedef std::vector<ArmorBox> ArmorBoxes;
|
||||
|
||||
/********************* 自瞄类定义 **********************/
|
||||
class ArmorFinder{
|
||||
public:
|
||||
ArmorFinder(uint8_t &color, Serial &u, const string ¶s_folder, const uint8_t &anti_top);
|
||||
~ArmorFinder() = default;
|
||||
|
||||
private:
|
||||
typedef cv::TrackerKCF TrackerToUse; // Tracker类型定义
|
||||
|
||||
typedef enum{
|
||||
SEARCHING_STATE, TRACKING_STATE, STANDBY_STATE
|
||||
} State; // 自瞄状态枚举定义
|
||||
|
||||
systime frame_time; // 当前帧对应时间
|
||||
const uint8_t &enemy_color; // 敌方颜色,引用外部变量,自动变化
|
||||
const uint8_t &is_anti_top; // 进入反陀螺,引用外部变量,自动变化
|
||||
State state; // 自瞄状态对象实例
|
||||
ArmorBox target_box, last_box; // 目标装甲板
|
||||
int anti_switch_cnt; // 防止乱切目标计数器
|
||||
cv::Ptr<cv::Tracker> tracker; // tracker对象实例
|
||||
Classifier classifier; // CNN分类器对象实例,用于数字识别
|
||||
int contour_area; // 装甲区域亮点个数,用于数字识别未启用时判断是否跟丢(已弃用)
|
||||
int tracking_cnt; // 记录追踪帧数,用于定时退出追踪
|
||||
Serial &serial; // 串口对象
|
||||
auto_aim::Solver solver; // PnP求解器
|
||||
|
||||
systime last_front_time; // 上次陀螺正对时间
|
||||
int anti_top_cnt;
|
||||
RoundQueue<double, 4> top_periodms; // 陀螺周期循环队列
|
||||
vector<systime> time_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 findArmorBox(const cv::Mat &src, ArmorBox &box);
|
||||
bool matchArmorBoxes(const cv::Mat &src, const LightBlobs &light_blobs, ArmorBoxes &armor_boxes);
|
||||
|
||||
bool stateSearchingTarget(cv::Mat &src); // searching state主函数
|
||||
bool stateTrackingTarget(cv::Mat &src); // tracking state主函数
|
||||
bool stateStandBy(); // stand by state主函数(已弃用)
|
||||
|
||||
void antiTop(double dist_m, double pitch_imu_deg); // 反小陀螺
|
||||
cv::Point3f getTarget3D(const ArmorBox &box); // 获取目标的3D坐标 (相对于相机)
|
||||
|
||||
bool sendBoxPosition(uint16_t shoot_delay); // 发送装甲板位置
|
||||
bool shouldFire() const { return can_fire; } // 获取开火建议
|
||||
public:
|
||||
void run(cv::Mat &src); // 自瞄主函数
|
||||
struct HistoryItem {
|
||||
cv::Point3f pos;
|
||||
double time;
|
||||
};
|
||||
std::vector<HistoryItem> history; // 历史位置缓存,用于速度预测
|
||||
cv::Point3f target_xyz; // PnP计算出的目标3D坐标 (cm)
|
||||
bool can_fire; // 是否满足开启射击条件
|
||||
};
|
||||
|
||||
#endif /* _ARMOR_FINDER_H_ */
|
||||
|
||||
27
armor/include/armor_finder/classifier/armor.hpp
Normal file
27
armor/include/armor_finder/classifier/armor.hpp
Normal file
@@ -0,0 +1,27 @@
|
||||
#ifndef AUTO_AIM__ARMOR_HPP
|
||||
#define AUTO_AIM__ARMOR_HPP
|
||||
|
||||
#include <opencv2/core.hpp>
|
||||
#include <Eigen/Dense>
|
||||
#include <vector>
|
||||
|
||||
namespace auto_aim
|
||||
{
|
||||
enum class ArmorType { small, big };
|
||||
enum class ArmorName { NO, B1, B2, B3, B4, B5, B7, B8, R1, R2, R3, R4, R5, R7, R8, outpost };
|
||||
|
||||
struct Armor {
|
||||
ArmorType type;
|
||||
ArmorName name;
|
||||
std::vector<cv::Point2f> points;
|
||||
Eigen::Vector3d xyz_in_gimbal;
|
||||
Eigen::Vector3d xyz_in_world;
|
||||
Eigen::Vector3d ypr_in_gimbal;
|
||||
Eigen::Vector3d ypr_in_world;
|
||||
Eigen::Vector3d ypd_in_world;
|
||||
double yaw_raw;
|
||||
};
|
||||
|
||||
} // namespace auto_aim
|
||||
|
||||
#endif // AUTO_AIM__ARMOR_HPP
|
||||
58
armor/include/armor_finder/classifier/classifier.h
Normal file
58
armor/include/armor_finder/classifier/classifier.h
Normal file
@@ -0,0 +1,58 @@
|
||||
//
|
||||
// Created by xinyang on 19-4-19.
|
||||
//
|
||||
// 为了一时方便,使用循环和Eigen自行编写的CNN前向传播类。
|
||||
// 没有显著的性能损失。
|
||||
// 但类定义了网络结构,同时实现的操作较少,可扩展性较差
|
||||
|
||||
#ifndef _CLASSIFIER_H_
|
||||
#define _CLASSIFIER_H_
|
||||
|
||||
#include <Eigen/Dense>
|
||||
#include <opencv2/core/eigen.hpp>
|
||||
#include <vector>
|
||||
#include <string>
|
||||
#include <opencv2/core.hpp>
|
||||
|
||||
using namespace std;
|
||||
using namespace Eigen;
|
||||
|
||||
class Classifier {
|
||||
private:
|
||||
bool state; // 标志分类器是否正确初始化
|
||||
|
||||
// 所有网络参数
|
||||
vector<vector<MatrixXd>> conv1_w, conv2_w, conv3_w;
|
||||
vector<double> conv1_b, conv2_b, conv3_b;
|
||||
MatrixXd fc1_w, fc2_w;
|
||||
VectorXd fc1_b, fc2_b;
|
||||
// 读取网络参数的函数
|
||||
vector<vector<MatrixXd>> load_conv_w(const string &file);
|
||||
vector<double> load_conv_b(const string &file);
|
||||
MatrixXd load_fc_w(const string &file);
|
||||
VectorXd load_fc_b(const string &file);
|
||||
// 目前支持的所有操作
|
||||
MatrixXd softmax(const MatrixXd &input);
|
||||
MatrixXd relu(const MatrixXd &input);
|
||||
MatrixXd leaky_relu(const MatrixXd &input, float alpha);
|
||||
vector<vector<MatrixXd>> apply_bias(const vector<vector<MatrixXd>> &input, const vector<double> &bias);
|
||||
vector<vector<MatrixXd>> relu(const vector<vector<MatrixXd>> &input);
|
||||
vector<vector<MatrixXd>> leaky_relu(const vector<vector<MatrixXd>> &input, float alpha);
|
||||
vector<vector<MatrixXd>> max_pool(const vector<vector<MatrixXd>> &input, int size);
|
||||
vector<vector<MatrixXd>> mean_pool(const vector<vector<MatrixXd>> &input, int size);
|
||||
vector<vector<MatrixXd>> pand(const vector<vector<MatrixXd>> &input, int val);
|
||||
MatrixXd conv(const MatrixXd &filter, const MatrixXd &input);
|
||||
vector<vector<MatrixXd>> conv2(const vector<vector<MatrixXd>> &filter, const vector<vector<MatrixXd>> &input);
|
||||
MatrixXd flatten(const vector<vector<MatrixXd>> &input);
|
||||
|
||||
public:
|
||||
explicit Classifier(const string &folder);
|
||||
~Classifier() = default;
|
||||
|
||||
MatrixXd calculate(const vector<vector<MatrixXd>> &input);
|
||||
explicit operator bool() const;
|
||||
int operator()(const cv::Mat &image);
|
||||
};
|
||||
|
||||
|
||||
#endif /* _CLASSIFIER_H */
|
||||
48
armor/include/armor_finder/classifier/solver.h
Normal file
48
armor/include/armor_finder/classifier/solver.h
Normal file
@@ -0,0 +1,48 @@
|
||||
#ifndef AUTO_AIM__SOLVER_HPP
|
||||
#define AUTO_AIM__SOLVER_HPP
|
||||
|
||||
#include <Eigen/Dense> // 必须在opencv2/core/eigen.hpp上面
|
||||
#include <Eigen/Geometry>
|
||||
#include <opencv2/core/eigen.hpp>
|
||||
|
||||
#include "armor.hpp"
|
||||
|
||||
namespace auto_aim
|
||||
{
|
||||
class Solver
|
||||
{
|
||||
public:
|
||||
explicit Solver(const std::string & config_path);
|
||||
|
||||
Eigen::Matrix3d R_gimbal2world() const;
|
||||
|
||||
void set_R_gimbal2world(const Eigen::Quaterniond & q);
|
||||
|
||||
void solve(Armor & armor) const;
|
||||
|
||||
std::vector<cv::Point2f> reproject_armor(
|
||||
const Eigen::Vector3d & xyz_in_world, double yaw, ArmorType type, ArmorName name) const;
|
||||
|
||||
double oupost_reprojection_error(Armor armor, const double & picth);
|
||||
|
||||
std::vector<cv::Point2f> world2pixel(const std::vector<cv::Point3f> & worldPoints);
|
||||
|
||||
private:
|
||||
cv::Mat camera_matrix_;
|
||||
cv::Mat distort_coeffs_;
|
||||
Eigen::Matrix3d R_gimbal2imubody_;
|
||||
Eigen::Matrix3d R_camera2gimbal_;
|
||||
Eigen::Vector3d t_camera2gimbal_;
|
||||
Eigen::Matrix3d R_gimbal2world_;
|
||||
|
||||
void optimize_yaw(Armor & armor) const;
|
||||
|
||||
double armor_reprojection_error(const Armor & armor, double yaw, const double & inclined) const;
|
||||
double SJTU_cost(
|
||||
const std::vector<cv::Point2f> & cv_refs, const std::vector<cv::Point2f> & cv_pts,
|
||||
const double & inclined) const;
|
||||
};
|
||||
|
||||
} // namespace auto_aim
|
||||
|
||||
#endif // AUTO_AIM__SOLVER_HPP
|
||||
61
armor/include/show_images/auto_trigger.h
Normal file
61
armor/include/show_images/auto_trigger.h
Normal file
@@ -0,0 +1,61 @@
|
||||
#ifndef AUTO_TRIGGER_H
|
||||
#define AUTO_TRIGGER_H
|
||||
|
||||
#include <armor_finder/armor_finder.h>
|
||||
#include <show_images/ballistic_predicition.h>
|
||||
#include <config/setconfig.h>
|
||||
#include <vector>
|
||||
#include <numeric>
|
||||
|
||||
/**
|
||||
* @brief 自动扳机逻辑类,负责发射时机决策。
|
||||
*/
|
||||
class AutoTrigger {
|
||||
public:
|
||||
/**
|
||||
* @brief 自动扳机决策函数
|
||||
* @param armor_finder 当前自瞄主对象 (用于获取历史轨迹)
|
||||
* @param v0 弹丸初速度
|
||||
* @param gimbal_yaw 当前云台实时自瞄角偏移 (Yaw, 度)
|
||||
* @param gimbal_pitch 当前云台实时自瞄角偏移 (Pitch, 度)
|
||||
* @return true 目标与预测弹着点重合,建议击发
|
||||
*/
|
||||
static bool should_fire(const ArmorFinder &armor_finder, double v0, double gimbal_yaw, double gimbal_pitch) {
|
||||
if (armor_finder.history.size() < 3) return false; // 轨迹点不足,不预测
|
||||
|
||||
// 1. 获取目标当前的 3D 状态 (相对于相机)
|
||||
const auto &latest = armor_finder.history.back();
|
||||
double dist = latest.pos.z / 100.0; // cm -> m
|
||||
|
||||
// 2. 估计目标速度 (简单线性回归或两点差分)
|
||||
const auto &first = armor_finder.history.front();
|
||||
double dt = latest.time - first.time;
|
||||
if (dt <= 0) return false;
|
||||
|
||||
cv::Point3f velocity = (latest.pos - first.pos) * (1.0 / dt); // cm/s
|
||||
|
||||
// 3. 计算飞行时间 (单位: s)
|
||||
double t_flight = BallisticSolver::get_flight_time(dist, -gimbal_pitch, v0, BALLISTIC_K);
|
||||
double t_total = t_flight + SYSTEM_DELAY / 1000.0;
|
||||
|
||||
// 4. 预测目标未来的位置 (cm)
|
||||
cv::Point3f pos_pred = latest.pos + velocity * t_total;
|
||||
|
||||
// 5. 将预测位置映射回像素坐标 (用于判断重合)
|
||||
double x_pred_pixel = pos_pred.x * FOCUS_PIXAL / pos_pred.z + IMAGE_CENTER_X;
|
||||
double y_pred_pixel = pos_pred.y * FOCUS_PIXAL / pos_pred.z + IMAGE_CENTER_Y;
|
||||
|
||||
// 6. 推断弹着点偏移 (像素级)
|
||||
// 理想打击点应该就在相机中心 (自瞄已经对准补差后的位置)
|
||||
// 但是我们需要判断当前云台的 "指向误差" 是否足够小
|
||||
double dist_to_center = sqrt(pow(x_pred_pixel - IMAGE_CENTER_X, 2) + pow(y_pred_pixel - IMAGE_CENTER_Y, 2));
|
||||
|
||||
// 7. 动态阈值判定 (依据目标距离和装甲板大小)
|
||||
// 距离越远,允许的像素误差越小
|
||||
double threshold = 200.0 / (dist + 0.001); // 示例阈值:5米处允许40像素误差
|
||||
|
||||
return dist_to_center < threshold;
|
||||
}
|
||||
};
|
||||
|
||||
#endif // AUTO_TRIGGER_H
|
||||
97
armor/include/show_images/ballistic_predicition.h
Normal file
97
armor/include/show_images/ballistic_predicition.h
Normal file
@@ -0,0 +1,97 @@
|
||||
/*
|
||||
*** 此文件用于hero弹道着落点位,通过3D建模以及理论发弹速度以及后期轨道修正手段 ***
|
||||
*** 实现对敌方装甲板的精准打击 ***
|
||||
*/
|
||||
|
||||
#ifndef BALLISTIC_PREDICITION_H
|
||||
#define BALLISTIC_PREDICITION_H
|
||||
|
||||
#include <Eigen/Dense>
|
||||
#include <opencv2/core.hpp>
|
||||
|
||||
/**
|
||||
* 弹着点计算结果
|
||||
*/
|
||||
struct ImpactPoint {
|
||||
Eigen::Vector3d xyz_in_camera; // 弹着点在相机坐标系中的位置 (m)
|
||||
double flight_time; // 弹丸飞行时间 (s)
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief 弹道计算类:根据 IMU 当前 pitch 和追踪装甲板距离,
|
||||
* 推算弹着点在相机坐标系中的三维坐标。
|
||||
*
|
||||
* 坐标系约定(与 solver.cpp 一致):
|
||||
* 世界系: x=前, y=左, z=上
|
||||
* 相机系: z=前, x=右, y=下(OpenCV 标准)
|
||||
*/
|
||||
class BallisticSolver {
|
||||
public:
|
||||
/**
|
||||
* @brief 根据水平距离和垂直高度差,迭代求解补偿 pitch 角。
|
||||
* @param d 水平距离 (m)
|
||||
* @param y 垂直高度差 (m,目标高于枪口为正)
|
||||
* @param v0 枪口初速度 (m/s)
|
||||
* @param k 空气阻力系数
|
||||
* @return 补偿后的 pitch 角 (度)
|
||||
*/
|
||||
static double get_pitch(double d, double y, double v0, double k = 0.1);
|
||||
|
||||
/**
|
||||
* @brief 计算弹丸飞行时间。
|
||||
* @param d 目标水平距离 (m,由追踪装甲板获得)
|
||||
* @param pitch 当前 IMU pitch 角 (度,仰为正)
|
||||
* @param v0 枪口初速度 (m/s)
|
||||
* @param k 空气阻力系数
|
||||
* @return 弹丸飞行时间 (s)
|
||||
*/
|
||||
static double get_flight_time(double d, double pitch, double v0, double k = 0.1);
|
||||
|
||||
/**
|
||||
* @brief 根据当前 IMU pitch 角推算弹丸在水平距离 d 处的垂直高度。
|
||||
* @param d 目标水平距离 (m)
|
||||
* @param pitch 当前 IMU pitch 角 (度,仰为正)
|
||||
* @param v0 枪口初速度 (m/s)
|
||||
* @param k 空气阻力系数
|
||||
* @return 弹着点相对枪口的垂直高度 (m,高于枪口为正)
|
||||
*/
|
||||
static double get_impact_y(double d, double pitch, double v0, double k = 0.1);
|
||||
|
||||
/**
|
||||
* [TEST] 用于验证弹道算法正确性:将弹着点反解算到相机坐标系,
|
||||
* 再通过 project_to_pixel 投影到像素并用红点显示。
|
||||
* 如果实验结果正确,可直接注释调用处,不影响其他结构。
|
||||
*
|
||||
* 坐标变换链:
|
||||
* xyz_camera = R_c2g^T * (R_g2w^T * xyz_world - t_c2g)
|
||||
*
|
||||
* @param xyz_in_world 目标在世界坐标系中的位置 (m,来自 PnP Solver)
|
||||
* @param pitch_imu 当前 IMU pitch 角 (度,仰为正)
|
||||
* @param v0 枪口初速度 (m/s)
|
||||
* @param R_camera2gimbal 相机到云台的旋转矩阵
|
||||
* @param R_gimbal2world 云台到世界的旋转矩阵
|
||||
* @param t_camera2gimbal 相机原点在云台系中的平移向量 (m)
|
||||
* @param k 空气阻力系数
|
||||
* @return ImpactPoint { 弹着点相机坐标(m), 飞行时间(s) }
|
||||
*/
|
||||
static ImpactPoint get_impact_in_camera(
|
||||
const Eigen::Vector3d& xyz_in_world,
|
||||
double pitch_imu,
|
||||
double v0,
|
||||
const Eigen::Matrix3d& R_camera2gimbal,
|
||||
const Eigen::Matrix3d& R_gimbal2world,
|
||||
const Eigen::Vector3d& t_camera2gimbal,
|
||||
double k = 0.1);
|
||||
|
||||
/**
|
||||
* [TEST] 将相机坐标系3D点简化投影到像素坐标(针孔模型,无畲变)。
|
||||
* @param xyz_in_camera 弹着点在相机坐标系中的位置 (m)
|
||||
* @param camera_matrix OpenCV 相机内参矩阵 (3x3 CV_64F)
|
||||
* @return 像素坐标
|
||||
*/
|
||||
static cv::Point2f project_to_pixel(
|
||||
const Eigen::Vector3d& xyz_in_camera,
|
||||
const cv::Mat& camera_matrix);
|
||||
};
|
||||
|
||||
#endif // BALLISTIC_PREDICITION_H
|
||||
23
armor/include/show_images/show_images.h
Normal file
23
armor/include/show_images/show_images.h
Normal file
@@ -0,0 +1,23 @@
|
||||
//
|
||||
// Created by xinyang on 19-3-27.
|
||||
//
|
||||
|
||||
#ifndef _SHOW_IMAGES_H_
|
||||
#define _SHOW_IMAGES_H_
|
||||
|
||||
#include <opencv2/core.hpp>
|
||||
#include <armor_finder/armor_finder.h>
|
||||
|
||||
//
|
||||
void showArmorBoxes(std::string windows_name, const cv::Mat &src, const ArmorBoxes &armor_boxes);
|
||||
void showArmorBox(std::string windows_name, const cv::Mat &src, const ArmorBox &armor_box);
|
||||
void showLightBlobs(std::string windows_name, const cv::Mat &src, const LightBlobs &light_blobs);
|
||||
void showArmorBoxesClass(std::string window_names, const cv::Mat &src, const ArmorBoxes &boxes);
|
||||
void showTrackSearchingPos(std::string window_names, const cv::Mat &src, const cv::Rect2d pos);
|
||||
|
||||
// [TEST] 在图像上标注弹着点(红色小圆点),用于验证弹道算法正确性。
|
||||
// 如果实验结果正确,直接注释调用处即可,不影响其他结构。
|
||||
// impact_pixel: 由 BallisticSolver::project_to_pixel() 计算得到的像素坐标。
|
||||
void showImpactPoint(const std::string& window_name, const cv::Mat& src, cv::Point2f impact_pixel);
|
||||
|
||||
#endif /* _SHOW_IMAGES_H_ */
|
||||
88
armor/src/armor_finder/anti_top/anti_top.cpp
Normal file
88
armor/src/armor_finder/anti_top/anti_top.cpp
Normal file
@@ -0,0 +1,88 @@
|
||||
//
|
||||
// Created by xinyang on 19-7-15.
|
||||
//
|
||||
|
||||
#include <armor_finder/armor_finder.h>
|
||||
#include <additions.h>
|
||||
#include <log.h>
|
||||
#include <show_images/ballistic_predicition.h>
|
||||
#include <config/setconfig.h>
|
||||
|
||||
template<int length>
|
||||
static double mean(RoundQueue<double, length> &vec) {
|
||||
double sum = 0;
|
||||
for (int i = 0; i < vec.size(); i++) {
|
||||
sum += vec[i];
|
||||
}
|
||||
return sum / length;
|
||||
}
|
||||
|
||||
static systime getFrontTime(const vector<systime> time_seq, const vector<float> angle_seq) {
|
||||
double A = 0, B = 0, C = 0, D = 0;
|
||||
int len = time_seq.size();
|
||||
for (int i = 0; i < len; i++) {
|
||||
A += angle_seq[i] * angle_seq[i];
|
||||
B += angle_seq[i];
|
||||
C += angle_seq[i] * time_seq[i];
|
||||
D += time_seq[i];
|
||||
cout << "(" << angle_seq[i] << ", " << time_seq[i] << ") ";
|
||||
}
|
||||
double b = (A * D - B * C) / (len * A - B * B);
|
||||
cout << b << endl;
|
||||
return b;
|
||||
}
|
||||
|
||||
void ArmorFinder::antiTop(double dist_m, double pitch_imu_deg) {
|
||||
if (target_box.rect == cv::Rect2d()) return;
|
||||
// 判断是否发生装甲目标切换。
|
||||
// 记录切换前一段时间目标装甲的角度和时间
|
||||
// 通过线性拟合计算出角度为0时对应的时间点
|
||||
// 通过两次装甲角度为零的时间差计算陀螺旋转周期
|
||||
// 根据旋转周期计算下一次装甲出现在角度为零的时间点
|
||||
if (getPointLength(last_box.getCenter() - target_box.getCenter()) > last_box.rect.height * 1.5) {
|
||||
auto front_time = getFrontTime(time_seq, angle_seq);
|
||||
auto once_periodms = getTimeIntervalms(front_time, last_front_time);
|
||||
// if (abs(once_periodms - top_periodms[-1]) > 50) {
|
||||
// sendBoxPosition(0);
|
||||
// return;
|
||||
// }
|
||||
LOGM(STR_CTR(WORD_GREEN, "Top period: %.1lf"), once_periodms);
|
||||
top_periodms.push(once_periodms);
|
||||
auto periodms = mean(top_periodms);
|
||||
systime curr_time;
|
||||
getsystime(curr_time);
|
||||
|
||||
// 飞行时间补偿(ms)
|
||||
double fly_time_ms = BallisticSolver::get_flight_time(
|
||||
dist_m, pitch_imu_deg, MUZZLE_VELOCITY, BALLISTIC_K) * 1000.0;
|
||||
constexpr double sys_delay_ms = SYSTEM_DELAY; // setconfig.h 默认 50 ms
|
||||
|
||||
// 修正公式:子弹命中时刻 = 发令时刻 + shoot_delay + sys_delay + fly_time
|
||||
// 令子弹命中时刻 = front_time + periodms×2
|
||||
int32_t delay_raw = static_cast<int32_t>(
|
||||
front_time + periodms * 2 - curr_time - sys_delay_ms - fly_time_ms);
|
||||
|
||||
// 若错过当前窗口(delay_raw < 0),顺延一个周期
|
||||
uint16_t shoot_delay = (delay_raw > 0)
|
||||
? static_cast<uint16_t>(delay_raw)
|
||||
: static_cast<uint16_t>(delay_raw + static_cast<int32_t>(periodms));
|
||||
if (anti_top_cnt < 4) {
|
||||
sendBoxPosition(0);
|
||||
} else if (abs(once_periodms - top_periodms[-1]) > 50) {
|
||||
sendBoxPosition(0);
|
||||
} else {
|
||||
sendBoxPosition(shoot_delay);
|
||||
}
|
||||
time_seq.clear();
|
||||
angle_seq.clear();
|
||||
last_front_time = front_time;
|
||||
} else {
|
||||
time_seq.emplace_back(frame_time);
|
||||
double dx = target_box.rect.x + target_box.rect.width / 2 - IMAGE_CENTER_X;
|
||||
double yaw = atan(dx / FOCUS_PIXAL) * 180 / PI;
|
||||
angle_seq.emplace_back(yaw);
|
||||
sendBoxPosition(0);
|
||||
}
|
||||
anti_top_cnt++;
|
||||
}
|
||||
|
||||
99
armor/src/armor_finder/armor_box/armor_box.cpp
Normal file
99
armor/src/armor_finder/armor_box/armor_box.cpp
Normal file
@@ -0,0 +1,99 @@
|
||||
//
|
||||
// Created by xinyang on 19-7-13.
|
||||
//
|
||||
|
||||
#include <armor_finder/armor_finder.h>
|
||||
#include <log.h>
|
||||
|
||||
ArmorBox::ArmorBox(const cv::Rect &pos, const LightBlobs &blobs, uint8_t color, int i, const std::vector<cv::Point2f> &pts) :
|
||||
rect(pos), light_blobs(blobs), box_color(color), id(i), points(pts) {};
|
||||
|
||||
// 获取装甲板中心点
|
||||
cv::Point2f ArmorBox::getCenter() const {
|
||||
return cv::Point2f(
|
||||
rect.x + rect.width / 2,
|
||||
rect.y + rect.height / 2
|
||||
);
|
||||
}
|
||||
|
||||
// 获取两个灯条中心点的间距
|
||||
double ArmorBox::getBlobsDistance() const {
|
||||
if (light_blobs.size() == 2) {
|
||||
auto &x = light_blobs[0].rect.center;
|
||||
auto &y = light_blobs[1].rect.center;
|
||||
return sqrt((x.x - y.x) * (x.x - y.x) + (x.y - y.y) * (x.y - y.y));
|
||||
} else {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
// 获取灯条长度和间距的比例
|
||||
double ArmorBox::lengthDistanceRatio() const {
|
||||
if (light_blobs.size() == 2) {
|
||||
return max(light_blobs[0].length, light_blobs[1].length)
|
||||
/ getBlobsDistance();
|
||||
} else {
|
||||
return 100;
|
||||
}
|
||||
}
|
||||
|
||||
// 计算装甲板到摄像头的距离
|
||||
double ArmorBox::getBoxDistance() const {
|
||||
if (light_blobs.size() == 2) {
|
||||
return DISTANCE_HEIGHT / 2 / max(light_blobs[0].length, light_blobs[1].length);
|
||||
} else {
|
||||
return DISTANCE_HEIGHT / rect.height;
|
||||
}
|
||||
}
|
||||
|
||||
// 判断装甲板的正对还是侧对(已弃用,误差过大)
|
||||
ArmorBox::BoxOrientation ArmorBox::getOrientation() const {
|
||||
if (light_blobs.size() != 2) {
|
||||
return UNKNOWN;
|
||||
}
|
||||
switch (id) {
|
||||
case R1:
|
||||
case R7:
|
||||
case R8:
|
||||
case B1:
|
||||
case B7:
|
||||
case B8:
|
||||
if (lengthDistanceRatio() < 0.26) {
|
||||
return FRONT;
|
||||
} else {
|
||||
return SIDE;
|
||||
}
|
||||
case R2:
|
||||
case R3:
|
||||
case R4:
|
||||
case R5:
|
||||
case B2:
|
||||
case B3:
|
||||
case B4:
|
||||
case B5:
|
||||
if (lengthDistanceRatio() < 0.51) {
|
||||
return FRONT;
|
||||
} else {
|
||||
return SIDE;
|
||||
}
|
||||
default:
|
||||
return UNKNOWN;
|
||||
}
|
||||
}
|
||||
// 装甲板的优先级比较
|
||||
bool ArmorBox::operator<(const ArmorBox &box) const {
|
||||
if (id != box.id) {
|
||||
if (box_color == BOX_BLUE) {
|
||||
return prior_blue[id2name[id]] < prior_blue[id2name[box.id]];
|
||||
} else {
|
||||
return prior_red[id2name[id]] < prior_red[id2name[box.id]];
|
||||
}
|
||||
} else {
|
||||
auto d1 = (rect.x - IMAGE_CENTER_X) * (rect.x - IMAGE_CENTER_X)
|
||||
+ (rect.y - IMAGE_CENTER_Y) * (rect.y - IMAGE_CENTER_Y);
|
||||
auto d2 = (box.rect.x - IMAGE_CENTER_X) * (box.rect.x - IMAGE_CENTER_X)
|
||||
+ (box.rect.y - IMAGE_CENTER_Y) * (box.rect.y - IMAGE_CENTER_Y);
|
||||
return d1 < d2;
|
||||
}
|
||||
}
|
||||
|
||||
148
armor/src/armor_finder/armor_finder.cpp
Normal file
148
armor/src/armor_finder/armor_finder.cpp
Normal file
@@ -0,0 +1,148 @@
|
||||
//
|
||||
// Created by xinyang on 19-3-27.
|
||||
//
|
||||
|
||||
/*===========================================================================*/
|
||||
/* 使用本代码的兵种 */
|
||||
/*===========================================================================*/
|
||||
/* _______________ _______________ _______________ _______________ */
|
||||
/* | _____ | | _ _ | | ____ | | _____ | */
|
||||
/* || |___ / || || | || | || || | ___| || || |___ | || */
|
||||
/* || |_ \ || || | || |_ || || |___ \ || || / / || */
|
||||
/* || ___) | || || |__ _| || || ___) | || || / / || */
|
||||
/* || |____/ || || |_| || || |____/ || || /_/ || */
|
||||
/* |_______________| |_______________| |_______________| |_______________| */
|
||||
/* */
|
||||
/*===========================================================================*/
|
||||
|
||||
#define LOG_LEVEL LOG_NONE
|
||||
#include <log.h>
|
||||
#include <options.h>
|
||||
#include <show_images/show_images.h>
|
||||
#include <opencv2/highgui.hpp>
|
||||
#include <armor_finder/armor_finder.h>
|
||||
|
||||
std::map<int, string> id2name = { //装甲板id到名称的map
|
||||
{-1, "OO"},{ 0, "NO"},
|
||||
{ 1, "B1"},{ 2, "B2"},{ 3, "B3"},{ 4, "B4"},{ 5, "B5"},{ 6, "B7"},{ 7, "B8"},
|
||||
{ 8, "R1"},{ 9, "R2"},{10, "R3"},{11, "R4"},{12, "R5"},{13, "R7"},{14, "R8"},
|
||||
};
|
||||
|
||||
std::map<string, int> name2id = { //装甲板名称到id的map
|
||||
{"OO", -1},{"NO", 0},
|
||||
{"B1", 1},{"B2", 2},{"B3", 3},{"B4", 4},{"B5", 5},{"B7", 6},{"B8", 7},
|
||||
{"R1", 8},{"R2", 9},{"R3", 10},{"R4", 11},{"R5", 12},{"R7", 13},{"R8", 14},
|
||||
};
|
||||
|
||||
std::map<string, int> prior_blue = {
|
||||
{"B8", 0}, {"B1", 1}, {"B3", 2}, {"B4", 2}, {"B5", 2}, {"B7", 3}, {"B2", 4},
|
||||
{"R8", 5}, {"R1", 6}, {"R3", 7}, {"R4", 7}, {"R5", 7}, {"R7", 8}, {"R2", 9},
|
||||
{"NO", 10},
|
||||
};
|
||||
|
||||
std::map<string, int> prior_red = {
|
||||
{"R8", 0}, {"R1", 1}, {"R3", 2}, {"R4", 2}, {"R5", 2}, {"R7", 3}, {"R2", 4},
|
||||
{"B8", 5}, {"B1", 6}, {"B3", 7}, {"B4", 7}, {"B5", 7}, {"B7", 8}, {"B2", 9},
|
||||
{"NO", 10},
|
||||
};
|
||||
|
||||
ArmorFinder::ArmorFinder(uint8_t &color, Serial &u, const string ¶s_folder, const uint8_t &anti_top) :
|
||||
serial(u),
|
||||
enemy_color(color),
|
||||
is_anti_top(anti_top),
|
||||
state(STANDBY_STATE),
|
||||
anti_switch_cnt(0),
|
||||
classifier(paras_folder),
|
||||
contour_area(0),
|
||||
tracking_cnt(0),
|
||||
solver(PROJECT_DIR"/others/solver_config.yml") {
|
||||
}
|
||||
|
||||
void ArmorFinder::run(cv::Mat &src) {
|
||||
getsystime(frame_time); // 获取当前帧时间(不是足够精确)
|
||||
// stateSearchingTarget(src); // for debug
|
||||
// goto end;
|
||||
switch (state) {
|
||||
case SEARCHING_STATE:
|
||||
if (stateSearchingTarget(src)) {
|
||||
if ((target_box.rect & cv::Rect2d(0, 0, 640, 480)) == target_box.rect) { // 判断装甲板区域是否脱离图像区域
|
||||
if (!classifier) { /* 如果分类器不可用 */
|
||||
cv::Mat roi = src(target_box.rect).clone(), roi_gray; /* 就使用装甲区域亮点数判断是否跟丢 */
|
||||
cv::cvtColor(roi, roi_gray, cv::COLOR_RGB2GRAY);
|
||||
cv::threshold(roi_gray, roi_gray, 180, 255, cv::THRESH_BINARY);
|
||||
contour_area = cv::countNonZero(roi_gray);
|
||||
}
|
||||
tracker = TrackerToUse::create(); // 成功搜寻到装甲板,创建tracker对象
|
||||
tracker->init(src, target_box.rect);
|
||||
state = TRACKING_STATE;
|
||||
tracking_cnt = 0;
|
||||
LOGM(STR_CTR(WORD_LIGHT_CYAN, "into track"));
|
||||
}
|
||||
}
|
||||
break;
|
||||
case TRACKING_STATE:
|
||||
if (!stateTrackingTarget(src) || ++tracking_cnt > 100) { // 最多追踪100帧图像
|
||||
state = SEARCHING_STATE;
|
||||
LOGM(STR_CTR(WORD_LIGHT_YELLOW, "into search!"));
|
||||
}
|
||||
break;
|
||||
case STANDBY_STATE:
|
||||
default:
|
||||
stateStandBy(); // currently meaningless
|
||||
}
|
||||
end:
|
||||
if(is_anti_top) { // 判断当前是否为反陀螺模式
|
||||
// dist_m: 目标水平距离(m),由 target_xyz (cm) 计算
|
||||
double dist_m = std::sqrt(
|
||||
target_xyz.x * target_xyz.x + target_xyz.z * target_xyz.z) / 100.0;
|
||||
// TODO: pitch_imu_deg 替换为从串口/IMU读入的实际 pitch 角 (度,仰为正)
|
||||
double pitch_imu_deg = 0.0;
|
||||
antiTop(dist_m, pitch_imu_deg);
|
||||
}else if(target_box.rect != cv::Rect2d()) {
|
||||
anti_top_cnt = 0;
|
||||
time_seq.clear();
|
||||
angle_seq.clear();
|
||||
sendBoxPosition(0);
|
||||
}
|
||||
|
||||
if(target_box.rect != cv::Rect2d()){
|
||||
last_box = target_box;
|
||||
}
|
||||
|
||||
if (show_armor_box) { // 根据条件显示当前目标装甲板
|
||||
showArmorBox("box", src, target_box);
|
||||
cv::waitKey(1);
|
||||
}
|
||||
|
||||
// 自动扳机位置预测逻辑:更新历史位置
|
||||
if (target_box.rect != cv::Rect2d()) {
|
||||
auto_aim::Armor armor;
|
||||
armor.type = (target_box.id == B1 || target_box.id == R1 || target_box.id == B2 || target_box.id == R2 || target_box.id == B7 || target_box.id == R7 || target_box.id == B8 || target_box.id == R8) ? auto_aim::ArmorType::big : auto_aim::ArmorType::small;
|
||||
armor.name = static_cast<auto_aim::ArmorName>(target_box.id); // This might need mapping
|
||||
armor.points = target_box.points;
|
||||
|
||||
// 获取当前云台位姿 (假设 mcu_data 有 q)
|
||||
// solver.set_R_gimbal2world(Eigen::Quaterniond(mcu_data.q[0], mcu_data.q[1], mcu_data.q[2], mcu_data.q[3]));
|
||||
|
||||
solver.solve(armor);
|
||||
|
||||
target_xyz = cv::Point3f(armor.xyz_in_gimbal.x() * 100.0, armor.xyz_in_gimbal.y() * 100.0, armor.xyz_in_gimbal.z() * 100.0); // 转换为cm
|
||||
cv::Point3f current_pos = target_xyz;
|
||||
double current_time = static_cast<double>(frame_time.tv_sec) + static_cast<double>(frame_time.tv_usec) / 1e6;
|
||||
history.push_back({current_pos, current_time});
|
||||
if (history.size() > 10) { // 仅保留最近10帧
|
||||
history.erase(history.begin());
|
||||
}
|
||||
} else {
|
||||
history.clear(); // 目标丢失,清空历史
|
||||
}
|
||||
}
|
||||
|
||||
cv::Point3f ArmorFinder::getTarget3D(const ArmorBox &box) {
|
||||
double z = box.getBoxDistance(); // 单位: cm
|
||||
double x = z * (box.getCenter().x - IMAGE_CENTER_X) / FOCUS_PIXAL;
|
||||
double y = z * (box.getCenter().y - IMAGE_CENTER_Y) / FOCUS_PIXAL;
|
||||
return cv::Point3f(x, y, z);
|
||||
}
|
||||
|
||||
|
||||
332
armor/src/armor_finder/classifier/classifier.cpp
Normal file
332
armor/src/armor_finder/classifier/classifier.cpp
Normal file
@@ -0,0 +1,332 @@
|
||||
//
|
||||
// Created by xinyang on 19-4-19.
|
||||
//
|
||||
// 对本文件的大致描述请看classifier.h
|
||||
|
||||
//#define LOG_LEVEL LOG_NONE
|
||||
#include <armor_finder/classifier/classifier.h>
|
||||
#include <log.h>
|
||||
#include <cstdio>
|
||||
#include <iostream>
|
||||
|
||||
|
||||
vector<vector<MatrixXd>> Classifier::load_conv_w(const string &file){
|
||||
vector<vector<MatrixXd>> result;
|
||||
FILE *fp = fopen(file.data(), "r");
|
||||
if(fp == nullptr){
|
||||
LOGE("%s open fail!", file.data());
|
||||
state = false;
|
||||
return result;
|
||||
}
|
||||
int channel_in, channel_out, row, col;
|
||||
fscanf(fp, "%d %d %d %d", &channel_in, &channel_out, &row, &col);
|
||||
for(int o=0; o<channel_in; o++){
|
||||
vector<MatrixXd> sub;
|
||||
for(int i=0; i<channel_out; i++){
|
||||
MatrixXd f(row, col);
|
||||
for(int r=0; r<row; r++){
|
||||
for(int c=0; c<col; c++){
|
||||
fscanf(fp, "%lf", &f(r, c));
|
||||
}
|
||||
}
|
||||
sub.emplace_back(f);
|
||||
}
|
||||
result.emplace_back(sub);
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
vector<double> Classifier::load_conv_b(const string &file){
|
||||
vector<double> result;
|
||||
FILE *fp = fopen(file.data(), "r");
|
||||
if(fp == nullptr){
|
||||
LOGE("%s open fail!", file.data());
|
||||
state = false;
|
||||
return result;
|
||||
}
|
||||
int len;
|
||||
fscanf(fp, "%d", &len);
|
||||
for(int i=0; i<len; i++) {
|
||||
double v;
|
||||
fscanf(fp, "%lf", &v);
|
||||
result.emplace_back(v);
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
MatrixXd Classifier::load_fc_w(const string &file){
|
||||
FILE *fp = fopen(file.data(), "r");
|
||||
if(fp == nullptr){
|
||||
LOGE("%s open fail!", file.data());
|
||||
state = false;
|
||||
return MatrixXd::Zero(1,1);
|
||||
}
|
||||
int row, col;
|
||||
fscanf(fp, "%d %d", &col, &row);
|
||||
MatrixXd mat(row, col);
|
||||
for(int c=0; c<col; c++){
|
||||
for(int r=0; r<row; r++){
|
||||
fscanf(fp, "%lf", &mat(r, c));
|
||||
}
|
||||
}
|
||||
return mat;
|
||||
}
|
||||
|
||||
VectorXd Classifier::load_fc_b(const string &file){
|
||||
FILE *fp = fopen(file.data(), "r");
|
||||
if(fp == nullptr){
|
||||
LOGE("%s open fail!", file.data());
|
||||
state = false;
|
||||
return VectorXd::Zero(1,1);
|
||||
}
|
||||
int row;
|
||||
fscanf(fp, "%d", &row);
|
||||
VectorXd vec(row, 1);
|
||||
for(int r=0; r<row; r++){
|
||||
fscanf(fp, "%lf", &vec(r));
|
||||
}
|
||||
return vec;
|
||||
}
|
||||
|
||||
MatrixXd Classifier::softmax(const MatrixXd &input){
|
||||
MatrixXd tmp = input.array() - input.maxCoeff();
|
||||
return tmp.array().exp() / tmp.array().exp().sum();
|
||||
}
|
||||
|
||||
vector<vector<MatrixXd>> Classifier::max_pool(const vector<vector<MatrixXd>> &input, int size){
|
||||
vector<vector<MatrixXd>> output;
|
||||
for(int sample=0; sample<input.size(); sample++) {
|
||||
vector<MatrixXd> sub;
|
||||
for (int channel = 0; channel < input[0].size(); channel++) {
|
||||
MatrixXd tmp(input[0][0].rows() / size, input[0][0].cols() / size);
|
||||
for (int row = 0; row < input[0][0].rows() / size; row++) {
|
||||
for (int col = 0; col < input[0][0].cols() / size; col++) {
|
||||
double max = 0;
|
||||
for (int x = 0; x < size; x++) {
|
||||
for (int y = 0; y < size; y++) {
|
||||
if(max < input[sample][channel](row * size + x, col * size + y)){
|
||||
max = input[sample][channel](row * size + x, col * size + y);
|
||||
}
|
||||
}
|
||||
}
|
||||
tmp(row, col) = max;
|
||||
}
|
||||
}
|
||||
sub.emplace_back(tmp);
|
||||
}
|
||||
output.emplace_back(sub);
|
||||
}
|
||||
return output;
|
||||
}
|
||||
|
||||
vector<vector<MatrixXd>> Classifier::mean_pool(const vector<vector<MatrixXd>> &input, int size){
|
||||
vector<vector<MatrixXd>> output;
|
||||
for(int sample=0; sample<input.size(); sample++) {
|
||||
vector<MatrixXd> sub;
|
||||
for (int channel = 0; channel < input[0].size(); channel++) {
|
||||
MatrixXd tmp(input[0][0].rows() / size, input[0][0].cols() / size);
|
||||
for (int row = 0; row < input[0][0].rows() / size; row++) {
|
||||
for (int col = 0; col < input[0][0].cols() / size; col++) {
|
||||
double val = 0;
|
||||
for (int x = 0; x < size; x++) {
|
||||
for (int y = 0; y < size; y++) {
|
||||
val += input[sample][channel](row * size + x, col * size + y);
|
||||
}
|
||||
}
|
||||
tmp(row, col) = val / size / size;
|
||||
}
|
||||
}
|
||||
sub.emplace_back(tmp);
|
||||
}
|
||||
output.emplace_back(sub);
|
||||
}
|
||||
return output;
|
||||
}
|
||||
|
||||
vector<vector<MatrixXd>> Classifier::apply_bias(const vector<vector<MatrixXd>> &input, const vector<double> &bias){
|
||||
assert(input[0].size()==bias.size());
|
||||
vector<vector<MatrixXd>> result;
|
||||
for(int samples=0; samples<input.size(); samples++){
|
||||
vector<MatrixXd> sub;
|
||||
for(int channels=0; channels<input[0].size(); channels++){
|
||||
MatrixXd mat = input[samples][channels].array() + bias[channels];
|
||||
sub.emplace_back(mat);
|
||||
}
|
||||
result.emplace_back(sub);
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
MatrixXd Classifier::relu(const MatrixXd &input){
|
||||
return input.unaryExpr([](double val){
|
||||
return (val>0)?(val):(0);
|
||||
});
|
||||
}
|
||||
|
||||
MatrixXd Classifier::leaky_relu(const MatrixXd &input, float alpha){
|
||||
return input.unaryExpr([&](double val){
|
||||
return (val>0)?(val):(alpha*val);
|
||||
});
|
||||
}
|
||||
|
||||
vector<vector<MatrixXd>> Classifier::relu(const vector<vector<MatrixXd>> &input){
|
||||
vector<vector<MatrixXd>> result;
|
||||
for(int samples=0; samples<input.size(); samples++){
|
||||
vector<MatrixXd> sub;
|
||||
for(int channels=0; channels<input[0].size(); channels++){
|
||||
sub.emplace_back(relu(input[samples][channels]));
|
||||
}
|
||||
result.emplace_back(sub);
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
vector<vector<MatrixXd>> Classifier::leaky_relu(const vector<vector<MatrixXd>> &input, float alpha){
|
||||
vector<vector<MatrixXd>> result;
|
||||
for(int samples=0; samples<input.size(); samples++){
|
||||
vector<MatrixXd> sub;
|
||||
for(int channels=0; channels<input[0].size(); channels++){
|
||||
sub.emplace_back(leaky_relu(input[samples][channels], alpha));
|
||||
}
|
||||
result.emplace_back(sub);
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
vector<vector<MatrixXd>> Classifier::pand(const vector<vector<MatrixXd>> &input, int val){
|
||||
vector<vector<MatrixXd>> result;
|
||||
for(int sample=0; sample<input.size(); sample++){
|
||||
vector<MatrixXd> sub;
|
||||
for(int channels=0; channels<input[0].size(); channels++){
|
||||
MatrixXd mat = MatrixXd::Zero(input[0][0].rows()+2*val, input[0][0].cols()+2*val);
|
||||
mat.block(val, val, input[0][0].rows(), input[0][0].cols()) = input[sample][channels];
|
||||
sub.emplace_back(mat);
|
||||
}
|
||||
result.emplace_back(sub);
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
MatrixXd Classifier::conv(const MatrixXd &filter, const MatrixXd &input){
|
||||
int result_rows = input.rows()-filter.rows()+1;
|
||||
int result_cols = input.cols()-filter.cols()+1;
|
||||
MatrixXd result(result_rows, result_cols);
|
||||
for(int row=0; row<result_rows; row++){
|
||||
for(int col=0; col<result_cols; col++){
|
||||
double val=0;
|
||||
for(int x=0; x<filter.cols(); x++){
|
||||
for(int y=0; y<filter.cols(); y++){
|
||||
val += input(row+x, col+y) * filter(x,y);
|
||||
}
|
||||
}
|
||||
result(row, col) = val;
|
||||
// result(row, col) = (input.block(row, col, size, size).array() * input.array()).sum();
|
||||
}
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
vector<vector<MatrixXd>> Classifier::conv2(const vector<vector<MatrixXd>> &filter, const vector<vector<MatrixXd>> &input){
|
||||
if(filter.size() != input[0].size()){
|
||||
LOGE("shape du not match, which is filter.size=%d, input[0].size()=%d", filter.size(), input[0].size());
|
||||
exit(-1);
|
||||
}
|
||||
vector<vector<MatrixXd>> result;
|
||||
int result_rows = input[0][0].rows()-filter[0][0].rows()+1;
|
||||
int result_cols = input[0][0].cols()-filter[0][0].cols()+1;
|
||||
for(int col=0; col<input.size(); col++){
|
||||
vector<MatrixXd> sub;
|
||||
for(int row=0; row<filter[0].size(); row++){
|
||||
MatrixXd val = MatrixXd::Zero(result_rows, result_cols);
|
||||
for(int x=0; x<filter.size(); x++){
|
||||
val += conv(filter[x][row], input[col][x]);
|
||||
}
|
||||
sub.emplace_back(val);
|
||||
}
|
||||
result.emplace_back(sub);
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
MatrixXd Classifier::flatten(const vector<vector<MatrixXd>> &input){
|
||||
int ones = input[0][0].rows()*input[0][0].cols();
|
||||
int channels = input[0].size();
|
||||
int samples = input.size();
|
||||
int row = input[0][0].rows();
|
||||
int col = input[0][0].cols();
|
||||
MatrixXd output(channels*ones,samples);
|
||||
for(int s=0; s<samples; s++) {
|
||||
for(int r=0, cnt=0; r<row; r++){
|
||||
for(int c=0; c<col; c++){
|
||||
for (int i = 0; i < channels; i++) {
|
||||
output(cnt++, s) = input[s][i](r, c);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
return output;
|
||||
}
|
||||
|
||||
Classifier::Classifier(const string &folder) : state(true){
|
||||
conv1_w = load_conv_w(folder+"conv1_w");
|
||||
conv1_b = load_conv_b(folder+"conv1_b");
|
||||
conv2_w = load_conv_w(folder+"conv2_w");
|
||||
conv2_b = load_conv_b(folder+"conv2_b");
|
||||
conv3_w = load_conv_w(folder+"conv3_w");
|
||||
conv3_b = load_conv_b(folder+"conv3_b");
|
||||
fc1_w = load_fc_w(folder+"fc1_w");
|
||||
fc1_b = load_fc_b(folder+"fc1_b");
|
||||
fc2_w = load_fc_w(folder+"fc2_w");
|
||||
fc2_b = load_fc_b(folder+"fc2_b");
|
||||
if(state){
|
||||
LOGM("Load para success!");
|
||||
}
|
||||
}
|
||||
|
||||
//#define PRINT_MAT(name) (cout << #name":\n" << name << endl)
|
||||
//#define PRINT_MULTI_MAT(name) (cout << #name":\n" << name[0][0] << endl)
|
||||
//#define PRINT_MAT_SHAPE(name) LOGM(#name":(%d, %d)", name.rows(), name.cols())
|
||||
//#define PRINT_MULTI_MAT_SHAPE(name) LOGM(#name":(%d, %d)", name[0][0].rows(), name[0][0].cols())
|
||||
|
||||
MatrixXd Classifier::calculate(const vector<vector<MatrixXd>> &input) {
|
||||
vector<vector<MatrixXd>> conv1_result = relu(apply_bias(conv2(conv1_w, input), conv1_b));
|
||||
vector<vector<MatrixXd>> pool1_result = mean_pool(conv1_result, 2);
|
||||
vector<vector<MatrixXd>> conv2_result = relu(apply_bias(conv2(conv2_w, pool1_result), conv2_b));
|
||||
vector<vector<MatrixXd>> pool2_result = mean_pool(conv2_result, 2);
|
||||
vector<vector<MatrixXd>> conv3_result = relu(apply_bias(conv2(conv3_w, pool2_result), conv3_b));
|
||||
MatrixXd flattened = flatten(conv3_result);
|
||||
MatrixXd y1 = fc1_w * flattened;
|
||||
y1.colwise() += fc1_b;
|
||||
MatrixXd fc1 = relu(y1);
|
||||
MatrixXd y2 = fc2_w * fc1;
|
||||
y2.colwise() += fc2_b;
|
||||
MatrixXd fc2 = softmax(y2);
|
||||
return fc2;
|
||||
}
|
||||
|
||||
Classifier::operator bool() const {
|
||||
return state;
|
||||
}
|
||||
|
||||
int Classifier::operator()(const cv::Mat &image) {
|
||||
MatrixXd r, g, b;
|
||||
std::vector<cv::Mat> channels;
|
||||
cv::split(image, channels);
|
||||
cv2eigen(channels[0], b);
|
||||
cv2eigen(channels[1], g);
|
||||
cv2eigen(channels[2], r);
|
||||
r /= 255;
|
||||
g /= 255;
|
||||
b /= 255;
|
||||
vector<MatrixXd> sub = {b, g, r};
|
||||
vector<vector<MatrixXd>> in = {sub};
|
||||
MatrixXd result = calculate(in);
|
||||
MatrixXd::Index minRow, minCol;
|
||||
result.maxCoeff(&minRow, &minCol);
|
||||
if(result(minRow, minCol) > 0.50){
|
||||
return minRow;
|
||||
}else{
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
295
armor/src/armor_finder/classifier/solver.cpp
Normal file
295
armor/src/armor_finder/classifier/solver.cpp
Normal file
@@ -0,0 +1,295 @@
|
||||
#include "solver.h"
|
||||
|
||||
#include <yaml-cpp/yaml.h>
|
||||
|
||||
#include <vector>
|
||||
|
||||
#include "tools/logger.hpp"
|
||||
#include "tools/math_tools.hpp"
|
||||
|
||||
namespace auto_aim
|
||||
{
|
||||
constexpr double LIGHTBAR_LENGTH = 56e-3; // m
|
||||
constexpr double BIG_ARMOR_WIDTH = 230e-3; // m
|
||||
constexpr double SMALL_ARMOR_WIDTH = 135e-3; // m
|
||||
|
||||
const std::vector<cv::Point3f> BIG_ARMOR_POINTS{
|
||||
{0, BIG_ARMOR_WIDTH / 2, LIGHTBAR_LENGTH / 2},
|
||||
{0, -BIG_ARMOR_WIDTH / 2, LIGHTBAR_LENGTH / 2},
|
||||
{0, -BIG_ARMOR_WIDTH / 2, -LIGHTBAR_LENGTH / 2},
|
||||
{0, BIG_ARMOR_WIDTH / 2, -LIGHTBAR_LENGTH / 2}};
|
||||
const std::vector<cv::Point3f> SMALL_ARMOR_POINTS{
|
||||
{0, SMALL_ARMOR_WIDTH / 2, LIGHTBAR_LENGTH / 2},
|
||||
{0, -SMALL_ARMOR_WIDTH / 2, LIGHTBAR_LENGTH / 2},
|
||||
{0, -SMALL_ARMOR_WIDTH / 2, -LIGHTBAR_LENGTH / 2},
|
||||
{0, SMALL_ARMOR_WIDTH / 2, -LIGHTBAR_LENGTH / 2}};
|
||||
|
||||
Solver::Solver(const std::string & config_path) : R_gimbal2world_(Eigen::Matrix3d::Identity())
|
||||
{
|
||||
auto yaml = YAML::LoadFile(config_path);
|
||||
|
||||
/*
|
||||
auto R_gimbal2imubody_data = yaml["R_gimbal2imubody"].as<std::vector<double>>();
|
||||
auto R_camera2gimbal_data = yaml["R_camera2gimbal"].as<std::vector<double>>();
|
||||
auto t_camera2gimbal_data = yaml["t_camera2gimbal"].as<std::vector<double>>();
|
||||
R_gimbal2imubody_ = Eigen::Matrix<double, 3, 3, Eigen::RowMajor>(R_gimbal2imubody_data.data());
|
||||
R_camera2gimbal_ = Eigen::Matrix<double, 3, 3, Eigen::RowMajor>(R_camera2gimbal_data.data());
|
||||
t_camera2gimbal_ = Eigen::Matrix<double, 3, 1>(t_camera2gimbal_data.data());
|
||||
*/
|
||||
|
||||
auto camera_matrix_data = yaml["camera_matrix"].as<std::vector<double>>();
|
||||
auto distort_coeffs_data = yaml["distort_coeffs"].as<std::vector<double>>();
|
||||
Eigen::Matrix<double, 3, 3, Eigen::RowMajor> camera_matrix(camera_matrix_data.data());
|
||||
Eigen::Matrix<double, 1, 5> distort_coeffs(distort_coeffs_data.data());
|
||||
cv::eigen2cv(camera_matrix, camera_matrix_);
|
||||
cv::eigen2cv(distort_coeffs, distort_coeffs_);
|
||||
}
|
||||
|
||||
Eigen::Matrix3d Solver::R_gimbal2world() const { return R_gimbal2world_; }
|
||||
|
||||
void Solver::set_R_gimbal2world(const Eigen::Quaterniond & q)
|
||||
{
|
||||
Eigen::Matrix3d R_imubody2imuabs = q.toRotationMatrix();
|
||||
R_gimbal2world_ = R_gimbal2imubody_.transpose() * R_imubody2imuabs * R_gimbal2imubody_;
|
||||
}
|
||||
|
||||
//solvePnP(获得姿态)
|
||||
void Solver::solve(Armor & armor) const
|
||||
{
|
||||
const auto & object_points =
|
||||
(armor.type == ArmorType::big) ? BIG_ARMOR_POINTS : SMALL_ARMOR_POINTS;
|
||||
|
||||
cv::Vec3d rvec, tvec;
|
||||
cv::solvePnP(
|
||||
object_points, armor.points, camera_matrix_, distort_coeffs_, rvec, tvec, false,
|
||||
cv::SOLVEPNP_IPPE);
|
||||
|
||||
Eigen::Vector3d xyz_in_camera;
|
||||
cv::cv2eigen(tvec, xyz_in_camera);
|
||||
armor.xyz_in_gimbal = R_camera2gimbal_ * xyz_in_camera + t_camera2gimbal_;
|
||||
armor.xyz_in_world = R_gimbal2world_ * armor.xyz_in_gimbal;
|
||||
|
||||
cv::Mat rmat;
|
||||
cv::Rodrigues(rvec, rmat);
|
||||
Eigen::Matrix3d R_armor2camera;
|
||||
cv::cv2eigen(rmat, R_armor2camera);
|
||||
Eigen::Matrix3d R_armor2gimbal = R_camera2gimbal_ * R_armor2camera;
|
||||
Eigen::Matrix3d R_armor2world = R_gimbal2world_ * R_armor2gimbal;
|
||||
armor.ypr_in_gimbal = tools::eulers(R_armor2gimbal, 2, 1, 0);
|
||||
armor.ypr_in_world = tools::eulers(R_armor2world, 2, 1, 0);
|
||||
|
||||
armor.ypd_in_world = tools::xyz2ypd(armor.xyz_in_world);
|
||||
|
||||
// 平衡不做yaw优化,因为pitch假设不成立
|
||||
auto is_balance = (armor.type == ArmorType::big) &&
|
||||
(armor.name == ArmorName::three || armor.name == ArmorName::four ||
|
||||
armor.name == ArmorName::five);
|
||||
if (is_balance) return;
|
||||
|
||||
optimize_yaw(armor);
|
||||
}
|
||||
|
||||
std::vector<cv::Point2f> Solver::reproject_armor(
|
||||
const Eigen::Vector3d & xyz_in_world, double yaw, ArmorType type, ArmorName name) const
|
||||
{
|
||||
auto sin_yaw = std::sin(yaw);
|
||||
auto cos_yaw = std::cos(yaw);
|
||||
|
||||
auto pitch = (name == ArmorName::outpost) ? -15.0 * CV_PI / 180.0 : 15.0 * CV_PI / 180.0;
|
||||
auto sin_pitch = std::sin(pitch);
|
||||
auto cos_pitch = std::cos(pitch);
|
||||
|
||||
// clang-format off
|
||||
const Eigen::Matrix3d R_armor2world {
|
||||
{cos_yaw * cos_pitch, -sin_yaw, cos_yaw * sin_pitch},
|
||||
{sin_yaw * cos_pitch, cos_yaw, sin_yaw * sin_pitch},
|
||||
{ -sin_pitch, 0, cos_pitch}
|
||||
};
|
||||
// clang-format on
|
||||
|
||||
// get R_armor2camera t_armor2camera
|
||||
const Eigen::Vector3d & t_armor2world = xyz_in_world;
|
||||
Eigen::Matrix3d R_armor2camera =
|
||||
R_camera2gimbal_.transpose() * R_gimbal2world_.transpose() * R_armor2world;
|
||||
Eigen::Vector3d t_armor2camera =
|
||||
R_camera2gimbal_.transpose() * (R_gimbal2world_.transpose() * t_armor2world - t_camera2gimbal_);
|
||||
|
||||
// get rvec tvec
|
||||
cv::Vec3d rvec;
|
||||
cv::Mat R_armor2camera_cv;
|
||||
cv::eigen2cv(R_armor2camera, R_armor2camera_cv);
|
||||
cv::Rodrigues(R_armor2camera_cv, rvec);
|
||||
cv::Vec3d tvec(t_armor2camera[0], t_armor2camera[1], t_armor2camera[2]);
|
||||
|
||||
// reproject
|
||||
std::vector<cv::Point2f> image_points;
|
||||
const auto & object_points = (type == ArmorType::big) ? BIG_ARMOR_POINTS : SMALL_ARMOR_POINTS;
|
||||
cv::projectPoints(object_points, rvec, tvec, camera_matrix_, distort_coeffs_, image_points);
|
||||
return image_points;
|
||||
}
|
||||
|
||||
double Solver::oupost_reprojection_error(Armor armor, const double & pitch)
|
||||
{
|
||||
// solve
|
||||
const auto & object_points =
|
||||
(armor.type == ArmorType::big) ? BIG_ARMOR_POINTS : SMALL_ARMOR_POINTS;
|
||||
|
||||
cv::Vec3d rvec, tvec;
|
||||
cv::solvePnP(
|
||||
object_points, armor.points, camera_matrix_, distort_coeffs_, rvec, tvec, false,
|
||||
cv::SOLVEPNP_IPPE);
|
||||
|
||||
Eigen::Vector3d xyz_in_camera;
|
||||
cv::cv2eigen(tvec, xyz_in_camera);
|
||||
armor.xyz_in_gimbal = R_camera2gimbal_ * xyz_in_camera + t_camera2gimbal_;
|
||||
armor.xyz_in_world = R_gimbal2world_ * armor.xyz_in_gimbal;
|
||||
|
||||
cv::Mat rmat;
|
||||
cv::Rodrigues(rvec, rmat);
|
||||
Eigen::Matrix3d R_armor2camera;
|
||||
cv::cv2eigen(rmat, R_armor2camera);
|
||||
Eigen::Matrix3d R_armor2gimbal = R_camera2gimbal_ * R_armor2camera;
|
||||
Eigen::Matrix3d R_armor2world = R_gimbal2world_ * R_armor2gimbal;
|
||||
armor.ypr_in_gimbal = tools::eulers(R_armor2gimbal, 2, 1, 0);
|
||||
armor.ypr_in_world = tools::eulers(R_armor2world, 2, 1, 0);
|
||||
|
||||
armor.ypd_in_world = tools::xyz2ypd(armor.xyz_in_world);
|
||||
|
||||
auto yaw = armor.ypr_in_world[0];
|
||||
auto xyz_in_world = armor.xyz_in_world;
|
||||
|
||||
auto sin_yaw = std::sin(yaw);
|
||||
auto cos_yaw = std::cos(yaw);
|
||||
|
||||
auto sin_pitch = std::sin(pitch);
|
||||
auto cos_pitch = std::cos(pitch);
|
||||
|
||||
// clang-format off
|
||||
const Eigen::Matrix3d _R_armor2world {
|
||||
{cos_yaw * cos_pitch, -sin_yaw, cos_yaw * sin_pitch},
|
||||
{sin_yaw * cos_pitch, cos_yaw, sin_yaw * sin_pitch},
|
||||
{ -sin_pitch, 0, cos_pitch}
|
||||
};
|
||||
// clang-format on
|
||||
|
||||
// get R_armor2camera t_armor2camera
|
||||
const Eigen::Vector3d & t_armor2world = xyz_in_world;
|
||||
Eigen::Matrix3d _R_armor2camera =
|
||||
R_camera2gimbal_.transpose() * R_gimbal2world_.transpose() * _R_armor2world;
|
||||
Eigen::Vector3d t_armor2camera =
|
||||
R_camera2gimbal_.transpose() * (R_gimbal2world_.transpose() * t_armor2world - t_camera2gimbal_);
|
||||
|
||||
// get rvec tvec
|
||||
cv::Vec3d _rvec;
|
||||
cv::Mat R_armor2camera_cv;
|
||||
cv::eigen2cv(_R_armor2camera, R_armor2camera_cv);
|
||||
cv::Rodrigues(R_armor2camera_cv, _rvec);
|
||||
cv::Vec3d _tvec(t_armor2camera[0], t_armor2camera[1], t_armor2camera[2]);
|
||||
|
||||
// reproject
|
||||
std::vector<cv::Point2f> image_points;
|
||||
cv::projectPoints(object_points, _rvec, _tvec, camera_matrix_, distort_coeffs_, image_points);
|
||||
|
||||
auto error = 0.0;
|
||||
for (int i = 0; i < 4; i++) error += cv::norm(armor.points[i] - image_points[i]);
|
||||
return error;
|
||||
}
|
||||
|
||||
void Solver::optimize_yaw(Armor & armor) const
|
||||
{
|
||||
Eigen::Vector3d gimbal_ypr = tools::eulers(R_gimbal2world_, 2, 1, 0);
|
||||
|
||||
constexpr double SEARCH_RANGE = 140; // degree
|
||||
auto yaw0 = tools::limit_rad(gimbal_ypr[0] - SEARCH_RANGE / 2 * CV_PI / 180.0);
|
||||
|
||||
auto min_error = 1e10;
|
||||
auto best_yaw = armor.ypr_in_world[0];
|
||||
|
||||
for (int i = 0; i < SEARCH_RANGE; i++) {
|
||||
double yaw = tools::limit_rad(yaw0 + i * CV_PI / 180.0);
|
||||
auto error = armor_reprojection_error(armor, yaw, (i - SEARCH_RANGE / 2) * CV_PI / 180.0);
|
||||
|
||||
if (error < min_error) {
|
||||
min_error = error;
|
||||
best_yaw = yaw;
|
||||
}
|
||||
}
|
||||
|
||||
armor.yaw_raw = armor.ypr_in_world[0];
|
||||
armor.ypr_in_world[0] = best_yaw;
|
||||
}
|
||||
|
||||
double Solver::SJTU_cost(
|
||||
const std::vector<cv::Point2f> & cv_refs, const std::vector<cv::Point2f> & cv_pts,
|
||||
const double & inclined) const
|
||||
{
|
||||
std::size_t size = cv_refs.size();
|
||||
std::vector<Eigen::Vector2d> refs;
|
||||
std::vector<Eigen::Vector2d> pts;
|
||||
for (std::size_t i = 0u; i < size; ++i) {
|
||||
refs.emplace_back(cv_refs[i].x, cv_refs[i].y);
|
||||
pts.emplace_back(cv_pts[i].x, cv_pts[i].y);
|
||||
}
|
||||
double cost = 0.;
|
||||
for (std::size_t i = 0u; i < size; ++i) {
|
||||
std::size_t p = (i + 1u) % size;
|
||||
// i - p 构成线段。过程:先移动起点,再补长度,再旋转
|
||||
Eigen::Vector2d ref_d = refs[p] - refs[i]; // 标准
|
||||
Eigen::Vector2d pt_d = pts[p] - pts[i];
|
||||
// 长度差代价 + 起点差代价(1 / 2)(0 度左右应该抛弃)
|
||||
double pixel_dis = // dis 是指方差平面内到原点的距离
|
||||
(0.5 * ((refs[i] - pts[i]).norm() + (refs[p] - pts[p]).norm()) +
|
||||
std::fabs(ref_d.norm() - pt_d.norm())) /
|
||||
ref_d.norm();
|
||||
double angular_dis = ref_d.norm() * tools::get_abs_angle(ref_d, pt_d) / ref_d.norm();
|
||||
// 平方可能是为了配合 sin 和 cos
|
||||
// 弧度差代价(0 度左右占比应该大)
|
||||
double cost_i =
|
||||
tools::square(pixel_dis * std::sin(inclined)) +
|
||||
tools::square(angular_dis * std::cos(inclined)) * 2.0; // DETECTOR_ERROR_PIXEL_BY_SLOPE
|
||||
// 重投影像素误差越大,越相信斜率
|
||||
cost += std::sqrt(cost_i);
|
||||
}
|
||||
return cost;
|
||||
}
|
||||
|
||||
double Solver::armor_reprojection_error(
|
||||
const Armor & armor, double yaw, const double & inclined) const
|
||||
{
|
||||
auto image_points = reproject_armor(armor.xyz_in_world, yaw, armor.type, armor.name);
|
||||
auto error = 0.0;
|
||||
for (int i = 0; i < 4; i++) error += cv::norm(armor.points[i] - image_points[i]);
|
||||
// auto error = SJTU_cost(image_points, armor.points, inclined);
|
||||
|
||||
return error;
|
||||
}
|
||||
|
||||
// 世界坐标到像素坐标的转换
|
||||
std::vector<cv::Point2f> Solver::world2pixel(const std::vector<cv::Point3f> & worldPoints)
|
||||
{
|
||||
Eigen::Matrix3d R_world2camera = R_camera2gimbal_.transpose() * R_gimbal2world_.transpose();
|
||||
Eigen::Vector3d t_world2camera = -R_camera2gimbal_.transpose() * t_camera2gimbal_;
|
||||
|
||||
cv::Mat rvec;
|
||||
cv::Mat tvec;
|
||||
cv::eigen2cv(R_world2camera, rvec);
|
||||
cv::eigen2cv(t_world2camera, tvec);
|
||||
|
||||
std::vector<cv::Point3f> valid_world_points;
|
||||
for (const auto & world_point : worldPoints) {
|
||||
Eigen::Vector3d world_point_eigen(world_point.x, world_point.y, world_point.z);
|
||||
Eigen::Vector3d camera_point = R_world2camera * world_point_eigen + t_world2camera;
|
||||
|
||||
if (camera_point.z() > 0) {
|
||||
valid_world_points.push_back(world_point);
|
||||
}
|
||||
}
|
||||
// 如果没有有效点,返回空vector
|
||||
if (valid_world_points.empty()) {
|
||||
return std::vector<cv::Point2f>();
|
||||
}
|
||||
std::vector<cv::Point2f> pixelPoints;
|
||||
cv::projectPoints(valid_world_points, rvec, tvec, camera_matrix_, distort_coeffs_, pixelPoints);
|
||||
return pixelPoints;
|
||||
}
|
||||
} // namespace auto_aim
|
||||
212
armor/src/armor_finder/find/find_armor_box.cpp
Normal file
212
armor/src/armor_finder/find/find_armor_box.cpp
Normal file
@@ -0,0 +1,212 @@
|
||||
//
|
||||
// Created by xinyang on 19-7-18.
|
||||
//
|
||||
|
||||
#include <armor_finder/armor_finder.h>
|
||||
#include <show_images/show_images.h>
|
||||
#include <options.h>
|
||||
#include <opencv2/highgui.hpp>
|
||||
|
||||
#define DO_NOT_CNT_TIME
|
||||
|
||||
#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;
|
||||
float angle_j = light_blob_j.rect.size.width > light_blob_j.rect.size.height ? light_blob_j.rect.angle :
|
||||
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);
|
||||
}
|
||||
|
||||
/* 判断两个灯条的错位度,不知道英文是什么!!! */
|
||||
static bool CuoWeiDuJudge(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;
|
||||
float angle_j = light_blob_j.rect.size.width > light_blob_j.rect.size.height ? light_blob_j.rect.angle :
|
||||
light_blob_j.rect.angle - 90;
|
||||
float angle = (angle_i + angle_j) / 2.0 / 180.0 * 3.14159265459;
|
||||
if (abs(angle_i - angle_j) > 90) {
|
||||
angle += 3.14159265459 / 2;
|
||||
}
|
||||
Vector2f orientation(cos(angle), sin(angle));
|
||||
Vector2f p2p(light_blob_j.rect.center.x - light_blob_i.rect.center.x,
|
||||
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;
|
||||
float angle_j = light_blob_j.rect.size.width > light_blob_j.rect.size.height ? light_blob_j.rect.angle :
|
||||
light_blob_j.rect.angle - 90;
|
||||
float angle = (angle_i + angle_j) / 2.0;
|
||||
if (abs(angle_i - angle_j) > 90) {
|
||||
angle += 90.0;
|
||||
}
|
||||
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 &&
|
||||
lengthRatioJudge(light_blob_i, light_blob_j) &&
|
||||
lengthJudge(light_blob_i, light_blob_j) &&
|
||||
// heightJudge(light_blob_i, light_blob_j) &&
|
||||
angelJudge(light_blob_i, light_blob_j) &&
|
||||
boxAngleJudge(light_blob_i, light_blob_j) &&
|
||||
CuoWeiDuJudge(light_blob_i, light_blob_j);
|
||||
|
||||
}
|
||||
// 匹配所有灯条,得出装甲板候选区
|
||||
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) {
|
||||
for (int j = i + 1; j < light_blobs.size(); ++j) {
|
||||
if (!isCoupleLight(light_blobs.at(i), light_blobs.at(j), enemy_color)) {
|
||||
continue;
|
||||
}
|
||||
cv::Rect2d rect_left = light_blobs.at(static_cast<unsigned long>(i)).rect.boundingRect();
|
||||
cv::Rect2d rect_right = light_blobs.at(static_cast<unsigned long>(j)).rect.boundingRect();
|
||||
double min_x, min_y, max_x, max_y;
|
||||
min_x = fmin(rect_left.x, rect_right.x) - 4;
|
||||
max_x = fmax(rect_left.x + rect_left.width, rect_right.x + rect_right.width) + 4;
|
||||
min_y = fmin(rect_left.y, rect_right.y) - 0.5 * (rect_left.height + rect_right.height) / 2.0;
|
||||
max_y = fmax(rect_left.y + rect_left.height, rect_right.y + rect_right.height) +
|
||||
0.5 * (rect_left.height + rect_right.height) / 2.0;
|
||||
if (min_x < 0 || max_x > src.cols || min_y < 0 || max_y > src.rows) {
|
||||
continue;
|
||||
}
|
||||
if (state == SEARCHING_STATE && (max_y + min_y) / 2 < 120) continue;
|
||||
if ((max_x - min_x) / (max_y - min_y) < 0.8) continue;
|
||||
LightBlobs pair_blobs = {light_blobs.at(i), light_blobs.at(j)};
|
||||
|
||||
// 计算PnP所需的4个角点
|
||||
const LightBlob &l1 = light_blobs.at(i);
|
||||
const LightBlob &l2 = light_blobs.at(j);
|
||||
|
||||
// 确定左右灯条
|
||||
const LightBlob &left = (l1.rect.center.x < l2.rect.center.x) ? l1 : l2;
|
||||
const LightBlob &right = (l1.rect.center.x < l2.rect.center.x) ? l2 : l1;
|
||||
|
||||
// 获取灯条的上下顶点
|
||||
auto getTopBottom = [](const LightBlob &lb, cv::Point2f &top, cv::Point2f &bottom) {
|
||||
cv::Point2f pts[4];
|
||||
lb.rect.points(pts);
|
||||
// 按照y轴排序获取上下端点
|
||||
std::sort(pts, pts + 4, [](const cv::Point2f &a, const cv::Point2f &b) { return a.y < b.y; });
|
||||
top = (pts[0] + pts[1]) / 2.0;
|
||||
bottom = (pts[2] + pts[3]) / 2.0;
|
||||
};
|
||||
|
||||
cv::Point2f lt, lb, rt, rb;
|
||||
getTopBottom(left, lt, lb);
|
||||
getTopBottom(right, rt, rb);
|
||||
|
||||
// PnP点序: 左上, 右上, 右下, 左下
|
||||
std::vector<cv::Point2f> armor_points = {lt, rt, rb, lb};
|
||||
|
||||
armor_boxes.emplace_back(
|
||||
cv::Rect2d(min_x, min_y, max_x - min_x, max_y - min_y),
|
||||
pair_blobs,
|
||||
enemy_color,
|
||||
0,
|
||||
armor_points
|
||||
);
|
||||
}
|
||||
}
|
||||
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 && 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 && state==SEARCHING_STATE) {
|
||||
showArmorBoxes("boxes", src, armor_boxes);
|
||||
cv::waitKey(1);
|
||||
}
|
||||
// 如果分类器可用,则使用分类器对装甲板候选区进行筛选
|
||||
if (classifier) {
|
||||
CNT_TIME("classify: %d", {
|
||||
for (auto &armor_box : armor_boxes) {
|
||||
cv::Mat roi = src(armor_box.rect).clone();
|
||||
cv::resize(roi, roi, cv::Size(48, 36));
|
||||
int c = classifier(roi);
|
||||
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()) <
|
||||
getPointLength(b.getCenter() - last_box.getCenter());
|
||||
} else {
|
||||
return a < b;
|
||||
}
|
||||
});
|
||||
for (auto &one_box : armor_boxes) {
|
||||
if (one_box.id != 0) {
|
||||
box = one_box;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (save_labelled_boxes) {
|
||||
for (const auto &one_box : armor_boxes) {
|
||||
char filename[100];
|
||||
sprintf(filename, PROJECT_DIR"/armor_box_photo/%s_%d.jpg", id2name[one_box.id].data(),
|
||||
time(nullptr) + clock());
|
||||
auto box_roi = src(one_box.rect);
|
||||
cv::resize(box_roi, box_roi, cv::Size(48, 36));
|
||||
cv::imwrite(filename, box_roi);
|
||||
}
|
||||
}
|
||||
if (box.rect == cv::Rect2d(0, 0, 0, 0)) {
|
||||
return false;
|
||||
}
|
||||
if (show_armor_boxes && state==SEARCHING_STATE) {
|
||||
showArmorBoxesClass("class", src, armor_boxes);
|
||||
}
|
||||
} else { // 如果分类器不可用,则直接选取候选区中的第一个区域作为目标(往往会误识别)
|
||||
box = armor_boxes[0];
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
152
armor/src/armor_finder/find/find_light_blobs.cpp
Normal file
152
armor/src/armor_finder/find/find_light_blobs.cpp
Normal file
@@ -0,0 +1,152 @@
|
||||
//
|
||||
// Created by xinyang on 19-7-10.
|
||||
//
|
||||
|
||||
#include <armor_finder/armor_finder.h>
|
||||
#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);
|
||||
region.y -= fmax(3, region.height * 0.05);
|
||||
region.width += 2 * fmax(3, region.width * 0.1);
|
||||
region.height += 2 * fmax(3, region.height * 0.05);
|
||||
region &= cv::Rect(0, 0, src.cols, src.rows);
|
||||
cv::Mat roi = src(region);
|
||||
int red_cnt = 0, blue_cnt = 0;
|
||||
for (int row = 0; row < roi.rows; row++) {
|
||||
for (int col = 0; col < roi.cols; col++) {
|
||||
red_cnt += roi.at<cv::Vec3b>(row, col)[2];
|
||||
blue_cnt += roi.at<cv::Vec3b>(row, col)[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);
|
||||
|
||||
static cv::Mat kernel_dilate = getStructuringElement(cv::MORPH_RECT, cv::Size(3, 5));
|
||||
dilate(src, src, kernel_dilate);
|
||||
|
||||
static cv::Mat kernel_dilate2 = getStructuringElement(cv::MORPH_RECT, cv::Size(3, 5));
|
||||
dilate(src, src, kernel_dilate2);
|
||||
|
||||
static cv::Mat kernel_erode2 = getStructuringElement(cv::MORPH_RECT, cv::Size(3, 5));
|
||||
erode(src, src, kernel_erode2);
|
||||
}
|
||||
// 在给定图像上寻找所有可能的灯条
|
||||
bool ArmorFinder::findLightBlobs(const cv::Mat &src, LightBlobs &light_blobs) {
|
||||
cv::Mat color_channel;
|
||||
cv::Mat src_bin_light, src_bin_dim;
|
||||
std::vector<cv::Mat> channels; // 通道拆分
|
||||
|
||||
cv::split(src, channels); /************************/
|
||||
if (enemy_color == ENEMY_BLUE) { /* */
|
||||
color_channel = channels[0]; /* 根据目标颜色进行通道提取 */
|
||||
} else if (enemy_color == ENEMY_RED) { /* */
|
||||
color_channel = channels[2]; /************************/
|
||||
}
|
||||
|
||||
int light_threshold;
|
||||
if(enemy_color == ENEMY_BLUE){
|
||||
light_threshold = 225;
|
||||
}else{
|
||||
light_threshold = 200;
|
||||
}
|
||||
cv::threshold(color_channel, src_bin_light, light_threshold, 255, cv::THRESH_BINARY); // 二值化对应通道
|
||||
if (src_bin_light.empty()) return false;
|
||||
imagePreProcess(src_bin_light); // 开闭运算
|
||||
|
||||
cv::threshold(color_channel, src_bin_dim, 140, 255, cv::THRESH_BINARY); // 二值化对应通道
|
||||
if (src_bin_dim.empty()) return false;
|
||||
imagePreProcess(src_bin_dim); // 开闭运算
|
||||
|
||||
if (src_bin_light.size() == cv::Size(640, 480) && show_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;
|
||||
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);
|
||||
for (int i = 0; i < light_contours_light.size(); i++) {
|
||||
if (hierarchy_light[i][2] == -1) {
|
||||
cv::RotatedRect rect = cv::minAreaRect(light_contours_light[i]);
|
||||
if (isValidLightBlob(light_contours_light[i], rect)) {
|
||||
light_blobs_light.emplace_back(
|
||||
rect, areaRatio(light_contours_light[i], rect), get_blob_color(src, rect)
|
||||
);
|
||||
}
|
||||
}
|
||||
}
|
||||
for (int i = 0; i < light_contours_dim.size(); i++) {
|
||||
if (hierarchy_dim[i][2] == -1) {
|
||||
cv::RotatedRect rect = cv::minAreaRect(light_contours_dim[i]);
|
||||
if (isValidLightBlob(light_contours_dim[i], rect)) {
|
||||
light_blobs_dim.emplace_back(
|
||||
rect, areaRatio(light_contours_dim[i], rect), get_blob_color(src, rect)
|
||||
);
|
||||
}
|
||||
}
|
||||
}
|
||||
vector<int> light_to_remove, dim_to_remove;
|
||||
for (int l = 0; l != light_blobs_light.size(); l++) {
|
||||
for (int d = 0; d != light_blobs_dim.size(); d++) {
|
||||
if (isSameBlob(light_blobs_light[l], light_blobs_dim[d])) {
|
||||
if (light_blobs_light[l].area_ratio > light_blobs_dim[d].area_ratio) {
|
||||
dim_to_remove.emplace_back(d);
|
||||
} else {
|
||||
light_to_remove.emplace_back(l);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
sort(light_to_remove.begin(), light_to_remove.end(), [](int a, int b) { return a > b; });
|
||||
sort(dim_to_remove.begin(), dim_to_remove.end(), [](int a, int b) { return a > b; });
|
||||
for (auto x : light_to_remove) {
|
||||
light_blobs_light.erase(light_blobs_light.begin() + x);
|
||||
}
|
||||
for (auto x : dim_to_remove) {
|
||||
light_blobs_dim.erase(light_blobs_dim.begin() + x);
|
||||
}
|
||||
for (const auto &light : light_blobs_light) {
|
||||
light_blobs.emplace_back(light);
|
||||
}
|
||||
for (const auto &dim : light_blobs_dim) {
|
||||
light_blobs.emplace_back(dim);
|
||||
}
|
||||
return light_blobs.size() >= 2;
|
||||
}
|
||||
38
armor/src/armor_finder/searching_state/searching_state.cpp
Normal file
38
armor/src/armor_finder/searching_state/searching_state.cpp
Normal file
@@ -0,0 +1,38 @@
|
||||
//
|
||||
// Created by xinyang on 19-3-27.
|
||||
//
|
||||
|
||||
#include <armor_finder/armor_finder.h>
|
||||
#include <show_images/show_images.h>
|
||||
#include <options.h>
|
||||
#include <log.h>
|
||||
|
||||
bool ArmorFinder::stateSearchingTarget(cv::Mat &src) {
|
||||
if (findArmorBox(src, target_box)) { // 在原图中寻找目标,并返回是否找到
|
||||
if (last_box.rect != cv::Rect2d() &&
|
||||
(getPointLength(last_box.getCenter() - target_box.getCenter()) > last_box.rect.height * 2.0) &&
|
||||
anti_switch_cnt++ < 3) { // 判断当前目标和上次有效目标是否为同一个目标
|
||||
target_box = ArmorBox(); // 并给3帧的时间,试图找到相同目标
|
||||
LOGM("anti-switch!"); // 即刚发生目标切换内的3帧内不发送目标位置
|
||||
return false; // 可以一定程度避免频繁多目标切换
|
||||
} else {
|
||||
anti_switch_cnt = 0;
|
||||
return true;
|
||||
}
|
||||
} else {
|
||||
target_box = ArmorBox();
|
||||
anti_switch_cnt++;
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
bool ArmorFinder::stateSearchingTarget(cv::Mat &src) {
|
||||
if (findArmorBox(src, target_box)) {
|
||||
return true;
|
||||
} else {
|
||||
target_box = ArmorBox();
|
||||
return false;
|
||||
}
|
||||
}
|
||||
*/
|
||||
88
armor/src/armor_finder/send_target/send_target.cpp
Normal file
88
armor/src/armor_finder/send_target/send_target.cpp
Normal file
@@ -0,0 +1,88 @@
|
||||
//
|
||||
// Created by xinyang on 19-7-11.
|
||||
//
|
||||
|
||||
#include <armor_finder/armor_finder.h>
|
||||
#include <config/setconfig.h>
|
||||
#include <show_images/ballistic_predicition.h>
|
||||
#include <show_images/auto_trigger.h>
|
||||
#include <log.h>
|
||||
|
||||
|
||||
static bool sendTarget(Serial &serial, double x, double y, double z, uint16_t shoot_delay) {
|
||||
static short x_tmp, y_tmp, z_tmp;
|
||||
uint8_t buff[10];
|
||||
|
||||
#ifdef WITH_COUNT_FPS
|
||||
static time_t last_time = time(nullptr);
|
||||
static int fps;
|
||||
time_t t = time(nullptr);
|
||||
if (last_time != t) {
|
||||
last_time = t;
|
||||
cout << "Armor: fps:" << fps << ", (" << x << "," << y << "," << z << ")" << endl;
|
||||
fps = 0;
|
||||
}
|
||||
fps += 1;
|
||||
#endif
|
||||
|
||||
#define MINMAX(value, min, max) value = ((value) < (min)) ? (min) : ((value) > (max) ? (max) : (value))
|
||||
|
||||
x_tmp = static_cast<short>(x * (32768 - 1) / 100);
|
||||
y_tmp = static_cast<short>(y * (32768 - 1) / 100);
|
||||
z_tmp = static_cast<short>(z * (32768 - 1) / 1000);
|
||||
|
||||
buff[0] = 's';
|
||||
buff[1] = static_cast<char>((x_tmp >> 8) & 0xFF);
|
||||
buff[2] = static_cast<char>((x_tmp >> 0) & 0xFF);
|
||||
buff[3] = static_cast<char>((y_tmp >> 8) & 0xFF);
|
||||
buff[4] = static_cast<char>((y_tmp >> 0) & 0xFF);
|
||||
buff[5] = static_cast<char>((z_tmp >> 8) & 0xFF);
|
||||
buff[6] = static_cast<char>((z_tmp >> 0) & 0xFF);
|
||||
buff[7] = static_cast<char>((shoot_delay >> 8) & 0xFF);
|
||||
buff[8] = static_cast<char>((shoot_delay >> 0) & 0xFF);
|
||||
buff[9] = 'e';
|
||||
// if(buff[7]<<8 | buff[8])
|
||||
// cout << (buff[7]<<8 | buff[8]) << endl;
|
||||
return serial.WriteData(buff, sizeof(buff));
|
||||
}
|
||||
|
||||
bool ArmorFinder::sendBoxPosition(uint16_t shoot_delay) {
|
||||
if (target_box.rect == cv::Rect2d()) return false;
|
||||
if (shoot_delay) {
|
||||
LOGM(STR_CTR(WORD_BLUE, "next box %dms"), shoot_delay);
|
||||
}
|
||||
auto rect = target_box.rect;
|
||||
double dx = rect.x + rect.width / 2 - IMAGE_CENTER_X;
|
||||
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 dist = sqrt(target_xyz.x * target_xyz.x + target_xyz.y * target_xyz.y + target_xyz.z * target_xyz.z) / 100.0; // 米
|
||||
|
||||
// 弹道补偿使用 PnP 提供的 3D 坐标
|
||||
double x_target = sqrt(target_xyz.x * target_xyz.x + target_xyz.z * target_xyz.z) / 100.0; // 水平距离
|
||||
double y_target = -target_xyz.y / 100.0; // 垂直高度差
|
||||
double pitch_comp = BallisticSolver::get_pitch(x_target, y_target, MUZZLE_VELOCITY, BALLISTIC_K);
|
||||
|
||||
// 计算是否满足开火条件 (例如残差小于 1.5 度)
|
||||
can_fire = AutoTrigger::should_fire(yaw, pitch_comp, 1.5);
|
||||
|
||||
return sendTarget(serial, yaw, pitch_comp, dist * 100.0, shoot_delay);
|
||||
}
|
||||
|
||||
11
armor/src/armor_finder/standby_state/standby_state.cpp
Normal file
11
armor/src/armor_finder/standby_state/standby_state.cpp
Normal file
@@ -0,0 +1,11 @@
|
||||
//
|
||||
// Created by xinyang on 19-3-27.
|
||||
//
|
||||
|
||||
#include <armor_finder/armor_finder.h>
|
||||
|
||||
bool ArmorFinder::stateStandBy() {
|
||||
state = SEARCHING_STATE;
|
||||
return true;
|
||||
}
|
||||
|
||||
71
armor/src/armor_finder/tracking_state/tracking_state.cpp
Normal file
71
armor/src/armor_finder/tracking_state/tracking_state.cpp
Normal file
@@ -0,0 +1,71 @@
|
||||
//
|
||||
// Created by xinyang on 19-3-27.
|
||||
//
|
||||
#define LOG_LEVEL LOG_NONE
|
||||
#include <log.h>
|
||||
#include <options.h>
|
||||
#include <armor_finder/armor_finder.h>
|
||||
#include <show_images/show_images.h>
|
||||
|
||||
bool ArmorFinder::stateTrackingTarget(cv::Mat &src) {
|
||||
cv::Rect pos(target_box.rect);
|
||||
if(!tracker->update(src, pos)){ // 使用KCFTracker进行追踪
|
||||
target_box = ArmorBox();
|
||||
LOGW("Track fail!");
|
||||
return false;
|
||||
}
|
||||
if((cv::Rect2d(pos) & cv::Rect2d(0, 0, 640, 480)) != cv::Rect2d(pos)){
|
||||
target_box = ArmorBox();
|
||||
LOGW("Track out range!");
|
||||
return false;
|
||||
}
|
||||
|
||||
// 获取相较于追踪区域两倍长款的区域,用于重新搜索,获取灯条信息
|
||||
cv::Rect2d bigger_rect;
|
||||
bigger_rect.x = pos.x - pos.width / 2.0;
|
||||
bigger_rect.y = pos.y - pos.height / 2.0;
|
||||
bigger_rect.height = pos.height * 2;
|
||||
bigger_rect.width = pos.width * 2;
|
||||
bigger_rect &= cv::Rect2d(0, 0, 640, 480);
|
||||
cv::Mat roi = src(bigger_rect).clone();
|
||||
|
||||
ArmorBox box;
|
||||
// 在区域内重新搜索。
|
||||
if(findArmorBox(roi, box)) { // 如果成功获取目标,则利用搜索区域重新更新追踪器
|
||||
target_box = box;
|
||||
target_box.rect.x += bigger_rect.x; // 添加roi偏移量
|
||||
target_box.rect.y += bigger_rect.y;
|
||||
for(auto &blob : target_box.light_blobs){
|
||||
blob.rect.center.x += bigger_rect.x;
|
||||
blob.rect.center.y += bigger_rect.y;
|
||||
}
|
||||
for(auto &pt : target_box.points){
|
||||
pt.x += bigger_rect.x;
|
||||
pt.y += bigger_rect.y;
|
||||
}
|
||||
tracker = TrackerToUse::create();
|
||||
tracker->init(src, target_box.rect);
|
||||
}else{ // 如果没有成功搜索目标,则使用判断是否跟丢。
|
||||
roi = src(pos).clone();
|
||||
if(classifier){ // 分类器可用,使用分类器判断。
|
||||
cv::resize(roi, roi, cv::Size(48, 36));
|
||||
if(classifier(roi) == 0){
|
||||
target_box = ArmorBox();
|
||||
LOGW("Track classify fail range!");
|
||||
return false;
|
||||
}
|
||||
}else{ // 分类器不可用,使用常规方法判断
|
||||
cv::Mat roi_gray;
|
||||
cv::cvtColor(roi, roi_gray, cv::COLOR_RGB2GRAY);
|
||||
cv::threshold(roi_gray, roi_gray, 180, 255, cv::THRESH_BINARY);
|
||||
contour_area = cv::countNonZero(roi_gray);
|
||||
if(abs(cv::countNonZero(roi_gray) - contour_area) > contour_area * 0.3){
|
||||
target_box = ArmorBox();
|
||||
return false;
|
||||
}
|
||||
}
|
||||
target_box.rect = pos;
|
||||
target_box.light_blobs.clear();
|
||||
}
|
||||
return true;
|
||||
}
|
||||
102
armor/src/show_images/ballistic_predicition.cpp
Normal file
102
armor/src/show_images/ballistic_predicition.cpp
Normal file
@@ -0,0 +1,102 @@
|
||||
#include <show_images/ballistic_predicition.h>
|
||||
#include <cmath>
|
||||
|
||||
/**
|
||||
* @brief 迭代法求解补偿 pitch 角。
|
||||
* 给定水平距离 d 和目标高度差 y,反算出应出射的 pitch 角(度)。
|
||||
*/
|
||||
double BallisticSolver::get_pitch(double d, double y, double v0, double k) {
|
||||
const double g = 9.80665;
|
||||
double pitch_new = atan2(y, d); // 初始猜测:几何仰角
|
||||
for (int i = 0; i < 20; ++i) {
|
||||
double cos_p = cos(pitch_new);
|
||||
double val = 1.0 - (k * d) / (v0 * cos_p);
|
||||
if (val <= 0) break;
|
||||
double t = -log(val) / k;
|
||||
double y_calc = (1.0/k) * (v0*sin(pitch_new) + g/k) * (1.0 - exp(-k*t)) - (g/k)*t;
|
||||
double dy = y - y_calc;
|
||||
pitch_new += atan2(dy, d);
|
||||
if (std::abs(dy) < 0.001) break;
|
||||
}
|
||||
return pitch_new * 180.0 / M_PI;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 计算弹丸飞行时间。
|
||||
* @param d 目标水平距离 (m)
|
||||
* @param pitch 当前 IMU pitch 角 (度,仰为正)
|
||||
* @param v0 枪口初速度 (m/s)
|
||||
* @param k 空气阻力系数
|
||||
* @brief 计算弹丸飞行时间(含空气阻力模型)。
|
||||
*
|
||||
* 运动方程:水平方向 v_x(t) = v0*cos(pitch)*exp(-k*t)
|
||||
* 水平位移 x(t) = (v0*cos(pitch)/k) * (1 - exp(-k*t))
|
||||
* 由 x(t) = d 解得 t。
|
||||
*/
|
||||
double BallisticSolver::get_flight_time(double d, double pitch, double v0, double k) {
|
||||
double cos_pitch = cos(pitch * M_PI / 180.0);
|
||||
double val = 1.0 - (k * d) / (v0 * cos_pitch);
|
||||
if (val <= 0) return 0.5; // 超过最大射程,返回兜底时间
|
||||
return -log(val) / k;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief 推断给定出射角下的落点高度(弹着点推断)。
|
||||
*/
|
||||
double BallisticSolver::get_impact_y(double d, double pitch, double v0, double k) {
|
||||
const double g = 9.80665;
|
||||
double pitch_rad = pitch * M_PI / 180.0;
|
||||
double t = get_flight_time(d, pitch, v0, k);
|
||||
return (1.0 / k) * (v0 * sin(pitch_rad) + g / k) * (1.0 - exp(-k * t)) - (g / k) * t;
|
||||
}
|
||||
|
||||
// ──────────────────── [TEST] 以下两个函数用于可视化验证弹道算法正确性 ────────────────────
|
||||
// 如果测试通过,直接注释掉 armor_finder.cpp 里的调用,不影响其他逻辑。
|
||||
|
||||
/**
|
||||
* [TEST] 将弹着点从世界坐标系反解算到相机坐标系。
|
||||
* 变换链:xyz_camera = R_c2g^T * (R_g2w^T * xyz_world - t_c2g)
|
||||
*/
|
||||
ImpactPoint BallisticSolver::get_impact_in_camera(
|
||||
const Eigen::Vector3d& xyz_in_world,
|
||||
double pitch_imu,
|
||||
double v0,
|
||||
const Eigen::Matrix3d& R_camera2gimbal,
|
||||
const Eigen::Matrix3d& R_gimbal2world,
|
||||
const Eigen::Vector3d& t_camera2gimbal,
|
||||
double k)
|
||||
{
|
||||
// 水平距离:世界系 x=前, y=左
|
||||
double d = std::sqrt(xyz_in_world.x() * xyz_in_world.x() +
|
||||
xyz_in_world.y() * xyz_in_world.y());
|
||||
|
||||
double impact_z = get_impact_y(d, pitch_imu, v0, k);
|
||||
double fly_time = get_flight_time(d, pitch_imu, v0, k);
|
||||
|
||||
// 弹着点世界坐标:水平 (x,y) 与目标相同,z 换为弹道高度
|
||||
Eigen::Vector3d impact_world(xyz_in_world.x(), xyz_in_world.y(), impact_z);
|
||||
|
||||
// 世界 → 云台 → 相机
|
||||
Eigen::Vector3d impact_gimbal = R_gimbal2world.transpose() * impact_world;
|
||||
Eigen::Vector3d impact_camera = R_camera2gimbal.transpose() * (impact_gimbal - t_camera2gimbal);
|
||||
|
||||
return ImpactPoint{ impact_camera, fly_time };
|
||||
}
|
||||
|
||||
/**
|
||||
* [TEST] 针孔投影:相机坐标系 3D 点 → 像素坐标(不含畸变,仅用于可视化)。
|
||||
*/
|
||||
cv::Point2f BallisticSolver::project_to_pixel(
|
||||
const Eigen::Vector3d& xyz_in_camera,
|
||||
const cv::Mat& camera_matrix)
|
||||
{
|
||||
if (xyz_in_camera.z() <= 0) return cv::Point2f(-1, -1); // 在相机背后,无效
|
||||
double fx = camera_matrix.at<double>(0, 0);
|
||||
double fy = camera_matrix.at<double>(1, 1);
|
||||
double cx = camera_matrix.at<double>(0, 2);
|
||||
double cy = camera_matrix.at<double>(1, 2);
|
||||
float u = static_cast<float>(fx * xyz_in_camera.x() / xyz_in_camera.z() + cx);
|
||||
float v = static_cast<float>(fy * xyz_in_camera.y() / xyz_in_camera.z() + cy);
|
||||
return cv::Point2f(u, v);
|
||||
}
|
||||
// ──────────────────────────────── [TEST END] ─────────────────────────────────────────────
|
||||
182
armor/src/show_images/show_images.cpp
Normal file
182
armor/src/show_images/show_images.cpp
Normal file
@@ -0,0 +1,182 @@
|
||||
#include <show_images/show_images.h>
|
||||
#include <opencv2/highgui.hpp>
|
||||
#include <options.h>
|
||||
#include <log.h>
|
||||
|
||||
using namespace cv;
|
||||
|
||||
|
||||
void drawLightBlobs(cv::Mat &src, const LightBlobs &blobs){
|
||||
for (const auto &blob:blobs) {
|
||||
Scalar color(0,255,0);
|
||||
if (blob.blob_color == BLOB_RED)
|
||||
color = Scalar(0, 0, 255);
|
||||
else if (blob.blob_color == BLOB_BLUE)
|
||||
color = Scalar(255, 0, 0);
|
||||
cv::Point2f vertices[4];
|
||||
blob.rect.points(vertices);
|
||||
for (int j = 0; j < 4; j++) {
|
||||
cv::line(src, vertices[j], vertices[(j + 1) % 4], color, 2);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**************************
|
||||
* 显示多个装甲板区域 *
|
||||
**************************/
|
||||
void showArmorBoxes(std::string windows_name, const cv::Mat &src, const ArmorBoxes &armor_boxes) {
|
||||
static Mat image2show;
|
||||
if (src.type() == CV_8UC1) {// 黑白图像
|
||||
cvtColor(src, image2show, COLOR_GRAY2RGB);
|
||||
} else if (src.type() == CV_8UC3) { //RGB 彩色
|
||||
image2show = src.clone();
|
||||
}
|
||||
|
||||
for (auto &box:armor_boxes) {
|
||||
if(box.box_color == BOX_BLUE) {
|
||||
rectangle(image2show, box.rect, Scalar(0, 255, 0), 1);
|
||||
drawLightBlobs(image2show, box.light_blobs);
|
||||
}else if(box.box_color == BOX_RED){
|
||||
rectangle(image2show, box.rect, Scalar(0, 255, 0), 1);
|
||||
drawLightBlobs(image2show, box.light_blobs);
|
||||
}
|
||||
|
||||
}
|
||||
imshow(windows_name, image2show);
|
||||
}
|
||||
|
||||
/**************************
|
||||
* 显示多个装甲板区域及其类别 *
|
||||
**************************/
|
||||
void showArmorBoxesClass(std::string window_names, const cv::Mat &src, const ArmorBoxes &boxes) {
|
||||
static Mat image2show;
|
||||
if (src.type() == CV_8UC1) { // 黑白图像
|
||||
cvtColor(src, image2show, COLOR_GRAY2RGB);
|
||||
} else if (src.type() == CV_8UC3) { //RGB 彩色
|
||||
image2show = src.clone();
|
||||
}
|
||||
for (const auto &box : boxes) {
|
||||
if(box.id != 0) {
|
||||
rectangle(image2show, box.rect, Scalar(0, 255, 0), 1);
|
||||
drawLightBlobs(image2show, box.light_blobs);
|
||||
if (box.id == -1)
|
||||
putText(image2show, id2name[box.id], Point(box.rect.x + 2, box.rect.y + 2), cv::FONT_HERSHEY_TRIPLEX, 1,
|
||||
Scalar(0, 255, 0));
|
||||
else if (1 <= box.id && box.id < 8)
|
||||
putText(image2show, id2name[box.id], Point(box.rect.x + 2, box.rect.y + 2), cv::FONT_HERSHEY_TRIPLEX, 1,
|
||||
Scalar(255, 0, 0));
|
||||
else if (8 <= box.id && box.id < 15)
|
||||
putText(image2show, id2name[box.id], Point(box.rect.x + 2, box.rect.y + 2), cv::FONT_HERSHEY_TRIPLEX, 1,
|
||||
Scalar(0, 0, 255));
|
||||
else if (box.id != 0)
|
||||
LOGE_INFO("Invalid box id:%d!", box.id);
|
||||
}
|
||||
}
|
||||
imshow(window_names, image2show);
|
||||
|
||||
}
|
||||
|
||||
/**************************
|
||||
* 显示单个装甲板区域及其类别 *
|
||||
**************************/
|
||||
void showArmorBox(std::string windows_name, const cv::Mat &src, const ArmorBox &box) {
|
||||
static Mat image2show;
|
||||
if(box.rect == cv::Rect2d()){
|
||||
imshow(windows_name, src);
|
||||
}
|
||||
if (src.type() == CV_8UC1) { // 黑白图像
|
||||
cvtColor(src, image2show, COLOR_GRAY2RGB);
|
||||
} else if (src.type() == CV_8UC3) { //RGB 彩色
|
||||
image2show = src.clone();
|
||||
}
|
||||
drawLightBlobs(image2show, box.light_blobs);
|
||||
// static FILE *fp = fopen(PROJECT_DIR"/ratio.txt", "w");
|
||||
// if(box.light_blobs.size() == 2)
|
||||
// fprintf(fp, "%lf %lf %lf\n", box.light_blobs[0].length, box.light_blobs[1].length, box.getBlobsDistance())
|
||||
// cout << box.lengthDistanceRatio() << endl;
|
||||
|
||||
if(box.getOrientation() == ArmorBox::FRONT){
|
||||
rectangle(image2show, box.rect, Scalar(0, 255, 0), 3);
|
||||
}else{
|
||||
rectangle(image2show, box.rect, Scalar(0, 255, 0), 1);
|
||||
}
|
||||
|
||||
char dist[10];
|
||||
sprintf(dist, "%.1f", box.getBoxDistance());
|
||||
if (box.id == -1)
|
||||
putText(image2show, id2name[box.id]+" "+dist, Point(box.rect.x + 2, box.rect.y + 2), cv::FONT_HERSHEY_TRIPLEX, 1,
|
||||
Scalar(0, 255, 0));
|
||||
else if (1 <= box.id && box.id < 8)
|
||||
putText(image2show, id2name[box.id]+" "+dist, Point(box.rect.x + 2, box.rect.y + 2), cv::FONT_HERSHEY_TRIPLEX, 1,
|
||||
Scalar(255, 0, 0));
|
||||
else if (8 <= box.id && box.id < 15)
|
||||
putText(image2show, id2name[box.id]+" "+dist, Point(box.rect.x + 2, box.rect.y + 2), cv::FONT_HERSHEY_TRIPLEX, 1,
|
||||
Scalar(0, 0, 255));
|
||||
else if (box.id != 0)
|
||||
LOGE_INFO("Invalid box id:%d!", box.id);
|
||||
imshow(windows_name, image2show);
|
||||
}
|
||||
|
||||
/**************************
|
||||
* 显示多个灯条区域 *
|
||||
**************************/
|
||||
void showLightBlobs(std::string windows_name, const cv::Mat &src, const LightBlobs &light_blobs) {
|
||||
static Mat image2show;
|
||||
|
||||
if (src.type() == CV_8UC1) { // 黑白图像
|
||||
cvtColor(src, image2show, COLOR_GRAY2RGB);
|
||||
} else if (src.type() == CV_8UC3) { //RGB 彩色
|
||||
image2show = src.clone();
|
||||
}
|
||||
|
||||
for (const auto &light_blob:light_blobs) {
|
||||
Scalar color(0, 255, 0);
|
||||
if (light_blob.blob_color == BLOB_RED)
|
||||
color = Scalar(0, 0, 255);
|
||||
else if (light_blob.blob_color == BLOB_BLUE)
|
||||
color = Scalar(255, 0, 0);
|
||||
cv::Point2f vertices[4];
|
||||
light_blob.rect.points(vertices);
|
||||
for (int j = 0; j < 4; j++) {
|
||||
cv::line(image2show, vertices[j], vertices[(j + 1) % 4], color, 2);
|
||||
}
|
||||
}
|
||||
imshow(windows_name, image2show);
|
||||
}
|
||||
|
||||
|
||||
void showTrackSearchingPos(std::string window_names, const cv::Mat &src, const cv::Rect2d pos){
|
||||
static Mat image2show;
|
||||
if (src.type() == CV_8UC1) { // 黑白图像
|
||||
cvtColor(src, image2show, COLOR_GRAY2RGB);
|
||||
} else if (src.type() == CV_8UC3) { //RGB 彩色
|
||||
image2show = src.clone();
|
||||
}
|
||||
rectangle(image2show, pos, Scalar(0, 255, 0), 1);
|
||||
imshow(window_names, image2show);
|
||||
}
|
||||
|
||||
// ─────────────── [TEST] 弹着点可视化 ───────────────────────────────────────────────────────
|
||||
// 在图像上画一个红色小圆点标注弹道落点位置,用于验证弹道算法正确性。
|
||||
// 验证通过后直接注释调用处即可,函数本身不影响任何发包逻辑。
|
||||
void showImpactPoint(const std::string& window_name, const cv::Mat& src, cv::Point2f impact_pixel) {
|
||||
static Mat image2show;
|
||||
if (src.type() == CV_8UC1) {
|
||||
cvtColor(src, image2show, COLOR_GRAY2RGB);
|
||||
} else if (src.type() == CV_8UC3) {
|
||||
image2show = src.clone();
|
||||
} else {
|
||||
return;
|
||||
}
|
||||
|
||||
// 越界检查
|
||||
int u = static_cast<int>(impact_pixel.x);
|
||||
int v = static_cast<int>(impact_pixel.y);
|
||||
if (u >= 0 && u < image2show.cols && v >= 0 && v < image2show.rows) {
|
||||
// 红色实心圆,半径 3px
|
||||
cv::circle(image2show, cv::Point(u, v), 3, Scalar(0, 0, 255), -1);
|
||||
}
|
||||
|
||||
imshow(window_name, image2show);
|
||||
}
|
||||
// ─────────────── [TEST END] ────────────────────────────────────────────────────────────────
|
||||
120
main.cpp
Normal file
120
main.cpp
Normal file
@@ -0,0 +1,120 @@
|
||||
/**********************************************************************/
|
||||
/* ____ _ _____ _ _ ____ __ __ ______ __ */
|
||||
/* / ___| | |_ _| | | | | _ \| \/ | / ___\ \ / / */
|
||||
/* \___ \ _ | | | | | | | |_____| |_) | |\/| |_____| | \ \ / / */
|
||||
/* ___) | |_| | | | | |_| |_____| _ <| | | |_____| |___ \ V / */
|
||||
/* |____/ \___/ |_| \___/ |_| \_\_| |_| \____| \_/ */
|
||||
/* */
|
||||
/**********************************************************************/
|
||||
// 本代码统一使用640×480大小的图像进行处理
|
||||
|
||||
#include <iostream>
|
||||
#include <thread>
|
||||
#include <opencv2/core/core.hpp>
|
||||
#include <serial.h>
|
||||
#include <camera/camera_wrapper.h>
|
||||
#include <camera/video_wrapper.h>
|
||||
#include <camera/wrapper_head.h>
|
||||
#include <armor_finder/armor_finder.h>
|
||||
#include <options.h>
|
||||
#include <additions.h>
|
||||
#include <config/setconfig.h>
|
||||
|
||||
#define DO_NOT_CNT_TIME
|
||||
|
||||
#include <log.h>
|
||||
|
||||
using namespace cv;
|
||||
using namespace std;
|
||||
|
||||
McuData mcu_data = { // 单片机端回传结构体
|
||||
0, // 当前云台yaw角
|
||||
0, // 当前云台pitch角
|
||||
ARMOR_STATE, // 当前状态,自瞄
|
||||
0, // 云台角度标记位
|
||||
0, // 是否为反陀螺模式
|
||||
ENEMY_RED, // 敌方颜色
|
||||
0, // 补偿量 (原能量机关x轴补偿量,现保留结构体对齐)
|
||||
0, // 补偿量 (原能量机关y轴补偿量,现保留结构体对齐)
|
||||
};
|
||||
|
||||
WrapperHead *video = nullptr; // 云台摄像头视频源
|
||||
|
||||
Serial serial(115200); // 串口对象
|
||||
uint8_t last_state = ARMOR_STATE; // 上次状态,用于初始化
|
||||
// 自瞄主程序对象
|
||||
ArmorFinder armor_finder(mcu_data.enemy_color, serial, PROJECT_DIR"/tools/para/", mcu_data.anti_top);
|
||||
|
||||
int main(int argc, char *argv[]) {
|
||||
processOptions(argc, argv); // 处理命令行参数
|
||||
thread receive(uartReceive, &serial); // 开启串口接收线程
|
||||
|
||||
int from_camera = 1; // 根据条件选择视频源
|
||||
if (!run_with_camera) {
|
||||
cout << "Input 1 for camera, 0 for video files" << endl;
|
||||
cin >> from_camera;
|
||||
}
|
||||
|
||||
while (true) {
|
||||
// 打开视频源
|
||||
if (from_camera) {
|
||||
video = new CameraWrapper(ARMOR_CAMERA_EXPOSURE, ARMOR_CAMERA_GAIN, 2);
|
||||
} else {
|
||||
video = new VideoWrapper(PROJECT_DIR"/video/blue_big.avi");
|
||||
}
|
||||
if (video->init()) {
|
||||
LOGM("video_source initialization successfully.");
|
||||
} else {
|
||||
LOGW("video_source unavailable!");
|
||||
}
|
||||
|
||||
// 跳过前10帧噪声图像。
|
||||
Mat src;
|
||||
for (int i = 0; i < 10; i++) {
|
||||
if (video) {
|
||||
video->read(src);
|
||||
}
|
||||
}
|
||||
bool ok = true;
|
||||
cout << "start running" << endl;
|
||||
do {
|
||||
CNT_TIME("Total", {
|
||||
if (last_state != ARMOR_STATE) {
|
||||
LOGM(STR_CTR(WORD_RED, "Start Armor!"));
|
||||
destroyAllWindows();
|
||||
if (from_camera) {
|
||||
delete video;
|
||||
video = new CameraWrapper(ARMOR_CAMERA_EXPOSURE, ARMOR_CAMERA_GAIN, 2/*, "armor"*/);
|
||||
if (video->init()) {
|
||||
LOGM("video_gimbal source initialization successfully.");
|
||||
} else {
|
||||
LOGW("video_gimbal source unavailable!");
|
||||
}
|
||||
}
|
||||
}
|
||||
CNT_TIME(STR_CTR(WORD_GREEN, "read img"), {
|
||||
if(!checkReconnect(video->read(src))) continue;
|
||||
});
|
||||
#ifdef GIMBAL_FLIP_MODE
|
||||
flip(src, src, GIMBAL_FLIP_MODE);
|
||||
#endif
|
||||
CNT_TIME("something whatever", {
|
||||
if (!from_camera) extract(src);
|
||||
if (save_video) saveVideos(src);
|
||||
if (show_origin) showOrigin(src);
|
||||
});
|
||||
CNT_TIME(STR_CTR(WORD_CYAN, "Armor Time"), {
|
||||
armor_finder.run(src);
|
||||
});
|
||||
last_state = ARMOR_STATE; // 强制保持在自瞄模式
|
||||
if(run_by_frame) cv::waitKey(0);
|
||||
});
|
||||
} while (ok);
|
||||
delete video;
|
||||
video = nullptr;
|
||||
cout << "Program fails. Restarting" << endl;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
BIN
others/MVCAMSDK_X64.lib
Normal file
BIN
others/MVCAMSDK_X64.lib
Normal file
Binary file not shown.
153
others/armor.Config
Normal file
153
others/armor.Config
Normal file
File diff suppressed because one or more lines are too long
77
others/include/additions.h
Normal file
77
others/include/additions.h
Normal file
@@ -0,0 +1,77 @@
|
||||
//
|
||||
// Created by sjturm on 19-5-17.
|
||||
//
|
||||
|
||||
#ifndef _ADDITIONS_H_
|
||||
#define _ADDITIONS_H_
|
||||
|
||||
#include <stdint.h>
|
||||
#include <systime.h>
|
||||
#include <serial.h>
|
||||
#include <opencv2/core.hpp>
|
||||
// 单片机端回传数据结构体
|
||||
struct McuData {
|
||||
float curr_yaw; // 当前云台yaw角度
|
||||
float curr_pitch; // 当前云台pitch角
|
||||
uint8_t state; // 当前状态
|
||||
uint8_t mark; // 云台角度标记位
|
||||
uint8_t anti_top; // 是否为反陀螺模式
|
||||
uint8_t enemy_color; // 敌方颜色
|
||||
int reserved_x; // 保留位 (原能量机关x轴补偿量)
|
||||
int reserved_y; // 保留位 (原能量机关y轴补偿量)
|
||||
};
|
||||
|
||||
extern McuData mcu_data;
|
||||
// 串口接收函数
|
||||
void uartReceive(Serial *pSerial);
|
||||
// 相机断线重连函数
|
||||
bool checkReconnect(bool is_camera_connect);
|
||||
// 视频保存函数
|
||||
void saveVideos(const cv::Mat &src);
|
||||
// 原始图像显示函数
|
||||
void showOrigin(const cv::Mat &src);
|
||||
// 图像裁剪函数
|
||||
void extract(cv::Mat &src);
|
||||
|
||||
double getPointLength(const cv::Point2f &p);
|
||||
|
||||
// 循环队列
|
||||
template<class type, int length>
|
||||
class RoundQueue {
|
||||
private:
|
||||
type data[length];
|
||||
int head;
|
||||
int tail;
|
||||
public:
|
||||
RoundQueue<type, length>() : head(0), tail(0) {};
|
||||
|
||||
constexpr int size() const {
|
||||
return length;
|
||||
};
|
||||
|
||||
bool empty() const {
|
||||
return head == tail;
|
||||
};
|
||||
|
||||
void push(const type &obj) {
|
||||
data[head] = obj;
|
||||
head = (head + 1) % length;
|
||||
if (head == tail) {
|
||||
tail = (tail + 1) % length;
|
||||
}
|
||||
};
|
||||
|
||||
bool pop(type &obj) {
|
||||
if (empty()) return false;
|
||||
obj = data[tail];
|
||||
tail = (tail + 1) % length;
|
||||
return true;
|
||||
};
|
||||
|
||||
type &operator[](int idx) {
|
||||
while (tail + idx < 0) idx += length;
|
||||
return data[(tail + idx) % length];
|
||||
};
|
||||
};
|
||||
|
||||
#endif /* _ADDITIONS_H_ */
|
||||
4842
others/include/camera/CameraApi.h
Normal file
4842
others/include/camera/CameraApi.h
Normal file
File diff suppressed because it is too large
Load Diff
5622
others/include/camera/CameraApiLoad.h
Normal file
5622
others/include/camera/CameraApiLoad.h
Normal file
File diff suppressed because it is too large
Load Diff
961
others/include/camera/CameraDefine.H
Normal file
961
others/include/camera/CameraDefine.H
Normal file
@@ -0,0 +1,961 @@
|
||||
#pragma once
|
||||
#ifndef _CAMERA_DEFINE_H_
|
||||
#define _CAMERA_DEFINE_H_
|
||||
|
||||
#include "CameraStatus.h"
|
||||
|
||||
#define MAX_CROSS_LINE 9
|
||||
|
||||
/// @ingroup MV_TYPEDEF
|
||||
/// \~chinese 相机的句柄类型定义
|
||||
/// \~english Camera handle type definition
|
||||
typedef int CameraHandle;
|
||||
|
||||
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese 图像查表变换的方式
|
||||
/// \~english Image lookup table transformation
|
||||
typedef enum
|
||||
{
|
||||
LUTMODE_PARAM_GEN=0, ///< \~chinese 通过调节参数动态生成LUT表。 \~english Dynamically generate LUT tables by adjusting parameters.
|
||||
LUTMODE_PRESET=1, ///< \~chinese 使用预设的LUT表 \~english Use a preset LUT table
|
||||
LUTMODE_USER_DEF=2 ///< \~chinese 使用用户自定义的LUT表 \~english Use a user-defined LUT table
|
||||
}emSdkLutMode;
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese 相机的视频流控制
|
||||
/// \~english Camera video flow control
|
||||
typedef enum
|
||||
{
|
||||
/// \~chinese 正常预览,捕获到图像就显示。(如果相机处于触发模式,则会等待触发帧的到来)
|
||||
/// \~english Normal preview, the captured image is displayed. (If the camera is in trigger mode, it will wait for the arrival of the trigger frame)
|
||||
RUNMODE_PLAY=0,
|
||||
RUNMODE_PAUSE=1, ///< \~chinese 暂停,会暂停相机的图像输出,同时也不会去捕获图像 \~english Pause, will pause the camera's image output, and will not capture the image.
|
||||
RUNMODE_STOP=2 ///< \~chinese 停止相机工作。反初始化后,相机就处于停止模式 \~english Stop the camera. Camera is in stop mode after deinitialization.
|
||||
}emSdkRunMode;
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese SDK内部显示接口的显示方式
|
||||
/// \~english How to display the internal display interface of the SDK
|
||||
typedef enum
|
||||
{
|
||||
DISPLAYMODE_SCALE=0, ///< \~chinese 缩放显示模式,缩放到显示控件的尺寸 \~english Zoom the display mode, zoom to the size of the display control
|
||||
DISPLAYMODE_REAL=1, ///< \~chinese 1:1显示模式,当图像尺寸大于显示控件的尺寸时,只显示局部 \~english 1:1 display mode, when the image size is larger than the size of the display control, only the local display
|
||||
DISPLAYMODE_2X=2, ///< \~chinese 放大2X \~english Zoom in 2X
|
||||
DISPLAYMODE_4X=3, ///< \~chinese 放大4X \~english Zoom in 4X
|
||||
DISPLAYMODE_8X=4, ///< \~chinese 放大8X \~english Zoom in 8X
|
||||
DISPLAYMODE_16X=5 ///< \~chinese 放大16X \~english Zoom in 16X
|
||||
}emSdkDisplayMode;
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese 录像状态
|
||||
/// \~english Recording status
|
||||
typedef enum
|
||||
{
|
||||
RECORD_STOP=0, ///< \~chinese 停止 \~english Stop
|
||||
RECORD_START=1, ///< \~chinese 录像中 \~english Start
|
||||
RECORD_PAUSE=2 ///< \~chinese 暂停 \~english Pause
|
||||
}emSdkRecordMode;
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese 图像的镜像操作
|
||||
/// \~english Image mirroring operation
|
||||
typedef enum
|
||||
{
|
||||
MIRROR_DIRECTION_HORIZONTAL=0, ///< \~chinese 水平镜像 \~english Horizontal mirroring
|
||||
MIRROR_DIRECTION_VERTICAL=1 ///< \~chinese 垂直镜像 \~english Vertical mirroring
|
||||
}emSdkMirrorDirection;
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese 图像的旋转操作
|
||||
/// \~english Rotation of the image
|
||||
typedef enum
|
||||
{
|
||||
ROTATE_DIRECTION_0=0, ///< \~chinese 不旋转 \~english Do not rotate
|
||||
ROTATE_DIRECTION_90=1, ///< \~chinese 逆时针90度 \~english Counterclockwise 90 degrees
|
||||
ROTATE_DIRECTION_180=2, ///< \~chinese 逆时针180度 \~english Counterclockwise 180 degrees
|
||||
ROTATE_DIRECTION_270=3, ///< \~chinese 逆时针270度 \~english Counterclockwise 270 degrees
|
||||
}emSdkRotateDirection;
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese 相机视频的帧率
|
||||
/// \~english Camera video frame rate
|
||||
typedef enum
|
||||
{
|
||||
FRAME_SPEED_LOW=0, ///< \~chinese 低速模式 \~english Low Speed
|
||||
FRAME_SPEED_NORMAL=1, ///< \~chinese 普通模式 \~english Normal Speed
|
||||
FRAME_SPEED_HIGH=2, ///< \~chinese 高速模式(需要较高的传输带宽,多设备共享传输带宽时会对帧率的稳定性有影响) \~english High Speed
|
||||
FRAME_SPEED_SUPER=3 ///< \~chinese 超高速模式(需要较高的传输带宽,多设备共享传输带宽时会对帧率的稳定性有影响) \~english Super Speed
|
||||
}emSdkFrameSpeed;
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese 保存文件的格式类型
|
||||
/// \~english Save file format type
|
||||
typedef enum
|
||||
{
|
||||
FILE_JPG = 1, ///< \~chinese JPG \~english JPG
|
||||
FILE_BMP = 2, ///< \~chinese BMP 24bit \~english BMP 24bit
|
||||
FILE_RAW = 4, ///< \~chinese RAW \~english RAW
|
||||
FILE_PNG = 8, ///< \~chinese PNG 24bit \~english PNG 24bit
|
||||
FILE_BMP_8BIT = 16, ///< \~chinese BMP 8bit \~english BMP 8bit
|
||||
FILE_PNG_8BIT = 32, ///< \~chinese PNG 8bit \~english PNG 8bit
|
||||
FILE_RAW_16BIT = 64 ///< \~chinese RAW 16bit \~english RAW 16bit
|
||||
}emSdkFileType;
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese 相机中的图像传感器的工作模式
|
||||
/// \~english Image Sensor Operation Mode in Camera
|
||||
typedef enum
|
||||
{
|
||||
/// \~chinese 连续采集模式
|
||||
/// \~english Continuous acquisition mode
|
||||
CONTINUATION=0,
|
||||
|
||||
/// \~chinese 软件触发模式,由软件发送指令后,传感器开始采集指定帧数的图像,采集完成后,停止输出
|
||||
/// \~english Software trigger mode. After the software sends the instruction, the sensor starts to capture the image of the specified frame number. After the acquisition is completed, the output is stopped.
|
||||
SOFT_TRIGGER=1,
|
||||
|
||||
/// \~chinese 硬件触发模式,当接收到外部信号,传感器开始采集指定帧数的图像,采集完成后,停止输出
|
||||
/// \~english In the hardware trigger mode, when receiving an external signal, the sensor starts to capture the image of the specified frame number. After the acquisition is completed, the output is stopped.
|
||||
EXTERNAL_TRIGGER=2
|
||||
} emSdkSnapMode;
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese 自动曝光时抗频闪的频率
|
||||
/// \~english Anti-strobe frequency at auto exposure
|
||||
typedef enum
|
||||
{
|
||||
/// \~chinese 50HZ,一般的灯光都是50HZ
|
||||
/// \~english 50HZ, the general lighting is 50HZ
|
||||
LIGHT_FREQUENCY_50HZ=0,
|
||||
|
||||
/// \~chinese 60HZ,主要是指显示器的
|
||||
/// \~english 60HZ, mainly refers to the monitor
|
||||
LIGHT_FREQUENCY_60HZ=1
|
||||
}emSdkLightFrequency;
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese 相机的配置参数,分为A,B,C,D 4组进行保存。
|
||||
/// \~english The camera configuration parameters are divided into groups A, B, C, and D for preservation.
|
||||
typedef enum
|
||||
{
|
||||
PARAMETER_TEAM_DEFAULT = 0xff, ///< \~chinese 默认参数 \~english Default parameters
|
||||
PARAMETER_TEAM_A = 0, ///< \~chinese 参数A \~english parametersA
|
||||
PARAMETER_TEAM_B = 1, ///< \~chinese 参数B \~english parametersB
|
||||
PARAMETER_TEAM_C = 2, ///< \~chinese 参数C \~english parametersC
|
||||
PARAMETER_TEAM_D = 3 ///< \~chinese 参数D \~english parametersD
|
||||
}emSdkParameterTeam;
|
||||
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese
|
||||
/// \brief 相机参数加载模式
|
||||
/// \note 您可以根据自己的使用环境,灵活使用以上几种方式加载参数。例如,以
|
||||
/// \note MV-U300为例,您希望多台该型号的相机在您的 电脑上都共用4组参数,那么就
|
||||
/// \note 使用PARAM_MODE_BY_MODEL方式;如果您希望其中某一台或者某几台MV-U300能
|
||||
/// \note 使用自己参数文件而其余的MV-U300又要使用相同的参数文件,那么使用
|
||||
/// \note PARAM_MODE_BY_NAME方式;如果您希望每台MV-U300都使用不同的参数文件,那么
|
||||
/// \note 使用PARAM_MODE_BY_SN方式。
|
||||
/// \note 参数文件存在安装目录的 \\Camera\\Configs 目录下,以config为后缀名的文件。
|
||||
/// \~english
|
||||
/// \brief Camera parameter loading mode
|
||||
/// \note You can use the above several ways to load parameters according to your own environment. For example, with
|
||||
/// \note MV-U300 as an example, you want multiple cameras of this model to share 4 sets of parameters on your computer.
|
||||
/// \note Use the PARAM_MODE_BY_MODEL method; if you want one or more of the MV-U300s
|
||||
/// \note Use your own parameter file and the rest of the MV-U300 use the same parameter file again, then use
|
||||
/// \note PARAM_MODE_BY_NAME way; if you want each MV-U300 to use a different parameter file, then
|
||||
/// \note Use the PARAM_MODE_BY_SN method.
|
||||
/// \note The parameter file exists in the \\Camera\\Configs directory of the installation directory, with a config extension file.
|
||||
typedef enum
|
||||
{
|
||||
/// \~chinese 根据相机型号名从文件中加载参数,例如MV-U300
|
||||
/// \note 所有同型号的相机共用ABCD四组参数文件。修改一台相机的参数文件,会影响到整个同型号的相机参数加载。
|
||||
/// \~english Load parameters from a file based on the camera model name, such as the MV-U300
|
||||
/// \note All ABCD four-group parameter files are shared by all cameras of the same model. Modifying a camera's parameter file will affect the entire camera model parameter loading.
|
||||
PARAM_MODE_BY_MODEL=0,
|
||||
|
||||
/// \~chinese 根据设备昵称(tSdkCameraDevInfo.acFriendlyName)从文件中加载参数,例如MV-U300,该昵称可自定义
|
||||
/// \note 所有设备名相同的相机,共用ABCD四组参数文件。
|
||||
/// \note 默认情况下,当电脑上只接了某型号一台相机时,
|
||||
/// \note 设备名都是一样的,而您希望某一台相机能够加载
|
||||
/// \note 不同的参数文件,则可以通过修改其设备名的方式
|
||||
/// \note 来让其加载指定的参数文件。
|
||||
/// \~english Load parameters from a file based on device nickname (tSdkCameraDevInfo.acFriendlyName), such as MV-U300, which can be customized
|
||||
/// \note All cameras with the same device name share the four ABCD parameter files.
|
||||
/// \note By default, when only one model of a camera is connected to the computer,
|
||||
/// \note The device name is the same, and you want a camera to load
|
||||
/// \note different parameter files, you can modify the device name
|
||||
/// \note to have it load the specified parameter file.
|
||||
PARAM_MODE_BY_NAME=1,
|
||||
|
||||
/// \~chinese 根据设备的唯一序列号从文件中加载参数,序列号在出厂时已经写入设备,每台相机拥有不同的序列号。
|
||||
/// \note 相机按照自己的唯一序列号来加载ABCD四组参数文件,
|
||||
/// \note 序列号在出厂时已经固化在相机内,每台相机的序列号
|
||||
/// \note 都不相同,通过这种方式,每台相机的参数文件都是独立的。
|
||||
/// \~english The parameters are loaded from the file according to the unique serial number of the device. The serial number is already written to the device at the factory and each camera has a different serial number.
|
||||
/// \note The camera loads ABCD four sets of parameter files according to their unique serial number.
|
||||
/// \note The serial number has been fixed in the camera at the factory, the serial number of each camera
|
||||
/// \note is not the same. In this way, the parameter files for each camera are independent.
|
||||
PARAM_MODE_BY_SN=2,
|
||||
|
||||
/// \~chinese 从设备的固态存储器中加载参数。不是所有的型号都支持从相机中读写参数组,由tSdkCameraCapbility.bParamInDevice决定
|
||||
/// \~english Load parameters from the device's solid-state memory. Not all models support reading and writing parameters from the camera, as determined by tSdkCameraCapbility.bParamInDevice
|
||||
PARAM_MODE_IN_DEVICE=3
|
||||
}emSdkParameterMode;
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese SDK生成的相机配置页面掩码值
|
||||
/// \~english SDK generated camera configuration page mask values
|
||||
typedef enum
|
||||
{
|
||||
PROP_SHEET_INDEX_EXPOSURE=0, ///< \~chinese 曝光设置 \~english Exposure Settings
|
||||
PROP_SHEET_INDEX_ISP_COLOR=1, ///< \~chinese 颜色矩阵设置 \~english Color Matrix Settings
|
||||
PROP_SHEET_INDEX_ISP_LUT=2, ///< \~chinese LUT设置 \~english LUT setting
|
||||
PROP_SHEET_INDEX_ISP_SHAPE=3, ///< \~chinese 变换设置 \~english transform settings
|
||||
PROP_SHEET_INDEX_VIDEO_FORMAT=4, ///< \~chinese 格式设置 \~english Formatting
|
||||
PROP_SHEET_INDEX_RESOLUTION=5, ///< \~chinese 分辨率设置 \~english resolution setting
|
||||
PROP_SHEET_INDEX_IO_CTRL=6, ///< \~chinese IO控制 \~english IO control
|
||||
PROP_SHEET_INDEX_TRIGGER_SET=7, ///< \~chinese 触发模式 \~english trigger setting
|
||||
PROP_SHEET_INDEX_OVERLAY=8, ///< \~chinese 十字线 \~english Crosshair
|
||||
PROP_SHEET_INDEX_DEVICE_INFO=9, ///< \~chinese 设备信息 \~english Device Information
|
||||
PROP_SHEET_INDEX_WDR=10 ///< \~chinese 宽动态 \~english Wide Dynamic
|
||||
}emSdkPropSheetMask;
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese SDK生成的相机配置页面的回调消息类型
|
||||
/// \~english SDK callback camera configuration page callback message type
|
||||
typedef enum
|
||||
{
|
||||
SHEET_MSG_LOAD_PARAM_DEFAULT=0, ///< \~chinese 参数被恢复成默认后,触发该消息 \~english After the parameter is restored to the default, the message is triggered
|
||||
SHEET_MSG_LOAD_PARAM_GROUP=1, ///< \~chinese 加载指定参数组,触发该消息 \~english Load the specified parameter group and trigger the message
|
||||
SHEET_MSG_LOAD_PARAM_FROMFILE=2, ///< \~chinese 从指定文件加载参数后,触发该消息 \~english Fires the message after loading parameters from the specified file
|
||||
SHEET_MSG_SAVE_PARAM_GROUP=3 ///< \~chinese 当前参数组被保存时,触发该消息 \~english Trigger this message when the current parameter group is saved
|
||||
}emSdkPropSheetMsg;
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese 可视化选择参考窗口的类型
|
||||
/// \~english Visualize the type of reference window
|
||||
typedef enum
|
||||
{
|
||||
REF_WIN_AUTO_EXPOSURE=0, ///< \~chinese 自动曝光窗口 \~english Automatic exposure window
|
||||
REF_WIN_WHITE_BALANCE=1, ///< \~chinese 白平衡窗口 \~english White balance window
|
||||
}emSdkRefWinType;
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese 可视化选择参考窗口的类型
|
||||
/// \~english Visualize the type of reference window
|
||||
typedef enum
|
||||
{
|
||||
RES_MODE_PREVIEW=0, ///< \~chinese 预览 \~english Preview
|
||||
RES_MODE_SNAPSHOT=1, ///< \~chinese 抓拍 \~english Snapshot
|
||||
}emSdkResolutionMode;
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese 白平衡时色温模式
|
||||
/// \~english White balance color temperature mode
|
||||
typedef enum
|
||||
{
|
||||
CT_MODE_AUTO=0, ///< \~chinese 自动识别色温 \~english Automatically recognize color temperature
|
||||
CT_MODE_PRESET=1, ///< \~chinese 使用指定的预设色温 \~english Use the specified preset color temperature
|
||||
CT_MODE_USER_DEF=2 ///< \~chinese 自定义色温(增益和矩阵) \~english Custom color temperature (gain and matrix)
|
||||
}emSdkClrTmpMode;
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese LUT的颜色通道
|
||||
/// \~english LUT color channel
|
||||
typedef enum
|
||||
{
|
||||
LUT_CHANNEL_ALL=0, ///< \~chinese R,B,G三通道同时调节 \~english R, B, G simultaneous adjustment of three channels
|
||||
LUT_CHANNEL_RED=1, ///< \~chinese 红色通道 \~english Red channel
|
||||
LUT_CHANNEL_GREEN=2, ///< \~chinese 绿色通道 \~english Green channel
|
||||
LUT_CHANNEL_BLUE=3, ///< \~chinese 蓝色通道 \~english Blue channel
|
||||
}emSdkLutChannel;
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese ISP处理单元
|
||||
/// \~english ISP processing unit
|
||||
typedef enum
|
||||
{
|
||||
ISP_PROCESSSOR_PC=0, ///< \~chinese 使用PC的软件ISP模块 \~english Use software ISP module of PC
|
||||
ISP_PROCESSSOR_DEVICE=1 ///< \~chinese 使用相机自带的硬件ISP模块 \~english Use the camera's own hardware ISP module
|
||||
}emSdkIspProcessor;
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese 闪光灯信号控制方式
|
||||
/// \~english Strobe signal control method
|
||||
typedef enum
|
||||
{
|
||||
STROBE_SYNC_WITH_TRIG_AUTO=0, ///< \~chinese 和触发信号同步,触发后,相机进行曝光时,自动生成STROBE信号。此时,有效极性可设置(@link #CameraSetStrobePolarity @endlink)。 \~english Synchronized with the trigger signal, the STROBE signal is automatically generated when the camera performs exposure. At this point, the effective polarity can be set (@link #CameraSetStrobePolarity @endlink).
|
||||
STROBE_SYNC_WITH_TRIG_MANUAL=1, ///< \~chinese 和触发信号同步,触发后,STROBE延时指定的时间后(@link #CameraSetStrobeDelayTime @endlink),再持续指定时间的脉冲(@link #CameraSetStrobePulseWidth @endlink),有效极性可设置(@link #CameraSetStrobePolarity @endlink)。 \~english Synchronized with the trigger signal. After the trigger, STROBE is delayed by the specified time (@link #CameraSetStrobeDelayTime @endlink) and continues for the specified time (@link #CameraSetStrobePulseWidth @endlink). The effective polarity can be set (@link #CameraSetStrobePolarity @endlink).
|
||||
STROBE_ALWAYS_HIGH=2, ///< \~chinese 始终为高,忽略STROBE信号的其他设置 \~english Always high, ignoring other settings of the STROBE signal
|
||||
STROBE_ALWAYS_LOW=3 ///< \~chinese 始终为低,忽略STROBE信号的其他设置 \~english Always low, ignoring other settings of the STROBE signal
|
||||
}emStrobeControl;
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese 硬件外触发的信号种类
|
||||
/// \~english Signal types triggered by hardware
|
||||
typedef enum
|
||||
{
|
||||
EXT_TRIG_LEADING_EDGE=0, ///< \~chinese 上升沿触发,默认为该方式 \~english Rising edge trigger, default is this method
|
||||
EXT_TRIG_TRAILING_EDGE=1, ///< \~chinese 下降沿触发 \~english Falling edge trigger
|
||||
EXT_TRIG_HIGH_LEVEL=2, ///< \~chinese 高电平触发,电平宽度决定曝光时间,仅部分型号的相机支持电平触发方式。 \~english The high level triggers, the level width determines the exposure time, only some models of cameras support level triggering.
|
||||
EXT_TRIG_LOW_LEVEL=3, ///< \~chinese 低电平触发 \~english Low level trigger
|
||||
EXT_TRIG_DOUBLE_EDGE=4, ///< \~chinese 双边沿触发 \~english Bilateral trigger
|
||||
}emExtTrigSignal;
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese 硬件外触发时的快门方式
|
||||
/// \~english Shutter mode when triggered by hardware
|
||||
typedef enum
|
||||
{
|
||||
EXT_TRIG_EXP_STANDARD=0, ///< \~chinese 标准方式,默认为该方式。 \~english Standard mode, the default is this mode.
|
||||
EXT_TRIG_EXP_GRR=1, ///< \~chinese 全局复位方式,部分滚动快门的CMOS型号的相机支持该方式,配合外部机械快门,可以达到全局快门的效果,适合拍高速运动的物体 \~english Global reset mode, part of the rolling shutter CMOS model camera supports this method, with the external mechanical shutter, you can achieve the effect of a global shutter, suitable for shooting high-speed objects
|
||||
}emExtTrigShutterMode;
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese 清晰度评估算法
|
||||
/// \~english Sharpness assessment algorithm
|
||||
typedef enum
|
||||
{
|
||||
EVALUATE_DEFINITION_DEVIATION=0, ///< \~chinese 方差法 \~english Variance method
|
||||
EVALUATE_DEFINITION_SMD=1, ///< \~chinese 相邻像素灰度方差法 \~english Adjacent Pixel Gray Difference Method
|
||||
EVALUATE_DEFINITION_GRADIENT=2, ///< \~chinese 梯度统计 \~english Gradient statistics
|
||||
EVALUATE_DEFINITION_SOBEL=3, ///< \~chinese Sobel \~english Sobel
|
||||
EVALUATE_DEFINITION_ROBERT=4, ///< \~chinese Robert \~english Robert
|
||||
EVALUATE_DEFINITION_LAPLACE=5, ///< \~chinese Laplace \~english Laplace
|
||||
|
||||
EVALUATE_DEFINITION_ALG_MAX=6, ///< \~chinese 算法个数 \~english The number of algorithms
|
||||
}emEvaluateDefinitionAlgorith;
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese 文字输出标志
|
||||
/// \~english Text output flag
|
||||
typedef enum
|
||||
{
|
||||
CAMERA_DT_VCENTER = 0x1, ///< \~chinese 垂直居中 \~english Vertically centered
|
||||
CAMERA_DT_BOTTOM = 0x2, ///< \~chinese 底部对齐 \~english Bottom alignment
|
||||
CAMERA_DT_HCENTER = 0x4, ///< \~chinese 水平居中 \~english Horizontally centered
|
||||
CAMERA_DT_RIGHT = 0x8, ///< \~chinese 右对齐 \~english Right alignment
|
||||
CAMERA_DT_SINGLELINE = 0x10, ///< \~chinese 单行显示 \~english Single-line display
|
||||
CAMERA_DT_ALPHA_BLEND = 0x20, ///< \~chinese Alpha混合 \~english Alpha blend
|
||||
CAMERA_DT_ANTI_ALIASING = 0x40, ///< \~chinese 抗锯齿 \~english Anti-aliasing
|
||||
}emCameraDrawTextFlags;
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese GPIO模式
|
||||
/// \~english GPIO Mode
|
||||
typedef enum
|
||||
{
|
||||
IOMODE_TRIG_INPUT=0, ///< \~chinese 触发输入 \~english Trigger input
|
||||
IOMODE_STROBE_OUTPUT=1, ///< \~chinese 闪光灯输出 \~english Strobe output
|
||||
IOMODE_GP_INPUT=2, ///< \~chinese 通用型输入 \~english Universal input
|
||||
IOMODE_GP_OUTPUT=3, ///< \~chinese 通用型输出 \~english Universal output
|
||||
IOMODE_PWM_OUTPUT=4, ///< \~chinese PWM型输出 \~english PWM output
|
||||
}emCameraGPIOMode;
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese 取图优先级
|
||||
/// \~english Get Image priority
|
||||
typedef enum
|
||||
{
|
||||
CAMERA_GET_IMAGE_PRIORITY_OLDEST=0, ///< \~chinese 获取缓存中最旧的一帧 \~english Get the oldest frame in the cache
|
||||
CAMERA_GET_IMAGE_PRIORITY_NEWEST=1, ///< \~chinese 获取缓存中最新的一帧(比此帧旧的将全部丢弃) \~english Get the latest frame in the cache (older than this frame will be discarded)
|
||||
|
||||
/// \~chinese 丢弃缓存中的所有帧,并且如果此刻相机正在曝光或传输将会被立即打断,等待接收下一帧
|
||||
/// \note 某些型号的相机不支持此功能,对于不支持此功能的相机这个标志相当于@link #CAMERA_GET_IMAGE_PRIORITY_OLDEST @endlink
|
||||
/// \~english All frames in the cache are discarded, and if the camera is now being exposed or transmitted it will be immediately interrupted, waiting to receive the next frame
|
||||
/// \note Some models do not support this feature. For cameras that do not support this feature this flag is equivalent to @link #CAMERA_GET_IMAGE_PRIORITY_OLDEST @endlink
|
||||
CAMERA_GET_IMAGE_PRIORITY_NEXT=2,
|
||||
}emCameraGetImagePriority;
|
||||
|
||||
/// @ingroup MV_ENUM_TYPE
|
||||
/// \~chinese 软触发功能标志
|
||||
/// \~english Soft trigger function flag
|
||||
typedef enum
|
||||
{
|
||||
CAMERA_ST_CLEAR_BUFFER_BEFORE = 0x1, ///< \~chinese 在软触发之前先清空相机已缓存的帧 \~english Empty camera-cached frames before soft triggering
|
||||
}emCameraSoftTriggerExFlags;
|
||||
|
||||
/// \~chinese 相机的设备信息
|
||||
/// \~english Camera device information
|
||||
typedef struct
|
||||
{
|
||||
char acProductSeries[32]; ///< \~chinese 产品系列 \~english Product Series
|
||||
char acProductName[32]; ///< \~chinese 产品名称 \~english product name
|
||||
|
||||
/// \~chinese 产品昵称,用户可自定义改昵称,保存在相机内,用于区分多个相机同时使用,可以用@link #CameraSetFriendlyName @endlink接口改变该昵称,设备重启后生效。
|
||||
/// \~english Product nicknames, users can customize the nickname, saved in the camera, used to distinguish between multiple cameras at the same time, you can use the @link #CameraSetFriendlyName @endlink interface to change the nickname, the device takes effect after restart.
|
||||
char acFriendlyName[32];
|
||||
char acLinkName[32]; ///< \~chinese 内核符号连接名,内部使用 \~english Kernel symbolic connection name, internal use
|
||||
char acDriverVersion[32]; ///< \~chinese 驱动版本 \~english Driver version
|
||||
char acSensorType[32]; ///< \~chinese sensor类型 \~english Sensor type
|
||||
char acPortType[32]; ///< \~chinese 接口类型 \~english Interface Type
|
||||
char acSn[32]; ///< \~chinese 产品唯一序列号 \~english Product unique serial number
|
||||
UINT uInstance; ///< \~chinese 该型号相机在该电脑上的实例索引号,用于区分同型号多相机 \~english The example index number of this model camera on this computer, used to distinguish the same model multiple cameras
|
||||
} tSdkCameraDevInfo;
|
||||
|
||||
/// @ingroup MV_MACRO_TYPE
|
||||
/// @{
|
||||
#define EXT_TRIG_MASK_GRR_SHUTTER 1 ///< \~chinese 快门支持GRR模式 \~english Shutter supports GRR mode
|
||||
#define EXT_TRIG_MASK_LEVEL_MODE 2 ///< \~chinese 支持电平触发 \~english Support level trigger
|
||||
#define EXT_TRIG_MASK_DOUBLE_EDGE 4 ///< \~chinese 支持双边沿触发 \~english Supports bilateral triggering
|
||||
|
||||
//tSdkResolutionRange结构体中SKIP、 BIN、RESAMPLE模式的掩码值
|
||||
#define MASK_2X2_HD (1<<0) //硬件SKIP、BIN、重采样 2X2
|
||||
#define MASK_3X3_HD (1<<1)
|
||||
#define MASK_4X4_HD (1<<2)
|
||||
#define MASK_5X5_HD (1<<3)
|
||||
#define MASK_6X6_HD (1<<4)
|
||||
#define MASK_7X7_HD (1<<5)
|
||||
#define MASK_8X8_HD (1<<6)
|
||||
#define MASK_9X9_HD (1<<7)
|
||||
#define MASK_10X10_HD (1<<8)
|
||||
#define MASK_11X11_HD (1<<9)
|
||||
#define MASK_12X12_HD (1<<10)
|
||||
#define MASK_13X13_HD (1<<11)
|
||||
#define MASK_14X14_HD (1<<12)
|
||||
#define MASK_15X15_HD (1<<13)
|
||||
#define MASK_16X16_HD (1<<14)
|
||||
#define MASK_17X17_HD (1<<15)
|
||||
#define MASK_2X2_SW (1<<16) //软件SKIP、BIN、重采样 2X2
|
||||
#define MASK_3X3_SW (1<<17)
|
||||
#define MASK_4X4_SW (1<<18)
|
||||
#define MASK_5X5_SW (1<<19)
|
||||
#define MASK_6X6_SW (1<<20)
|
||||
#define MASK_7X7_SW (1<<21)
|
||||
#define MASK_8X8_SW (1<<22)
|
||||
#define MASK_9X9_SW (1<<23)
|
||||
#define MASK_10X10_SW (1<<24)
|
||||
#define MASK_11X11_SW (1<<25)
|
||||
#define MASK_12X12_SW (1<<26)
|
||||
#define MASK_13X13_SW (1<<27)
|
||||
#define MASK_14X14_SW (1<<28)
|
||||
#define MASK_15X15_SW (1<<29)
|
||||
#define MASK_16X16_SW (1<<30)
|
||||
#define MASK_17X17_SW (1<<31)
|
||||
/// @}
|
||||
|
||||
/// \~chinese 相机的分辨率设定范围,可用于构件UI
|
||||
/// \~english Camera resolution setting range, can be used for component UI
|
||||
typedef struct
|
||||
{
|
||||
INT iHeightMax; ///< \~chinese 图像最大高度 \~english Maximum image height
|
||||
INT iHeightMin; ///< \~chinese 图像最小高度 \~english Image minimum height
|
||||
INT iWidthMax; ///< \~chinese 图像最大宽度 \~english The maximum width of the image
|
||||
INT iWidthMin; ///< \~chinese 图像最小宽度 \~english The minimum width of the image
|
||||
UINT uSkipModeMask; ///< \~chinese SKIP模式掩码,为0,表示不支持SKIP 。bit0为1,表示支持SKIP 2x2 ;bit1为1,表示支持SKIP 3x3.... \~english The SKIP mode mask, which is 0, indicates that SKIP is not supported. Bit0 is 1 to indicate that SKIP 2x2 is supported; bit1 is 1 to indicate that SKIP 3x3 is supported....
|
||||
UINT uBinSumModeMask; ///< \~chinese BIN(求和)模式掩码,为0,表示不支持BIN 。bit0为1,表示支持BIN 2x2 ;bit1为1,表示支持BIN 3x3.... \~english The BIN (sum) pattern mask, which is 0, indicates that BIN is not supported. Bit0 is 1, indicating that BIN 2x2 is supported; bit1 is 1, indicating that BIN 3x3 is supported....
|
||||
UINT uBinAverageModeMask; ///< \~chinese BIN(求均值)模式掩码,为0,表示不支持BIN 。bit0为1,表示支持BIN 2x2 ;bit1为1,表示支持BIN 3x3.... \~english The BIN (mean value) mode mask, which is 0, indicates that BIN is not supported. Bit0 is 1, indicating that BIN 2x2 is supported; bit1 is 1, indicating that BIN 3x3 is supported....
|
||||
UINT uResampleMask; ///< \~chinese 硬件重采样的掩码 \~english Hardware resampling mask
|
||||
} tSdkResolutionRange;
|
||||
|
||||
/// \~chinese 相机的分辨率描述
|
||||
/// \~english Camera resolution description
|
||||
typedef struct
|
||||
{
|
||||
INT iIndex; ///< \~chinese 索引号,[0,N]表示预设的分辨率(N 为预设分辨率的最大个数,一般不超过20),OXFF 表示自定义分辨率(ROI) \~english Index number, [0, N] indicates the preset resolution (N is the maximum number of preset resolutions, generally no more than 20), OXFF indicates custom resolution (ROI)
|
||||
char acDescription[32]; ///< \~chinese 该分辨率的描述信息。仅预设分辨率时该信息有效。自定义分辨率可忽略该信息 \~english The description of the resolution. This information is valid only when the resolution is preset. Custom resolution ignores this information
|
||||
UINT uBinSumMode; ///< \~chinese BIN(求和)的模式,范围不能超过tSdkResolutionRange.uBinSumModeMask \~english The BIN (sum) mode cannot exceed the tSdkResolutionRange.uBinSumModeMask
|
||||
UINT uBinAverageMode; ///< \~chinese BIN(求均值)的模式,范围不能超过tSdkResolutionRange.uBinAverageModeMask \~english BIN (average) mode, the range cannot exceed tSdkResolutionRange.uBinAverageModeMask
|
||||
UINT uSkipMode; ///< \~chinese 是否SKIP的尺寸,为0表示禁止SKIP模式,范围不能超过tSdkResolutionRange.uSkipModeMask \~english Whether the SKIP size is 0 indicates that the SKIP mode is disabled and the range cannot exceed the tSdkResolutionRange.uSkipModeMask
|
||||
UINT uResampleMask; ///< \~chinese 硬件重采样的掩码 \~english Hardware resampling mask
|
||||
INT iHOffsetFOV; ///< \~chinese 采集视场相对于Sensor最大视场左上角的水平偏移 \~english The horizontal offset of the acquisition field of view relative to the top left corner of the Sensor's largest field of view
|
||||
INT iVOffsetFOV; ///< \~chinese 采集视场相对于Sensor最大视场左上角的垂直偏移 \~english The vertical offset of the acquisition field of view relative to the upper left corner of the Sensor's largest field of view
|
||||
INT iWidthFOV; ///< \~chinese 采集视场的宽度 \~english The width of the field of view
|
||||
INT iHeightFOV; ///< \~chinese 采集视场的高度 \~english The height of the field of view
|
||||
INT iWidth; ///< \~chinese 相机最终输出的图像的宽度 \~english The width of the final output image of the camera
|
||||
INT iHeight; ///< \~chinese 相机最终输出的图像的高度 \~english The height of the final output image of the camera
|
||||
INT iWidthZoomHd; ///< \~chinese 硬件缩放的宽度,不需要进行此操作的分辨率,此变量设置为0. \~english The width of the hardware zoom, resolution that does not require this operation, this variable is set to 0.
|
||||
INT iHeightZoomHd; ///< \~chinese 硬件缩放的高度,不需要进行此操作的分辨率,此变量设置为0. \~english The height of the hardware zoom, resolution that does not require this operation, this variable is set to 0.
|
||||
INT iWidthZoomSw; ///< \~chinese 软件缩放的宽度,不需要进行此操作的分辨率,此变量设置为0. \~english The width of the software's zoom, which does not require the resolution of this operation, this variable is set to 0.
|
||||
INT iHeightZoomSw; ///< \~chinese 软件缩放的高度,不需要进行此操作的分辨率,此变量设置为0. \~english The height of the software's zoom, which does not require the resolution of this operation, this variable is set to 0.
|
||||
} tSdkImageResolution;
|
||||
|
||||
/// \~chinese 相机白平衡色温模式描述信息
|
||||
/// \~english Camera white balance color temperature mode description information
|
||||
typedef struct
|
||||
{
|
||||
INT iIndex; ///< \~chinese 模式索引号 \~english Mode index number
|
||||
char acDescription[32]; ///< \~chinese 描述信息 \~english Description
|
||||
} tSdkColorTemperatureDes;
|
||||
|
||||
/// \~chinese 相机帧率描述信息
|
||||
/// \~english Camera frame rate description information
|
||||
typedef struct
|
||||
{
|
||||
INT iIndex; ///< \~chinese 帧率索引号,一般0对应于低速模式,1对应于普通模式,2对应于高速模式 \~english Frame rate index number, generally 0 corresponds to low speed mode, 1 corresponds to normal mode, 2 corresponds to high speed mode
|
||||
char acDescription[32]; ///< \~chinese 描述信息 \~english Description
|
||||
} tSdkFrameSpeed;
|
||||
|
||||
/// \~chinese 相机曝光功能范围定义
|
||||
/// \see tSdkCameraCapbility.sExposeDesc
|
||||
/// \~english Camera exposure function scope definition
|
||||
/// \see tSdkCameraCapbility.sExposeDesc
|
||||
typedef struct
|
||||
{
|
||||
UINT uiTargetMin; ///< \~chinese 自动曝光亮度目标最小值 \~english Auto exposure brightness target minimum
|
||||
UINT uiTargetMax; ///< \~chinese 自动曝光亮度目标最大值 \~english Auto exposure brightness target maximum
|
||||
UINT uiAnalogGainMin; ///< \~chinese 模拟增益的最小值,单位为fAnalogGainStep中定义 \~english The minimum value of the analog gain in fAnalog defined in GainStep
|
||||
UINT uiAnalogGainMax; ///< \~chinese 模拟增益的最大值,单位为fAnalogGainStep中定义 \~english The maximum value of the analog gain in fAnalog defined in GainStep
|
||||
float fAnalogGainStep; ///< \~chinese 模拟增益每增加1,对应的增加的放大倍数。例如,uiAnalogGainMin一般为16,fAnalogGainStep一般为0.125,那么最小放大倍数就是16*0.125 = 2倍 \~english Each increase in analog gain corresponds to an increased amplification factor. For example, uiAnalogGainMin is generally 16 and fAnalogGainStep is generally 0.125, so the minimum magnification is 16*0.125 = 2 times
|
||||
UINT uiExposeTimeMin; ///< \~chinese 手动模式下,曝光时间的最小值,单位:行。根据CameraGetExposureLineTime可以获得一行对应的时间(微秒),从而得到整帧的曝光时间 \~english The minimum exposure time in manual mode, unit: line. According to CameraGetExposureLineTime can get a row of corresponding time (microseconds) to get the entire frame exposure time
|
||||
UINT uiExposeTimeMax; ///< \~chinese 手动模式下,曝光时间的最大值,单位:行 \~english Maximum exposure time in manual mode, unit: line
|
||||
} tSdkExpose;
|
||||
|
||||
/// \~chinese 触发模式描述
|
||||
/// \~english Trigger mode description
|
||||
typedef struct
|
||||
{
|
||||
INT iIndex; ///< \~chinese 模式索引号 \~english Mode index number
|
||||
char acDescription[32]; ///< \~chinese 该模式的描述信息 \~english Description information of this mode
|
||||
} tSdkTrigger;
|
||||
|
||||
/// \~chinese 传输分包大小描述(针对某些网络相机有效)
|
||||
/// \~english Transmission packet size description (valid for some web cameras)
|
||||
typedef struct
|
||||
{
|
||||
INT iIndex; ///< \~chinese 分包大小索引号 \~english Packet size index number
|
||||
char acDescription[32]; ///< \~chinese 对应的描述信息 \~english Corresponding description information
|
||||
UINT iPackSize; ///< \~chinese 包大小 \~english Packet size
|
||||
} tSdkPackLength;
|
||||
|
||||
/// \~chinese 预设的LUT表描述
|
||||
/// \~english Preset LUT Table Description
|
||||
typedef struct
|
||||
{
|
||||
INT iIndex; ///< \~chinese 索引 \~english index
|
||||
char acDescription[32]; ///< \~chinese 描述信息 \~english description
|
||||
} tSdkPresetLut;
|
||||
|
||||
/// \~chinese AE算法描述
|
||||
/// \~english AE algorithm description
|
||||
typedef struct
|
||||
{
|
||||
INT iIndex; ///< \~chinese 索引 \~english index
|
||||
char acDescription[32]; ///< \~chinese 描述信息 \~english description
|
||||
} tSdkAeAlgorithm;
|
||||
|
||||
/// \~chinese RAW转RGB算法描述
|
||||
/// \~english RAW to RGB algorithm description
|
||||
typedef struct
|
||||
{
|
||||
INT iIndex; ///< \~chinese 索引 \~english index
|
||||
char acDescription[32]; ///< \~chinese 描述信息 \~english description
|
||||
} tSdkBayerDecodeAlgorithm;
|
||||
|
||||
/// \~chinese 帧统计信息
|
||||
/// \~english Frame statistics
|
||||
typedef struct
|
||||
{
|
||||
INT iTotal; ///< \~chinese 当前采集的总帧数(包括错误帧) \~english The current total number of frames collected (including error frames)
|
||||
INT iCapture; ///< \~chinese 当前采集的有效帧的数量 \~english The number of valid frames currently collected
|
||||
INT iLost; ///< \~chinese 当前丢帧的数量 \~english Current number of dropped frames
|
||||
} tSdkFrameStatistic;
|
||||
|
||||
/// \~chinese 相机输出的图像数据格式
|
||||
/// \~english Camera output image data format
|
||||
typedef struct
|
||||
{
|
||||
INT iIndex; ///< \~chinese 格式种类编号 \~english Format type number
|
||||
char acDescription[32]; ///< \~chinese 描述信息 \~english description
|
||||
UINT iMediaType; ///< \~chinese 对应的图像格式编码,如CAMERA_MEDIA_TYPE_BAYGR8。 \~english Corresponding image format encoding, such as CAMERA_MEDIA_TYPE_BAYGR8.
|
||||
} tSdkMediaType;
|
||||
|
||||
/// \~chinese 伽马的设定范围
|
||||
/// \~english Gamma setting range
|
||||
typedef struct
|
||||
{
|
||||
INT iMin; ///< \~chinese 最小值 \~english min
|
||||
INT iMax; ///< \~chinese 最大值 \~english max
|
||||
} tGammaRange;
|
||||
|
||||
/// \~chinese 对比度的设定范围
|
||||
/// \~english Contrast setting range
|
||||
typedef struct
|
||||
{
|
||||
INT iMin; ///< \~chinese 最小值 \~english min
|
||||
INT iMax; ///< \~chinese 最大值 \~english max
|
||||
} tContrastRange;
|
||||
|
||||
/// \~chinese RGB三通道数字增益的设定范围
|
||||
/// \~english RGB three channel digital gain setting range
|
||||
typedef struct
|
||||
{
|
||||
INT iRGainMin; ///< \~chinese 红色增益的最小值 \~english Red gain minimum
|
||||
INT iRGainMax; ///< \~chinese 红色增益的最大值 \~english Red gain maximum
|
||||
INT iGGainMin; ///< \~chinese 绿色增益的最小值 \~english Green gain minimum
|
||||
INT iGGainMax; ///< \~chinese 绿色增益的最大值 \~english Green gain maximum
|
||||
INT iBGainMin; ///< \~chinese 蓝色增益的最小值 \~english Blue gain minimum
|
||||
INT iBGainMax; ///< \~chinese 蓝色增益的最大值 \~english blue gain maximum
|
||||
} tRgbGainRange;
|
||||
|
||||
/// \~chinese 饱和度设定的范围
|
||||
/// \~english Saturation setting range
|
||||
typedef struct
|
||||
{
|
||||
INT iMin; ///< \~chinese 最小值 \~english min
|
||||
INT iMax; ///< \~chinese 最大值 \~english max
|
||||
} tSaturationRange;
|
||||
|
||||
/// \~chinese 锐化的设定范围
|
||||
/// \~english Sharpening setting range
|
||||
typedef struct
|
||||
{
|
||||
INT iMin; ///< \~chinese 最小值 \~english min
|
||||
INT iMax; ///< \~chinese 最大值 \~english max
|
||||
} tSharpnessRange;
|
||||
|
||||
/// \~chinese ISP模块的使能信息
|
||||
/// \~english ISP module enable information
|
||||
typedef struct
|
||||
{
|
||||
BOOL bMonoSensor; ///< \~chinese 表示该型号相机是否为黑白相机,如果是黑白相机,则颜色相关的功能都无法调节 \~english Indicates whether this model is a black-and-white camera. If it is a black-and-white camera, color-related functions cannot be adjusted.
|
||||
BOOL bWbOnce; ///< \~chinese 表示该型号相机是否支持手动白平衡功能 \~english Indicates whether this model camera supports manual white balance function
|
||||
BOOL bAutoWb; ///< \~chinese 表示该型号相机是否支持自动白平衡功能 \~english Indicates whether this model camera supports automatic white balance function
|
||||
BOOL bAutoExposure; ///< \~chinese 表示该型号相机是否支持自动曝光功能 \~english Indicates whether this model camera supports auto exposure function
|
||||
BOOL bManualExposure; ///< \~chinese 表示该型号相机是否支持手动曝光功能 \~english Indicates whether this model camera supports manual exposure function
|
||||
BOOL bAntiFlick; ///< \~chinese 表示该型号相机是否支持抗频闪功能 \~english Indicates whether this model camera supports anti-strobe function
|
||||
BOOL bDeviceIsp; ///< \~chinese 表示该型号相机是否支持硬件ISP功能 \~english Indicates whether this model camera supports hardware ISP function
|
||||
BOOL bForceUseDeviceIsp;///< \~chinese bDeviceIsp和bForceUseDeviceIsp同时为TRUE时,表示强制只用硬件ISP,不可取消。 \~english When both bDeviceIsp and bForceUseDeviceIsp are TRUE, this means that only the hardware ISP is forced and cannot be cancelled.
|
||||
BOOL bZoomHD; ///< \~chinese 相机硬件是否支持图像缩放输出(只能是缩小)。 \~english Whether the camera hardware supports image scaling output (can only be reduced).
|
||||
} tSdkIspCapacity;
|
||||
|
||||
/// \~chinese 定义整合的设备描述信息,这些信息可以用于动态构建UI
|
||||
/// \note 调用@link #CameraGetCapability @endlink获取本结构
|
||||
/// \~english Define integrated device description information that can be used to dynamically build UI
|
||||
/// \note call @link #CameraGetCapability @endlink to get this structure
|
||||
typedef struct
|
||||
{
|
||||
|
||||
tSdkTrigger *pTriggerDesc; ///< \~chinese 触发模式 \~english trigger mode
|
||||
INT iTriggerDesc; ///< \~chinese 触发模式的个数,即pTriggerDesc数组的大小 \~english The number of trigger modes, that is, the size of the pTriggerDesc array
|
||||
|
||||
tSdkImageResolution *pImageSizeDesc;///< \~chinese 预设分辨率 \~english Preset resolution
|
||||
INT iImageSizeDesc; ///< \~chinese 预设分辨率的个数,即pImageSizeDesc数组的大小 \~english The number of preset resolutions, that is, the size of the pImageSizeDesc array
|
||||
|
||||
tSdkColorTemperatureDes *pClrTempDesc;///< \~chinese 预设色温,用于白平衡 \~english Preset color temperature for white balance
|
||||
INT iClrTempDesc; ///< \~chinese 预设色温个数 \~english The number of preset color temperatures
|
||||
|
||||
tSdkMediaType *pMediaTypeDesc; ///< \~chinese 相机输出图像格式 \~english Camera output image format
|
||||
INT iMediaTypdeDesc; ///< \~chinese 相机输出图像格式的种类个数,即pMediaTypeDesc数组的大小。 \~english The number of types of camera output image formats, that is, the size of the pMediaTypeDesc array.
|
||||
|
||||
tSdkFrameSpeed *pFrameSpeedDesc; ///< \~chinese 可调节帧速类型,对应界面上普通 高速 和超级三种速度设置 \~english Adjustable frame rate type, normal high speed and super three speed settings on the corresponding interface
|
||||
INT iFrameSpeedDesc; ///< \~chinese 可调节帧速类型的个数,即pFrameSpeedDesc数组的大小。 \~english The number of frame rate types that can be adjusted, that is, the size of the pFrameSpeedDesc array.
|
||||
|
||||
tSdkPackLength *pPackLenDesc; ///< \~chinese 传输包长度,一般用于网络设备 \~english Transmission packet length, generally used for network equipment
|
||||
INT iPackLenDesc; ///< \~chinese 可供选择的传输分包长度的个数,即pPackLenDesc数组的大小。 \~english The number of transmission packetization lengths available for selection, which is the size of the pPackLenDesc array.
|
||||
|
||||
INT iOutputIoCounts; ///< \~chinese 可编程输出IO的个数 \~english Number of programmable output IOs
|
||||
INT iInputIoCounts; ///< \~chinese 可编程输入IO的个数 \~english Number of programmable input IOs
|
||||
|
||||
tSdkPresetLut *pPresetLutDesc; ///< \~chinese 相机预设的LUT表 \~english Camera preset LUT table
|
||||
INT iPresetLut; ///< \~chinese 相机预设的LUT表的个数,即pPresetLutDesc数组的大小 \~english The number of LUT tables preset by the camera, that is, the size of the pPresetLutDesc array
|
||||
|
||||
INT iUserDataMaxLen; ///< \~chinese 指示该相机中用于保存用户数据区的最大长度。为0表示无。 \~english Indicates the maximum length in the camera used to save the user data area. 0 means no.
|
||||
BOOL bParamInDevice; ///< \~chinese 指示该设备是否支持从设备中读写参数组。1为支持,0不支持。 \~english Indicates whether the device supports reading and writing parameter groups from the device. 1 is supported, 0 is not supported.
|
||||
|
||||
tSdkAeAlgorithm *pAeAlmSwDesc; ///< \~chinese 软件自动曝光算法描述 \~english Software auto exposure algorithm description
|
||||
int iAeAlmSwDesc; ///< \~chinese 软件自动曝光算法个数 \~english Software automatic exposure algorithm number
|
||||
|
||||
tSdkAeAlgorithm *pAeAlmHdDesc; ///< \~chinese 硬件自动曝光算法描述,为NULL表示不支持硬件自动曝光 \~english Hardware auto exposure algorithm description, NULL means hardware auto exposure is not supported
|
||||
int iAeAlmHdDesc; ///< \~chinese 硬件自动曝光算法个数,为0表示不支持硬件自动曝光 \~english Number of hardware auto exposure algorithms, 0 means hardware auto exposure is not supported
|
||||
|
||||
tSdkBayerDecodeAlgorithm *pBayerDecAlmSwDesc; ///< \~chinese 软件Bayer转换为RGB数据的算法描述 \~english Algorithm Description of Software Bayer Conversion to RGB Data
|
||||
int iBayerDecAlmSwDesc; ///< \~chinese 软件Bayer转换为RGB数据的算法个数 \~english The number of algorithms that Bayer converts to RGB data
|
||||
|
||||
tSdkBayerDecodeAlgorithm *pBayerDecAlmHdDesc; ///< \~chinese 硬件Bayer转换为RGB数据的算法描述,为NULL表示不支持 \~english Hardware Bayer converts to RGB data algorithm description, is not supported for NULL representation
|
||||
int iBayerDecAlmHdDesc; ///< \~chinese 硬件Bayer转换为RGB数据的算法个数,为0表示不支持 \~english The number of algorithms that hardware Bayer converts to RGB data, 0 means not supported
|
||||
|
||||
/* 图像参数的调节范围定义,用于动态构建UI*/
|
||||
tSdkExpose sExposeDesc; ///< \~chinese 曝光的范围值 \~english Exposure range value
|
||||
tSdkResolutionRange sResolutionRange; ///< \~chinese 分辨率范围描述 \~english Resolution range description
|
||||
tRgbGainRange sRgbGainRange; ///< \~chinese 图像数字增益范围描述 \~english Image digital gain range description
|
||||
tSaturationRange sSaturationRange; ///< \~chinese 饱和度范围描述 \~english Saturation range description
|
||||
tGammaRange sGammaRange; ///< \~chinese 伽马范围描述 \~english Gamma range description
|
||||
tContrastRange sContrastRange; ///< \~chinese 对比度范围描述 \~english Contrast range description
|
||||
tSharpnessRange sSharpnessRange; ///< \~chinese 锐化范围描述 \~english Sharpening range description
|
||||
tSdkIspCapacity sIspCapacity; ///< \~chinese ISP能力描述 \~english ISP capability description
|
||||
|
||||
|
||||
} tSdkCameraCapbility;
|
||||
|
||||
|
||||
/// \~chinese 图像帧头信息
|
||||
/// \~english Image frame header information
|
||||
typedef struct
|
||||
{
|
||||
UINT uiMediaType; ///< \~chinese 图像格式 \~english Image Format
|
||||
UINT uBytes; ///< \~chinese 图像数据字节数 \~english Total bytes
|
||||
INT iWidth; ///< \~chinese 图像的宽度,调用图像处理函数后,该变量可能被动态修改,来指示处理后的图像尺寸 \~english The width of the image, after calling the image processing function, the variable may be dynamically modified to indicate the image size after processing
|
||||
INT iHeight; ///< \~chinese 图像的高度,调用图像处理函数后,该变量可能被动态修改,来指示处理后的图像尺寸 \~english The height of the image, after calling the image processing function, the variable may be dynamically modified to indicate the image size after processing
|
||||
INT iWidthZoomSw; ///< \~chinese 软件缩放的宽度,不需要进行软件裁剪的图像,此变量设置为0. \~english The width of the software zoom, which does not require software cropping. This variable is set to 0.
|
||||
INT iHeightZoomSw; ///< \~chinese 软件缩放的高度,不需要进行软件裁剪的图像,此变量设置为0. \~english Software zoom height, no software cropped image is required. This variable is set to 0.
|
||||
BOOL bIsTrigger; ///< \~chinese 指示是否为触发帧 \~english is trigger
|
||||
UINT uiTimeStamp; ///< \~chinese 该帧的采集时间,单位0.1毫秒 \~english The frame acquisition time, in units of 0.1 milliseconds
|
||||
UINT uiExpTime; ///< \~chinese 当前图像的曝光值,单位为微秒us \~english Exposure of the current image in microseconds us
|
||||
float fAnalogGain; ///< \~chinese 当前图像的模拟增益倍数 \~english The current image's analog gain multiplier
|
||||
INT iGamma; ///< \~chinese 该帧图像的伽马设定值,仅当LUT模式为动态参数生成时有效,其余模式下为-1 \~english The gamma setting value of the frame image is valid only when the LUT mode is a dynamic parameter generation, and is -1 in other modes.
|
||||
INT iContrast; ///< \~chinese 该帧图像的对比度设定值,仅当LUT模式为动态参数生成时有效,其余模式下为-1 \~english The contrast setting value of the frame image is only valid when the LUT mode is generated by the dynamic parameter, and is -1 in other modes.
|
||||
INT iSaturation; ///< \~chinese 该帧图像的饱和度设定值,对于黑白相机无意义,为0 \~english The saturation value of the frame image, which is meaningless for a black and white camera, is 0
|
||||
float fRgain; ///< \~chinese 该帧图像处理的红色数字增益倍数,对于黑白相机无意义,为1 \~english The red digital gain multiple of this frame image processing is meaningless for a black and white camera and is 1
|
||||
float fGgain; ///< \~chinese 该帧图像处理的绿色数字增益倍数,对于黑白相机无意义,为1 \~english The green digital gain multiplier for this frame image processing, meaning no significance for black and white cameras, is 1
|
||||
float fBgain; ///< \~chinese 该帧图像处理的蓝色数字增益倍数,对于黑白相机无意义,为1 \~english The blue digital gain multiplier for this frame image processing, meaning no significance for black and white cameras, is 1
|
||||
}tSdkFrameHead;
|
||||
|
||||
/// \~chinese 图像帧描述
|
||||
/// \~english Image frame description
|
||||
typedef struct sCameraFrame
|
||||
{
|
||||
tSdkFrameHead head; ///< \~chinese 帧头 \~english Frame Head
|
||||
BYTE * pBuffer; ///< \~chinese 数据区 \~english Image Data
|
||||
}tSdkFrame;
|
||||
|
||||
/// @ingroup API_GRAB_CB
|
||||
/// \~chinese 图像捕获的回调函数定义
|
||||
/// \~english Callback function definition for image capture
|
||||
typedef void (WINAPI* CAMERA_SNAP_PROC)(CameraHandle hCamera, BYTE *pFrameBuffer, tSdkFrameHead* pFrameHead,PVOID pContext);
|
||||
|
||||
/// @ingroup API_SETTINGS_PAGE
|
||||
/// \~chinese 相机配置页面的消息回调函数定义
|
||||
/// \~english camera configuration page message callback function definition
|
||||
typedef void (WINAPI* CAMERA_PAGE_MSG_PROC)(CameraHandle hCamera,UINT MSG,UINT uParam,PVOID pContext);
|
||||
|
||||
/// @ingroup API_RECONNECT
|
||||
/// \~chinese 相机连接状态回调
|
||||
/// \param [in] hCamera 相机句柄
|
||||
/// \param [in] MSG 消息,0: 相机连接断开 1: 相机连接恢复
|
||||
/// \param [in] uParam 附加信息
|
||||
/// \param [in] pContext 用户数据
|
||||
/// \return 无
|
||||
/// \note USB相机uParam取值:
|
||||
/// \note 未定义
|
||||
/// \note 网口相机uParam取值:
|
||||
/// \note 当MSG=0时:未定义
|
||||
/// \note 当MSG=1时:
|
||||
/// \note 0:上次掉线原因,网络通讯失败
|
||||
/// \note 1:上次掉线原因,相机掉电
|
||||
/// \~english Camera connection status callback
|
||||
/// \param [in] hCamera Camera handle
|
||||
/// \param [in] MSG message, 0: Camera disconnected 1: Camera connection restored
|
||||
/// \param [in] uParam Additional Information
|
||||
/// \param [in] pContext user data
|
||||
/// \return None
|
||||
/// \note USB camera uParam value:
|
||||
/// \note Undefined
|
||||
/// \note network camera uParam value:
|
||||
/// \note When MSG=0: Undefined
|
||||
/// \note When MSG=1:
|
||||
/// \note 0: The last dropped reason, network communication failed
|
||||
/// \note 1: The last dropped reason, the camera lost power
|
||||
typedef void (WINAPI* CAMERA_CONNECTION_STATUS_CALLBACK)(CameraHandle hCamera,UINT MSG,UINT uParam,PVOID pContext);
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////
|
||||
// Grabber 相关
|
||||
|
||||
/// \~chinese Grabber统计信息
|
||||
/// \~english Grabber statistics
|
||||
typedef struct
|
||||
{
|
||||
int Width; ///< \~chinese 帧宽度 \~english Frame image width
|
||||
int Height; ///< \~chinese 帧高度 \~english Frame image height
|
||||
int Disp; ///< \~chinese 显示帧数量 \~english Display frame number
|
||||
int Capture; ///< \~chinese 采集的有效帧的数量 \~english The number of valid frames collected
|
||||
int Lost; ///< \~chinese 丢帧的数量 \~english The number of dropped frames
|
||||
int Error; ///< \~chinese 错帧的数量 \~english The number of error frames
|
||||
float DispFps; ///< \~chinese 显示帧率 \~english Display frame rate
|
||||
float CapFps; ///< \~chinese 捕获帧率 \~english Capture frame rate
|
||||
}tSdkGrabberStat;
|
||||
|
||||
/// @ingroup GRABBER_CB
|
||||
/// \~chinese 图像捕获的回调函数定义
|
||||
/// \~english Callback function definition for image capture
|
||||
typedef void (__stdcall *pfnCameraGrabberFrameCallback)(
|
||||
void* Grabber,
|
||||
BYTE *pFrameBuffer,
|
||||
tSdkFrameHead* pFrameHead,
|
||||
void* Context);
|
||||
|
||||
/// @ingroup GRABBER_CB
|
||||
/// \~chinese 帧监听函数定义
|
||||
/// \param [in] Grabber
|
||||
/// \param [in] Phase 图像处理阶段
|
||||
/// \param [in] pFrameBuffer 帧数据
|
||||
/// \param [in] pFrameHead 帧头
|
||||
/// \param [in] Context 用户数据
|
||||
/// \return 0:Grabber将会丢弃此帧并结束针对此帧的所有后续处理阶段 1:继续下一阶段处理
|
||||
/// \note 每当Grabber捕获到一帧图像时,会分3个阶段来依次调用FrameListener
|
||||
/// \note 阶段0: RAW数据处理,pFrameBuffer=Raw数据
|
||||
/// \note 阶段1: 截图前处理,pFrameBuffer=RGB数据
|
||||
/// \note 阶段2: 显示前处理,pFrameBuffer=RGB数据
|
||||
/// \note 特别的,当相机掉线后此回调也会被调用,此时Phase=-1,pFrameBuffer=NULL,pFrameHead=NULL。
|
||||
/// \~english Frame listening function definition
|
||||
/// \param [in] Grabber
|
||||
/// \param [in] Phase image processing phase
|
||||
/// \param [in] pFrameBuffer frame data
|
||||
/// \param [in] pFrameHead Frame Header
|
||||
/// \param [in] Context user data
|
||||
/// \return 0: Grabber will discard this frame and end all subsequent processing stages for this frame 1: Continue to the next stage of processing
|
||||
/// \note Whenever Grabber captures a frame of image, it will call FrameListener in turn in 3 stages.
|
||||
/// \note Phase 0: RAW data processing, pFrameBuffer= Raw data
|
||||
/// \note Phase 1: Screenshot pre-processing, pFrameBuffer=RGB data
|
||||
/// \note Phase 2: Display preprocessing, pFrameBuffer=RGB data
|
||||
/// \note In particular, this callback will be called when the camera is disconnected. At this time, Phase=-1, pFrameBuffer=NULL, and pFrameHead=NULL.
|
||||
typedef int (__stdcall *pfnCameraGrabberFrameListener)(
|
||||
void* Grabber,
|
||||
int Phase,
|
||||
BYTE *pFrameBuffer,
|
||||
tSdkFrameHead* pFrameHead,
|
||||
void* Context);
|
||||
|
||||
/// @ingroup GRABBER_SNAPSHOT
|
||||
/// \~chinese 异步抓图的回调函数定义
|
||||
/// \warning Image需要调用 @link CameraImage_Destroy @endlink 释放
|
||||
/// \~english Asynchronous snapshot callback function definition
|
||||
/// \warning Image needs to call @link CameraImage_Destroy @endlink to release
|
||||
typedef void (__stdcall *pfnCameraGrabberSaveImageComplete)(
|
||||
void* Grabber,
|
||||
void* Image, // 需要调用CameraImage_Destroy释放
|
||||
CameraSdkStatus Status,
|
||||
void* Context
|
||||
);
|
||||
|
||||
|
||||
/// @ingroup MV_MACRO_TYPE
|
||||
/// @{
|
||||
//----------------------------IMAGE FORMAT DEFINE------------------------------------
|
||||
//----------------------------图像格式定义-------------------------------------------
|
||||
#define CAMERA_MEDIA_TYPE_MONO 0x01000000
|
||||
#define CAMERA_MEDIA_TYPE_RGB 0x02000000
|
||||
#define CAMERA_MEDIA_TYPE_COLOR 0x02000000
|
||||
#define CAMERA_MEDIA_TYPE_CUSTOM 0x80000000
|
||||
#define CAMERA_MEDIA_TYPE_COLOR_MASK 0xFF000000
|
||||
#define CAMERA_MEDIA_TYPE_OCCUPY1BIT 0x00010000
|
||||
#define CAMERA_MEDIA_TYPE_OCCUPY2BIT 0x00020000
|
||||
#define CAMERA_MEDIA_TYPE_OCCUPY4BIT 0x00040000
|
||||
#define CAMERA_MEDIA_TYPE_OCCUPY8BIT 0x00080000
|
||||
#define CAMERA_MEDIA_TYPE_OCCUPY10BIT 0x000A0000
|
||||
#define CAMERA_MEDIA_TYPE_OCCUPY12BIT 0x000C0000
|
||||
#define CAMERA_MEDIA_TYPE_OCCUPY16BIT 0x00100000
|
||||
#define CAMERA_MEDIA_TYPE_OCCUPY24BIT 0x00180000
|
||||
#define CAMERA_MEDIA_TYPE_OCCUPY32BIT 0x00200000
|
||||
#define CAMERA_MEDIA_TYPE_OCCUPY36BIT 0x00240000
|
||||
#define CAMERA_MEDIA_TYPE_OCCUPY48BIT 0x00300000
|
||||
#define CAMERA_MEDIA_TYPE_OCCUPY64BIT 0x00400000
|
||||
|
||||
#define CAMERA_MEDIA_TYPE_EFFECTIVE_PIXEL_SIZE_MASK 0x00FF0000
|
||||
#define CAMERA_MEDIA_TYPE_EFFECTIVE_PIXEL_SIZE_SHIFT 16
|
||||
|
||||
#define CAMERA_MEDIA_TYPE_PIXEL_SIZE(type) (((type) & CAMERA_MEDIA_TYPE_EFFECTIVE_PIXEL_SIZE_MASK) >> CAMERA_MEDIA_TYPE_EFFECTIVE_PIXEL_SIZE_SHIFT)
|
||||
|
||||
|
||||
#define CAMERA_MEDIA_TYPE_ID_MASK 0x0000FFFF
|
||||
#define CAMERA_MEDIA_TYPE_COUNT 0x46
|
||||
|
||||
/*mono*/
|
||||
#define CAMERA_MEDIA_TYPE_MONO1P (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY1BIT | 0x0037)
|
||||
#define CAMERA_MEDIA_TYPE_MONO2P (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY2BIT | 0x0038)
|
||||
#define CAMERA_MEDIA_TYPE_MONO4P (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY4BIT | 0x0039)
|
||||
#define CAMERA_MEDIA_TYPE_MONO8 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x0001)
|
||||
#define CAMERA_MEDIA_TYPE_MONO8S (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x0002)
|
||||
#define CAMERA_MEDIA_TYPE_MONO10 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0003)
|
||||
#define CAMERA_MEDIA_TYPE_MONO10_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0004)
|
||||
#define CAMERA_MEDIA_TYPE_MONO12 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0005)
|
||||
#define CAMERA_MEDIA_TYPE_MONO12_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0006)
|
||||
#define CAMERA_MEDIA_TYPE_MONO14 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0025)
|
||||
#define CAMERA_MEDIA_TYPE_MONO16 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0007)
|
||||
|
||||
/*Bayer */
|
||||
#define CAMERA_MEDIA_TYPE_BAYGR8 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x0008)
|
||||
#define CAMERA_MEDIA_TYPE_BAYRG8 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x0009)
|
||||
#define CAMERA_MEDIA_TYPE_BAYGB8 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x000A)
|
||||
#define CAMERA_MEDIA_TYPE_BAYBG8 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x000B)
|
||||
|
||||
#define CAMERA_MEDIA_TYPE_BAYGR10_MIPI (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY10BIT | 0x0026)
|
||||
#define CAMERA_MEDIA_TYPE_BAYRG10_MIPI (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY10BIT | 0x0027)
|
||||
#define CAMERA_MEDIA_TYPE_BAYGB10_MIPI (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY10BIT | 0x0028)
|
||||
#define CAMERA_MEDIA_TYPE_BAYBG10_MIPI (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY10BIT | 0x0029)
|
||||
|
||||
|
||||
#define CAMERA_MEDIA_TYPE_BAYGR10 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x000C)
|
||||
#define CAMERA_MEDIA_TYPE_BAYRG10 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x000D)
|
||||
#define CAMERA_MEDIA_TYPE_BAYGB10 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x000E)
|
||||
#define CAMERA_MEDIA_TYPE_BAYBG10 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x000F)
|
||||
|
||||
#define CAMERA_MEDIA_TYPE_BAYGR12 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0010)
|
||||
#define CAMERA_MEDIA_TYPE_BAYRG12 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0011)
|
||||
#define CAMERA_MEDIA_TYPE_BAYGB12 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0012)
|
||||
#define CAMERA_MEDIA_TYPE_BAYBG12 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0013)
|
||||
|
||||
|
||||
#define CAMERA_MEDIA_TYPE_BAYGR10_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0026)
|
||||
#define CAMERA_MEDIA_TYPE_BAYRG10_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0027)
|
||||
#define CAMERA_MEDIA_TYPE_BAYGB10_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0028)
|
||||
#define CAMERA_MEDIA_TYPE_BAYBG10_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0029)
|
||||
|
||||
#define CAMERA_MEDIA_TYPE_BAYGR12_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x002A)
|
||||
#define CAMERA_MEDIA_TYPE_BAYRG12_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x002B)
|
||||
#define CAMERA_MEDIA_TYPE_BAYGB12_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x002C)
|
||||
#define CAMERA_MEDIA_TYPE_BAYBG12_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x002D)
|
||||
|
||||
#define CAMERA_MEDIA_TYPE_BAYGR16 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x002E)
|
||||
#define CAMERA_MEDIA_TYPE_BAYRG16 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x002F)
|
||||
#define CAMERA_MEDIA_TYPE_BAYGB16 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0030)
|
||||
#define CAMERA_MEDIA_TYPE_BAYBG16 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0031)
|
||||
|
||||
/*RGB */
|
||||
#define CAMERA_MEDIA_TYPE_RGB8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x0014)
|
||||
#define CAMERA_MEDIA_TYPE_BGR8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x0015)
|
||||
#define CAMERA_MEDIA_TYPE_RGBA8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY32BIT | 0x0016)
|
||||
#define CAMERA_MEDIA_TYPE_BGRA8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY32BIT | 0x0017)
|
||||
#define CAMERA_MEDIA_TYPE_RGB10 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0018)
|
||||
#define CAMERA_MEDIA_TYPE_BGR10 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0019)
|
||||
#define CAMERA_MEDIA_TYPE_RGB12 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x001A)
|
||||
#define CAMERA_MEDIA_TYPE_BGR12 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x001B)
|
||||
#define CAMERA_MEDIA_TYPE_RGB16 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0033)
|
||||
#define CAMERA_MEDIA_TYPE_BGR16 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x004B)
|
||||
#define CAMERA_MEDIA_TYPE_RGBA16 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY64BIT | 0x0064)
|
||||
#define CAMERA_MEDIA_TYPE_BGRA16 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY64BIT | 0x0051)
|
||||
#define CAMERA_MEDIA_TYPE_RGB10V1_PACKED (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY32BIT | 0x001C)
|
||||
#define CAMERA_MEDIA_TYPE_RGB10P32 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY32BIT | 0x001D)
|
||||
#define CAMERA_MEDIA_TYPE_RGB12V1_PACKED (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY36BIT | 0X0034)
|
||||
#define CAMERA_MEDIA_TYPE_RGB565P (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0035)
|
||||
#define CAMERA_MEDIA_TYPE_BGR565P (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0X0036)
|
||||
|
||||
/*YUV and YCbCr*/
|
||||
#define CAMERA_MEDIA_TYPE_YUV411_8_UYYVYY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x001E)
|
||||
#define CAMERA_MEDIA_TYPE_YUV422_8_UYVY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x001F)
|
||||
#define CAMERA_MEDIA_TYPE_YUV422_8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0032)
|
||||
#define CAMERA_MEDIA_TYPE_YUV8_UYV (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x0020)
|
||||
#define CAMERA_MEDIA_TYPE_YCBCR8_CBYCR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x003A)
|
||||
//CAMERA_MEDIA_TYPE_YCBCR422_8 : YYYYCbCrCbCr
|
||||
#define CAMERA_MEDIA_TYPE_YCBCR422_8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x003B)
|
||||
#define CAMERA_MEDIA_TYPE_YCBCR422_8_CBYCRY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0043)
|
||||
#define CAMERA_MEDIA_TYPE_YCBCR411_8_CBYYCRYY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x003C)
|
||||
#define CAMERA_MEDIA_TYPE_YCBCR601_8_CBYCR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x003D)
|
||||
#define CAMERA_MEDIA_TYPE_YCBCR601_422_8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x003E)
|
||||
#define CAMERA_MEDIA_TYPE_YCBCR601_422_8_CBYCRY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0044)
|
||||
#define CAMERA_MEDIA_TYPE_YCBCR601_411_8_CBYYCRYY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x003F)
|
||||
#define CAMERA_MEDIA_TYPE_YCBCR709_8_CBYCR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x0040)
|
||||
#define CAMERA_MEDIA_TYPE_YCBCR709_422_8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0041)
|
||||
#define CAMERA_MEDIA_TYPE_YCBCR709_422_8_CBYCRY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0045)
|
||||
#define CAMERA_MEDIA_TYPE_YCBCR709_411_8_CBYYCRYY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0042)
|
||||
|
||||
/*RGB Planar */
|
||||
#define CAMERA_MEDIA_TYPE_RGB8_PLANAR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x0021)
|
||||
#define CAMERA_MEDIA_TYPE_RGB10_PLANAR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0022)
|
||||
#define CAMERA_MEDIA_TYPE_RGB12_PLANAR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0023)
|
||||
#define CAMERA_MEDIA_TYPE_RGB16_PLANAR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0024)
|
||||
|
||||
/*MindVision 12bit packed bayer*/
|
||||
#define CAMERA_MEDIA_TYPE_BAYGR12_PACKED_MV (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0060)
|
||||
#define CAMERA_MEDIA_TYPE_BAYRG12_PACKED_MV (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0061)
|
||||
#define CAMERA_MEDIA_TYPE_BAYGB12_PACKED_MV (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0062)
|
||||
#define CAMERA_MEDIA_TYPE_BAYBG12_PACKED_MV (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0063)
|
||||
|
||||
/*MindVision 12bit packed monochome*/
|
||||
#define CAMERA_MEDIA_TYPE_MONO12_PACKED_MV (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0064)
|
||||
/// @}
|
||||
|
||||
#endif
|
||||
333
others/include/camera/CameraGrabber.h
Normal file
333
others/include/camera/CameraGrabber.h
Normal file
@@ -0,0 +1,333 @@
|
||||
#ifndef _MV_CAMERA_GRABBER_H_
|
||||
#define _MV_CAMERA_GRABBER_H_
|
||||
|
||||
#include "CameraDefine.h"
|
||||
#include "CameraStatus.h"
|
||||
|
||||
|
||||
/// @ingroup GRABBER_CREATE
|
||||
/// \~chinese
|
||||
/// \brief <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>б<EFBFBD><D0B1><EFBFBD><EFBFBD>û<EFBFBD>ѡ<EFBFBD><D1A1>Ҫ<EFBFBD><EFBFBD><F2BFAAB5><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \param [out] Grabber <20><><EFBFBD><EFBFBD><EFBFBD>´<EFBFBD><C2B4><EFBFBD><EFBFBD>IJɼ<C4B2><C9BC><EFBFBD>
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \note <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ڲ<EFBFBD>ʹ<EFBFBD><CAB9><EFBFBD><EFBFBD> @link CameraInit @endlink <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>˿<EFBFBD><CBBF><EFBFBD>ʹ<EFBFBD><CAB9> @link CameraGrabber_GetCameraHandle @endlink <20><>ȡ<EFBFBD><C8A1><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʹ<EFBFBD><CAB9><EFBFBD><EFBFBD><EFBFBD><EFBFBD>SDK API<50><49><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \~english
|
||||
/// \brief Pop-up camera list allows the user to select the camera to open
|
||||
/// \param [out] Grabber returns newly created grabber
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
/// \note This function uses @link CameraInit @endlink internally to open the camera, so you can use @link CameraGrabber_GetCameraHandle @endlink to get the camera handle and use other SDK APIs to operate the camera.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraGrabber_CreateFromDevicePage(
|
||||
void** Grabber
|
||||
);
|
||||
|
||||
/// @ingroup GRABBER_CREATE
|
||||
/// \~chinese
|
||||
/// \brief ʹ<><CAB9><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>б<EFBFBD><D0B1><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Grabber
|
||||
/// \param [out] Grabber <20><><EFBFBD><EFBFBD><EFBFBD>´<EFBFBD><C2B4><EFBFBD><EFBFBD>IJɼ<C4B2><C9BC><EFBFBD>
|
||||
/// \param [in] Index <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \note <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ڲ<EFBFBD>ʹ<EFBFBD><CAB9><EFBFBD><EFBFBD> @link CameraInit @endlink <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>˿<EFBFBD><CBBF><EFBFBD>ʹ<EFBFBD><CAB9> @link CameraGrabber_GetCameraHandle @endlink <20><>ȡ<EFBFBD><C8A1><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʹ<EFBFBD><CAB9><EFBFBD><EFBFBD><EFBFBD><EFBFBD>SDK API<50><49><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \~english
|
||||
/// \brief Creating a Grabber Using a Camera List Index
|
||||
/// \param [out] Grabber returns newly created grabber
|
||||
/// \param [in] Index Camera index
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
/// \note This function uses @link CameraInit @endlink internally to open the camera, so you can use @link CameraGrabber_GetCameraHandle @endlink to get the camera handle and use other SDK APIs to operate the camera.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraGrabber_CreateByIndex(
|
||||
void** Grabber,
|
||||
int Index
|
||||
);
|
||||
|
||||
/// @ingroup GRABBER_CREATE
|
||||
/// \~chinese
|
||||
/// \brief ʹ<><CAB9><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ƴ<EFBFBD><C6B4><EFBFBD>Grabber
|
||||
/// \param [out] Grabber <20><><EFBFBD><EFBFBD><EFBFBD>´<EFBFBD><C2B4><EFBFBD><EFBFBD>IJɼ<C4B2><C9BC><EFBFBD>
|
||||
/// \param [in] Name <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ơ<EFBFBD>@link #tSdkCameraDevInfo.acFriendlyName @endlink
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \note <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ڲ<EFBFBD>ʹ<EFBFBD><CAB9><EFBFBD><EFBFBD> @link CameraInit @endlink <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>˿<EFBFBD><CBBF><EFBFBD>ʹ<EFBFBD><CAB9> @link CameraGrabber_GetCameraHandle @endlink <20><>ȡ<EFBFBD><C8A1><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʹ<EFBFBD><CAB9><EFBFBD><EFBFBD><EFBFBD><EFBFBD>SDK API<50><49><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \~english
|
||||
/// \brief Create a Grabber with a Camera Name
|
||||
/// \param [out] Grabber returns newly created grabber
|
||||
/// \param [in] Name Camera name.@link #tSdkCameraDevInfo.acFriendlyName @endlink
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
/// \note This function uses @link CameraInit @endlink internally to open the camera, so you can use @link CameraGrabber_GetCameraHandle @endlink to get the camera handle and use other SDK APIs to operate the camera.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraGrabber_CreateByName(
|
||||
void** Grabber,
|
||||
char* Name
|
||||
);
|
||||
|
||||
/// @ingroup GRABBER_CREATE
|
||||
/// \~chinese
|
||||
/// \brief <20><><EFBFBD>豸<EFBFBD><E8B1B8>Ϣ<EFBFBD><CFA2><EFBFBD><EFBFBD>Grabber
|
||||
/// \param [out] Grabber <20><><EFBFBD><EFBFBD><EFBFBD>´<EFBFBD><C2B4><EFBFBD><EFBFBD>IJɼ<C4B2><C9BC><EFBFBD>
|
||||
/// \param [in] pDevInfo <20>豸<EFBFBD><E8B1B8>Ϣ<EFBFBD><CFA2>@link #CameraEnumerateDevice @endlink
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \note <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ڲ<EFBFBD>ʹ<EFBFBD><CAB9><EFBFBD><EFBFBD> @link CameraInit @endlink <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>˿<EFBFBD><CBBF><EFBFBD>ʹ<EFBFBD><CAB9> @link CameraGrabber_GetCameraHandle @endlink <20><>ȡ<EFBFBD><C8A1><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʹ<EFBFBD><CAB9><EFBFBD><EFBFBD><EFBFBD><EFBFBD>SDK API<50><49><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \~english
|
||||
/// \brief Create Grabber from device info
|
||||
/// \param [out] Grabber returns newly created grabber
|
||||
/// \param [in] pDevInfo device information. @link #CameraEnumerateDevice @endlink
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
/// \note This function uses @link CameraInit @endlink internally to open the camera, so you can use @link CameraGrabber_GetCameraHandle @endlink to get the camera handle and use other SDK APIs to operate the camera.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraGrabber_Create(
|
||||
void** Grabber,
|
||||
tSdkCameraDevInfo* pDevInfo
|
||||
);
|
||||
|
||||
/// @ingroup GRABBER_DESTROY
|
||||
/// \~chinese
|
||||
/// \brief <20><><EFBFBD><EFBFBD>Grabber
|
||||
/// \param [in] Grabber <20>ɼ<EFBFBD><C9BC><EFBFBD>
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Destroy Grabber
|
||||
/// \param [in] Grabber
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraGrabber_Destroy(
|
||||
void* Grabber
|
||||
);
|
||||
|
||||
/// @ingroup GRABBER_CTRL
|
||||
/// \~chinese
|
||||
/// \brief <20><><EFBFBD><EFBFBD>Ԥ<EFBFBD><D4A4><EFBFBD><EFBFBD>Ƶ<EFBFBD><C6B5><EFBFBD><EFBFBD>ʾ<EFBFBD><CABE><EFBFBD><EFBFBD>
|
||||
/// \param [in] Grabber <20>ɼ<EFBFBD><C9BC><EFBFBD>
|
||||
/// \param [in] hWnd <20><>ʾ<EFBFBD><CABE><EFBFBD>ڵĴ<DAB5><C4B4>ھ<EFBFBD><DABE><EFBFBD>
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Set the preview video display window
|
||||
/// \param [in] Grabber
|
||||
/// \param [in] hWnd window handle of the display window
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraGrabber_SetHWnd(
|
||||
void* Grabber,
|
||||
HWND hWnd
|
||||
);
|
||||
|
||||
/// @ingroup GRABBER_CTRL
|
||||
/// \~chinese
|
||||
/// \brief <20><><EFBFBD><EFBFBD>Grabberȡͼʱʹ<CAB1>õ<EFBFBD><C3B5><EFBFBD><EFBFBD>ȼ<EFBFBD>
|
||||
/// \param [in] Grabber <20>ɼ<EFBFBD><C9BC><EFBFBD>
|
||||
/// \param [in] Priority ȡͼ<C8A1><CDBC><EFBFBD>ȼ<EFBFBD> <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD>@link #emCameraGetImagePriority @endlink
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Sets the priority used by Grabber when fetching graphs
|
||||
/// \param [in] Grabber
|
||||
/// \param [in] Priority GetImageBuffer priority, For details see: @link #emCameraGetImagePriority @endlink
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraGrabber_SetPriority(
|
||||
void* Grabber,
|
||||
UINT Priority
|
||||
);
|
||||
|
||||
/// @ingroup GRABBER_CTRL
|
||||
/// \~chinese
|
||||
/// \brief <20><>ʼ<EFBFBD>ɼ<EFBFBD>
|
||||
/// \param [in] Grabber <20>ɼ<EFBFBD><C9BC><EFBFBD>
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \note Grabber<65><72><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ɼ<EFBFBD>״̬<D7B4><CCAC><EFBFBD>ɼ<EFBFBD><C9BC>ص<EFBFBD><D8B5><EFBFBD>ץͼ<D7A5>ȹ<EFBFBD><C8B9>ܲ<EFBFBD><DCB2><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \~english
|
||||
/// \brief Start Grabber
|
||||
/// \param [in] Grabber
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
/// \note Grabber must enter the acquisition state, grab callbacks, snapshot and other functions in order to function properly
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraGrabber_StartLive(
|
||||
void* Grabber
|
||||
);
|
||||
|
||||
/// @ingroup GRABBER_CTRL
|
||||
/// \~chinese
|
||||
/// \brief ֹͣ<CDA3>ɼ<EFBFBD>
|
||||
/// \param [in] Grabber <20>ɼ<EFBFBD><C9BC><EFBFBD>
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \warning <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ڲ<EFBFBD><DAB2><EFBFBD><EFBFBD>ȴ<EFBFBD><C8B4><EFBFBD><EFBFBD>лص<D0BB><D8B5><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ŷ<EFBFBD><C5B7>ص<EFBFBD><D8B5><EFBFBD><EFBFBD><EFBFBD>,<2C><><EFBFBD><EFBFBD><EFBFBD>ڵȴ<DAB5>ʱ<EFBFBD><CAB1><EFBFBD>ɷ<EFBFBD>windows<77><73>Ϣ<EFBFBD><CFA2>
|
||||
/// \~english
|
||||
/// \brief Stop Grabber
|
||||
/// \param [in] Grabber
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
/// \warning This function will wait for all callbacks to end before returning to the caller,And it will dispatch windows messages while waiting.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraGrabber_StopLive(
|
||||
void* Grabber
|
||||
);
|
||||
|
||||
/// @ingroup GRABBER_SNAPSHOT
|
||||
/// \~chinese
|
||||
/// \brief ͬ<><CDAC>ץͼ
|
||||
/// \param [in] Grabber <20>ɼ<EFBFBD><C9BC><EFBFBD>
|
||||
/// \param [out] Image <20><><EFBFBD><EFBFBD>ץȡ<D7A5><C8A1><EFBFBD><EFBFBD>ͼ<EFBFBD><CDBC> \note <20><>Ҫ<EFBFBD><D2AA><EFBFBD><EFBFBD>@link #CameraImage_Destroy @endlink<6E>ͷ<EFBFBD>
|
||||
/// \param [in] TimeOut <20><>ʱʱ<CAB1>䣨<EFBFBD><E4A3A8><EFBFBD>룩
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Synchronized snapshot
|
||||
/// \param [in] Grabber
|
||||
/// \param [out] Image Returns Captured Image \note Need to Call @link #CameraImage_Destroy @endlink Release
|
||||
/// \param [in] TimeOut Timeout (milliseconds)
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraGrabber_SaveImage(
|
||||
void* Grabber,
|
||||
void** Image,
|
||||
DWORD TimeOut
|
||||
);
|
||||
|
||||
/// @ingroup GRABBER_SNAPSHOT
|
||||
/// \~chinese
|
||||
/// \brief <20>ύһ<E1BDBB><D2BB><EFBFBD>첽<EFBFBD><ECB2BD>ץͼ<D7A5><CDBC><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ύ<EFBFBD>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD>ץͼ<D7A5><CDBC><EFBFBD>ɻ<EFBFBD><C9BB>ص<EFBFBD><D8B5>û<EFBFBD><C3BB><EFBFBD><EFBFBD>õ<EFBFBD><C3B5><EFBFBD><EFBFBD>ɺ<EFBFBD><C9BA><EFBFBD>
|
||||
/// \param [in] Grabber <20>ɼ<EFBFBD><C9BC><EFBFBD>
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \see CameraGrabber_SetSaveImageCompleteCallback
|
||||
/// \~english
|
||||
/// \brief Submit an asynchronous snapshot request, complete the user's completion function after the completion of the submission.
|
||||
/// \param [in] Grabber
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
/// \see CameraGrabber_SetSaveImageCompleteCallback
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraGrabber_SaveImageAsync(
|
||||
void* Grabber
|
||||
);
|
||||
|
||||
/// @ingroup GRABBER_SNAPSHOT
|
||||
/// \~chinese
|
||||
/// \brief <20>ύһ<E1BDBB><D2BB><EFBFBD>첽<EFBFBD><ECB2BD>ץͼ<D7A5><CDBC><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ύ<EFBFBD>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD>ץͼ<D7A5><CDBC><EFBFBD>ɻ<EFBFBD><C9BB>ص<EFBFBD><D8B5>û<EFBFBD><C3BB><EFBFBD><EFBFBD>õ<EFBFBD><C3B5><EFBFBD><EFBFBD>ɺ<EFBFBD><C9BA><EFBFBD>
|
||||
/// \param [in] Grabber <20>ɼ<EFBFBD><C9BC><EFBFBD>
|
||||
/// \param [in] UserData <20>û<EFBFBD><C3BB><EFBFBD><EFBFBD>ݣ<EFBFBD><DDA3><EFBFBD>ʹ<EFBFBD><CAB9> @link CameraImage_GetUserData @endlink <20><>Image<67><65>ȡ<EFBFBD><C8A1>ֵ
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \see CameraGrabber_SetSaveImageCompleteCallback
|
||||
/// \~english
|
||||
/// \brief Submit an asynchronous snapshot request, complete the user's completion function after the completion of the submission.
|
||||
/// \param [in] Grabber
|
||||
/// \param [in] UserData user data, which can be obtained from Image using @link CameraImage_GetUserData @endlink
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
/// \see CameraGrabber_SetSaveImageCompleteCallback
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraGrabber_SaveImageAsyncEx(
|
||||
void* Grabber,
|
||||
void* UserData
|
||||
);
|
||||
|
||||
/// @ingroup GRABBER_SNAPSHOT
|
||||
/// \~chinese
|
||||
/// \brief <20><><EFBFBD><EFBFBD><EFBFBD>첽<EFBFBD><ECB2BD>ʽץͼ<D7A5><CDBC><EFBFBD><EFBFBD><EFBFBD>ɺ<EFBFBD><C9BA><EFBFBD>
|
||||
/// \param [in] Grabber <20>ɼ<EFBFBD><C9BC><EFBFBD>
|
||||
/// \param [in] Callback <20><><EFBFBD>첽ץͼ<D7A5><CDBC><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʱ<EFBFBD><CAB1><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \param [in] Context <20><>Callback<63><6B><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʱ<EFBFBD><CAB1><EFBFBD><EFBFBD>Ϊ<EFBFBD><CEAA><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Callback
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \see CameraGrabber_SaveImageAsync CameraGrabber_SaveImageAsyncEx
|
||||
/// \~english
|
||||
/// \brief Set the completion function of asynchronous mode snapshot
|
||||
/// \param [in] Grabber
|
||||
/// \param [in] Callback Callback is called when the asynchronous snapshot task completes
|
||||
/// \param [in] Context Passed as a parameter when the Callback is invoked
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
/// \see CameraGrabber_SaveImageAsync CameraGrabber_SaveImageAsyncEx
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraGrabber_SetSaveImageCompleteCallback(
|
||||
void* Grabber,
|
||||
pfnCameraGrabberSaveImageComplete Callback,
|
||||
void* Context
|
||||
);
|
||||
|
||||
/// @ingroup GRABBER_CB
|
||||
/// \~chinese
|
||||
/// \brief <20><><EFBFBD><EFBFBD>֡<EFBFBD><D6A1><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \param [in] Grabber <20>ɼ<EFBFBD><C9BC><EFBFBD>
|
||||
/// \param [in] Listener <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \param [in] Context <20><>Listener<65><72><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʱ<EFBFBD><CAB1><EFBFBD><EFBFBD>Ϊ<EFBFBD><CEAA><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Listener
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Set frame listening function
|
||||
/// \param [in] Grabber
|
||||
/// \param [in] Listener listener function
|
||||
/// \param [in] Context Passed as a parameter when the Listener is invoked
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraGrabber_SetFrameListener(
|
||||
void* Grabber,
|
||||
pfnCameraGrabberFrameListener Listener,
|
||||
void* Context
|
||||
);
|
||||
|
||||
/// @ingroup GRABBER_CB
|
||||
/// \~chinese
|
||||
/// \brief <20><><EFBFBD><EFBFBD>RAW<41><57><EFBFBD>ݻص<DDBB><D8B5><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \param [in] Grabber <20>ɼ<EFBFBD><C9BC><EFBFBD>
|
||||
/// \param [in] Callback Raw<61>ص<EFBFBD><D8B5><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \param [in] Context <20><>Callback<63><6B><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʱ<EFBFBD><CAB1><EFBFBD><EFBFBD>Ϊ<EFBFBD><CEAA><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Callback
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Set RAW data callback function
|
||||
/// \param [in] Grabber
|
||||
/// \param [in] Callback Raw data callback function
|
||||
/// \param [in] Context Passed as a parameter when the Callback is invoked
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraGrabber_SetRawCallback(
|
||||
void* Grabber,
|
||||
pfnCameraGrabberFrameCallback Callback,
|
||||
void* Context
|
||||
);
|
||||
|
||||
/// @ingroup GRABBER_CB
|
||||
/// \~chinese
|
||||
/// \brief <20><><EFBFBD><EFBFBD>RGB<47>ص<EFBFBD><D8B5><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \param [in] Grabber <20>ɼ<EFBFBD><C9BC><EFBFBD>
|
||||
/// \param [in] Callback RGB<47>ص<EFBFBD><D8B5><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \param [in] Context <20><>Callback<63><6B><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʱ<EFBFBD><CAB1><EFBFBD><EFBFBD>Ϊ<EFBFBD><CEAA><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Callback
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Set RGB callback function
|
||||
/// \param [in] Grabber
|
||||
/// \param [in] Callback RGB data callback function
|
||||
/// \param [in] Context Passed as a parameter when the Callback is invoked
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraGrabber_SetRGBCallback(
|
||||
void* Grabber,
|
||||
pfnCameraGrabberFrameCallback Callback,
|
||||
void* Context
|
||||
);
|
||||
|
||||
/// @ingroup GRABBER_CTRL
|
||||
/// \~chinese
|
||||
/// \brief <20><>ȡ<EFBFBD><C8A1><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \param [in] Grabber <20>ɼ<EFBFBD><C9BC><EFBFBD>
|
||||
/// \param [out] hCamera <20><><EFBFBD>ص<EFBFBD><D8B5><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Get camera handle
|
||||
/// \param [in] Grabber
|
||||
/// \param [out] hCamera returned camera handle
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraGrabber_GetCameraHandle(
|
||||
void* Grabber,
|
||||
CameraHandle *hCamera
|
||||
);
|
||||
|
||||
/// @ingroup GRABBER_CTRL
|
||||
/// \~chinese
|
||||
/// \brief <20><>ȡ֡ͳ<D6A1><CDB3><EFBFBD><EFBFBD>Ϣ
|
||||
/// \param [in] Grabber <20>ɼ<EFBFBD><C9BC><EFBFBD>
|
||||
/// \param [out] stat <20><><EFBFBD>ص<EFBFBD>ͳ<EFBFBD><CDB3><EFBFBD><EFBFBD>Ϣ
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Get frame statistics
|
||||
/// \param [in] Grabber
|
||||
/// \param [out] stat returned statistics
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraGrabber_GetStat(
|
||||
void* Grabber,
|
||||
tSdkGrabberStat *stat
|
||||
);
|
||||
|
||||
/// @ingroup GRABBER_CTRL
|
||||
/// \~chinese
|
||||
/// \brief <20><>ȡ<EFBFBD><C8A1><EFBFBD><EFBFBD>DevInfo
|
||||
/// \param [in] Grabber <20>ɼ<EFBFBD><C9BC><EFBFBD>
|
||||
/// \param [out] DevInfo <20><><EFBFBD>ص<EFBFBD><D8B5><EFBFBD><EFBFBD><EFBFBD>DevInfo
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Get Camera DevInfo
|
||||
/// \param [in] Grabber
|
||||
/// \param [out] DevInfo Returns Camera DevInfo
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraGrabber_GetCameraDevInfo(
|
||||
void* Grabber,
|
||||
tSdkCameraDevInfo *DevInfo
|
||||
);
|
||||
|
||||
|
||||
|
||||
|
||||
#endif // _MV_CAMERA_GRABBER_H_
|
||||
380
others/include/camera/CameraImage.h
Normal file
380
others/include/camera/CameraImage.h
Normal file
@@ -0,0 +1,380 @@
|
||||
#ifndef _MV_CAMERA_IMAGE_H_
|
||||
#define _MV_CAMERA_IMAGE_H_
|
||||
|
||||
#include "CameraDefine.h"
|
||||
#include "CameraStatus.h"
|
||||
|
||||
|
||||
/// @ingroup MV_IMAGE
|
||||
/// \~chinese
|
||||
/// \brief <20><><EFBFBD><EFBFBD>һ<EFBFBD><D2BB><EFBFBD>µ<EFBFBD>Image
|
||||
/// \param [out] Image <20>´<EFBFBD><C2B4><EFBFBD><EFBFBD><EFBFBD>ͼƬ
|
||||
/// \param [in] pFrameBuffer ֡<><D6A1><EFBFBD><EFBFBD>
|
||||
/// \param [in] pFrameHead ֡ͷ
|
||||
/// \param [in] bCopy TRUE: <20><><EFBFBD>Ƴ<EFBFBD>һ<EFBFBD><D2BB><EFBFBD>µ<EFBFBD>֡<EFBFBD><D6A1><EFBFBD><EFBFBD> FALSE: <20><><EFBFBD><EFBFBD><EFBFBD>ƣ<EFBFBD>ֱ<EFBFBD><D6B1>ʹ<EFBFBD><CAB9>pFrameBufferָ<72><D6B8><EFBFBD>Ļ<EFBFBD><C4BB><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Create a new Image
|
||||
/// \param [out] Image Newly Created Image
|
||||
/// \param [in] pFrameBuffer frame data
|
||||
/// \param [in] pFrameHead Frame Header
|
||||
/// \param [in] bCopy TRUE: Copy a new frame data FALSE: Do not copy, directly use the buffer pointed to by pFrameBuffer
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraImage_Create(
|
||||
void** Image,
|
||||
BYTE *pFrameBuffer,
|
||||
tSdkFrameHead* pFrameHead,
|
||||
BOOL bCopy
|
||||
);
|
||||
|
||||
/// @ingroup MV_IMAGE
|
||||
/// \~chinese
|
||||
/// \brief <20><><EFBFBD><EFBFBD>һ<EFBFBD><D2BB><EFBFBD>յ<EFBFBD>Image
|
||||
/// \param [out] Image <20>´<EFBFBD><C2B4><EFBFBD><EFBFBD><EFBFBD>ͼƬ
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Create an empty Image
|
||||
/// \param [out] Image Newly Created Image
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraImage_CreateEmpty(
|
||||
void** Image
|
||||
);
|
||||
|
||||
/// @ingroup MV_IMAGE
|
||||
/// \~chinese
|
||||
/// \brief <20><><EFBFBD><EFBFBD>Image
|
||||
/// \param [in] Image
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Destroy Image
|
||||
/// \param [in] Image
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraImage_Destroy(
|
||||
void* Image
|
||||
);
|
||||
|
||||
/// @ingroup MV_IMAGE
|
||||
/// \~chinese
|
||||
/// \brief <20><>Image<67><65>ȡ֡<C8A1><D6A1><EFBFBD>ݺ<EFBFBD>֡ͷ
|
||||
/// \param [in] Image
|
||||
/// \param [out] DataBuffer ֡<><D6A1><EFBFBD><EFBFBD>
|
||||
/// \param [out] Head ֡ͷ
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Get frame data and frame header from Image
|
||||
/// \param [in] Image
|
||||
/// \param [out] DataBuffer Frame Data
|
||||
/// \param [out] Head header
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraImage_GetData(
|
||||
void* Image,
|
||||
BYTE** DataBuffer,
|
||||
tSdkFrameHead** Head
|
||||
);
|
||||
|
||||
/// @ingroup MV_IMAGE
|
||||
/// \~chinese
|
||||
/// \brief <20><>ȡImage<67><65><EFBFBD>û<EFBFBD><C3BB>Զ<EFBFBD><D4B6><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \param [in] Image
|
||||
/// \param [out] UserData <20><><EFBFBD><EFBFBD><EFBFBD>û<EFBFBD><C3BB>Զ<EFBFBD><D4B6><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Get User's Custom Data of Image
|
||||
/// \param [in] Image
|
||||
/// \param [out] UserData returns user-defined data
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraImage_GetUserData(
|
||||
void* Image,
|
||||
void** UserData
|
||||
);
|
||||
|
||||
/// @ingroup MV_IMAGE
|
||||
/// \~chinese
|
||||
/// \brief <20><><EFBFBD><EFBFBD>Image<67><65><EFBFBD>û<EFBFBD><C3BB>Զ<EFBFBD><D4B6><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \param [in] Image
|
||||
/// \param [in] UserData <20>û<EFBFBD><C3BB>Զ<EFBFBD><D4B6><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Set user-defined data for Image
|
||||
/// \param [in] Image
|
||||
/// \param [in] UserData User-defined data
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraImage_SetUserData(
|
||||
void* Image,
|
||||
void* UserData
|
||||
);
|
||||
|
||||
/// @ingroup MV_IMAGE
|
||||
/// \~chinese
|
||||
/// \brief <20>ж<EFBFBD>һ<EFBFBD><D2BB>Image<67>Ƿ<EFBFBD>Ϊ<EFBFBD><CEAA>
|
||||
/// \param [in] Image
|
||||
/// \param [out] IsEmpty Ϊ<>շ<EFBFBD><D5B7><EFBFBD>:TRUE(1) <20><><EFBFBD><EFBFBD>:FALSE(0)
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Determine if an Image is empty
|
||||
/// \param [in] Image
|
||||
/// \param [out] IsEmpty Empty Returns: TRUE(1) Otherwise returns: FALSE(0)
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraImage_IsEmpty(
|
||||
void* Image,
|
||||
BOOL* IsEmpty
|
||||
);
|
||||
|
||||
/// @ingroup MV_IMAGE
|
||||
/// \~chinese
|
||||
/// \brief <20><><EFBFBD><EFBFBD>Image<67><65>ָ<EFBFBD><D6B8><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \param [in] Image
|
||||
/// \param [in] hWnd Ŀ<>Ĵ<EFBFBD><C4B4><EFBFBD>
|
||||
/// \param [in] Algorithm <20><><EFBFBD><EFBFBD><EFBFBD>㷨 0<><30><EFBFBD><EFBFBD><EFBFBD>ٵ<EFBFBD><D9B5><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Բ<EFBFBD> 1<><31><EFBFBD>ٶ<EFBFBD><D9B6><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Draw Image to the specified window
|
||||
/// \param [in] Image
|
||||
/// \param [in] hWnd destination window
|
||||
/// \param [in] Algorithm scaling algorithm 0:fast but slightly worse quality 1:slower but better quality
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraImage_Draw(
|
||||
void* Image,
|
||||
HWND hWnd,
|
||||
int Algorithm
|
||||
);
|
||||
|
||||
/// @ingroup MV_IMAGE
|
||||
/// \~chinese
|
||||
/// \brief <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Image<67><65>ָ<EFBFBD><D6B8><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \param [in] Image
|
||||
/// \param [in] hWnd Ŀ<>Ĵ<EFBFBD><C4B4><EFBFBD>
|
||||
/// \param [in] Algorithm <20><><EFBFBD><EFBFBD><EFBFBD>㷨 0<><30><EFBFBD><EFBFBD><EFBFBD>ٵ<EFBFBD><D9B5><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Բ<EFBFBD> 1<><31><EFBFBD>ٶ<EFBFBD><D9B6><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Pull up drawing Image to the specified window
|
||||
/// \param [in] Image
|
||||
/// \param [in] hWnd destination window
|
||||
/// \param [in] Algorithm scaling algorithm 0:fast but slightly worse quality 1:slower but better quality
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraImage_DrawFit(
|
||||
void* Image,
|
||||
HWND hWnd,
|
||||
int Algorithm
|
||||
);
|
||||
|
||||
/// @ingroup MV_IMAGE
|
||||
/// \~chinese
|
||||
/// \brief <20><><EFBFBD><EFBFBD>Image<67><65>ָ<EFBFBD><D6B8>DC
|
||||
/// \param [in] Image
|
||||
/// \param [in] hDC Ŀ<><C4BF>DC
|
||||
/// \param [in] Algorithm <20><><EFBFBD><EFBFBD><EFBFBD>㷨 0<><30><EFBFBD><EFBFBD><EFBFBD>ٵ<EFBFBD><D9B5><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Բ<EFBFBD> 1<><31><EFBFBD>ٶ<EFBFBD><D9B6><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \param [in] xDst Ŀ<><C4BF><EFBFBD><EFBFBD><EFBFBD>ε<EFBFBD><CEB5><EFBFBD><EFBFBD>Ͻ<EFBFBD>X<EFBFBD><58><EFBFBD><EFBFBD>
|
||||
/// \param [in] yDst Ŀ<><C4BF><EFBFBD><EFBFBD><EFBFBD>ε<EFBFBD><CEB5><EFBFBD><EFBFBD>Ͻ<EFBFBD>Y<EFBFBD><59><EFBFBD><EFBFBD>
|
||||
/// \param [in] cxDst Ŀ<><C4BF><EFBFBD><EFBFBD><EFBFBD>εĿ<CEB5><C4BF><EFBFBD>
|
||||
/// \param [in] cyDst Ŀ<><C4BF><EFBFBD><EFBFBD><EFBFBD>εĸ߶<C4B8>
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Draw Image to specified DC
|
||||
/// \param [in] Image
|
||||
/// \param [in] hDC destination DC
|
||||
/// \param [in] Algorithm scaling algorithm 0:fast but slightly worse quality 1:slower but better quality
|
||||
/// \param [in] xDst The X coordinate of the upper left corner of the target rectangle
|
||||
/// \param [in] yDst The Y coordinate of the upper left corner of the target rectangle
|
||||
/// \param [in] cxDst Width of target rectangle
|
||||
/// \param [in] cyDst Height of target rectangle
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraImage_DrawToDC(
|
||||
void* Image,
|
||||
HDC hDC,
|
||||
int Algorithm,
|
||||
int xDst,
|
||||
int yDst,
|
||||
int cxDst,
|
||||
int cyDst
|
||||
);
|
||||
|
||||
/// @ingroup MV_IMAGE
|
||||
/// \~chinese
|
||||
/// \brief <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Image<67><65>ָ<EFBFBD><D6B8>DC
|
||||
/// \param [in] Image
|
||||
/// \param [in] hDC Ŀ<><C4BF>DC
|
||||
/// \param [in] Algorithm <20><><EFBFBD><EFBFBD><EFBFBD>㷨 0<><30><EFBFBD><EFBFBD><EFBFBD>ٵ<EFBFBD><D9B5><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Բ<EFBFBD> 1<><31><EFBFBD>ٶ<EFBFBD><D9B6><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \param [in] xDst Ŀ<><C4BF><EFBFBD><EFBFBD><EFBFBD>ε<EFBFBD><CEB5><EFBFBD><EFBFBD>Ͻ<EFBFBD>X<EFBFBD><58><EFBFBD><EFBFBD>
|
||||
/// \param [in] yDst Ŀ<><C4BF><EFBFBD><EFBFBD><EFBFBD>ε<EFBFBD><CEB5><EFBFBD><EFBFBD>Ͻ<EFBFBD>Y<EFBFBD><59><EFBFBD><EFBFBD>
|
||||
/// \param [in] cxDst Ŀ<><C4BF><EFBFBD><EFBFBD><EFBFBD>εĿ<CEB5><C4BF><EFBFBD>
|
||||
/// \param [in] cyDst Ŀ<><C4BF><EFBFBD><EFBFBD><EFBFBD>εĸ߶<C4B8>
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Pull up drawing Image to specified DC
|
||||
/// \param [in] Image
|
||||
/// \param [in] hDC destination DC
|
||||
/// \param [in] Algorithm scaling algorithm 0:fast but slightly worse quality 1:slower but better quality
|
||||
/// \param [in] xDst The X coordinate of the upper left corner of the target rectangle
|
||||
/// \param [in] yDst The Y coordinate of the upper left corner of the target rectangle
|
||||
/// \param [in] cxDst Width of target rectangle
|
||||
/// \param [in] cyDst Height of target rectangle
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraImage_DrawToDCFit(
|
||||
void* Image,
|
||||
HDC hDC,
|
||||
int Algorithm,
|
||||
int xDst,
|
||||
int yDst,
|
||||
int cxDst,
|
||||
int cyDst
|
||||
);
|
||||
|
||||
/// @ingroup MV_IMAGE
|
||||
/// \~chinese
|
||||
/// \brief <20><><EFBFBD><EFBFBD>Image<67><65>ָ<EFBFBD><D6B8><EFBFBD><EFBFBD><EFBFBD>ڣ<EFBFBD><DAA3><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ţ<EFBFBD>
|
||||
/// \param [in] Image
|
||||
/// \param [in] hWnd Ŀ<>Ĵ<EFBFBD><C4B4><EFBFBD>
|
||||
/// \param [in] xDst Ŀ<><C4BF><EFBFBD><EFBFBD><EFBFBD>ε<EFBFBD><CEB5><EFBFBD><EFBFBD>Ͻ<EFBFBD>X<EFBFBD><58><EFBFBD><EFBFBD>
|
||||
/// \param [in] yDst Ŀ<><C4BF><EFBFBD><EFBFBD><EFBFBD>ε<EFBFBD><CEB5><EFBFBD><EFBFBD>Ͻ<EFBFBD>Y<EFBFBD><59><EFBFBD><EFBFBD>
|
||||
/// \param [in] cxDst Ŀ<><C4BF><EFBFBD><EFBFBD><EFBFBD>εĿ<CEB5><C4BF><EFBFBD>
|
||||
/// \param [in] cyDst Ŀ<><C4BF><EFBFBD><EFBFBD><EFBFBD>εĸ߶<C4B8>
|
||||
/// \param [in] xSrc ͼ<><CDBC><EFBFBD><EFBFBD><EFBFBD>ε<EFBFBD><CEB5><EFBFBD><EFBFBD>Ͻ<EFBFBD>X<EFBFBD><58><EFBFBD><EFBFBD>
|
||||
/// \param [in] ySrc ͼ<><CDBC><EFBFBD><EFBFBD><EFBFBD>ε<EFBFBD><CEB5><EFBFBD><EFBFBD>Ͻ<EFBFBD>Y<EFBFBD><59><EFBFBD><EFBFBD>
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Draw Image to specified window (without scaling)
|
||||
/// \param [in] Image
|
||||
/// \param [in] hWnd destination window
|
||||
/// \param [in] xDst The X coordinate of the upper left corner of the target rectangle
|
||||
/// \param [in] yDst The Y coordinate of the upper left corner of the target rectangle
|
||||
/// \param [in] cxDst Width of target rectangle
|
||||
/// \param [in] cyDst Height of target rectangle
|
||||
/// \param [in] xSrc X coordinate of the upper left corner of the image rectangle
|
||||
/// \param [in] ySrc Y coordinate of the upper left corner of the image rectangle
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraImage_BitBlt(
|
||||
void* Image,
|
||||
HWND hWnd,
|
||||
int xDst,
|
||||
int yDst,
|
||||
int cxDst,
|
||||
int cyDst,
|
||||
int xSrc,
|
||||
int ySrc
|
||||
);
|
||||
|
||||
/// @ingroup MV_IMAGE
|
||||
/// \~chinese
|
||||
/// \brief <20><><EFBFBD><EFBFBD>Image<67><65>ָ<EFBFBD><D6B8>DC<44><43><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ţ<EFBFBD>
|
||||
/// \param [in] Image
|
||||
/// \param [in] hDC Ŀ<><C4BF>DC
|
||||
/// \param [in] xDst Ŀ<><C4BF><EFBFBD><EFBFBD><EFBFBD>ε<EFBFBD><CEB5><EFBFBD><EFBFBD>Ͻ<EFBFBD>X<EFBFBD><58><EFBFBD><EFBFBD>
|
||||
/// \param [in] yDst Ŀ<><C4BF><EFBFBD><EFBFBD><EFBFBD>ε<EFBFBD><CEB5><EFBFBD><EFBFBD>Ͻ<EFBFBD>Y<EFBFBD><59><EFBFBD><EFBFBD>
|
||||
/// \param [in] cxDst Ŀ<><C4BF><EFBFBD><EFBFBD><EFBFBD>εĿ<CEB5><C4BF><EFBFBD>
|
||||
/// \param [in] cyDst Ŀ<><C4BF><EFBFBD><EFBFBD><EFBFBD>εĸ߶<C4B8>
|
||||
/// \param [in] xSrc ͼ<><CDBC><EFBFBD><EFBFBD><EFBFBD>ε<EFBFBD><CEB5><EFBFBD><EFBFBD>Ͻ<EFBFBD>X<EFBFBD><58><EFBFBD><EFBFBD>
|
||||
/// \param [in] ySrc ͼ<><CDBC><EFBFBD><EFBFBD><EFBFBD>ε<EFBFBD><CEB5><EFBFBD><EFBFBD>Ͻ<EFBFBD>Y<EFBFBD><59><EFBFBD><EFBFBD>
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Draw Image to specified DC (without scaling)
|
||||
/// \param [in] Image
|
||||
/// \param [in] hDC destination DC
|
||||
/// \param [in] xDst The X coordinate of the upper left corner of the target rectangle
|
||||
/// \param [in] yDst The Y coordinate of the upper left corner of the target rectangle
|
||||
/// \param [in] cxDst Width of target rectangle
|
||||
/// \param [in] cyDst Height of target rectangle
|
||||
/// \param [in] xSrc X coordinate of the upper left corner of the image rectangle
|
||||
/// \param [in] ySrc Y coordinate of the upper left corner of the image rectangle
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraImage_BitBltToDC(
|
||||
void* Image,
|
||||
HDC hDC,
|
||||
int xDst,
|
||||
int yDst,
|
||||
int cxDst,
|
||||
int cyDst,
|
||||
int xSrc,
|
||||
int ySrc
|
||||
);
|
||||
|
||||
/// @ingroup MV_IMAGE
|
||||
/// \~chinese
|
||||
/// \brief <20><>bmp<6D><70>ʽ<EFBFBD><CABD><EFBFBD><EFBFBD>Image
|
||||
/// \param [in] Image
|
||||
/// \param [in] FileName <20>ļ<EFBFBD><C4BC><EFBFBD>
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Save Image as bmp
|
||||
/// \param [in] Image
|
||||
/// \param [in] FileName file name
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraImage_SaveAsBmp(
|
||||
void* Image,
|
||||
char const* FileName
|
||||
);
|
||||
|
||||
/// @ingroup MV_IMAGE
|
||||
/// \~chinese
|
||||
/// \brief <20><>jpg<70><67>ʽ<EFBFBD><CABD><EFBFBD><EFBFBD>Image
|
||||
/// \param [in] Image
|
||||
/// \param [in] FileName <20>ļ<EFBFBD><C4BC><EFBFBD>
|
||||
/// \param [in] Quality <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>(1-100)<29><>100Ϊ<30><CEAA><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ѵ<EFBFBD><D1B5>ļ<EFBFBD>Ҳ<EFBFBD><D2B2><EFBFBD><EFBFBD>
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Save Image as jpg
|
||||
/// \param [in] Image
|
||||
/// \param [in] FileName file name
|
||||
/// \param [in] Quality save quality (1-100), 100 is the best quality but the file is also the largest
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraImage_SaveAsJpeg(
|
||||
void* Image,
|
||||
char const* FileName,
|
||||
BYTE Quality
|
||||
);
|
||||
|
||||
/// @ingroup MV_IMAGE
|
||||
/// \~chinese
|
||||
/// \brief <20><>png<6E><67>ʽ<EFBFBD><CABD><EFBFBD><EFBFBD>Image
|
||||
/// \param [in] Image
|
||||
/// \param [in] FileName <20>ļ<EFBFBD><C4BC><EFBFBD>
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Save Image as png
|
||||
/// \param [in] Image
|
||||
/// \param [in] FileName file name
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraImage_SaveAsPng(
|
||||
void* Image,
|
||||
char const* FileName
|
||||
);
|
||||
|
||||
/// @ingroup MV_IMAGE
|
||||
/// \~chinese
|
||||
/// \brief <20><>raw<61><77>ʽ<EFBFBD><CABD><EFBFBD><EFBFBD>Image
|
||||
/// \param [in] Image
|
||||
/// \param [in] FileName <20>ļ<EFBFBD><C4BC><EFBFBD>
|
||||
/// \param [in] Format 0: 8Bit Raw 1: 16Bit Raw
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Save Image as raw
|
||||
/// \param [in] Image
|
||||
/// \param [in] FileName file name
|
||||
/// \param [in] Format 0: 8Bit Raw 1: 16Bit Raw
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraImage_SaveAsRaw(
|
||||
void* Image,
|
||||
char const* FileName,
|
||||
int Format
|
||||
);
|
||||
|
||||
/// @ingroup MV_IMAGE
|
||||
/// \~chinese
|
||||
/// \brief <20><>Image<67><65><EFBFBD><EFBFBD>һ<EFBFBD><D2BB>IPicture
|
||||
/// \param [in] Image
|
||||
/// \param [out] NewPic <20>´<EFBFBD><C2B4><EFBFBD><EFBFBD><EFBFBD>IPicture
|
||||
/// \return <20>ɹ<EFBFBD><C9B9><EFBFBD><EFBFBD><EFBFBD> CAMERA_STATUS_SUCCESS(0)<29><><EFBFBD><EFBFBD><EFBFBD>ط<F2B7B5BB>0ֵ<30>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>, <20><><EFBFBD>ο<EFBFBD> CameraStatus.h <20>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6>塣
|
||||
/// \~english
|
||||
/// \brief Create an IPicture from an Image
|
||||
/// \param [in] Image
|
||||
/// \param [out] NewPic Newly created IPicture
|
||||
/// \return Returns CAMERA_STATUS_SUCCESS(0) successfully. Otherwise, it returns a non-zero error code. Please refer to the definition of the error code in CameraStatus.h.
|
||||
MVSDK_API CameraSdkStatus __stdcall CameraImage_IPicture(
|
||||
void* Image,
|
||||
IPicture** NewPic
|
||||
);
|
||||
|
||||
|
||||
|
||||
|
||||
#endif // _MV_CAMERA_IMAGE_H_
|
||||
114
others/include/camera/CameraStatus.h
Normal file
114
others/include/camera/CameraStatus.h
Normal file
@@ -0,0 +1,114 @@
|
||||
#ifndef __CAMERA_STATUS_DEF__
|
||||
#define __CAMERA_STATUS_DEF__
|
||||
|
||||
/// @ingroup MV_TYPEDEF
|
||||
/// \~chinese SDK<44><4B><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
/// \~english SDK error code
|
||||
typedef int CameraSdkStatus;
|
||||
|
||||
|
||||
/*<2A><><EFBFBD>õĺ<C3B5>*/
|
||||
#define SDK_SUCCESS(_FUC_) (_FUC_ == CAMERA_STATUS_SUCCESS)
|
||||
|
||||
#define SDK_UNSUCCESS(_FUC_) (_FUC_ != CAMERA_STATUS_SUCCESS)
|
||||
|
||||
#define SDK_UNSUCCESS_RETURN(_FUC_,RET) if((RET = _FUC_) != CAMERA_STATUS_SUCCESS)\
|
||||
{\
|
||||
return RET;\
|
||||
}
|
||||
|
||||
#define SDK_UNSUCCESS_BREAK(_FUC_) if(_FUC_ != CAMERA_STATUS_SUCCESS)\
|
||||
{\
|
||||
break;\
|
||||
}
|
||||
|
||||
|
||||
/// @ingroup MV_MACRO_TYPE
|
||||
/// @{
|
||||
/* <20><><EFBFBD>ô<EFBFBD><C3B4><EFBFBD> */
|
||||
|
||||
#define CAMERA_STATUS_SUCCESS 0 ///< \~chinese <20><><EFBFBD><EFBFBD><EFBFBD>ɹ<EFBFBD> \~english Successful
|
||||
#define CAMERA_STATUS_FAILED -1 ///< \~chinese <20><><EFBFBD><EFBFBD>ʧ<EFBFBD><CAA7> \~english operation failed
|
||||
#define CAMERA_STATUS_INTERNAL_ERROR -2 ///< \~chinese <20>ڲ<EFBFBD><DAB2><EFBFBD><EFBFBD><EFBFBD> \~english internal error
|
||||
#define CAMERA_STATUS_UNKNOW -3 ///< \~chinese δ֪<CEB4><D6AA><EFBFBD><EFBFBD> \~english unknown error
|
||||
#define CAMERA_STATUS_NOT_SUPPORTED -4 ///< \~chinese <20><>֧<EFBFBD>ָù<D6B8><C3B9><EFBFBD> \~english Does not support this feature
|
||||
#define CAMERA_STATUS_NOT_INITIALIZED -5 ///< \~chinese <20><>ʼ<EFBFBD><CABC>δ<EFBFBD><CEB4><EFBFBD><EFBFBD> \~english Incomplete initialization
|
||||
#define CAMERA_STATUS_PARAMETER_INVALID -6 ///< \~chinese <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ч \~english Invalid argument
|
||||
#define CAMERA_STATUS_PARAMETER_OUT_OF_BOUND -7 ///< \~chinese <20><><EFBFBD><EFBFBD>Խ<EFBFBD><D4BD> \~english Out of bounds of parameters
|
||||
#define CAMERA_STATUS_UNENABLED -8 ///< \~chinese δʹ<CEB4><CAB9> \~english Not enabled
|
||||
#define CAMERA_STATUS_USER_CANCEL -9 ///< \~chinese <20>û<EFBFBD><C3BB>ֶ<EFBFBD>ȡ<EFBFBD><C8A1><EFBFBD>ˣ<EFBFBD><CBA3><EFBFBD><EFBFBD><EFBFBD>roi<6F><69><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ȡ<EFBFBD><C8A1><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD> \~english The user manually canceled, such as roi panel click cancel, return
|
||||
#define CAMERA_STATUS_PATH_NOT_FOUND -10 ///< \~chinese ע<><D7A2><EFBFBD><EFBFBD><EFBFBD><EFBFBD>û<EFBFBD><C3BB><EFBFBD>ҵ<EFBFBD><D2B5><EFBFBD>Ӧ<EFBFBD><D3A6>·<EFBFBD><C2B7> \~english The corresponding path was not found in the registry
|
||||
#define CAMERA_STATUS_SIZE_DISMATCH -11 ///< \~chinese <20><><EFBFBD><EFBFBD>ͼ<EFBFBD><CDBC><EFBFBD><EFBFBD><EFBFBD>ݳ<EFBFBD><DDB3>ȺͶ<C8BA><CDB6><EFBFBD><EFBFBD>ijߴ粻ƥ<E7B2BB><C6A5> \~english The length of the obtained image data does not match the defined size
|
||||
#define CAMERA_STATUS_TIME_OUT -12 ///< \~chinese <20><>ʱ<EFBFBD><CAB1><EFBFBD><EFBFBD> \~english Timeout error
|
||||
#define CAMERA_STATUS_IO_ERROR -13 ///< \~chinese Ӳ<><D3B2>IO<49><4F><EFBFBD><EFBFBD> \~english Hardware IO error
|
||||
#define CAMERA_STATUS_COMM_ERROR -14 ///< \~chinese ͨѶ<CDA8><D1B6><EFBFBD><EFBFBD> \~english Communication error
|
||||
#define CAMERA_STATUS_BUS_ERROR -15 ///< \~chinese <20><><EFBFBD>ߴ<EFBFBD><DFB4><EFBFBD> \~english Bus error
|
||||
#define CAMERA_STATUS_NO_DEVICE_FOUND -16 ///< \~chinese û<>з<EFBFBD><D0B7><EFBFBD><EFBFBD>豸 \~english No device found
|
||||
#define CAMERA_STATUS_NO_LOGIC_DEVICE_FOUND -17 ///< \~chinese δ<>ҵ<EFBFBD><D2B5><EFBFBD><DFBC>豸 \~english Logical device not found
|
||||
#define CAMERA_STATUS_DEVICE_IS_OPENED -18 ///< \~chinese <20>豸<EFBFBD>Ѿ<EFBFBD><D1BE><EFBFBD><EFBFBD><EFBFBD> \~english The device is already open
|
||||
#define CAMERA_STATUS_DEVICE_IS_CLOSED -19 ///< \~chinese <20>豸<EFBFBD>Ѿ<EFBFBD><D1BE>ر<EFBFBD> \~english Device is off
|
||||
#define CAMERA_STATUS_DEVICE_VEDIO_CLOSED -20 ///< \~chinese û<>д<EFBFBD><D0B4><EFBFBD><EFBFBD>豸<EFBFBD><E8B1B8>Ƶ<EFBFBD><C6B5><EFBFBD><EFBFBD><EFBFBD><EFBFBD>¼<EFBFBD><C2BC><EFBFBD><EFBFBD><EFBFBD>صĺ<D8B5><C4BA><EFBFBD>ʱ<EFBFBD><CAB1><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ƶû<C6B5>д<D0B4><F2BFAAA3><EFBFBD><EFBFBD>ط<EFBFBD><D8B7>ظô<D8B8><C3B4><EFBFBD><EFBFBD><EFBFBD> \~english Without opening the device video, when the video-related function is called, if the camera video is not open, the error is returned back.
|
||||
#define CAMERA_STATUS_NO_MEMORY -21 ///< \~chinese û<><C3BB><EFBFBD>㹻ϵͳ<CFB5>ڴ<EFBFBD> \~english Not enough system memory
|
||||
#define CAMERA_STATUS_FILE_CREATE_FAILED -22 ///< \~chinese <20><><EFBFBD><EFBFBD><EFBFBD>ļ<EFBFBD>ʧ<EFBFBD><CAA7> \~english Failed to create file
|
||||
#define CAMERA_STATUS_FILE_INVALID -23 ///< \~chinese <20>ļ<EFBFBD><C4BC><EFBFBD>ʽ<EFBFBD><CABD>Ч \~english Invalid file format
|
||||
#define CAMERA_STATUS_WRITE_PROTECTED -24 ///< \~chinese д<><D0B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>д \~english Write protection, not write
|
||||
#define CAMERA_STATUS_GRAB_FAILED -25 ///< \~chinese <20><><EFBFBD>ݲɼ<DDB2>ʧ<EFBFBD><CAA7> \~english Data collection failed
|
||||
#define CAMERA_STATUS_LOST_DATA -26 ///< \~chinese <20><><EFBFBD>ݶ<EFBFBD>ʧ<EFBFBD><CAA7><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD> \~english Loss of data, incomplete
|
||||
#define CAMERA_STATUS_EOF_ERROR -27 ///< \~chinese δ<><CEB4><EFBFBD>յ<EFBFBD>֡<EFBFBD><D6A1><EFBFBD><EFBFBD><EFBFBD><EFBFBD> \~english No frame terminator received
|
||||
#define CAMERA_STATUS_BUSY -28 ///< \~chinese <20><>æ(<28><>һ<EFBFBD>β<EFBFBD><CEB2><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ڽ<EFBFBD><DABD><EFBFBD><EFBFBD><EFBFBD>)<29><><EFBFBD>˴β<CBB4><CEB2><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ܽ<EFBFBD><DCBD><EFBFBD> \~english Busy (last operation is still in progress), this operation cannot be performed
|
||||
#define CAMERA_STATUS_WAIT -29 ///< \~chinese <20><>Ҫ<EFBFBD>ȴ<EFBFBD>(<28><><EFBFBD>в<EFBFBD><D0B2><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>)<29><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ٴγ<D9B4><CEB3><EFBFBD> \~english Need to wait (condition of operation is not established), can try again
|
||||
#define CAMERA_STATUS_IN_PROCESS -30 ///< \~chinese <20><><EFBFBD>ڽ<EFBFBD><DABD>У<EFBFBD><D0A3>Ѿ<EFBFBD><D1BE><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD> \~english Ongoing, has been operated
|
||||
#define CAMERA_STATUS_IIC_ERROR -31 ///< \~chinese IIC<49><43><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD> \~english IIC transmission error
|
||||
#define CAMERA_STATUS_SPI_ERROR -32 ///< \~chinese SPI<50><49><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD> \~english SPI transmission error
|
||||
#define CAMERA_STATUS_USB_CONTROL_ERROR -33 ///< \~chinese USB<53><42><EFBFBD>ƴ<EFBFBD><C6B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD> \~english USB control transmission error
|
||||
#define CAMERA_STATUS_USB_BULK_ERROR -34 ///< \~chinese USB BULK<4C><4B><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD> \~english USB BULK transmission error
|
||||
#define CAMERA_STATUS_SOCKET_INIT_ERROR -35 ///< \~chinese <20><><EFBFBD>紫<EFBFBD><E7B4AB><EFBFBD><EFBFBD><D7BC><EFBFBD>ʼ<EFBFBD><CABC>ʧ<EFBFBD><CAA7> \~english Network Transport Suite Initialization Failed
|
||||
#define CAMERA_STATUS_GIGE_FILTER_INIT_ERROR -36 ///< \~chinese <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ں˹<DABA><CBB9><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʼ<EFBFBD><CABC>ʧ<EFBFBD>ܣ<EFBFBD><DCA3><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ƿ<EFBFBD><C7B7><EFBFBD>ȷ<EFBFBD><C8B7>װ<EFBFBD><D7B0><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>°<EFBFBD>װ<EFBFBD><D7B0> \~english The webcam kernel filter driver failed to initialize. Please check if the driver is installed correctly or reinstall it.
|
||||
#define CAMERA_STATUS_NET_SEND_ERROR -37 ///< \~chinese <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ݷ<EFBFBD><DDB7>ʹ<EFBFBD><CDB4><EFBFBD> \~english Network data sending error
|
||||
#define CAMERA_STATUS_DEVICE_LOST -38 ///< \~chinese <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʧȥ<CAA7><C8A5><EFBFBD>ӣ<EFBFBD><D3A3><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ⳬʱ \~english Lost connection with webcam, heartbeat timeout
|
||||
#define CAMERA_STATUS_DATA_RECV_LESS -39 ///< \~chinese <20><><EFBFBD>յ<EFBFBD><D5B5><EFBFBD><EFBFBD>ֽ<EFBFBD><D6BD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD> \~english Received fewer bytes than requested
|
||||
#define CAMERA_STATUS_FUNCTION_LOAD_FAILED -40 ///< \~chinese <20><><EFBFBD>ļ<EFBFBD><C4BC>м<EFBFBD><D0BC>س<EFBFBD><D8B3><EFBFBD>ʧ<EFBFBD><CAA7> \~english Failed to load program from file
|
||||
#define CAMERA_STATUS_CRITICAL_FILE_LOST -41 ///< \~chinese <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ļ<EFBFBD><C4BC><EFBFBD>ʧ<EFBFBD><CAA7> \~english The file necessary to run the program is missing.
|
||||
#define CAMERA_STATUS_SENSOR_ID_DISMATCH -42 ///< \~chinese <20>̼<EFBFBD><CCBC>ͳ<EFBFBD><CDB3><EFBFBD><EFBFBD><EFBFBD>ƥ<EFBFBD>䣬ԭ<E4A3AC><D4AD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>˴<EFBFBD><CBB4><EFBFBD><EFBFBD>Ĺ̼<C4B9><CCBC><EFBFBD> \~english The firmware and program do not match because the wrong firmware was downloaded.
|
||||
#define CAMERA_STATUS_OUT_OF_RANGE -43 ///< \~chinese <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ч<EFBFBD><D0A7>Χ<EFBFBD><CEA7> \~english The parameter is out of valid range.
|
||||
#define CAMERA_STATUS_REGISTRY_ERROR -44 ///< \~chinese <20><>װ<EFBFBD><D7B0><EFBFBD><EFBFBD>ע<EFBFBD><D7A2><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>°<EFBFBD>װ<EFBFBD><D7B0><EFBFBD><EFBFBD><F2A3ACBB><EFBFBD><EFBFBD><EFBFBD><EFBFBD>а<EFBFBD>װĿ¼Setup/Installer.exe \~english Setup registration error. Please reinstall the program, or run the installation directory Setup/Installer.exe
|
||||
#define CAMERA_STATUS_ACCESS_DENY -45 ///< \~chinese <20><>ֹ<EFBFBD><D6B9><EFBFBD>ʡ<EFBFBD>ָ<EFBFBD><D6B8><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ѿ<EFBFBD><D1BE><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ռ<EFBFBD><D5BC>ʱ<EFBFBD><CAB1><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʸ<EFBFBD><CAB8><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>᷵<EFBFBD>ظ<EFBFBD>״̬<D7B4><CCAC>(һ<><D2BB><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ܱ<EFBFBD><DCB1><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ͬʱ<CDAC><CAB1><EFBFBD><EFBFBD>) \~english No Access. When the specified camera has been occupied by another program, it will return to this state if you request to access the camera. (A camera cannot be accessed simultaneously by multiple programs)
|
||||
#define CAMERA_STATUS_CAMERA_NEED_RESET -46 ///< \~chinese <20><>ʾ<EFBFBD><CABE><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ҫ<EFBFBD><D2AA>λ<EFBFBD><CEBB><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʹ<EFBFBD>ã<EFBFBD><C3A3><EFBFBD>ʱ<EFBFBD><CAB1><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ϵ<EFBFBD><CFB5><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ϵͳ<CFB5><EFBFBD><F3A3ACB1><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʹ<EFBFBD>á<EFBFBD> \~english It means that the camera needs to be reset before it can be used normally. At this time, please make the camera power off and restart, or restart the operating system, then it can be used normally.
|
||||
#define CAMERA_STATUS_ISP_MOUDLE_NOT_INITIALIZED -47 ///< \~chinese ISPģ<50><C4A3>δ<EFBFBD><CEB4>ʼ<EFBFBD><CABC> \~english ISP module is not initialized
|
||||
#define CAMERA_STATUS_ISP_DATA_CRC_ERROR -48 ///< \~chinese <20><><EFBFBD><EFBFBD>У<EFBFBD><D0A3><EFBFBD><EFBFBD><EFBFBD><EFBFBD> \~english Data check error
|
||||
#define CAMERA_STATUS_MV_TEST_FAILED -49 ///< \~chinese <20><><EFBFBD>ݲ<EFBFBD><DDB2><EFBFBD>ʧ<EFBFBD><CAA7> \~english Data test failed
|
||||
#define CAMERA_STATUS_INTERNAL_ERR1 -50 ///< \~chinese <20>ڲ<EFBFBD><DAB2><EFBFBD><EFBFBD><EFBFBD>1 \~english Internal error 1
|
||||
#define CAMERA_STATUS_U3V_NO_CONTROL_EP -51 ///< \~chinese U3V<33><56><EFBFBD>ƶ˵<C6B6>δ<EFBFBD>ҵ<EFBFBD> \~english U3V control endpoint not found
|
||||
#define CAMERA_STATUS_U3V_CONTROL_ERROR -52 ///< \~chinese U3V<33><56><EFBFBD><EFBFBD>ͨѶ<CDA8><D1B6><EFBFBD><EFBFBD> \~english U3V control communication error
|
||||
#define CAMERA_STATUS_INVALID_FRIENDLY_NAME -53 ///< \~chinese <20><>Ч<EFBFBD><D0A7><EFBFBD>豸<EFBFBD><E8B1B8><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ﲻ<EFBFBD>ܰ<EFBFBD><DCB0><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ַ<EFBFBD>(\/:*?"<>|") \~english Invalid device name, the name cannot contain the following characters (\/:*?"<>|")
|
||||
|
||||
|
||||
|
||||
//<2F><>AIA<49>ƶ<EFBFBD><C6B6>ı<EFBFBD><EFBFBD><D7BC>ͬ
|
||||
/*#define CAMERA_AIA_SUCCESS 0x0000 */
|
||||
#define CAMERA_AIA_PACKET_RESEND 0x0100 ///< \~chinese <20><>֡<EFBFBD><D6A1>Ҫ<EFBFBD>ش<EFBFBD> \~english The frame needs to be retransmitted
|
||||
#define CAMERA_AIA_NOT_IMPLEMENTED 0x8001 ///< \~chinese <20>豸<EFBFBD><E8B1B8>֧<EFBFBD>ֵ<EFBFBD><D6B5><EFBFBD><EFBFBD><EFBFBD> \~english Device does not support commands
|
||||
#define CAMERA_AIA_INVALID_PARAMETER 0x8002 ///< \~chinese <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ƿ<EFBFBD> \~english Illegal command parameters
|
||||
#define CAMERA_AIA_INVALID_ADDRESS 0x8003 ///< \~chinese <20><><EFBFBD>ɷ<EFBFBD><C9B7>ʵĵ<CAB5>ַ \~english Inaccessible address
|
||||
#define CAMERA_AIA_WRITE_PROTECT 0x8004 ///< \~chinese <20><><EFBFBD>ʵĶ<CAB5><C4B6><EFBFBD>д \~english The accessed object cannot be written
|
||||
#define CAMERA_AIA_BAD_ALIGNMENT 0x8005 ///< \~chinese <20><><EFBFBD>ʵĵ<CAB5>ַû<D6B7>а<EFBFBD><D0B0><EFBFBD>Ҫ<EFBFBD><D2AA><EFBFBD><EFBFBD><EFBFBD><EFBFBD> \~english Visited address is not aligned as required
|
||||
#define CAMERA_AIA_ACCESS_DENIED 0x8006 ///< \~chinese û<>з<EFBFBD><D0B7><EFBFBD>Ȩ<EFBFBD><C8A8> \~english No access
|
||||
#define CAMERA_AIA_BUSY 0x8007 ///< \~chinese <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ڴ<EFBFBD><DAB4><EFBFBD><EFBFBD><EFBFBD> \~english Command is processing
|
||||
#define CAMERA_AIA_DEPRECATED 0x8008 ///< \~chinese 0x8008-0x0800B 0x800F <20><>ָ<EFBFBD><D6B8><EFBFBD>Ѿ<EFBFBD><D1BE><EFBFBD><EFBFBD><EFBFBD> \~english 0x8008-0x0800B 0x800F This instruction has been deprecated
|
||||
#define CAMERA_AIA_PACKET_UNAVAILABLE 0x800C ///< \~chinese <20><><EFBFBD><EFBFBD>Ч \~english Invalid package
|
||||
#define CAMERA_AIA_DATA_OVERRUN 0x800D ///< \~chinese <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ͨ<EFBFBD><CDA8><EFBFBD><EFBFBD><EFBFBD>յ<EFBFBD><D5B5><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ݱ<EFBFBD><DDB1><EFBFBD>Ҫ<EFBFBD>Ķ<EFBFBD> \~english Data overflow, usually more data than needed
|
||||
#define CAMERA_AIA_INVALID_HEADER 0x800E ///< \~chinese <20><><EFBFBD>ݰ<EFBFBD>ͷ<EFBFBD><CDB7><EFBFBD><EFBFBD>ijЩ<C4B3><D0A9><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Э<EFBFBD>鲻ƥ<E9B2BB><C6A5> \~english Some areas in the packet header do not match the protocol
|
||||
#define CAMERA_AIA_PACKET_NOT_YET_AVAILABLE 0x8010 ///< \~chinese ͼ<><CDBC><EFBFBD>ְ<EFBFBD><D6B0><EFBFBD><EFBFBD>ݻ<EFBFBD>δ<CEB4><D7BC><EFBFBD>ã<EFBFBD><C3A3><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ڴ<EFBFBD><DAB4><EFBFBD>ģʽ<C4A3><CABD>Ӧ<EFBFBD>ó<EFBFBD><C3B3><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʳ<EFBFBD>ʱ \~english Image packet data is not ready yet. It is mostly used in trigger mode. Application access timeout
|
||||
#define CAMERA_AIA_PACKET_AND_PREV_REMOVED_FROM_MEMORY 0x8011 ///< \~chinese <20><>Ҫ<EFBFBD><D2AA><EFBFBD>ʵķְ<C4B7><D6B0>Ѿ<EFBFBD><D1BE><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ڡ<EFBFBD><DAA1><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ش<EFBFBD>ʱ<EFBFBD><CAB1><EFBFBD><EFBFBD><EFBFBD>Ѿ<EFBFBD><D1BE><EFBFBD><EFBFBD>ڻ<EFBFBD><DABB><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD> \~english Subcontracts that require access no longer exist. Mostly used for data retransmission is not in the buffer
|
||||
#define CAMERA_AIA_PACKET_REMOVED_FROM_MEMORY 0x8012 ///< \~chinese CAMERA_AIA_PACKET_AND_PREV_REMOVED_FROM_MEMORY \~english CAMERA_AIA_PACKET_AND_PREV_REMOVED_FROM_MEMORY
|
||||
#define CAMERA_AIA_NO_REF_TIME 0x0813 ///< \~chinese û<>вο<D0B2>ʱ<EFBFBD><CAB1>Դ<EFBFBD><D4B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʱ<EFBFBD><CAB1>ͬ<EFBFBD><CDAC><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ִ<EFBFBD><D6B4>ʱ \~english There is no reference clock source. When used for time synchronization commands
|
||||
#define CAMERA_AIA_PACKET_TEMPORARILY_UNAVAILABLE 0x0814 ///< \~chinese <20><><EFBFBD><EFBFBD><EFBFBD>ŵ<EFBFBD><C5B5><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>⣬<EFBFBD><E2A3AC>ǰ<EFBFBD>ְ<EFBFBD><D6B0><EFBFBD>ʱ<EFBFBD><CAB1><EFBFBD><EFBFBD><EFBFBD>ã<EFBFBD><C3A3><EFBFBD><EFBFBD>Ժ<EFBFBD><D4BA><EFBFBD><EFBFBD>з<EFBFBD><D0B7><EFBFBD> \~english Due to channel bandwidth issues, the current subcontracting is temporarily unavailable and needs to be accessed later
|
||||
#define CAMERA_AIA_OVERFLOW 0x0815 ///< \~chinese <20>豸<EFBFBD><E8B1B8><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ͨ<EFBFBD><CDA8><EFBFBD>Ƕ<EFBFBD><C7B6><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD> \~english Data overflow on the device, usually the queue is full
|
||||
#define CAMERA_AIA_ACTION_LATE 0x0816 ///< \~chinese <20><><EFBFBD><EFBFBD>ִ<EFBFBD><D6B4><EFBFBD>Ѿ<EFBFBD><D1BE><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ч<EFBFBD><D0A7>ָ<EFBFBD><D6B8>ʱ<EFBFBD><CAB1> \~english Command execution has exceeded valid specified time
|
||||
#define CAMERA_AIA_ERROR 0x8FFF ///< \~chinese <20><><EFBFBD><EFBFBD> \~english error
|
||||
|
||||
/// @} end of MV_MACRO_TYPE
|
||||
|
||||
|
||||
|
||||
#endif
|
||||
2823
others/include/camera/camera_api.h
Normal file
2823
others/include/camera/camera_api.h
Normal file
File diff suppressed because it is too large
Load Diff
665
others/include/camera/camera_define.h
Normal file
665
others/include/camera/camera_define.h
Normal file
@@ -0,0 +1,665 @@
|
||||
#pragma once
|
||||
#ifndef _CAMERA_DEFINE_H_
|
||||
#define _CAMERA_DEFINE_H_
|
||||
|
||||
#include "camera_status.h"
|
||||
|
||||
#define MAX_CROSS_LINE 9
|
||||
|
||||
//相机的句柄类型定义
|
||||
typedef int CameraHandle;
|
||||
typedef int INT;
|
||||
typedef long LONG;
|
||||
typedef unsigned int UINT;
|
||||
typedef unsigned long long UINT64;
|
||||
typedef int BOOL;
|
||||
typedef unsigned char BYTE;
|
||||
typedef unsigned int DWORD;
|
||||
typedef void* PVOID;
|
||||
typedef void* HWND;
|
||||
typedef char* LPCTSTR;
|
||||
typedef unsigned short USHORT;
|
||||
typedef short SHORT;
|
||||
typedef unsigned char* LPBYTE;
|
||||
typedef char CHAR;
|
||||
typedef short WORD;
|
||||
typedef INT HANDLE;
|
||||
typedef void VOID;
|
||||
typedef unsigned long ULONG;
|
||||
typedef void** LPVOID;
|
||||
typedef unsigned char UCHAR;
|
||||
typedef void* HMODULE;
|
||||
|
||||
|
||||
|
||||
#define TRUE 1
|
||||
#define FALSE 0
|
||||
//图像查表变换的方式
|
||||
typedef enum
|
||||
{
|
||||
LUTMODE_PARAM_GEN=0,//通过调节参数动态生成LUT表
|
||||
LUTMODE_PRESET, //使用预设的LUT表
|
||||
LUTMODE_USER_DEF //使用用户自定义的LUT表
|
||||
}emSdkLutMode;
|
||||
|
||||
//相机的视频流控制
|
||||
typedef enum
|
||||
{
|
||||
RUNMODE_PLAY=0, //正常预览,捕获到图像就显示。(如果相机处于触发模式,则会等待触发帧的到来)
|
||||
RUNMODE_PAUSE, //暂停,会暂停相机的图像输出,同时也不会去捕获图像
|
||||
RUNMODE_STOP //停止相机工作。反初始化后,相机就处于停止模式
|
||||
}emSdkRunMode;
|
||||
|
||||
//SDK内部显示接口的显示方式
|
||||
typedef enum
|
||||
{
|
||||
DISPLAYMODE_SCALE=0, //缩放显示模式,缩放到显示控件的尺寸
|
||||
DISPLAYMODE_REAL //1:1显示模式,当图像尺寸大于显示控件的尺寸时,只显示局部
|
||||
}emSdkDisplayMode;
|
||||
|
||||
//录像状态
|
||||
typedef enum
|
||||
{
|
||||
RECORD_STOP = 0, //停止
|
||||
RECORD_START, //录像中
|
||||
RECORD_PAUSE //暂停
|
||||
}emSdkRecordMode;
|
||||
|
||||
//图像的镜像操作
|
||||
typedef enum
|
||||
{
|
||||
MIRROR_DIRECTION_HORIZONTAL = 0,//水平镜像
|
||||
MIRROR_DIRECTION_VERTICAL //垂直镜像
|
||||
}emSdkMirrorDirection;
|
||||
|
||||
//相机视频的帧率
|
||||
typedef enum
|
||||
{
|
||||
FRAME_SPEED_LOW = 0, //低速模式
|
||||
FRAME_SPEED_NORMAL, //普通模式
|
||||
FRAME_SPEED_HIGH, //高速模式(需要较高的传输带宽,多设备共享传输带宽时会对帧率的稳定性有影响)
|
||||
FRAME_SPEED_SUPER //超高速模式(需要较高的传输带宽,多设备共享传输带宽时会对帧率的稳定性有影响)
|
||||
}emSdkFrameSpeed;
|
||||
|
||||
//保存文件的格式类型
|
||||
typedef enum
|
||||
{
|
||||
FILE_JPG = 1,//JPG
|
||||
FILE_BMP = 2,//BMP
|
||||
FILE_RAW = 4,//相机输出的bayer格式文件,对于不支持bayer格式输出相机,无法保存为该格式
|
||||
FILE_PNG = 8 //PNG
|
||||
}emSdkFileType;
|
||||
|
||||
//相机中的图像传感器的工作模式
|
||||
typedef enum
|
||||
{
|
||||
CONTINUATION = 0,//连续采集模式
|
||||
SOFT_TRIGGER, //软件触发模式,由软件发送指令后,传感器开始采集指定帧数的图像,采集完成后,停止输出
|
||||
EXTERNAL_TRIGGER //硬件触发模式,当接收到外部信号,传感器开始采集指定帧数的图像,采集完成后,停止输出
|
||||
} emSdkSnapMode;
|
||||
|
||||
//自动曝光时抗频闪的频闪
|
||||
typedef enum
|
||||
{
|
||||
LIGHT_FREQUENCY_50HZ = 0,//50HZ,一般的灯光都是50HZ
|
||||
LIGHT_FREQUENCY_60HZ //60HZ,主要是指显示器的
|
||||
}emSdkLightFrequency;
|
||||
|
||||
//相机的配置参数,分为A,B,C,D 4组进行保存。
|
||||
typedef enum
|
||||
{
|
||||
PARAMETER_TEAM_DEFAULT = 0xff,
|
||||
PARAMETER_TEAM_A = 0,
|
||||
PARAMETER_TEAM_B = 1,
|
||||
PARAMETER_TEAM_C = 2,
|
||||
PARAMETER_TEAM_D = 3
|
||||
}emSdkParameterTeam;
|
||||
|
||||
|
||||
/*emSdkParameterMode 相机参数加载模式,参数加载分为从文件和从设备加载两种方式
|
||||
|
||||
PARAM_MODE_BY_MODEL:所有同型号的相机共用ABCD四组参数文件。修改
|
||||
一台相机的参数文件,会影响到整个同型号的
|
||||
相机参数加载。
|
||||
|
||||
PARAM_MODE_BY_NAME:所有设备名相同的相机,共用ABCD四组参数文件。
|
||||
默认情况下,当电脑上只接了某型号一台相机时,
|
||||
设备名都是一样的,而您希望某一台相机能够加载
|
||||
不同的参数文件,则可以通过修改其设备名的方式
|
||||
来让其加载指定的参数文件。
|
||||
|
||||
PARAM_MODE_BY_SN:相机按照自己的唯一序列号来加载ABCD四组参数文件,
|
||||
序列号在出厂时已经固化在相机内,每台相机的序列号
|
||||
都不相同,通过这种方式,每台相机的参数文件都是独立的。
|
||||
|
||||
您可以根据自己的使用环境,灵活使用以上几种方式加载参数。例如,以
|
||||
MV-U300为例,您希望多台该型号的相机在您的 电脑上都共用4组参数,那么就
|
||||
使用PARAM_MODE_BY_MODEL方式;如果您希望其中某一台或者某几台MV-U300能
|
||||
使用自己参数文件而其余的MV-U300又要使用相同的参数文件,那么使用
|
||||
PARAM_MODE_BY_NAME方式;如果您希望每台MV-U300都使用不同的参数文件,那么
|
||||
使用PARAM_MODE_BY_SN方式。
|
||||
参数文件存在安装目录的 \Camera\Configs 目录下,以config为后缀名的文件。
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
PARAM_MODE_BY_MODEL = 0, //根据相机型号名从文件中加载参数,例如MV-U300
|
||||
PARAM_MODE_BY_NAME, //根据设备昵称(tSdkCameraDevInfo.acFriendlyName)从文件中加载参数,例如MV-U300,该昵称可自定义
|
||||
PARAM_MODE_BY_SN, //根据设备的唯一序列号从文件中加载参数,序列号在出厂时已经写入设备,每台相机拥有不同的序列号。
|
||||
PARAM_MODE_IN_DEVICE //从设备的固态存储器中加载参数。不是所有的型号都支持从相机中读写参数组,由tSdkCameraCapbility.bParamInDevice决定
|
||||
}emSdkParameterMode;
|
||||
|
||||
|
||||
//SDK生成的相机配置页面掩码值
|
||||
typedef enum
|
||||
{
|
||||
PROP_SHEET_INDEX_EXPOSURE = 0,
|
||||
PROP_SHEET_INDEX_ISP_COLOR,
|
||||
PROP_SHEET_INDEX_ISP_LUT,
|
||||
PROP_SHEET_INDEX_ISP_SHAPE,
|
||||
PROP_SHEET_INDEX_VIDEO_FORMAT,
|
||||
PROP_SHEET_INDEX_RESOLUTION,
|
||||
PROP_SHEET_INDEX_IO_CTRL,
|
||||
PROP_SHEET_INDEX_TRIGGER_SET,
|
||||
PROP_SHEET_INDEX_OVERLAY,
|
||||
PROP_SHEET_INDEX_DEVICE_INFO
|
||||
}emSdkPropSheetMask;
|
||||
|
||||
//SDK生成的相机配置页面的回调消息类型
|
||||
typedef enum
|
||||
{
|
||||
SHEET_MSG_LOAD_PARAM_DEFAULT = 0, //参数被恢复成默认后,触发该消息
|
||||
SHEET_MSG_LOAD_PARAM_GROUP, //加载指定参数组,触发该消息
|
||||
SHEET_MSG_LOAD_PARAM_FROMFILE, //从指定文件加载参数后,触发该消息
|
||||
SHEET_MSG_SAVE_PARAM_GROUP //当前参数组被保存时,触发该消息
|
||||
}emSdkPropSheetMsg;
|
||||
|
||||
//可视化选择参考窗口的类型
|
||||
typedef enum
|
||||
{
|
||||
REF_WIN_AUTO_EXPOSURE = 0,
|
||||
REF_WIN_WHITE_BALANCE,
|
||||
}emSdkRefWinType;
|
||||
|
||||
//可视化选择参考窗口的类型
|
||||
typedef enum
|
||||
{
|
||||
RES_MODE_PREVIEW = 0,
|
||||
RES_MODE_SNAPSHOT,
|
||||
}emSdkResolutionMode;
|
||||
|
||||
//白平衡时色温模式
|
||||
typedef enum
|
||||
{
|
||||
CT_MODE_AUTO = 0, //自动识别色温
|
||||
CT_MODE_PRESET, //使用指定的预设色温
|
||||
CT_MODE_USER_DEF //自定义色温(增益和矩阵)
|
||||
}emSdkClrTmpMode;
|
||||
|
||||
//LUT的颜色通道
|
||||
typedef enum
|
||||
{
|
||||
LUT_CHANNEL_ALL = 0,//R,B,G三通道同时调节
|
||||
LUT_CHANNEL_RED, //红色通道
|
||||
LUT_CHANNEL_GREEN, //绿色通道
|
||||
LUT_CHANNEL_BLUE, //蓝色通道
|
||||
}emSdkLutChannel;
|
||||
|
||||
//ISP处理单元
|
||||
typedef enum
|
||||
{
|
||||
ISP_PROCESSSOR_PC = 0,//使用PC的软件ISP模块
|
||||
ISP_PROCESSSOR_DEVICE //使用相机自带的硬件ISP模块
|
||||
}emSdkIspProcessor;
|
||||
|
||||
//闪光灯信号控制方式
|
||||
typedef enum
|
||||
{
|
||||
STROBE_SYNC_WITH_TRIG_AUTO = 0, //和触发信号同步,触发后,相机进行曝光时,自动生成STROBE信号。此时,有效极性可设置(CameraSetStrobePolarity)。
|
||||
STROBE_SYNC_WITH_TRIG_MANUAL, //和触发信号同步,触发后,STROBE延时指定的时间后(CameraSetStrobeDelayTime),再持续指定时间的脉冲(CameraSetStrobePulseWidth),有效极性可设置(CameraSetStrobePolarity)。
|
||||
STROBE_ALWAYS_HIGH, //始终为高,忽略STROBE信号的其他设置
|
||||
STROBE_ALWAYS_LOW //始终为低,忽略STROBE信号的其他设置
|
||||
}emStrobeControl;
|
||||
|
||||
//硬件外触发的信号种类
|
||||
typedef enum
|
||||
{
|
||||
EXT_TRIG_LEADING_EDGE = 0, //上升沿触发,默认为该方式
|
||||
EXT_TRIG_TRAILING_EDGE, //下降沿触发
|
||||
EXT_TRIG_HIGH_LEVEL, //高电平触发,电平宽度决定曝光时间,仅部分型号的相机支持电平触发方式。
|
||||
EXT_TRIG_LOW_LEVEL //低电平触发,
|
||||
}emExtTrigSignal;
|
||||
|
||||
//硬件外触发时的快门方式
|
||||
typedef enum
|
||||
{
|
||||
EXT_TRIG_EXP_STANDARD = 0, //标准方式,默认为该方式。
|
||||
EXT_TRIG_EXP_GRR, //全局复位方式,部分滚动快门的CMOS型号的相机支持该方式,配合外部机械快门,可以达到全局快门的效果,适合拍高速运动的物体
|
||||
}emExtTrigShutterMode;
|
||||
|
||||
|
||||
//相机的设备信息
|
||||
typedef struct
|
||||
{
|
||||
char acProductSeries[32]; // 产品系列
|
||||
char acProductName[32]; // 产品名称
|
||||
char acFriendlyName[32]; // 产品昵称,用户可自定义改昵称,保存在相机内,用于区分多个相机同时使用,可以用CameraSetFriendlyName接口改变该昵称,设备重启后生效。
|
||||
char acLinkName[32]; // 内核符号连接名,内部使用
|
||||
char acDriverVersion[32]; // 驱动版本
|
||||
char acSensorType[32]; // sensor类型
|
||||
char acPortType[32]; // 接口类型
|
||||
char acSn[32]; // 产品唯一序列号
|
||||
UINT uInstance; // 该型号相机在该电脑上的实例索引号,用于区分同型号多相机
|
||||
} tSdkCameraDevInfo;
|
||||
|
||||
//tSdkResolutionRange结构体中SKIP、 BIN、RESAMPLE模式的掩码值
|
||||
#define MASK_2X2_HD (1<<0) //硬件SKIP、BIN、重采样 2X2
|
||||
#define MASK_3X3_HD (1<<1)
|
||||
#define MASK_4X4_HD (1<<2)
|
||||
#define MASK_5X5_HD (1<<3)
|
||||
#define MASK_6X6_HD (1<<4)
|
||||
#define MASK_7X7_HD (1<<5)
|
||||
#define MASK_8X8_HD (1<<6)
|
||||
#define MASK_9X9_HD (1<<7)
|
||||
#define MASK_10X10_HD (1<<8)
|
||||
#define MASK_11X11_HD (1<<9)
|
||||
#define MASK_12X12_HD (1<<10)
|
||||
#define MASK_13X13_HD (1<<11)
|
||||
#define MASK_14X14_HD (1<<12)
|
||||
#define MASK_15X15_HD (1<<13)
|
||||
#define MASK_16X16_HD (1<<14)
|
||||
#define MASK_17X17_HD (1<<15)
|
||||
#define MASK_2X2_SW (1<<16) //硬件SKIP、BIN、重采样 2X2
|
||||
#define MASK_3X3_SW (1<<17)
|
||||
#define MASK_4X4_SW (1<<18)
|
||||
#define MASK_5X5_SW (1<<19)
|
||||
#define MASK_6X6_SW (1<<20)
|
||||
#define MASK_7X7_SW (1<<21)
|
||||
#define MASK_8X8_SW (1<<22)
|
||||
#define MASK_9X9_SW (1<<23)
|
||||
#define MASK_10X10_SW (1<<24)
|
||||
#define MASK_11X11_SW (1<<25)
|
||||
#define MASK_12X12_SW (1<<26)
|
||||
#define MASK_13X13_SW (1<<27)
|
||||
#define MASK_14X14_SW (1<<28)
|
||||
#define MASK_15X15_SW (1<<29)
|
||||
#define MASK_16X16_SW (1<<30)
|
||||
#define MASK_17X17_SW (1<<31)
|
||||
|
||||
//相机的分辨率设定范围,用于构件UI
|
||||
typedef struct
|
||||
{
|
||||
INT iHeightMax; //图像最大高度
|
||||
INT iHeightMin; //图像最小高度
|
||||
INT iWidthMax; //图像最大宽度
|
||||
INT iWidthMin; //图像最小宽度
|
||||
UINT uSkipModeMask; //SKIP模式掩码,为0,表示不支持SKIP 。bit0为1,表示支持SKIP 2x2 ;bit1为1,表示支持SKIP 3x3....
|
||||
UINT uBinSumModeMask; //BIN(求和)模式掩码,为0,表示不支持BIN 。bit0为1,表示支持BIN 2x2 ;bit1为1,表示支持BIN 3x3....
|
||||
UINT uBinAverageModeMask; //BIN(求均值)模式掩码,为0,表示不支持BIN 。bit0为1,表示支持BIN 2x2 ;bit1为1,表示支持BIN 3x3....
|
||||
UINT uResampleMask; //硬件重采样的掩码
|
||||
} tSdkResolutionRange;
|
||||
|
||||
|
||||
//相机的分辨率描述
|
||||
typedef struct
|
||||
{
|
||||
INT iIndex; // 索引号,[0,N]表示预设的分辨率(N 为预设分辨率的最大个数,一般不超过20),OXFF 表示自定义分辨率(ROI)
|
||||
char acDescription[32]; // 该分辨率的描述信息。仅预设分辨率时该信息有效。自定义分辨率可忽略该信息
|
||||
UINT uBinSumMode; // BIN(求和)的模式,范围不能超过tSdkResolutionRange中uBinSumModeMask
|
||||
UINT uBinAverageMode; // BIN(求均值)的模式,范围不能超过tSdkResolutionRange中uBinAverageModeMask
|
||||
UINT uSkipMode; // 是否SKIP的尺寸,为0表示禁止SKIP模式,范围不能超过tSdkResolutionRange中uSkipModeMask
|
||||
UINT uResampleMask; // 硬件重采样的掩码
|
||||
INT iHOffsetFOV; // 采集视场相对于Sensor最大视场左上角的垂直偏移
|
||||
INT iVOffsetFOV; // 采集视场相对于Sensor最大视场左上角的水平偏移
|
||||
INT iWidthFOV; // 采集视场的宽度
|
||||
INT iHeightFOV; // 采集视场的高度
|
||||
INT iWidth; // 相机最终输出的图像的宽度
|
||||
INT iHeight; // 相机最终输出的图像的高度
|
||||
INT iWidthZoomHd; // 硬件缩放的宽度,不需要进行此操作的分辨率,此变量设置为0.
|
||||
INT iHeightZoomHd; // 硬件缩放的高度,不需要进行此操作的分辨率,此变量设置为0.
|
||||
INT iWidthZoomSw; // 软件缩放的宽度,不需要进行此操作的分辨率,此变量设置为0.
|
||||
INT iHeightZoomSw; // 软件缩放的高度,不需要进行此操作的分辨率,此变量设置为0.
|
||||
} tSdkImageResolution;
|
||||
|
||||
//相机白平衡色温模式描述信息
|
||||
typedef struct
|
||||
{
|
||||
INT iIndex; // 模式索引号
|
||||
char acDescription[32]; // 描述信息
|
||||
} tSdkColorTemperatureDes;
|
||||
|
||||
//相机帧率描述信息
|
||||
typedef struct
|
||||
{
|
||||
INT iIndex; // 帧率索引号,一般0对应于低速模式,1对应于普通模式,2对应于高速模式
|
||||
char acDescription[32]; // 描述信息
|
||||
} tSdkFrameSpeed;
|
||||
|
||||
//相机曝光功能范围定义
|
||||
typedef struct
|
||||
{
|
||||
UINT uiTargetMin; //自动曝光亮度目标最小值
|
||||
UINT uiTargetMax; //自动曝光亮度目标最大值
|
||||
UINT uiAnalogGainMin; //模拟增益的最小值,单位为fAnalogGainStep中定义
|
||||
UINT uiAnalogGainMax; //模拟增益的最大值,单位为fAnalogGainStep中定义
|
||||
float fAnalogGainStep; //模拟增益每增加1,对应的增加的放大倍数。例如,uiAnalogGainMin一般为16,fAnalogGainStep一般为0.125,那么最小放大倍数就是16*0.125 = 2倍
|
||||
UINT uiExposeTimeMin; //手动模式下,曝光时间的最小值,单位:行。根据CameraGetExposureLineTime可以获得一行对应的时间(微秒),从而得到整帧的曝光时间
|
||||
UINT uiExposeTimeMax; //手动模式下,曝光时间的最大值,单位:行
|
||||
} tSdkExpose;
|
||||
|
||||
//触发模式描述
|
||||
typedef struct
|
||||
{
|
||||
INT iIndex; //模式索引号
|
||||
char acDescription[32]; //该模式的描述信息
|
||||
} tSdkTrigger;
|
||||
|
||||
//传输分包大小描述(主要是针对网络相机有效)
|
||||
typedef struct
|
||||
{
|
||||
INT iIndex; //分包大小索引号
|
||||
char acDescription[32]; //对应的描述信息
|
||||
UINT iPackSize;
|
||||
} tSdkPackLength;
|
||||
|
||||
//预设的LUT表描述
|
||||
typedef struct
|
||||
{
|
||||
INT iIndex; //编号
|
||||
char acDescription[32]; //描述信息
|
||||
} tSdkPresetLut;
|
||||
|
||||
//AE算法描述
|
||||
typedef struct
|
||||
{
|
||||
INT iIndex; //编号
|
||||
char acDescription[32]; //描述信息
|
||||
} tSdkAeAlgorithm;
|
||||
|
||||
//RAW转RGB算法描述
|
||||
typedef struct
|
||||
{
|
||||
INT iIndex; //编号
|
||||
char acDescription[32]; //描述信息
|
||||
} tSdkBayerDecodeAlgorithm;
|
||||
|
||||
|
||||
//帧率统计信息
|
||||
typedef struct
|
||||
{
|
||||
INT iTotal; //当前采集的总帧数(包括错误帧)
|
||||
INT iCapture; //当前采集的有效帧的数量
|
||||
INT iLost; //当前丢帧的数量
|
||||
} tSdkFrameStatistic;
|
||||
|
||||
//相机输出的图像数据格式
|
||||
typedef struct
|
||||
{
|
||||
INT iIndex; //格式种类编号
|
||||
char acDescription[32]; //描述信息
|
||||
UINT iMediaType; //对应的图像格式编码,如CAMERA_MEDIA_TYPE_BAYGR8,在本文件中有定义。
|
||||
} tSdkMediaType;
|
||||
|
||||
//伽马的设定范围
|
||||
typedef struct
|
||||
{
|
||||
INT iMin; //最小值
|
||||
INT iMax; //最大值
|
||||
} tGammaRange;
|
||||
|
||||
//对比度的设定范围
|
||||
typedef struct
|
||||
{
|
||||
INT iMin; //最小值
|
||||
INT iMax; //最大值
|
||||
} tContrastRange;
|
||||
|
||||
//RGB三通道数字增益的设定范围
|
||||
typedef struct
|
||||
{
|
||||
INT iRGainMin; //红色增益的最小值
|
||||
INT iRGainMax; //红色增益的最大值
|
||||
INT iGGainMin; //绿色增益的最小值
|
||||
INT iGGainMax; //绿色增益的最大值
|
||||
INT iBGainMin; //蓝色增益的最小值
|
||||
INT iBGainMax; //蓝色增益的最大值
|
||||
} tRgbGainRange;
|
||||
|
||||
//饱和度设定的范围
|
||||
typedef struct
|
||||
{
|
||||
INT iMin; //最小值
|
||||
INT iMax; //最大值
|
||||
} tSaturationRange;
|
||||
|
||||
//锐化的设定范围
|
||||
typedef struct
|
||||
{
|
||||
INT iMin; //最小值
|
||||
INT iMax; //最大值
|
||||
} tSharpnessRange;
|
||||
|
||||
//ISP模块的使能信息
|
||||
typedef struct
|
||||
{
|
||||
BOOL bMonoSensor; //表示该型号相机是否为黑白相机,如果是黑白相机,则颜色相关的功能都无法调节
|
||||
BOOL bWbOnce; //表示该型号相机是否支持手动白平衡功能
|
||||
BOOL bAutoWb; //表示该型号相机是否支持自动白平衡功能
|
||||
BOOL bAutoExposure; //表示该型号相机是否支持自动曝光功能
|
||||
BOOL bManualExposure; //表示该型号相机是否支持手动曝光功能
|
||||
BOOL bAntiFlick; //表示该型号相机是否支持抗频闪功能
|
||||
BOOL bDeviceIsp; //表示该型号相机是否支持硬件ISP功能
|
||||
BOOL bForceUseDeviceIsp;//bDeviceIsp和bForceUseDeviceIsp同时为TRUE时,表示强制只用硬件ISP,不可取消。
|
||||
BOOL bZoomHD; //相机硬件是否支持图像缩放输出(只能是缩小)。
|
||||
} tSdkIspCapacity;
|
||||
|
||||
/* 定义整合的设备描述信息,这些信息可以用于动态构建UI */
|
||||
typedef struct
|
||||
{
|
||||
|
||||
tSdkTrigger *pTriggerDesc; // 触发模式
|
||||
INT iTriggerDesc; // 触发模式的个数,即pTriggerDesc数组的大小
|
||||
|
||||
tSdkImageResolution *pImageSizeDesc;// 预设分辨率选择
|
||||
INT iImageSizeDesc; // 预设分辨率的个数,即pImageSizeDesc数组的大小
|
||||
|
||||
tSdkColorTemperatureDes *pClrTempDesc;// 预设色温模式,用于白平衡
|
||||
INT iClrTempDesc;
|
||||
|
||||
tSdkMediaType *pMediaTypeDesc; // 相机输出图像格式
|
||||
INT iMediaTypdeDesc; // 相机输出图像格式的种类个数,即pMediaTypeDesc数组的大小。
|
||||
|
||||
tSdkFrameSpeed *pFrameSpeedDesc; // 可调节帧速类型,对应界面上普通 高速 和超级三种速度设置
|
||||
INT iFrameSpeedDesc; // 可调节帧速类型的个数,即pFrameSpeedDesc数组的大小。
|
||||
|
||||
tSdkPackLength *pPackLenDesc; // 传输包长度,一般用于网络设备
|
||||
INT iPackLenDesc; // 可供选择的传输分包长度的个数,即pPackLenDesc数组的大小。
|
||||
|
||||
INT iOutputIoCounts; // 可编程输出IO的个数
|
||||
INT iInputIoCounts; // 可编程输入IO的个数
|
||||
|
||||
tSdkPresetLut *pPresetLutDesc; // 相机预设的LUT表
|
||||
INT iPresetLut; // 相机预设的LUT表的个数,即pPresetLutDesc数组的大小
|
||||
|
||||
INT iUserDataMaxLen; // 指示该相机中用于保存用户数据区的最大长度。为0表示无。
|
||||
BOOL bParamInDevice; // 指示该设备是否支持从设备中读写参数组。1为支持,0不支持。
|
||||
|
||||
tSdkAeAlgorithm *pAeAlmSwDesc; // 软件自动曝光算法描述
|
||||
int iAeAlmSwDesc; // 软件自动曝光算法个数
|
||||
|
||||
tSdkAeAlgorithm *pAeAlmHdDesc; // 硬件自动曝光算法描述,为NULL表示不支持硬件自动曝光
|
||||
int iAeAlmHdDesc; // 硬件自动曝光算法个数,为0表示不支持硬件自动曝光
|
||||
|
||||
tSdkBayerDecodeAlgorithm *pBayerDecAlmSwDesc; // 软件Bayer转换为RGB数据的算法描述
|
||||
int iBayerDecAlmSwDesc; // 软件Bayer转换为RGB数据的算法个数
|
||||
|
||||
tSdkBayerDecodeAlgorithm *pBayerDecAlmHdDesc; // 硬件Bayer转换为RGB数据的算法描述,为NULL表示不支持
|
||||
int iBayerDecAlmHdDesc; // 硬件Bayer转换为RGB数据的算法个数,为0表示不支持
|
||||
|
||||
/* 图像参数的调节范围定义,用于动态构建UI*/
|
||||
tSdkExpose sExposeDesc; // 曝光的范围值
|
||||
tSdkResolutionRange sResolutionRange; // 分辨率范围描述
|
||||
tRgbGainRange sRgbGainRange; // 图像数字增益范围描述
|
||||
tSaturationRange sSaturationRange; // 饱和度范围描述
|
||||
tGammaRange sGammaRange; // 伽马范围描述
|
||||
tContrastRange sContrastRange; // 对比度范围描述
|
||||
tSharpnessRange sSharpnessRange; // 锐化范围描述
|
||||
tSdkIspCapacity sIspCapacity; // ISP能力描述
|
||||
|
||||
|
||||
} tSdkCameraCapbility;
|
||||
|
||||
|
||||
//图像帧头信息
|
||||
typedef struct
|
||||
{
|
||||
UINT uiMediaType; // 图像格式,Image Format
|
||||
UINT uBytes; // 图像数据字节数,Total bytes
|
||||
INT iWidth; // 图像的宽度,调用图像处理函数后,该变量可能被动态修改,来指示处理后的图像尺寸
|
||||
INT iHeight; // 图像的高度,调用图像处理函数后,该变量可能被动态修改,来指示处理后的图像尺寸
|
||||
INT iWidthZoomSw; // 软件缩放的宽度,不需要进行软件裁剪的图像,此变量设置为0.
|
||||
INT iHeightZoomSw; // 软件缩放的高度,不需要进行软件裁剪的图像,此变量设置为0.
|
||||
BOOL bIsTrigger; // 指示是否为触发帧 is trigger
|
||||
UINT uiTimeStamp; // 该帧的采集时间,单位0.1毫秒
|
||||
UINT uiExpTime; // 当前图像的曝光值,单位为微秒us
|
||||
float fAnalogGain; // 当前图像的模拟增益倍数
|
||||
INT iGamma; // 该帧图像的伽马设定值,仅当LUT模式为动态参数生成时有效,其余模式下为-1
|
||||
INT iContrast; // 该帧图像的对比度设定值,仅当LUT模式为动态参数生成时有效,其余模式下为-1
|
||||
INT iSaturation; // 该帧图像的饱和度设定值,对于黑白相机无意义,为0
|
||||
float fRgain; // 该帧图像处理的红色数字增益倍数,对于黑白相机无意义,为1
|
||||
float fGgain; // 该帧图像处理的绿色数字增益倍数,对于黑白相机无意义,为1
|
||||
float fBgain; // 该帧图像处理的蓝色数字增益倍数,对于黑白相机无意义,为1
|
||||
}tSdkFrameHead;
|
||||
|
||||
//图像帧描述
|
||||
typedef struct sCameraFrame
|
||||
{
|
||||
tSdkFrameHead head; //帧头
|
||||
BYTE * pBuffer; //数据区
|
||||
}tSdkFrame;
|
||||
|
||||
//图像捕获的回调函数定义
|
||||
typedef void (*CAMERA_SNAP_PROC)(CameraHandle hCamera, BYTE *pFrameBuffer, tSdkFrameHead* pFrameHead,PVOID pContext);
|
||||
|
||||
//SDK生成的相机配置页面的消息回调函数定义
|
||||
typedef void (*CAMERA_PAGE_MSG_PROC)(CameraHandle hCamera,UINT MSG,UINT uParam,PVOID pContext);
|
||||
|
||||
|
||||
//----------------------------IMAGE FORMAT DEFINE------------------------------------
|
||||
//----------------------------图像格式定义-------------------------------------------
|
||||
#define CAMERA_MEDIA_TYPE_MONO 0x01000000
|
||||
#define CAMERA_MEDIA_TYPE_RGB 0x02000000
|
||||
#define CAMERA_MEDIA_TYPE_COLOR 0x02000000
|
||||
#define CAMERA_MEDIA_TYPE_CUSTOM 0x80000000
|
||||
#define CAMERA_MEDIA_TYPE_COLOR_MASK 0xFF000000
|
||||
#define CAMERA_MEDIA_TYPE_OCCUPY1BIT 0x00010000
|
||||
#define CAMERA_MEDIA_TYPE_OCCUPY2BIT 0x00020000
|
||||
#define CAMERA_MEDIA_TYPE_OCCUPY4BIT 0x00040000
|
||||
#define CAMERA_MEDIA_TYPE_OCCUPY8BIT 0x00080000
|
||||
#define CAMERA_MEDIA_TYPE_OCCUPY10BIT 0x000A0000
|
||||
#define CAMERA_MEDIA_TYPE_OCCUPY12BIT 0x000C0000
|
||||
#define CAMERA_MEDIA_TYPE_OCCUPY16BIT 0x00100000
|
||||
#define CAMERA_MEDIA_TYPE_OCCUPY24BIT 0x00180000
|
||||
#define CAMERA_MEDIA_TYPE_OCCUPY32BIT 0x00200000
|
||||
#define CAMERA_MEDIA_TYPE_OCCUPY36BIT 0x00240000
|
||||
#define CAMERA_MEDIA_TYPE_OCCUPY48BIT 0x00300000
|
||||
#define CAMERA_MEDIA_TYPE_EFFECTIVE_PIXEL_SIZE_MASK 0x00FF0000
|
||||
#define CAMERA_MEDIA_TYPE_EFFECTIVE_PIXEL_SIZE_SHIFT 16
|
||||
|
||||
|
||||
#define CAMERA_MEDIA_TYPE_ID_MASK 0x0000FFFF
|
||||
#define CAMERA_MEDIA_TYPE_COUNT 0x46
|
||||
|
||||
/*mono*/
|
||||
#define CAMERA_MEDIA_TYPE_MONO1P (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY1BIT | 0x0037)
|
||||
#define CAMERA_MEDIA_TYPE_MONO2P (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY2BIT | 0x0038)
|
||||
#define CAMERA_MEDIA_TYPE_MONO4P (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY4BIT | 0x0039)
|
||||
#define CAMERA_MEDIA_TYPE_MONO8 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x0001)
|
||||
#define CAMERA_MEDIA_TYPE_MONO8S (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x0002)
|
||||
#define CAMERA_MEDIA_TYPE_MONO10 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0003)
|
||||
#define CAMERA_MEDIA_TYPE_MONO10_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0004)
|
||||
#define CAMERA_MEDIA_TYPE_MONO12 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0005)
|
||||
#define CAMERA_MEDIA_TYPE_MONO12_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0006)
|
||||
#define CAMERA_MEDIA_TYPE_MONO14 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0025)
|
||||
#define CAMERA_MEDIA_TYPE_MONO16 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0007)
|
||||
|
||||
/*Bayer */
|
||||
#define CAMERA_MEDIA_TYPE_BAYGR8 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x0008)
|
||||
#define CAMERA_MEDIA_TYPE_BAYRG8 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x0009)
|
||||
#define CAMERA_MEDIA_TYPE_BAYGB8 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x000A)
|
||||
#define CAMERA_MEDIA_TYPE_BAYBG8 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x000B)
|
||||
|
||||
#define CAMERA_MEDIA_TYPE_BAYGR10_MIPI (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY10BIT | 0x0026)
|
||||
#define CAMERA_MEDIA_TYPE_BAYRG10_MIPI (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY10BIT | 0x0027)
|
||||
#define CAMERA_MEDIA_TYPE_BAYGB10_MIPI (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY10BIT | 0x0028)
|
||||
#define CAMERA_MEDIA_TYPE_BAYBG10_MIPI (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY10BIT | 0x0029)
|
||||
|
||||
|
||||
#define CAMERA_MEDIA_TYPE_BAYGR10 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x000C)
|
||||
#define CAMERA_MEDIA_TYPE_BAYRG10 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x000D)
|
||||
#define CAMERA_MEDIA_TYPE_BAYGB10 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x000E)
|
||||
#define CAMERA_MEDIA_TYPE_BAYBG10 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x000F)
|
||||
|
||||
#define CAMERA_MEDIA_TYPE_BAYGR12 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0010)
|
||||
#define CAMERA_MEDIA_TYPE_BAYRG12 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0011)
|
||||
#define CAMERA_MEDIA_TYPE_BAYGB12 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0012)
|
||||
#define CAMERA_MEDIA_TYPE_BAYBG12 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0013)
|
||||
|
||||
|
||||
#define CAMERA_MEDIA_TYPE_BAYGR10_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0026)
|
||||
#define CAMERA_MEDIA_TYPE_BAYRG10_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0027)
|
||||
#define CAMERA_MEDIA_TYPE_BAYGB10_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0028)
|
||||
#define CAMERA_MEDIA_TYPE_BAYBG10_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0029)
|
||||
|
||||
#define CAMERA_MEDIA_TYPE_BAYGR12_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x002A)
|
||||
#define CAMERA_MEDIA_TYPE_BAYRG12_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x002B)
|
||||
#define CAMERA_MEDIA_TYPE_BAYGB12_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x002C)
|
||||
#define CAMERA_MEDIA_TYPE_BAYBG12_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x002D)
|
||||
|
||||
#define CAMERA_MEDIA_TYPE_BAYGR16 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x002E)
|
||||
#define CAMERA_MEDIA_TYPE_BAYRG16 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x002F)
|
||||
#define CAMERA_MEDIA_TYPE_BAYGB16 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0030)
|
||||
#define CAMERA_MEDIA_TYPE_BAYBG16 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0031)
|
||||
|
||||
/*RGB */
|
||||
#define CAMERA_MEDIA_TYPE_RGB8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x0014)
|
||||
#define CAMERA_MEDIA_TYPE_BGR8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x0015)
|
||||
#define CAMERA_MEDIA_TYPE_RGBA8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY32BIT | 0x0016)
|
||||
#define CAMERA_MEDIA_TYPE_BGRA8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY32BIT | 0x0017)
|
||||
#define CAMERA_MEDIA_TYPE_RGB10 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0018)
|
||||
#define CAMERA_MEDIA_TYPE_BGR10 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0019)
|
||||
#define CAMERA_MEDIA_TYPE_RGB12 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x001A)
|
||||
#define CAMERA_MEDIA_TYPE_BGR12 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x001B)
|
||||
#define CAMERA_MEDIA_TYPE_RGB16 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0033)
|
||||
#define CAMERA_MEDIA_TYPE_RGB10V1_PACKED (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY32BIT | 0x001C)
|
||||
#define CAMERA_MEDIA_TYPE_RGB10P32 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY32BIT | 0x001D)
|
||||
#define CAMERA_MEDIA_TYPE_RGB12V1_PACKED (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY36BIT | 0X0034)
|
||||
#define CAMERA_MEDIA_TYPE_RGB565P (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0035)
|
||||
#define CAMERA_MEDIA_TYPE_BGR565P (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0X0036)
|
||||
|
||||
/*YUV and YCbCr*/
|
||||
#define CAMERA_MEDIA_TYPE_YUV411_8_UYYVYY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x001E)
|
||||
#define CAMERA_MEDIA_TYPE_YUV422_8_UYVY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x001F)
|
||||
#define CAMERA_MEDIA_TYPE_YUV422_8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0032)
|
||||
#define CAMERA_MEDIA_TYPE_YUV8_UYV (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x0020)
|
||||
#define CAMERA_MEDIA_TYPE_YCBCR8_CBYCR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x003A)
|
||||
//CAMERA_MEDIA_TYPE_YCBCR422_8 : YYYYCbCrCbCr
|
||||
#define CAMERA_MEDIA_TYPE_YCBCR422_8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x003B)
|
||||
#define CAMERA_MEDIA_TYPE_YCBCR422_8_CBYCRY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0043)
|
||||
#define CAMERA_MEDIA_TYPE_YCBCR411_8_CBYYCRYY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x003C)
|
||||
#define CAMERA_MEDIA_TYPE_YCBCR601_8_CBYCR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x003D)
|
||||
#define CAMERA_MEDIA_TYPE_YCBCR601_422_8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x003E)
|
||||
#define CAMERA_MEDIA_TYPE_YCBCR601_422_8_CBYCRY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0044)
|
||||
#define CAMERA_MEDIA_TYPE_YCBCR601_411_8_CBYYCRYY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x003F)
|
||||
#define CAMERA_MEDIA_TYPE_YCBCR709_8_CBYCR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x0040)
|
||||
#define CAMERA_MEDIA_TYPE_YCBCR709_422_8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0041)
|
||||
#define CAMERA_MEDIA_TYPE_YCBCR709_422_8_CBYCRY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0045)
|
||||
#define CAMERA_MEDIA_TYPE_YCBCR709_411_8_CBYYCRYY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0042)
|
||||
|
||||
/*RGB Planar */
|
||||
#define CAMERA_MEDIA_TYPE_RGB8_PLANAR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x0021)
|
||||
#define CAMERA_MEDIA_TYPE_RGB10_PLANAR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0022)
|
||||
#define CAMERA_MEDIA_TYPE_RGB12_PLANAR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0023)
|
||||
#define CAMERA_MEDIA_TYPE_RGB16_PLANAR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0024)
|
||||
|
||||
|
||||
#endif
|
||||
102
others/include/camera/camera_status.h
Normal file
102
others/include/camera/camera_status.h
Normal file
@@ -0,0 +1,102 @@
|
||||
#ifndef __CAMERA_STATUS_DEF__
|
||||
#define __CAMERA_STATUS_DEF__
|
||||
|
||||
typedef int CameraSdkStatus;
|
||||
|
||||
|
||||
/*常用的宏*/
|
||||
#define SDK_SUCCESS(_FUC_) (_FUC_ == CAMERA_STATUS_SUCCESS)
|
||||
|
||||
#define SDK_UNSUCCESS(_FUC_) (_FUC_ != CAMERA_STATUS_SUCCESS)
|
||||
|
||||
#define SDK_UNSUCCESS_RETURN(_FUC_,RET) if((RET = _FUC_) != CAMERA_STATUS_SUCCESS)\
|
||||
{\
|
||||
return RET;\
|
||||
}
|
||||
|
||||
#define SDK_UNSUCCESS_BREAK(_FUC_) if(_FUC_ != CAMERA_STATUS_SUCCESS)\
|
||||
{\
|
||||
break;\
|
||||
}
|
||||
|
||||
|
||||
/* 常用错误 */
|
||||
|
||||
#define CAMERA_STATUS_SUCCESS 0 // 操作成功
|
||||
#define CAMERA_STATUS_FAILED -1 // 操作失败
|
||||
#define CAMERA_STATUS_INTERNAL_ERROR -2 // 内部错误
|
||||
#define CAMERA_STATUS_UNKNOW -3 // 未知错误
|
||||
#define CAMERA_STATUS_NOT_SUPPORTED -4 // 不支持该功能
|
||||
#define CAMERA_STATUS_NOT_INITIALIZED -5 // 初始化未完成
|
||||
#define CAMERA_STATUS_PARAMETER_INVALID -6 // 参数无效
|
||||
#define CAMERA_STATUS_PARAMETER_OUT_OF_BOUND -7 // 参数越界
|
||||
#define CAMERA_STATUS_UNENABLED -8 // 未使能
|
||||
#define CAMERA_STATUS_USER_CANCEL -9 // 用户手动取消了,比如roi面板点击取消,返回
|
||||
#define CAMERA_STATUS_PATH_NOT_FOUND -10 // 注册表中没有找到对应的路径
|
||||
#define CAMERA_STATUS_SIZE_DISMATCH -11 // 获得图像数据长度和定义的尺寸不匹配
|
||||
#define CAMERA_STATUS_TIME_OUT -12 // 超时错误
|
||||
#define CAMERA_STATUS_IO_ERROR -13 // 硬件IO错误
|
||||
#define CAMERA_STATUS_COMM_ERROR -14 // 通讯错误
|
||||
#define CAMERA_STATUS_BUS_ERROR -15 // 总线错误
|
||||
#define CAMERA_STATUS_NO_DEVICE_FOUND -16 // 没有发现设备
|
||||
#define CAMERA_STATUS_NO_LOGIC_DEVICE_FOUND -17 // 未找到逻辑设备
|
||||
#define CAMERA_STATUS_DEVICE_IS_OPENED -18 // 设备已经打开
|
||||
#define CAMERA_STATUS_DEVICE_IS_CLOSED -19 // 设备已经关闭
|
||||
#define CAMERA_STATUS_DEVICE_VEDIO_CLOSED -20 // 没有打开设备视频,调用录像相关的函数时,如果相机视频没有打开,则回返回该错误。
|
||||
#define CAMERA_STATUS_NO_MEMORY -21 // 没有足够系统内存
|
||||
#define CAMERA_STATUS_FILE_CREATE_FAILED -22 // 创建文件失败
|
||||
#define CAMERA_STATUS_FILE_INVALID -23 // 文件格式无效
|
||||
#define CAMERA_STATUS_WRITE_PROTECTED -24 // 写保护,不可写
|
||||
#define CAMERA_STATUS_GRAB_FAILED -25 // 数据采集失败
|
||||
#define CAMERA_STATUS_LOST_DATA -26 // 数据丢失,不完整
|
||||
#define CAMERA_STATUS_EOF_ERROR -27 // 未接收到帧结束符
|
||||
#define CAMERA_STATUS_BUSY -28 // 正忙(上一次操作还在进行中),此次操作不能进行
|
||||
#define CAMERA_STATUS_WAIT -29 // 需要等待(进行操作的条件不成立),可以再次尝试
|
||||
#define CAMERA_STATUS_IN_PROCESS -30 // 正在进行,已经被操作过
|
||||
#define CAMERA_STATUS_IIC_ERROR -31 // IIC传输错误
|
||||
#define CAMERA_STATUS_SPI_ERROR -32 // SPI传输错误
|
||||
#define CAMERA_STATUS_USB_CONTROL_ERROR -33 // USB控制传输错误
|
||||
#define CAMERA_STATUS_USB_BULK_ERROR -34 // USB BULK传输错误
|
||||
#define CAMERA_STATUS_SOCKET_INIT_ERROR -35 // 网络传输套件初始化失败
|
||||
#define CAMERA_STATUS_GIGE_FILTER_INIT_ERROR -36 // 网络相机内核过滤驱动初始化失败,请检查是否正确安装了驱动,或者重新安装。
|
||||
#define CAMERA_STATUS_NET_SEND_ERROR -37 // 网络数据发送错误
|
||||
#define CAMERA_STATUS_DEVICE_LOST -38 // 与网络相机失去连接,心跳检测超时
|
||||
#define CAMERA_STATUS_DATA_RECV_LESS -39 // 接收到的字节数比请求的少
|
||||
#define CAMERA_STATUS_FUNCTION_LOAD_FAILED -40 // 从文件中加载程序失败
|
||||
#define CAMERA_STATUS_CRITICAL_FILE_LOST -41 // 程序运行所必须的文件丢失。
|
||||
#define CAMERA_STATUS_SENSOR_ID_DISMATCH -42 // 固件和程序不匹配,原因是下载了错误的固件。
|
||||
#define CAMERA_STATUS_OUT_OF_RANGE -43 // 参数超出有效范围。
|
||||
#define CAMERA_STATUS_REGISTRY_ERROR -44 // 安装程序注册错误。请重新安装程序,或者运行安装目录Setup/Installer.exe
|
||||
#define CAMERA_STATUS_ACCESS_DENY -45 // 禁止访问。指定相机已经被其他程序占用时,再申请访问该相机,会返回该状态。(一个相机不能被多个程序同时访问)
|
||||
#define CAMERA_STATUS_CAMERA_NEED_RESET -46 // 表示相机需要复位后才能正常使用,此时请让相机断电重启,或者重启操作系统后,便可正常使用。
|
||||
|
||||
|
||||
|
||||
//和AIA制定的标准相同
|
||||
/*#define CAMERA_AIA_SUCCESS 0x0000 */
|
||||
#define CAMERA_AIA_PACKET_RESEND 0x0100 //该帧需要重传
|
||||
#define CAMERA_AIA_NOT_IMPLEMENTED 0x8001 //设备不支持的命令
|
||||
#define CAMERA_AIA_INVALID_PARAMETER 0x8002 //命令参数非法
|
||||
#define CAMERA_AIA_INVALID_ADDRESS 0x8003 //不可访问的地址
|
||||
#define CAMERA_AIA_WRITE_PROTECT 0x8004 //访问的对象不可写
|
||||
#define CAMERA_AIA_BAD_ALIGNMENT 0x8005 //访问的地址没有按照要求对齐
|
||||
#define CAMERA_AIA_ACCESS_DENIED 0x8006 //没有访问权限
|
||||
#define CAMERA_AIA_BUSY 0x8007 //命令正在处理中
|
||||
#define CAMERA_AIA_DEPRECATED 0x8008 //0x8008-0x0800B 0x800F 该指令已经废弃
|
||||
#define CAMERA_AIA_PACKET_UNAVAILABLE 0x800C //包无效
|
||||
#define CAMERA_AIA_DATA_OVERRUN 0x800D //数据溢出,通常是收到的数据比需要的多
|
||||
#define CAMERA_AIA_INVALID_HEADER 0x800E //数据包头部中某些区域与协议不匹配
|
||||
#define CAMERA_AIA_PACKET_NOT_YET_AVAILABLE 0x8010 //图像分包数据还未准备好,多用于触发模式,应用程序访问超时
|
||||
#define CAMERA_AIA_PACKET_AND_PREV_REMOVED_FROM_MEMORY 0x8011 //需要访问的分包已经不存在。多用于重传时数据已经不在缓冲区中
|
||||
#define CAMERA_AIA_PACKET_REMOVED_FROM_MEMORY 0x8012 //CAMERA_AIA_PACKET_AND_PREV_REMOVED_FROM_MEMORY
|
||||
#define CAMERA_AIA_NO_REF_TIME 0x0813 //没有参考时钟源。多用于时间同步的命令执行时
|
||||
#define CAMERA_AIA_PACKET_TEMPORARILY_UNAVAILABLE 0x0814 //由于信道带宽问题,当前分包暂时不可用,需稍后进行访问
|
||||
#define CAMERA_AIA_OVERFLOW 0x0815 //设备端数据溢出,通常是队列已满
|
||||
#define CAMERA_AIA_ACTION_LATE 0x0816 //命令执行已经超过有效的指定时间
|
||||
#define CAMERA_AIA_ERROR 0x8FFF //错误
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
#endif
|
||||
58
others/include/camera/camera_wrapper.h
Normal file
58
others/include/camera/camera_wrapper.h
Normal file
@@ -0,0 +1,58 @@
|
||||
//
|
||||
// Created by zhikun on 18-11-7.
|
||||
//
|
||||
|
||||
#ifndef _CAMERA_WRAPPER_H_
|
||||
#define _CAMERA_WRAPPER_H_
|
||||
|
||||
#include <additions.h>
|
||||
#include <opencv2/core.hpp>
|
||||
#include <camera/wrapper_head.h>
|
||||
|
||||
#ifdef Windows
|
||||
#include "camera/CameraApi.h"
|
||||
#elif defined(Linux) || defined(Darwin)
|
||||
#include <camera/camera_api.h>
|
||||
#endif
|
||||
|
||||
class CameraWrapper: public WrapperHead {
|
||||
friend void cameraCallback(CameraHandle hCamera, BYTE *pFrameBuffer, tSdkFrameHead* pFrameHead,PVOID pContext);
|
||||
private:
|
||||
const std::string name;
|
||||
//int mode;
|
||||
|
||||
//bool init_done;
|
||||
|
||||
unsigned char* rgb_buffer;
|
||||
int camera_cnts;
|
||||
int camera_status;
|
||||
tSdkCameraDevInfo camera_enum_list[2];
|
||||
int h_camera;
|
||||
char camera_name[32];
|
||||
|
||||
tSdkCameraCapbility tCapability;
|
||||
tSdkFrameHead frame_info;
|
||||
BYTE *pby_buffer;
|
||||
cv::Mat image_header;
|
||||
int channel;
|
||||
|
||||
RoundQueue<cv::Mat, 2> src_queue;
|
||||
public:
|
||||
int gain;
|
||||
int exposure;
|
||||
|
||||
int mode;
|
||||
bool init_done;
|
||||
|
||||
CameraWrapper(int exposure, int gain, int camera_mode=1, const std::string &n="NULL");
|
||||
~CameraWrapper() final;
|
||||
|
||||
bool init() final;
|
||||
bool read(cv::Mat& src) final;
|
||||
bool readRaw(cv::Mat& src);
|
||||
bool readProcessed(cv::Mat& src);
|
||||
bool readCallback(cv::Mat& src);
|
||||
};
|
||||
|
||||
|
||||
#endif /* _CAMERA_WRAPPER_H_ */
|
||||
43
others/include/camera/video_wrapper.h
Normal file
43
others/include/camera/video_wrapper.h
Normal file
@@ -0,0 +1,43 @@
|
||||
//
|
||||
// Created by zhikun on 18-11-16.
|
||||
// wrapper for video read from file
|
||||
//
|
||||
|
||||
#ifndef STEREOVISION_FROM_VIDEO_FILE_VIDEO_WRAPPER_H
|
||||
#define STEREOVISION_FROM_VIDEO_FILE_VIDEO_WRAPPER_H
|
||||
|
||||
|
||||
#include <opencv2/core/core.hpp>
|
||||
#include <opencv2/highgui/highgui.hpp>
|
||||
#include <opencv2/imgproc/imgproc.hpp>
|
||||
|
||||
#include "wrapper_head.h"
|
||||
|
||||
|
||||
class VideoWrapper:public WrapperHead {
|
||||
public:
|
||||
VideoWrapper(const std::string& filename);
|
||||
~VideoWrapper();
|
||||
|
||||
|
||||
/**
|
||||
* @brief initialize cameras
|
||||
* @return bool value: whether it success
|
||||
*/
|
||||
bool init() final;
|
||||
|
||||
|
||||
/**
|
||||
* @brief read images from camera
|
||||
* @param src_left : output source video of left camera
|
||||
* @param src_right : output source video of right camera
|
||||
* @return bool value: whether the reading is successful
|
||||
*/
|
||||
bool read(cv::Mat &src) final;
|
||||
private:
|
||||
cv::VideoCapture video;
|
||||
|
||||
};
|
||||
|
||||
|
||||
#endif //STEREOVISION_FROM_VIDEO_FILE_VIDEO_WRAPPER_H
|
||||
22
others/include/camera/wrapper_head.h
Normal file
22
others/include/camera/wrapper_head.h
Normal file
@@ -0,0 +1,22 @@
|
||||
//
|
||||
// Created by zhikun on 18-11-18.
|
||||
//
|
||||
|
||||
#ifndef STEREOVISION_FROM_VIDEO_FILE_WRAPPER_HEAD_H
|
||||
#define STEREOVISION_FROM_VIDEO_FILE_WRAPPER_HEAD_H
|
||||
|
||||
#include <opencv2/core/core.hpp>
|
||||
|
||||
/**
|
||||
* @brief A virtual class for wrapper of camera and video files
|
||||
*/
|
||||
class WrapperHead {
|
||||
public:
|
||||
virtual ~WrapperHead() = default;;
|
||||
virtual bool init() = 0;
|
||||
virtual bool read(cv::Mat &src) = 0;
|
||||
};
|
||||
|
||||
|
||||
|
||||
#endif //STEREOVISION_FROM_VIDEO_FILE_WRAPPER_HEAD_H
|
||||
103
others/include/config/setconfig.h
Normal file
103
others/include/config/setconfig.h
Normal file
@@ -0,0 +1,103 @@
|
||||
// 本文件定义了在不同步兵车辆上运行时需要根据车辆情况而发生变化的参数
|
||||
// 以下所有参数都给定了默认值,如果想要修改,推荐在该文件目录下新建文件config.h,并在config.h中写定自定义参数
|
||||
|
||||
#ifndef _SETCONFIG_H_
|
||||
#define _SETCONFIG_H_
|
||||
|
||||
#define WITH_CONFIG
|
||||
|
||||
#ifdef WITH_CONFIG
|
||||
#include <config/config.h>
|
||||
#else
|
||||
#warning "Without config.h"
|
||||
#endif
|
||||
|
||||
#ifndef ARMOR_CAMERA_EXPOSURE
|
||||
#define ARMOR_CAMERA_EXPOSURE (10)
|
||||
#endif
|
||||
|
||||
#ifndef ENERGY_CAMERA_EXPOSURE
|
||||
#define ENERGY_CAMERA_EXPOSURE (10)
|
||||
#endif
|
||||
|
||||
#ifndef CAMERA_RED_GAIN
|
||||
#define CAMERA_RED_GAIN (100)
|
||||
#endif
|
||||
|
||||
#ifndef CAMERA_GREEN_GAIN
|
||||
#define CAMERA_GREEN_GAIN (100)
|
||||
#endif
|
||||
|
||||
#ifndef CAMERA_BLUE_GAIN
|
||||
#define CAMERA_BLUE_GAIN (100)
|
||||
#endif
|
||||
|
||||
|
||||
#ifndef ARMOR_CAMERA_GAIN
|
||||
#define ARMOR_CAMERA_GAIN (64)
|
||||
#endif
|
||||
#ifndef ENERGY_CAMERA_GAIN
|
||||
#define ENERGY_CAMERA_GAIN (30)
|
||||
#endif
|
||||
|
||||
#ifndef YAW_AIM_KD
|
||||
#define YAW_AIM_KD (0.4)
|
||||
#endif
|
||||
#ifndef YAW_AIM_KP
|
||||
#define YAW_AIM_KP (0.75)
|
||||
#endif
|
||||
#ifndef YAW_AIM_KI
|
||||
#define YAW_AIM_KI (0.01)
|
||||
#endif
|
||||
#ifndef PITCH_AIM_KD
|
||||
#define PITCH_AIM_KD (0)
|
||||
#endif
|
||||
#ifndef PITCH_AIM_KP
|
||||
#define PITCH_AIM_KP (0)
|
||||
#endif
|
||||
#ifndef PITCH_AIM_KI
|
||||
#define PITCH_AIM_KI (0)
|
||||
#endif
|
||||
|
||||
#ifndef RED_COMPENSATE_YAW
|
||||
#define RED_COMPENSATE_YAW (5)
|
||||
#endif
|
||||
#ifndef RED_COMPENSATE_PITCH
|
||||
#define RED_COMPENSATE_PITCH (74)
|
||||
#endif
|
||||
|
||||
#ifndef BLUE_COMPENSATE_YAW
|
||||
#define BLUE_COMPENSATE_YAW (5)
|
||||
#endif
|
||||
#ifndef BLUE_COMPENSATE_PITCH
|
||||
#define BLUE_COMPENSATE_PITCH (74)
|
||||
#endif
|
||||
|
||||
#ifndef EXTRA_DELTA_X
|
||||
#define EXTRA_DELTA_X (0)
|
||||
#endif
|
||||
#ifndef EXTRA_DELTA_Y
|
||||
#define EXTRA_DELTA_Y (10)
|
||||
#endif
|
||||
|
||||
/*弹道相关参数 第一个为初速度,第二个为空气阻力系数,第三个为系统延迟*/
|
||||
#ifndef MUZZLE_VELOCITY
|
||||
#define MUZZLE_VELOCITY (11.0)
|
||||
#endif
|
||||
|
||||
#ifndef BALLISTIC_K
|
||||
#define BALLISTIC_K (0.1)
|
||||
#endif
|
||||
|
||||
#ifndef SYSTEM_DELAY
|
||||
#define SYSTEM_DELAY (50.0)
|
||||
#endif
|
||||
|
||||
// 到此为止
|
||||
|
||||
//#define GIMBAL_FLIP_MODE (-1)
|
||||
//#define CHASSIS_FLIP_MODE (-1)
|
||||
//#define WITH_TIME_BASED_CAMERA_GAIN
|
||||
#define WITH_COUNT_FPS
|
||||
|
||||
#endif /* SETCONFIG_H */
|
||||
24
others/include/constants.h
Normal file
24
others/include/constants.h
Normal file
@@ -0,0 +1,24 @@
|
||||
//
|
||||
// Created by xinyang on 19-7-8.
|
||||
//
|
||||
|
||||
#ifndef _CONSTANTS_H_
|
||||
#define _CONSTANTS_H_
|
||||
|
||||
#define PI (3.14159265459)
|
||||
|
||||
#define ENEMY_BLUE 0
|
||||
#define ENEMY_RED 1
|
||||
|
||||
#define ALLY_BLUE ENEMY_RED
|
||||
#define ALLY_RED ENEMY_BLUE
|
||||
|
||||
#define BIG_ENERGY_STATE 'b'
|
||||
#define SMALL_ENERGY_STATE 's'
|
||||
#define ARMOR_STATE 'a'
|
||||
|
||||
#define FOCUS_PIXAL_8MM (1488)
|
||||
#define FOCUS_PIXAL_5MM (917)
|
||||
#define FOCUS_PIXAL FOCUS_PIXAL_8MM
|
||||
|
||||
#endif /* _CONSTANTS_H */
|
||||
181
others/include/log.h
Normal file
181
others/include/log.h
Normal file
@@ -0,0 +1,181 @@
|
||||
//
|
||||
// Created by xinyang on 19-2-19.
|
||||
//
|
||||
// 该文件提供一个更加方便的调试信息输出方式
|
||||
// 所有输出信息分为三个LEVEL:MSG,WARNING,ERROR
|
||||
// 可使用宏LOG_LEVEL定义当前文件使用的输出LEVEL
|
||||
// 高于该LEVEL的输出讲不会被显示
|
||||
// ============================================================
|
||||
// 输出API:
|
||||
// LOG(level, format, ...)
|
||||
// arguments: level:当前输出的level
|
||||
// format:标准printf格式化字符串
|
||||
// LOGM(format, ...) 使用MSG level进行输出
|
||||
// LOGW(format, ...) 使用WARNING level进行输出
|
||||
// LOGE(format, ...) 使用ERROR level进行输出
|
||||
// ============================================================
|
||||
// 输出颜色API:(仅对部分终端生效)
|
||||
// STR_CTR(ctrs, str)
|
||||
// arguments: ctrs:该字符串对应的颜色(所有以WORD开头的宏)
|
||||
// str:需要上色的字符串
|
||||
// ============================================================
|
||||
// 时间计算API:(需要配合systime.h使用)
|
||||
// CNT_TIME(tag, codes, ...)
|
||||
// arguments: tag:显示代码块执行时间前的用户信息,支持printf格式化字符串
|
||||
// codes:需要被统计时间的代码块
|
||||
// attention: 代码块内定义的局部变量作用域仅限于该代码块
|
||||
// 代码块内不支持使用break,continue语句,将无法达到预想效果
|
||||
// 支持多出口离开代码块都能显示代码块执行时间
|
||||
//
|
||||
#ifndef _LOG_H_
|
||||
#define _LOG_H_
|
||||
|
||||
#include <stdio.h>
|
||||
#include <systime.h>
|
||||
#include <iostream>
|
||||
|
||||
/************** Define the control code *************/
|
||||
#define START_CTR "\033[0"
|
||||
#define END_CTR "m"
|
||||
#define CLEAR_CODE ";0"
|
||||
#define LIGHT_CODE ";1"
|
||||
#define LINE_CODE ";4"
|
||||
#define BLINK_CODE ";5"
|
||||
#define REVERSE_CODE ";7"
|
||||
#define VANISH_CODE ";8"
|
||||
#define WORD_WHITE_CODE ";30"
|
||||
#define WORD_RED_CODE ";31"
|
||||
#define WORD_GREEN_CODE ";32"
|
||||
#define WORD_YELLOW_CODE ";33"
|
||||
#define WORD_BLUE_CODE ";34"
|
||||
#define WORD_PURPLE_CODE ";35"
|
||||
#define WORD_CYAN_CODE ";36"
|
||||
#define WORD_GRAY_CODE ";37"
|
||||
#define BACK_WHITE_CODE ";40"
|
||||
#define BACK_RED_CODE ";41"
|
||||
#define BACK_GREEN_CODE ";42"
|
||||
#define BACK_YELLOW_CODE ";43"
|
||||
#define BACK_BLUE_CODE ";44"
|
||||
#define BACK_PURPLE_CODE ";45"
|
||||
#define BACK_CYAN_CODE ";46"
|
||||
#define BACK_GRAY_CODE ";47"
|
||||
|
||||
#define CTRS(ctrs) START_CTR ctrs END_CTR
|
||||
#define STR_CTR(ctrs, str) START_CTR ctrs END_CTR str CLEAR_ALL
|
||||
|
||||
#define WORD_WHITE WORD_WHITE_CODE
|
||||
#define WORD_RED WORD_RED_CODE
|
||||
#define WORD_GREEN WORD_GREEN_CODE
|
||||
#define WORD_YELLOW WORD_YELLOW_CODE
|
||||
#define WORD_BLUE WORD_BLUE_CODE
|
||||
#define WORD_PURPLE WORD_PURPLE_CODE
|
||||
#define WORD_CYAN WORD_CYAN_CODE
|
||||
#define WORD_GRAY WORD_GRAY_CODE
|
||||
#define WORD_LIGHT_WHITE LIGHT_CODE WORD_WHITE
|
||||
#define WORD_LIGHT_RED LIGHT_CODE WORD_RED
|
||||
#define WORD_LIGHT_GREEN LIGHT_CODE WORD_GREEN
|
||||
#define WORD_LIGHT_YELLOW LIGHT_CODE WORD_YELLOW
|
||||
#define WORD_LIGHT_BLUE LIGHT_CODE WORD_BLUE
|
||||
#define WORD_LIGHT_PURPLE LIGHT_CODE WORD_PURPLE
|
||||
#define WORD_LIGHT_CYAN LIGHT_CODE WORD_CYAN
|
||||
#define WORD_LIGHT_GRAY LIGHT_CODE WORD_GRAY
|
||||
#define CLEAR_ALL CTRS(CLEAR_CODE)
|
||||
/*************** Define the log level value ***************/
|
||||
#define LOG_NONE 0
|
||||
#define LOG_ERROR 1
|
||||
#define LOG_WARNING 2
|
||||
#define LOG_MSG 3
|
||||
#define LOG_NOTHING 4
|
||||
/************** Ensure the current log level **************/
|
||||
#ifndef LOG_LEVEL
|
||||
#define LOG_LEVEL LOG_MSG
|
||||
#endif
|
||||
#if LOG_LEVEL < LOG_NONE
|
||||
#define LOG_LEVEL LOG_NONE
|
||||
#elif LOG_LEVEL > LOG_MSG
|
||||
#define LOG_LEVEL LOG_MSG
|
||||
#endif
|
||||
/******* Ensure the color corresponding to the level ******/
|
||||
#ifndef LOG_ERROR_COLOR
|
||||
#define LOG_ERROR_COLOR WORD_RED
|
||||
#endif
|
||||
#ifndef LOG_WARNING_COLOR
|
||||
#define LOG_WARNING_COLOR WORD_YELLOW
|
||||
#endif
|
||||
#ifndef LOG_MSG_COLOR
|
||||
#define LOG_MSG_COLOR WORD_GRAY
|
||||
#endif
|
||||
#ifndef LOG_LINK_COLOR
|
||||
#define LOG_LINK_COLOR LINE_CODE WORD_BLUE
|
||||
#endif
|
||||
|
||||
/********************** log place *************************/
|
||||
#ifndef LOG_OUT
|
||||
#define LOG_OUT stdout
|
||||
#endif
|
||||
/******************** The log API *************************/
|
||||
#define LOG_0(format, ...) fprintf(LOG_OUT, format, ##__VA_ARGS__)
|
||||
#if LOG_LEVEL >= LOG_ERROR
|
||||
#define LOG_1(format, ...) fprintf(LOG_OUT, format, ##__VA_ARGS__)
|
||||
#else
|
||||
#define LOG_1(format, ...) ((void)0)
|
||||
#endif
|
||||
#if LOG_LEVEL >= LOG_WARNING
|
||||
#define LOG_2(format, ...) fprintf(LOG_OUT, format, ##__VA_ARGS__)
|
||||
#else
|
||||
#define LOG_2(format, ...) ((void)0)
|
||||
#endif
|
||||
#if LOG_LEVEL >= LOG_MSG
|
||||
#define LOG_3(format, ...) fprintf(LOG_OUT, format, ##__VA_ARGS__)
|
||||
#else
|
||||
#define LOG_3(format, ...) ((void)0)
|
||||
#endif
|
||||
#define LOG_4(format, ...) ((void)0)
|
||||
#define LOG_(level, format, ...) LOG_##level (format, ##__VA_ARGS__)
|
||||
#define LOG(level, format, ...) LOG_(level, format"\n", ##__VA_ARGS__)
|
||||
|
||||
#define LOGA(format, ...) LOG(LOG_NONE, format, ##__VA_ARGS__)
|
||||
#define LOGA_INFO(format, ...) LOG(LOG_NONE, "<%s:%d>: " format, ##__VA_ARGS__)
|
||||
#define LOGE(format, ...) LOG(LOG_ERROR, STR_CTR(LOG_ERROR_COLOR, "<ERROR>: " format), ## __VA_ARGS__)
|
||||
#define LOGW(format, ...) LOG(LOG_WARNING, STR_CTR(LOG_WARNING_COLOR,"<WARNING>: " format), ## __VA_ARGS__)
|
||||
#define LOGM(format, ...) LOG(LOG_MSG, STR_CTR(LOG_MSG_COLOR, "<MSG>: " format), ## __VA_ARGS__)
|
||||
#define LOGE_INFO(format, ...) LOG(LOG_ERROR, \
|
||||
STR_CTR(LOG_ERROR_COLOR, "<") \
|
||||
STR_CTR(LOG_LINK_COLOR, "%s:%d") \
|
||||
STR_CTR(LOG_ERROR_COLOR, " ERROR>: " format), \
|
||||
__FILE__, __LINE__, ##__VA_ARGS__)
|
||||
#define LOGW_INFO(format, ...) LOG(LOG_WARNING, \
|
||||
STR_CTR(LOG_WARNING_COLOR,"<") \
|
||||
STR_CTR(LOG_LINK_COLOR,"%s:%d") \
|
||||
STR_CTR(LOG_WARNING_COLOR, " WARNING>: " format), \
|
||||
__FILE__, __LINE__, ##__VA_ARGS__)
|
||||
#define LOGM_INFO(format, ...) LOG(LOG_MSG, \
|
||||
STR_CTR(LOG_MSG_COLOR, "<") \
|
||||
STR_CTR(LOG_LINK_COLOR, "%s:%d") \
|
||||
STR_CTR(LOG_MSG_COLOR, " MSG>: " format), \
|
||||
__FILE__, __LINE__, ##__VA_ARGS__)
|
||||
|
||||
/******************** the time counter API ************************/
|
||||
#if !defined(DO_NOT_CNT_TIME) && LOG_LEVEL > LOG_NONE
|
||||
#define CNT_TIME(tag, codes, ...) do{ \
|
||||
class { \
|
||||
private: \
|
||||
systime begin; \
|
||||
public: \
|
||||
TimeCounter(){ \
|
||||
getsystime(begin); \
|
||||
} \
|
||||
~TimeCounter(){ \
|
||||
systime end; \
|
||||
getsystime(end); \
|
||||
LOGM(tag": %.1lfms", ##__VA_ARGS__, getTimeIntervalms(end, begin)); \
|
||||
} \
|
||||
} time_cnt; \
|
||||
codes; \
|
||||
}while (0)
|
||||
#else
|
||||
#define CNT_TIME(tag, codes, ...) codes
|
||||
#endif
|
||||
#else /* _LOG_H_ */
|
||||
#warning "Multiple include of log.h, some settings may not work."
|
||||
#endif /* _LOG_H_ */
|
||||
30
others/include/options.h
Normal file
30
others/include/options.h
Normal file
@@ -0,0 +1,30 @@
|
||||
//
|
||||
// Created by xinyang on 19-3-27.
|
||||
//
|
||||
|
||||
#ifndef _OPTIONS_H_
|
||||
#define _OPTIONS_H_
|
||||
|
||||
#ifdef PATH
|
||||
#define PROJECT_DIR PATH
|
||||
#else
|
||||
#define PROJECT_DIR ""
|
||||
#endif
|
||||
|
||||
extern bool show_armor_box;
|
||||
extern bool show_armor_boxes;
|
||||
extern bool show_light_blobs;
|
||||
extern bool show_origin;
|
||||
extern bool run_with_camera;
|
||||
extern bool save_video;
|
||||
extern bool wait_uart;
|
||||
extern bool save_labelled_boxes;
|
||||
extern bool show_process;
|
||||
extern bool save_mark;
|
||||
extern bool show_info;
|
||||
extern bool run_by_frame;
|
||||
|
||||
|
||||
void processOptions(int argc, char **argv);
|
||||
|
||||
#endif /* _OPTIONS_H_ */
|
||||
61
others/include/serial.h
Normal file
61
others/include/serial.h
Normal file
@@ -0,0 +1,61 @@
|
||||
#ifndef _SERIAL_H_
|
||||
#define _SERIAL_H_
|
||||
|
||||
#ifdef Windows
|
||||
|
||||
#include <Windows.h>
|
||||
|
||||
class Serial
|
||||
{
|
||||
public:
|
||||
Serial(UINT baud = CBR_115200, char parity = 'N', UINT databits = 8, UINT stopsbits = 1, DWORD dwCommEvents = EV_RXCHAR);
|
||||
~Serial();
|
||||
|
||||
bool InitPort(UINT portNo = 1, UINT baud = CBR_9600, char parity = 'N', UINT databits = 8, UINT stopsbits = 1, DWORD dwCommEvents = EV_RXCHAR);
|
||||
UINT GetBytesInCOM() const ;
|
||||
bool WriteData(const unsigned char* pData, unsigned int length);
|
||||
bool ReadData(unsigned char* buffer, unsigned int length);
|
||||
private:
|
||||
bool openPort(UINT portNo);
|
||||
void ClosePort();
|
||||
void ErrorHandler();
|
||||
private:
|
||||
HANDLE hComm;
|
||||
UINT portNo;
|
||||
UINT baud;
|
||||
char parity;
|
||||
UINT databits;
|
||||
UINT stopsbits;
|
||||
DWORD dwCommEvents;
|
||||
};
|
||||
|
||||
#elif defined(Linux) || defined(Darwin)
|
||||
|
||||
#include <errno.h>
|
||||
#include <fcntl.h>
|
||||
#include <termios.h>
|
||||
#include <unistd.h>
|
||||
|
||||
class Serial {
|
||||
private:
|
||||
int fd;
|
||||
int nSpeed;
|
||||
char nEvent;
|
||||
int nBits;
|
||||
int nStop;
|
||||
|
||||
int set_opt(int fd, int nSpeed, char nEvent, int nBits, int nStop);
|
||||
|
||||
public:
|
||||
Serial(int nSpeed = 115200, char nEvent = 'N', int nBits = 8, int nStop = 1);
|
||||
~Serial();
|
||||
|
||||
bool InitPort(int nSpeed = 115200, char nEvent = 'N', int nBits = 8, int nStop = 1);
|
||||
// int GetBytesInCOM() const ;
|
||||
bool WriteData(const unsigned char* pData, unsigned int length);
|
||||
bool ReadData(unsigned char* buffer, unsigned int length);
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
#endif /* _SERIAL_H_ */
|
||||
23
others/include/systime.h
Normal file
23
others/include/systime.h
Normal file
@@ -0,0 +1,23 @@
|
||||
//
|
||||
// Created by xinyang on 19-7-31.
|
||||
//
|
||||
// 提供一个多平台统一的精确到毫秒的系统时间接口
|
||||
// 该时间仅用于表示相对时间
|
||||
|
||||
#ifndef _PLATFORM_H_
|
||||
#define _PLATFORM_H_
|
||||
|
||||
typedef double systime;
|
||||
|
||||
void getsystime(systime &t);
|
||||
double getTimeIntervalms(const systime &now, const systime &last);
|
||||
|
||||
#if defined(Linux) || defined(Darwin)
|
||||
#include <sys/time.h>
|
||||
#elif defined(Windows)
|
||||
#include <Windows.h>
|
||||
#else
|
||||
#error "nonsupport platform."
|
||||
#endif
|
||||
|
||||
#endif /* _PLATFORM_H_ */
|
||||
BIN
others/libMVSDK.so
Normal file
BIN
others/libMVSDK.so
Normal file
Binary file not shown.
BIN
others/libmvsdk.dylib
Normal file
BIN
others/libmvsdk.dylib
Normal file
Binary file not shown.
5
others/solver_config.yml
Normal file
5
others/solver_config.yml
Normal file
@@ -0,0 +1,5 @@
|
||||
camera_matrix: [1731.7, 0.0, 639.5, 0.0, 1726.7, 359.5, 0.0, 0.0, 1.0]
|
||||
distort_coeffs: [-0.088, 0.841, 0.0, 0.0, 0.0]
|
||||
R_gimbal2imubody: [1, 0, 0, 0, 1, 0, 0, 0, 1]
|
||||
R_camera2gimbal: [1, 0, 0, 0, 1, 0, 0, 0, 1]
|
||||
t_camera2gimbal: [0, 0, 0]
|
||||
120
others/src/additions.cpp
Normal file
120
others/src/additions.cpp
Normal file
@@ -0,0 +1,120 @@
|
||||
//
|
||||
// Created by sjturm on 19-5-17.
|
||||
//
|
||||
|
||||
#include <cstring>
|
||||
#include <iostream>
|
||||
#include <fstream>
|
||||
#include <opencv2/core/core.hpp>
|
||||
#include <opencv2/highgui/highgui.hpp>
|
||||
#include <opencv2/imgproc/imgproc.hpp>
|
||||
#include <opencv2/videoio/videoio_c.h>
|
||||
#include <additions.h>
|
||||
#include <camera/camera_wrapper.h>
|
||||
#include <armor_finder/armor_finder.h>
|
||||
#include <log.h>
|
||||
|
||||
#define RECEIVE_LOG_LEVEL LOG_MSG
|
||||
|
||||
using namespace std;
|
||||
using namespace cv;
|
||||
|
||||
extern WrapperHead *video;
|
||||
|
||||
extern Serial serial;
|
||||
extern uint8_t last_state;
|
||||
|
||||
extern ArmorFinder armor_finder;
|
||||
|
||||
void uartReceive(Serial *pSerial) {
|
||||
char buffer[40];
|
||||
LOGM(STR_CTR(WORD_LIGHT_WHITE, "data receive start!"));
|
||||
while (true) {
|
||||
memset(buffer, 0, sizeof(buffer));
|
||||
pSerial->ReadData((uint8_t *) buffer, sizeof(mcu_data)+1);
|
||||
if (buffer[sizeof(mcu_data)] == '\n') {
|
||||
memcpy(&mcu_data, buffer, sizeof(mcu_data));
|
||||
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);
|
||||
// static int t = time(nullptr);
|
||||
// static int cnt = 0;
|
||||
// if(time(nullptr) > t){
|
||||
// t = time(nullptr);
|
||||
// LOGM("fps:%d", cnt);
|
||||
// cnt = 0;
|
||||
// }else{
|
||||
// cnt++;
|
||||
// }
|
||||
}else{
|
||||
// LOGW("corrupt data!");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
cv::VideoWriter initVideoWriter(const std::string &filename_prefix) {
|
||||
cv::VideoWriter video;
|
||||
std::ifstream in(filename_prefix + "cnt.txt");
|
||||
int cnt = 0;
|
||||
if (in.is_open()) {
|
||||
in >> cnt;
|
||||
in.close();
|
||||
}
|
||||
std::string file_name = filename_prefix + std::to_string(cnt) + ".avi";
|
||||
cnt++;
|
||||
std::ofstream out(filename_prefix + "cnt.txt");
|
||||
if (out.is_open()) {
|
||||
out << cnt << std::endl;
|
||||
out.close();
|
||||
}
|
||||
video.open(file_name, CV_FOURCC('P', 'I', 'M', '1'), 90, cv::Size(640, 480), true);
|
||||
return video;
|
||||
}
|
||||
|
||||
bool checkReconnect(bool is_camera_connect) {
|
||||
if (!is_camera_connect) {
|
||||
int curr_gain = ((CameraWrapper* )video)->gain;
|
||||
int curr_exposure = ((CameraWrapper* )video)->exposure;
|
||||
int curr_mode = ((CameraWrapper* )video)->mode; // 获取原始模式
|
||||
|
||||
delete video;
|
||||
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();
|
||||
}
|
||||
return is_camera_connect;
|
||||
}
|
||||
|
||||
auto video_writer = initVideoWriter(PROJECT_DIR"/video/");
|
||||
|
||||
void saveVideos(const cv::Mat &gimbal_src) {
|
||||
if (!gimbal_src.empty()) {
|
||||
video_writer.write(gimbal_src);
|
||||
} else return;
|
||||
}
|
||||
|
||||
void showOrigin(const cv::Mat &src) {
|
||||
if (!src.empty()) {
|
||||
imshow("origin", src);
|
||||
cv::waitKey(1);
|
||||
} else return;
|
||||
}
|
||||
|
||||
void extract(cv::Mat &src) {//图像预处理,将视频切成640×480的大小
|
||||
if (src.empty()) return;
|
||||
float length = static_cast<float>(src.cols);
|
||||
float width = static_cast<float>(src.rows);
|
||||
if (length / width > 1280.0 / 1024.0) {
|
||||
length *= 1024 / width;
|
||||
resize(src, src, cv::Size(length, 1024));
|
||||
src = src(Rect((length - 1280) / 2, 0, 1280, 1024));
|
||||
} else {
|
||||
width *= 1280.0 / length;
|
||||
resize(src, src, cv::Size(1280, width));
|
||||
src = src(Rect(0, (width - 1024) / 2, 1280, 1024));
|
||||
}
|
||||
}
|
||||
|
||||
double getPointLength(const cv::Point2f &p) {
|
||||
return sqrt(p.x * p.x + p.y * p.y);
|
||||
}
|
||||
189
others/src/camera/camera_wrapper.cpp
Normal file
189
others/src/camera/camera_wrapper.cpp
Normal file
@@ -0,0 +1,189 @@
|
||||
//
|
||||
// Created by zhikun on 18-11-7.
|
||||
//
|
||||
#include <iostream>
|
||||
#include <camera/camera_wrapper.h>
|
||||
#include <log.h>
|
||||
#include <additions.h>
|
||||
#include <options.h>
|
||||
#include <config/setconfig.h>
|
||||
|
||||
using namespace std;
|
||||
using namespace cv;
|
||||
|
||||
CameraWrapper::CameraWrapper(int exposure, int gain, int camera_mode, const std::string &n) :
|
||||
name(n),
|
||||
init_done(false),
|
||||
mode(camera_mode),
|
||||
camera_cnts(2),
|
||||
camera_status(-1),
|
||||
rgb_buffer(nullptr),
|
||||
channel(3),
|
||||
gain(gain),
|
||||
exposure(exposure){
|
||||
}
|
||||
|
||||
void cameraCallback(CameraHandle hCamera, BYTE *pFrameBuffer, tSdkFrameHead* pFrameHead,PVOID pContext){
|
||||
CameraWrapper *c = (CameraWrapper*)pContext;
|
||||
CameraImageProcess(hCamera, pFrameBuffer, c->rgb_buffer, pFrameHead);
|
||||
// 使用 cv::Mat 替代 IplImage
|
||||
cv::Mat img(pFrameHead->iHeight, pFrameHead->iWidth,
|
||||
c->channel == 3 ? CV_8UC3 : CV_8UC1,
|
||||
c->rgb_buffer, pFrameHead->iWidth * c->channel);
|
||||
c->src_queue.push(img.clone());
|
||||
}
|
||||
|
||||
bool CameraWrapper::init() {
|
||||
CameraSdkInit(1);
|
||||
int camera_enumerate_device_status = CameraEnumerateDevice(camera_enum_list, &camera_cnts);
|
||||
if (camera_enumerate_device_status != CAMERA_STATUS_SUCCESS) {
|
||||
LOGE("CameraEnumerateDevice fail with %d!", camera_enumerate_device_status);
|
||||
return false;
|
||||
}
|
||||
if (camera_cnts == 0) {
|
||||
LOGE("No camera device detected!");
|
||||
return false;
|
||||
} else if (camera_cnts >= 1) {
|
||||
LOGM("%d camera device detected!", camera_cnts);
|
||||
}
|
||||
int i;
|
||||
for (i = 0; i < camera_cnts; i++) {
|
||||
camera_status = CameraInit(&camera_enum_list[i], -1, -1, &h_camera);
|
||||
if (camera_status != CAMERA_STATUS_SUCCESS) {
|
||||
CameraUnInit(h_camera);
|
||||
continue;
|
||||
}
|
||||
CameraGetFriendlyName(h_camera, camera_name);
|
||||
if (name == "NULL" || strcmp(name.data(), camera_name) == 0) {
|
||||
break;
|
||||
}
|
||||
CameraUnInit(h_camera);
|
||||
}
|
||||
if (i >= camera_cnts) {
|
||||
LOGE("No device name %s or device open error!!", name.data());
|
||||
return false;
|
||||
}
|
||||
|
||||
auto status = CameraGetCapability(h_camera, &tCapability);
|
||||
if (status != CAMERA_STATUS_SUCCESS) {
|
||||
cout << "CameraGetCapability return error code " << status << endl;
|
||||
return false;
|
||||
}
|
||||
|
||||
rgb_buffer = (unsigned char *) malloc(tCapability.sResolutionRange.iHeightMax *
|
||||
tCapability.sResolutionRange.iWidthMax * 3);
|
||||
#ifdef Windows
|
||||
char filepath[200];
|
||||
sprintf(filepath, PROJECT_DIR"/others/%s.Config", name.data());
|
||||
if (CameraReadParameterFromFile(h_camera, filepath) != CAMERA_STATUS_SUCCESS) {
|
||||
LOGE("Load parameter %s from file fail!", filepath);
|
||||
return false;
|
||||
}
|
||||
if (CameraLoadParameter(h_camera, PARAMETER_TEAM_A) != CAMERA_STATUS_SUCCESS) {
|
||||
LOGE("CameraLoadParameter %s fail!", filepath);
|
||||
return false;
|
||||
}
|
||||
LOGM("successfully loaded %s!", filepath);
|
||||
#elif defined(Linux)
|
||||
CameraReadParameterFromFile(h_camera, PROJECT_DIR"/others/MV-UB31-Group0.config");
|
||||
CameraLoadParameter(h_camera, PARAMETER_TEAM_A);
|
||||
CameraSetAeState(h_camera, false);
|
||||
CameraSetExposureTime(h_camera, exposure * 1000);
|
||||
CameraSetAnalogGain(h_camera, gain);
|
||||
#endif
|
||||
double t;
|
||||
int g;
|
||||
CameraGetExposureTime(h_camera, &t);
|
||||
CameraGetAnalogGain(h_camera, &g);
|
||||
LOGM("Exposure time: %lfms, gain:%d", t / 1000.0, g);
|
||||
/*让SDK进入工作模式,开始接收来自相机发送的图像
|
||||
数据。如果当前相机是触发模式,则需要接收到
|
||||
触发帧以后才会更新图像。 */
|
||||
CameraPlay(h_camera);
|
||||
|
||||
/*其他的相机参数设置
|
||||
例如 CameraSetExposureTime CameraGetExposureTime 设置/读取曝光时间
|
||||
CameraSetImageResolution CameraGetImageResolution 设置/读取分辨率
|
||||
CameraSetGamma、CameraSetContrast、CameraSetGain等设置图像伽马、对比度、RGB数字增益等等。
|
||||
CameraGetFriendlyName CameraSetFriendlyName 获取/设置相机名称(该名称可写入相机硬件)
|
||||
*/
|
||||
cout << tCapability.sIspCapacity.bMonoSensor << endl;
|
||||
if (tCapability.sIspCapacity.bMonoSensor) {
|
||||
channel = 1;
|
||||
CameraSetIspOutFormat(h_camera, CAMERA_MEDIA_TYPE_MONO8);
|
||||
LOGM("camera %s mono ", camera_name);
|
||||
} else {
|
||||
channel = 3;
|
||||
CameraSetIspOutFormat(h_camera, CAMERA_MEDIA_TYPE_BGR8);
|
||||
LOGM("camera %s color ", camera_name);
|
||||
}
|
||||
if(mode == 2){
|
||||
CameraSetCallbackFunction(h_camera, cameraCallback, this, nullptr);
|
||||
}
|
||||
init_done = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
bool CameraWrapper::read(cv::Mat &src) {
|
||||
if(init_done) {
|
||||
if (mode == 0)return readProcessed(src);
|
||||
if (mode == 1)return readRaw(src);
|
||||
if (mode == 2)return readCallback(src);
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
bool CameraWrapper::readRaw(cv::Mat &src) {
|
||||
if (CameraGetImageBuffer(h_camera, &frame_info, &pby_buffer, 500) == CAMERA_STATUS_SUCCESS) {
|
||||
// 使用 cv::Mat 替代 IplImage
|
||||
cv::Mat img(frame_info.iHeight, frame_info.iWidth, CV_8UC1, pby_buffer, frame_info.iWidth);
|
||||
src = img.clone();
|
||||
|
||||
//在成功调用CameraGetImageBuffer后,必须调用CameraReleaseImageBuffer来释放获得的buffer。
|
||||
//否则再次调用CameraGetImageBuffer时,程序将被挂起一直阻塞,直到其他线程中调用CameraReleaseImageBuffer来释放了buffer
|
||||
CameraReleaseImageBuffer(h_camera, pby_buffer);
|
||||
|
||||
return true;
|
||||
} else {
|
||||
src = cv::Mat();
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
bool CameraWrapper::readProcessed(cv::Mat &src) {
|
||||
if (CameraGetImageBuffer(h_camera, &frame_info, &pby_buffer, 500) == CAMERA_STATUS_SUCCESS) {
|
||||
CameraImageProcess(h_camera, pby_buffer, rgb_buffer,
|
||||
&frame_info); // this function is super slow, better not to use it.
|
||||
// 使用 cv::Mat 替代 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);
|
||||
src = img.clone();
|
||||
//在成功调用CameraGetImageBuffer后,必须调用CameraReleaseImageBuffer来释放获得的buffer。
|
||||
//否则再次调用CameraGetImageBuffer时,程序将被挂起一直阻塞,直到其他线程中调用CameraReleaseImageBuffer来释放了buffer
|
||||
CameraReleaseImageBuffer(h_camera, pby_buffer);
|
||||
return true;
|
||||
} else {
|
||||
src = cv::Mat();
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
bool CameraWrapper::readCallback(cv::Mat &src) {
|
||||
systime ts, te;
|
||||
getsystime(ts);
|
||||
while(src_queue.empty()){
|
||||
getsystime(te);
|
||||
if(getTimeIntervalms(te, ts) > 500){
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return src_queue.pop(src);
|
||||
}
|
||||
|
||||
CameraWrapper::~CameraWrapper() {
|
||||
CameraUnInit(h_camera);
|
||||
//注意,先反初始化后再free
|
||||
if (rgb_buffer != nullptr)
|
||||
free(rgb_buffer);
|
||||
}
|
||||
21
others/src/camera/video_wrapper.cpp
Normal file
21
others/src/camera/video_wrapper.cpp
Normal file
@@ -0,0 +1,21 @@
|
||||
//
|
||||
// Created by xixiliadorabarry on 1/24/19.
|
||||
//
|
||||
|
||||
#include "camera/video_wrapper.h"
|
||||
|
||||
|
||||
VideoWrapper::VideoWrapper(const std::string &filename) {
|
||||
video.open(filename);
|
||||
}
|
||||
|
||||
VideoWrapper::~VideoWrapper() = default;
|
||||
|
||||
|
||||
bool VideoWrapper::init() {
|
||||
return video.isOpened();
|
||||
}
|
||||
|
||||
bool VideoWrapper::read(cv::Mat &src) {
|
||||
return video.read(src);
|
||||
}
|
||||
135
others/src/options.cpp
Normal file
135
others/src/options.cpp
Normal file
@@ -0,0 +1,135 @@
|
||||
//
|
||||
// Created by xinyang on 19-3-27.
|
||||
//
|
||||
|
||||
#include <options.h>
|
||||
#include <log.h>
|
||||
#include <cstring>
|
||||
#include <map>
|
||||
#include <string>
|
||||
|
||||
bool show_armor_box = true;
|
||||
bool show_armor_boxes = false;
|
||||
bool show_light_blobs = false;
|
||||
bool show_origin = false;
|
||||
bool run_with_camera = true;
|
||||
bool save_video = false;
|
||||
bool wait_uart = false;
|
||||
bool save_labelled_boxes = false;
|
||||
bool show_process = false;
|
||||
bool save_mark = false;
|
||||
|
||||
bool show_info = true;
|
||||
bool run_by_frame = false;
|
||||
|
||||
// 使用map保存所有选项及其描述和操作,加快查找速度。
|
||||
std::map<std::string, std::pair<std::string, void(*)(void)>> options = {
|
||||
{"--help",{
|
||||
"show the help information.", [](){
|
||||
LOG(LOG_MSG, "<HELP>: " STR_CTR(WORD_BLUE, "All options below are for debug use."));
|
||||
for(const auto &option : options){
|
||||
LOG(LOG_MSG, "<HELP>: " STR_CTR(WORD_GREEN, "%s: %s"), option.first.data(), option.second.first.data());
|
||||
}
|
||||
}
|
||||
}},
|
||||
{"--show-armor-box", {
|
||||
"show the aim box.", []() {
|
||||
show_armor_box = true;
|
||||
LOGM("Enable show armor box");
|
||||
}
|
||||
}},
|
||||
{"--show-armor-boxes",{
|
||||
"show the candidate aim boxes.", [](){
|
||||
show_armor_boxes = true;
|
||||
LOGM("Enable show armor boxes");
|
||||
}
|
||||
}},
|
||||
{"--show-light-blobs",{
|
||||
"show the candidate light blobs.", [](){
|
||||
show_light_blobs = true;
|
||||
LOGM("Enable show light blobs");
|
||||
}
|
||||
}},
|
||||
{"--show-origin", {
|
||||
"show the origin image.", [](){
|
||||
show_origin = true;
|
||||
LOGM("Enable show origin");
|
||||
}
|
||||
}},
|
||||
{"--run-with-camera", {
|
||||
"start the program with camera directly without asking.", []() {
|
||||
run_with_camera = true;
|
||||
LOGM("Run with camera!");
|
||||
}
|
||||
}},
|
||||
{"--save-video", {
|
||||
"save the video.", [](){
|
||||
save_video = true;
|
||||
LOGM("Enable save video!");
|
||||
}
|
||||
}},
|
||||
{"--save-labelled-boxes",{
|
||||
"save the candidate boxes with their id labels.", [](){
|
||||
save_labelled_boxes = true;
|
||||
LOGM("labelled armor boxes will be saved!");
|
||||
}
|
||||
}},
|
||||
{"--wait-uart", {
|
||||
"wait uart until ready before running.", [](){
|
||||
wait_uart = true;
|
||||
LOGM("Enable wait uart!");
|
||||
}
|
||||
}},
|
||||
{"--run-by-frame",{
|
||||
"run the code frame by frame.(normally used when run video)", [](){
|
||||
run_by_frame = true;
|
||||
LOGM("Enable run frame by frame");
|
||||
}
|
||||
}},
|
||||
{"--show-process", {
|
||||
"", [](){
|
||||
show_process = true;
|
||||
LOGM("Enable show processed image!");
|
||||
}
|
||||
}},
|
||||
|
||||
{"--save-mark", {
|
||||
"", [](){
|
||||
save_mark = true;
|
||||
LOGM("Write down mark");
|
||||
}
|
||||
}},
|
||||
{"--show-info", {
|
||||
"", [](){
|
||||
show_info = true;
|
||||
LOGM("Show information!");
|
||||
}
|
||||
}},
|
||||
{"--show-all", {
|
||||
"show all image windows.", [](){
|
||||
show_armor_box = true;
|
||||
LOGM("Enable show armor box");
|
||||
show_armor_boxes = true;
|
||||
LOGM("Enable show armor boxes");
|
||||
show_light_blobs = true;
|
||||
LOGM("Enable show light blobs");
|
||||
show_origin = true;
|
||||
LOGM("Enable show origin");
|
||||
show_process = true;
|
||||
LOGM("Enable show processed image");
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
void processOptions(int argc, char **argv) {
|
||||
if (argc >= 2) {
|
||||
for (int i = 1; i < argc; i++) {
|
||||
auto key = options.find(std::string(argv[i])); // 寻找对应选项。
|
||||
if(key != options.end()){
|
||||
key->second.second();
|
||||
}else{
|
||||
LOGW("Unknown option: %s. Use --help to see options.", argv[i]);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
342
others/src/serial.cpp
Normal file
342
others/src/serial.cpp
Normal file
@@ -0,0 +1,342 @@
|
||||
#include <serial.h>
|
||||
#include <options.h>
|
||||
#include <iostream>
|
||||
|
||||
//#define LOG_LEVEL LOG_NONE
|
||||
#include <log.h>
|
||||
|
||||
using namespace std;
|
||||
|
||||
#ifdef Windows
|
||||
|
||||
Serial::Serial(UINT baud, char parity, UINT databits, UINT stopsbits, DWORD dwCommEvents) :
|
||||
hComm(INVALID_HANDLE_VALUE),
|
||||
portNo(3),
|
||||
parity(parity),
|
||||
databits(databits),
|
||||
stopsbits(stopsbits),
|
||||
dwCommEvents(dwCommEvents){
|
||||
if (wait_uart) {
|
||||
LOGM("Waiting for serial COM%d", portNo);
|
||||
while (InitPort(portNo, baud, parity, databits, stopsbits, dwCommEvents) == false);
|
||||
LOGM("Port COM%d open success!", portNo);
|
||||
} else {
|
||||
if (InitPort(portNo, baud, parity, databits, stopsbits, dwCommEvents)) {
|
||||
LOGM("Port COM%d open success!", portNo);
|
||||
} else {
|
||||
LOGE("Port COM%d open fail!", portNo);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
Serial::~Serial() {
|
||||
ClosePort();
|
||||
}
|
||||
|
||||
void Serial::ErrorHandler() {
|
||||
if (wait_uart) {
|
||||
LOGE("Serial COM%d offline, waiting for serial COM%d", portNo, portNo);
|
||||
while (InitPort(portNo, baud, parity, databits, stopsbits, dwCommEvents) == false);
|
||||
LOGM("Port COM%d reopen success!", portNo);
|
||||
}
|
||||
}
|
||||
|
||||
bool Serial::openPort(UINT portNo) {
|
||||
char szPort[50];
|
||||
sprintf_s(szPort, "COM%d", portNo);
|
||||
|
||||
/** 打开指定的串口 */
|
||||
hComm = CreateFileA(szPort, /** 设备名,COM1,COM2等 */
|
||||
GENERIC_READ | GENERIC_WRITE, /** 访问模式,可同时读写 */
|
||||
0, /** 共享模式,0表示不共享 */
|
||||
NULL, /** 安全性设置,一般使用NULL */
|
||||
OPEN_EXISTING, /** 该参数表示设备必须存在,否则创建失败 */
|
||||
0,
|
||||
0);
|
||||
|
||||
return hComm != INVALID_HANDLE_VALUE;
|
||||
}
|
||||
|
||||
void Serial::ClosePort() {
|
||||
/** 如果有串口被打开,关闭它 */
|
||||
if (hComm != INVALID_HANDLE_VALUE) {
|
||||
CloseHandle(hComm);
|
||||
hComm = INVALID_HANDLE_VALUE;
|
||||
}
|
||||
}
|
||||
|
||||
bool Serial::InitPort(UINT portNo, UINT baud, char parity, UINT databits, UINT stopsbits, DWORD dwCommEvents) {
|
||||
/** 临时变量,将制定参数转化为字符串形式,以构造DCB结构 */
|
||||
char szDCBparam[50];
|
||||
sprintf_s(szDCBparam, "baud=%d parity=%c data=%d stop=%d", baud, parity, databits, stopsbits);
|
||||
|
||||
if (!openPort(portNo)){
|
||||
cout << "open error!" << endl;
|
||||
return false;
|
||||
}
|
||||
|
||||
BOOL bIsSuccess = TRUE;
|
||||
COMMTIMEOUTS CommTimeouts;
|
||||
CommTimeouts.ReadIntervalTimeout = 0;
|
||||
CommTimeouts.ReadTotalTimeoutMultiplier = 0;
|
||||
CommTimeouts.ReadTotalTimeoutConstant = 0;
|
||||
CommTimeouts.WriteTotalTimeoutMultiplier = 0;
|
||||
CommTimeouts.WriteTotalTimeoutConstant = 0;
|
||||
if (bIsSuccess) {
|
||||
bIsSuccess = SetCommTimeouts(hComm, &CommTimeouts);
|
||||
} else {
|
||||
cout << "SetCommTimeouts error!" << endl;
|
||||
}
|
||||
|
||||
DCB dcb;
|
||||
if (bIsSuccess) {
|
||||
/** 获取当前串口配置参数,并且构造串口DCB参数 */
|
||||
bIsSuccess = GetCommState(hComm, &dcb);
|
||||
bIsSuccess = BuildCommDCB(szDCBparam, &dcb);
|
||||
if (!bIsSuccess) {
|
||||
|
||||
cout << "Create dcb fail with "<< GetLastError() << endl;
|
||||
}
|
||||
/** 开启RTS flow控制 */
|
||||
dcb.fRtsControl = RTS_CONTROL_ENABLE;
|
||||
}
|
||||
|
||||
if (bIsSuccess) {
|
||||
/** 使用DCB参数配置串口状态 */
|
||||
bIsSuccess = SetCommState(hComm, &dcb);
|
||||
if (!bIsSuccess) {
|
||||
cout << "SetCommState error!" << endl;
|
||||
}
|
||||
}
|
||||
|
||||
/** 清空串口缓冲区 */
|
||||
PurgeComm(hComm, PURGE_RXCLEAR | PURGE_TXCLEAR | PURGE_RXABORT | PURGE_TXABORT);
|
||||
|
||||
return bIsSuccess;
|
||||
}
|
||||
|
||||
UINT Serial::GetBytesInCOM() const {
|
||||
DWORD dwError = 0; /** 错误码 */
|
||||
COMSTAT comstat; /** COMSTAT结构体,记录通信设备的状态信息 */
|
||||
memset(&comstat, 0, sizeof(COMSTAT));
|
||||
|
||||
UINT BytesInQue = 0;
|
||||
/** 在调用ReadFile和WriteFile之前,通过本函数清除以前遗留的错误标志 */
|
||||
if (ClearCommError(hComm, &dwError, &comstat)) {
|
||||
BytesInQue = comstat.cbInQue; /** 获取在输入缓冲区中的字节数 */
|
||||
}
|
||||
|
||||
return BytesInQue;
|
||||
}
|
||||
|
||||
bool Serial::WriteData(const unsigned char* pData, unsigned int length) {
|
||||
if (hComm == INVALID_HANDLE_VALUE) {
|
||||
ErrorHandler();
|
||||
return false;
|
||||
}
|
||||
|
||||
/** 向缓冲区写入指定量的数据 */
|
||||
BOOL bResult = TRUE;
|
||||
DWORD BytesToSend = 0;
|
||||
bResult = WriteFile(hComm, pData, length, &BytesToSend, NULL);
|
||||
if (!bResult) {
|
||||
DWORD dwError = GetLastError();
|
||||
/** 清空串口缓冲区 */
|
||||
PurgeComm(hComm, PURGE_RXCLEAR | PURGE_RXABORT);
|
||||
ErrorHandler();
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
bool Serial::ReadData(unsigned char *buffer, unsigned int length) {
|
||||
if (hComm == INVALID_HANDLE_VALUE) {
|
||||
ErrorHandler();
|
||||
return false;
|
||||
}
|
||||
|
||||
/** 从缓冲区读取length字节的数据 */
|
||||
BOOL bResult = TRUE;
|
||||
DWORD totalRead = 0, onceRead = 0;
|
||||
while (totalRead < length) {
|
||||
bResult = ReadFile(hComm, buffer, length-totalRead, &onceRead, NULL);
|
||||
totalRead += onceRead;
|
||||
if ((!bResult)) {
|
||||
/** 获取错误码,可以根据该错误码查出错误原因 */
|
||||
DWORD dwError = GetLastError();
|
||||
|
||||
/** 清空串口缓冲区 */
|
||||
PurgeComm(hComm, PURGE_RXCLEAR | PURGE_RXABORT);
|
||||
ErrorHandler();
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return bResult;
|
||||
}
|
||||
|
||||
#elif defined(Linux) || defined(Darwin)
|
||||
|
||||
#include <string.h>
|
||||
|
||||
using namespace std;
|
||||
|
||||
string get_uart_dev_name() {
|
||||
FILE *ls = popen("ls /dev/ttyCH341USB* --color=never", "r");
|
||||
char name[20] = {0};
|
||||
fscanf(ls, "%s", name);
|
||||
return name;
|
||||
}
|
||||
|
||||
Serial::Serial(int nSpeed, char nEvent, int nBits, int nStop) :
|
||||
nSpeed(nSpeed), nEvent(nEvent), nBits(nBits), nStop(nStop) {
|
||||
if (wait_uart) {
|
||||
LOGM("Wait for serial be ready!");
|
||||
while (!InitPort(nSpeed, nEvent, nBits, nStop));
|
||||
LOGM("Port set successfully!");
|
||||
} else {
|
||||
if (InitPort(nSpeed, nEvent, nBits, nStop)) {
|
||||
LOGM("Port set successfully!");
|
||||
} else {
|
||||
LOGE("Port set fail!");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
Serial::~Serial() {
|
||||
close(fd);
|
||||
fd = -1;
|
||||
}
|
||||
|
||||
bool Serial::InitPort(int nSpeed, char nEvent, int nBits, int nStop) {
|
||||
string name = get_uart_dev_name();
|
||||
if (name == "") {
|
||||
return false;
|
||||
}
|
||||
if ((fd = open(name.data(), O_RDWR)) < 0) {
|
||||
return false;
|
||||
}
|
||||
if (set_opt(fd, nSpeed, nEvent, nBits, nStop) < 0) {
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
//int GetBytesInCOM() const {
|
||||
//
|
||||
//}
|
||||
|
||||
bool Serial::WriteData(const unsigned char *pData, unsigned int length) {
|
||||
int cnt = 0, curr = 0;
|
||||
if (fd <= 0){
|
||||
if(wait_uart){
|
||||
InitPort(nSpeed, nEvent, nBits, nStop);
|
||||
}
|
||||
return false;
|
||||
}
|
||||
while ((curr = write(fd, pData + cnt, length - cnt)) > 0 && (cnt += curr) < length);
|
||||
if (curr < 0) {
|
||||
LOGE("Serial offline!");
|
||||
close(fd);
|
||||
if (wait_uart) {
|
||||
InitPort(nSpeed, nEvent, nBits, nStop);
|
||||
}
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
bool Serial::ReadData(unsigned char *buffer, unsigned int length) {
|
||||
int cnt = 0, curr = 0;
|
||||
while ((curr = read(fd, buffer + cnt, length - cnt)) > 0 && (cnt += curr) < length);
|
||||
if (curr < 0) {
|
||||
LOGE("Serial offline!");
|
||||
close(fd);
|
||||
if (wait_uart) {
|
||||
InitPort(nSpeed, nEvent, nBits, nStop);
|
||||
}
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
int Serial::set_opt(int fd, int nSpeed, char nEvent, int nBits, int nStop) {
|
||||
termios newtio{}, oldtio{};
|
||||
if (tcgetattr(fd, &oldtio) != 0) {
|
||||
perror("SetupSerial 1");
|
||||
return -1;
|
||||
}
|
||||
bzero(&newtio, sizeof(newtio));
|
||||
newtio.c_cflag |= CLOCAL | CREAD;
|
||||
newtio.c_cflag &= ~CSIZE;
|
||||
|
||||
switch (nBits) {
|
||||
case 7:
|
||||
newtio.c_cflag |= CS7;
|
||||
break;
|
||||
case 8:
|
||||
newtio.c_cflag |= CS8;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
switch (nEvent) {
|
||||
case 'O': //奇校验
|
||||
newtio.c_cflag |= PARENB;
|
||||
newtio.c_cflag |= PARODD;
|
||||
newtio.c_iflag |= (INPCK | ISTRIP);
|
||||
break;
|
||||
case 'E': //偶校验
|
||||
newtio.c_iflag |= (INPCK | ISTRIP);
|
||||
newtio.c_cflag |= PARENB;
|
||||
newtio.c_cflag &= ~PARODD;
|
||||
break;
|
||||
case 'N': //无校验
|
||||
newtio.c_cflag &= ~PARENB;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
switch (nSpeed) {
|
||||
case 2400:
|
||||
cfsetispeed(&newtio, B2400);
|
||||
cfsetospeed(&newtio, B2400);
|
||||
break;
|
||||
case 4800:
|
||||
cfsetispeed(&newtio, B4800);
|
||||
cfsetospeed(&newtio, B4800);
|
||||
break;
|
||||
case 9600:
|
||||
cfsetispeed(&newtio, B9600);
|
||||
cfsetospeed(&newtio, B9600);
|
||||
break;
|
||||
case 115200:
|
||||
cfsetispeed(&newtio, B115200);
|
||||
cfsetospeed(&newtio, B115200);
|
||||
break;
|
||||
default:
|
||||
cfsetispeed(&newtio, B9600);
|
||||
cfsetospeed(&newtio, B9600);
|
||||
break;
|
||||
}
|
||||
|
||||
if (nStop == 1) {
|
||||
newtio.c_cflag &= ~CSTOPB;
|
||||
} else if (nStop == 2) {
|
||||
newtio.c_cflag |= CSTOPB;
|
||||
}
|
||||
|
||||
newtio.c_cc[VTIME] = 0;
|
||||
newtio.c_cc[VMIN] = 0;
|
||||
tcflush(fd, TCIFLUSH);
|
||||
if ((tcsetattr(fd, TCSANOW, &newtio)) != 0) {
|
||||
perror("com set error");
|
||||
return -1;
|
||||
}
|
||||
printf("set done!\n");
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
#endif /* switch os */
|
||||
36
others/src/systime.cpp
Normal file
36
others/src/systime.cpp
Normal file
@@ -0,0 +1,36 @@
|
||||
//
|
||||
// Created by xinyang on 19-7-31.
|
||||
//
|
||||
#include <systime.h>
|
||||
|
||||
#if defined(Linux) || defined(Darwin)
|
||||
|
||||
static systime getsystime(){
|
||||
timeval tv;
|
||||
gettimeofday(&tv, nullptr);
|
||||
return tv.tv_usec / 1000.0 + tv.tv_sec * 1000.0;
|
||||
}
|
||||
|
||||
void getsystime(systime &t) {
|
||||
static systime time_base = getsystime();
|
||||
timeval tv;
|
||||
gettimeofday(&tv, nullptr);
|
||||
t = tv.tv_usec / 1000.0 + tv.tv_sec * 1000.0 - time_base;
|
||||
}
|
||||
|
||||
#elif defined(Windows)
|
||||
|
||||
void getsystime(systime &t){
|
||||
SYSTEMTIME tv;
|
||||
GetLocalTime(&tv);
|
||||
t = tv.wMilliseconds + tv.wSecond * 1000.0;
|
||||
}
|
||||
|
||||
#else
|
||||
#error "nonsupport platform."
|
||||
#endif
|
||||
|
||||
|
||||
double getTimeIntervalms(const systime &now, const systime &last) {
|
||||
return now - last;
|
||||
}
|
||||
232
tools/TrainCNN/backward.py
Executable file
232
tools/TrainCNN/backward.py
Executable file
@@ -0,0 +1,232 @@
|
||||
#!/usr/bin/python3
|
||||
print("Preparing...")
|
||||
import tensorflow as tf
|
||||
import os
|
||||
from tqdm import tqdm
|
||||
import generate
|
||||
import forward
|
||||
import cv2
|
||||
import numpy as np
|
||||
import mvsdk
|
||||
|
||||
print("Finish!")
|
||||
|
||||
|
||||
def save_kernal(fp, val):
|
||||
print(val.shape[2], file=fp)
|
||||
print(val.shape[3], file=fp)
|
||||
print(val.shape[1], file=fp)
|
||||
print(val.shape[0], file=fp)
|
||||
for in_channel in range(val.shape[2]):
|
||||
for out_channel in range(val.shape[3]):
|
||||
for row in range(val.shape[0]):
|
||||
for col in range(val.shape[1]):
|
||||
print(val[row][col][in_channel][out_channel], file=fp)
|
||||
|
||||
|
||||
def save_weight_mat(fp, val):
|
||||
print(val.shape[0], file=fp)
|
||||
print(val.shape[1], file=fp)
|
||||
for row in range(val.shape[0]):
|
||||
for col in range(val.shape[1]):
|
||||
print(val[row][col], file=fp)
|
||||
|
||||
|
||||
def save_bias(fp, val):
|
||||
print(val.shape[0], file=fp)
|
||||
for i in range(val.shape[0]):
|
||||
print(val[i], file=fp)
|
||||
|
||||
|
||||
def save_para(folder, paras, names, info):
|
||||
os.system("mkdir %s/%s" % (folder, info))
|
||||
for para, name in zip(paras, names):
|
||||
fp = open("%s/%s/%s" % (folder, info, name), "w")
|
||||
if name[-1:] == "b":
|
||||
save_bias(fp, para)
|
||||
elif name[:2] == "fc":
|
||||
save_weight_mat(fp, para)
|
||||
elif name[:4] == "conv":
|
||||
save_kernal(fp, para)
|
||||
fp.close()
|
||||
|
||||
|
||||
STEPS = 100000
|
||||
BATCH = 40
|
||||
LEARNING_RATE_BASE = 0.0003
|
||||
LEARNING_RATE_DECAY = 0.99
|
||||
MOVING_AVERAGE_DECAY = 0.99
|
||||
|
||||
|
||||
def train(dataset, show_bar=False):
|
||||
x = tf.placeholder(tf.float32, [None, generate.SRC_ROWS, generate.SRC_COLS, generate.SRC_CHANNELS])
|
||||
y_ = tf.placeholder(tf.float32, [None, forward.OUTPUT_NODES])
|
||||
keep_rate = tf.placeholder(tf.float32)
|
||||
nodes, vars, vars_name = forward.forward(x, 0.01, keep_rate)
|
||||
y = nodes[-1]
|
||||
|
||||
ce = tf.nn.sparse_softmax_cross_entropy_with_logits(logits=y, labels=tf.argmax(y_, 1))
|
||||
# ce = tf.nn.weighted_cross_entropy_with_logits(logits=y, labels=tf.argmax(y_, 1), pos_weight=1)
|
||||
cem = tf.reduce_mean(ce)
|
||||
loss = cem + tf.add_n(tf.get_collection("losses"))
|
||||
|
||||
global_step = tf.Variable(0, trainable=False)
|
||||
learning_rate = tf.train.exponential_decay(
|
||||
LEARNING_RATE_BASE,
|
||||
global_step,
|
||||
len(dataset.train_samples) / BATCH,
|
||||
LEARNING_RATE_DECAY,
|
||||
staircase=False)
|
||||
train_step = tf.train.AdamOptimizer(learning_rate).minimize(loss, global_step=global_step)
|
||||
|
||||
ema = tf.train.ExponentialMovingAverage(MOVING_AVERAGE_DECAY, global_step)
|
||||
ema_op = ema.apply(tf.trainable_variables())
|
||||
with tf.control_dependencies([train_step, ema_op]):
|
||||
train_op = tf.no_op(name='train')
|
||||
|
||||
correct_prediction = tf.equal(tf.argmax(y, 1), tf.argmax(y_, 1))
|
||||
accuracy = tf.reduce_mean(tf.cast(correct_prediction, tf.float32))
|
||||
|
||||
config = tf.ConfigProto(gpu_options=tf.GPUOptions(allow_growth=True))
|
||||
with tf.Session(config=config) as sess:
|
||||
init_op = tf.global_variables_initializer()
|
||||
sess.run(init_op)
|
||||
|
||||
bar = tqdm(range(STEPS), ascii=True, dynamic_ncols=True)
|
||||
for i in bar:
|
||||
images_samples, labels_samples = dataset.sample_train_sets(BATCH, 0.03)
|
||||
|
||||
_, loss_value, step = sess.run(
|
||||
[train_op, loss, global_step],
|
||||
feed_dict={x: images_samples, y_: labels_samples, keep_rate: 0.3}
|
||||
)
|
||||
|
||||
if step % 500 == 0:
|
||||
test_images, test_labels = dataset.sample_test_sets(10000)
|
||||
test_acc, output = sess.run([accuracy, y],
|
||||
feed_dict={x: test_images, y_: test_labels, keep_rate: 1.0})
|
||||
output = np.argmax(output, axis=1)
|
||||
real = np.argmax(test_labels, axis=1)
|
||||
print("=============test-set===============")
|
||||
for n in range(forward.OUTPUT_NODES):
|
||||
print("label: %d, precise: %f, recall: %f" %
|
||||
(n, np.mean(real[output == n] == n), np.mean(output[real == n] == n)))
|
||||
|
||||
train_images, train_labels = dataset.sample_train_sets(10000)
|
||||
train_acc, output = sess.run([accuracy, y],
|
||||
feed_dict={x: train_images, y_: train_labels, keep_rate: 1.0})
|
||||
output = np.argmax(output, axis=1)
|
||||
real = np.argmax(train_labels, axis=1)
|
||||
print("=============train-set===============")
|
||||
for n in range(forward.OUTPUT_NODES):
|
||||
print("label: %d, precise: %f, recall: %f" %
|
||||
(n, np.mean(real[output == n] == n), np.mean(output[real == n] == n)))
|
||||
print("\n")
|
||||
if train_acc >= 0.99 and test_acc >= 0.99:
|
||||
vars_val = sess.run(vars)
|
||||
save_para(
|
||||
"model",
|
||||
vars_val,
|
||||
vars_name,
|
||||
"steps:%d-train_acc:%f-test_acc:%f" % (step, train_acc, test_acc)
|
||||
)
|
||||
bar.set_postfix({"loss": loss_value, "train_acc": train_acc, "test_acc": test_acc})
|
||||
# print("save done!")
|
||||
|
||||
# pred = sess.run(y, feed_dict={x: test_images, keep_rate:1.0})
|
||||
|
||||
# nodes_val = sess.run(nodes, feed_dict={x:test_images})
|
||||
# return vars_val, nodes_val
|
||||
DevList = mvsdk.CameraEnumerateDevice()
|
||||
nDev = len(DevList)
|
||||
if nDev < 1:
|
||||
print("No camera was found!")
|
||||
return
|
||||
|
||||
for i, DevInfo in enumerate(DevList):
|
||||
print("{}: {} {}".format(i, DevInfo.GetFriendlyName(), DevInfo.GetPortType()))
|
||||
i = 0 if nDev == 1 else int(input("Select camera: "))
|
||||
DevInfo = DevList[i]
|
||||
print(DevInfo)
|
||||
|
||||
# 打开相机
|
||||
hCamera = 0
|
||||
try:
|
||||
hCamera = mvsdk.CameraInit(DevInfo, -1, -1)
|
||||
except mvsdk.CameraException as e:
|
||||
print("CameraInit Failed({}): {}".format(e.error_code, e.message))
|
||||
return
|
||||
|
||||
# 获取相机特性描述
|
||||
cap = mvsdk.CameraGetCapability(hCamera)
|
||||
|
||||
# 判断是黑白相机还是彩色相机
|
||||
monoCamera = (cap.sIspCapacity.bMonoSensor != 0)
|
||||
|
||||
# 黑白相机让ISP直接输出MONO数据,而不是扩展成R=G=B的24位灰度
|
||||
if monoCamera:
|
||||
mvsdk.CameraSetIspOutFormat(hCamera, mvsdk.CAMERA_MEDIA_TYPE_MONO8)
|
||||
else:
|
||||
mvsdk.CameraSetIspOutFormat(hCamera, mvsdk.CAMERA_MEDIA_TYPE_BGR8)
|
||||
|
||||
# 相机模式切换成连续采集
|
||||
mvsdk.CameraSetTriggerMode(hCamera, 0)
|
||||
|
||||
# 手动曝光,曝光时间30ms
|
||||
mvsdk.CameraSetAeState(hCamera, 0)
|
||||
mvsdk.CameraSetExposureTime(hCamera, 30 * 1000)
|
||||
|
||||
# 让SDK内部取图线程开始工作
|
||||
mvsdk.CameraPlay(hCamera)
|
||||
|
||||
# 计算RGB buffer所需的大小,这里直接按照相机的最大分辨率来分配
|
||||
FrameBufferSize = cap.sResolutionRange.iWidthMax * cap.sResolutionRange.iHeightMax * (1 if monoCamera else 3)
|
||||
|
||||
# 分配RGB buffer,用来存放ISP输出的图像
|
||||
# 备注:从相机传输到PC端的是RAW数据,在PC端通过软件ISP转为RGB数据(如果是黑白相机就不需要转换格式,但是ISP还有其它处理,所以也需要分配这个buffer)
|
||||
pFrameBuffer = mvsdk.CameraAlignMalloc(FrameBufferSize, 16)
|
||||
|
||||
while (cv2.waitKey(1) & 0xFF) != ord('q'):
|
||||
# 从相机取一帧图片
|
||||
try:
|
||||
pRawData, FrameHead = mvsdk.CameraGetImageBuffer(hCamera, 200)
|
||||
mvsdk.CameraImageProcess(hCamera, pRawData, pFrameBuffer, FrameHead)
|
||||
mvsdk.CameraReleaseImageBuffer(hCamera, pRawData)
|
||||
# 此时图片已经存储在pFrameBuffer中,对于彩色相机pFrameBuffer=RGB数据,黑白相机pFrameBuffer=8位灰度数据
|
||||
# 把pFrameBuffer转换成opencv的图像格式以进行后续算法处理
|
||||
frame_data = (mvsdk.c_ubyte * FrameHead.uBytes).from_address(pFrameBuffer)
|
||||
frame = np.frombuffer(frame_data, dtype=np.uint8)
|
||||
frame = frame.reshape((FrameHead.iHeight, FrameHead.iWidth,
|
||||
1 if FrameHead.uiMediaType == mvsdk.CAMERA_MEDIA_TYPE_MONO8 else 3))
|
||||
|
||||
frame = cv2.resize(frame, (640, 480), interpolation=cv2.INTER_LINEAR)
|
||||
cv2.imshow("Press q to end", frame)
|
||||
if (cv2.waitKey(1) & 0xFF) == ord(' '):
|
||||
roi = cv2.selectROI("roi", frame)
|
||||
roi = frame[roi[1]:roi[1] + roi[3], roi[0]:roi[0] + roi[2]]
|
||||
print(roi)
|
||||
cv2.imshow("box", roi)
|
||||
image = cv2.resize(roi, (48, 36))
|
||||
image = image.astype(np.float32) / 255.0
|
||||
out = sess.run(y, feed_dict={x: [image]})
|
||||
print(out)
|
||||
print(np.argmax(out))
|
||||
|
||||
except mvsdk.CameraException as e:
|
||||
if e.error_code != mvsdk.CAMERA_STATUS_TIME_OUT:
|
||||
print("CameraGetImageBuffer failed({}): {}".format(e.error_code, e.message))
|
||||
|
||||
# 关闭相机
|
||||
mvsdk.CameraUnInit(hCamera)
|
||||
|
||||
# 释放帧缓存
|
||||
mvsdk.CameraAlignFree(pFrameBuffer)
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
# import os
|
||||
# os.environ["CUDA_DEVICE_ORDER"] = "PCI_BUS_ID"
|
||||
# os.environ["CUDA_VISIBLE_DEVICES"] = "-1"
|
||||
dataset = generate.DataSet("/home/xinyang/Workspace/box_resize")
|
||||
train(dataset, show_bar=True)
|
||||
input("press enter to continue...")
|
||||
94
tools/TrainCNN/cv_grab.py
Normal file
94
tools/TrainCNN/cv_grab.py
Normal file
@@ -0,0 +1,94 @@
|
||||
#coding=utf-8
|
||||
import cv2
|
||||
import numpy as np
|
||||
import mvsdk
|
||||
|
||||
def main_loop():
|
||||
# 枚举相机
|
||||
DevList = mvsdk.CameraEnumerateDevice()
|
||||
nDev = len(DevList)
|
||||
if nDev < 1:
|
||||
print("No camera was found!")
|
||||
return
|
||||
|
||||
for i, DevInfo in enumerate(DevList):
|
||||
print("{}: {} {}".format(i, DevInfo.GetFriendlyName(), DevInfo.GetPortType()))
|
||||
i = 0 if nDev == 1 else int(input("Select camera: "))
|
||||
DevInfo = DevList[i]
|
||||
print(DevInfo)
|
||||
|
||||
# 打开相机
|
||||
hCamera = 0
|
||||
try:
|
||||
hCamera = mvsdk.CameraInit(DevInfo, -1, -1)
|
||||
except mvsdk.CameraException as e:
|
||||
print("CameraInit Failed({}): {}".format(e.error_code, e.message) )
|
||||
return
|
||||
|
||||
# 获取相机特性描述
|
||||
cap = mvsdk.CameraGetCapability(hCamera)
|
||||
|
||||
# 判断是黑白相机还是彩色相机
|
||||
monoCamera = (cap.sIspCapacity.bMonoSensor != 0)
|
||||
|
||||
# 黑白相机让ISP直接输出MONO数据,而不是扩展成R=G=B的24位灰度
|
||||
if monoCamera:
|
||||
mvsdk.CameraSetIspOutFormat(hCamera, mvsdk.CAMERA_MEDIA_TYPE_MONO8)
|
||||
else:
|
||||
mvsdk.CameraSetIspOutFormat(hCamera, mvsdk.CAMERA_MEDIA_TYPE_BGR8)
|
||||
|
||||
# 相机模式切换成连续采集
|
||||
mvsdk.CameraSetTriggerMode(hCamera, 0)
|
||||
|
||||
# 手动曝光,曝光时间30ms
|
||||
mvsdk.CameraSetAeState(hCamera, 0)
|
||||
mvsdk.CameraSetExposureTime(hCamera, 30 * 1000)
|
||||
|
||||
# 让SDK内部取图线程开始工作
|
||||
mvsdk.CameraPlay(hCamera)
|
||||
|
||||
# 计算RGB buffer所需的大小,这里直接按照相机的最大分辨率来分配
|
||||
FrameBufferSize = cap.sResolutionRange.iWidthMax * cap.sResolutionRange.iHeightMax * (1 if monoCamera else 3)
|
||||
|
||||
# 分配RGB buffer,用来存放ISP输出的图像
|
||||
# 备注:从相机传输到PC端的是RAW数据,在PC端通过软件ISP转为RGB数据(如果是黑白相机就不需要转换格式,但是ISP还有其它处理,所以也需要分配这个buffer)
|
||||
pFrameBuffer = mvsdk.CameraAlignMalloc(FrameBufferSize, 16)
|
||||
|
||||
while (cv2.waitKey(1) & 0xFF) != ord('q'):
|
||||
# 从相机取一帧图片
|
||||
try:
|
||||
pRawData, FrameHead = mvsdk.CameraGetImageBuffer(hCamera, 200)
|
||||
mvsdk.CameraImageProcess(hCamera, pRawData, pFrameBuffer, FrameHead)
|
||||
mvsdk.CameraReleaseImageBuffer(hCamera, pRawData)
|
||||
|
||||
# 此时图片已经存储在pFrameBuffer中,对于彩色相机pFrameBuffer=RGB数据,黑白相机pFrameBuffer=8位灰度数据
|
||||
# 把pFrameBuffer转换成opencv的图像格式以进行后续算法处理
|
||||
frame_data = (mvsdk.c_ubyte * FrameHead.uBytes).from_address(pFrameBuffer)
|
||||
frame = np.frombuffer(frame_data, dtype=np.uint8)
|
||||
frame = frame.reshape((FrameHead.iHeight, FrameHead.iWidth, 1 if FrameHead.uiMediaType == mvsdk.CAMERA_MEDIA_TYPE_MONO8 else 3) )
|
||||
|
||||
frame = cv2.resize(frame, (640,480), interpolation = cv2.INTER_LINEAR)
|
||||
cv2.imshow("Press q to end", frame)
|
||||
roi = cv2.selectROI("roi", frame)
|
||||
roi = frame[roi[1]:roi[1]+roi[3], roi[0]:roi[0]+roi[2]]
|
||||
print(roi)
|
||||
cv2.imshow("box", roi)
|
||||
|
||||
|
||||
except mvsdk.CameraException as e:
|
||||
if e.error_code != mvsdk.CAMERA_STATUS_TIME_OUT:
|
||||
print("CameraGetImageBuffer failed({}): {}".format(e.error_code, e.message) )
|
||||
|
||||
# 关闭相机
|
||||
mvsdk.CameraUnInit(hCamera)
|
||||
|
||||
# 释放帧缓存
|
||||
mvsdk.CameraAlignFree(pFrameBuffer)
|
||||
|
||||
def main():
|
||||
try:
|
||||
main_loop()
|
||||
finally:
|
||||
cv2.destroyAllWindows()
|
||||
|
||||
main()
|
||||
114
tools/TrainCNN/forward.py
Normal file
114
tools/TrainCNN/forward.py
Normal file
@@ -0,0 +1,114 @@
|
||||
import tensorflow as tf
|
||||
|
||||
|
||||
def get_weight(shape, regularizer=None):
|
||||
w = tf.Variable(tf.truncated_normal(shape, stddev=0.1))
|
||||
if regularizer is not None:
|
||||
tf.add_to_collection('losses', tf.contrib.layers.l2_regularizer(regularizer)(w))
|
||||
return w
|
||||
|
||||
|
||||
def get_bias(shape):
|
||||
b = tf.Variable(tf.zeros(shape))
|
||||
return b
|
||||
|
||||
|
||||
def conv2d(x, w):
|
||||
return tf.nn.conv2d(x, w, strides=[1, 1, 1, 1], padding="VALID")
|
||||
|
||||
|
||||
def avg_pool_2x2(x):
|
||||
return tf.nn.avg_pool(x, ksize=[1, 2, 2, 1], strides=[1, 2, 2, 1], padding="VALID")
|
||||
|
||||
|
||||
def max_pool_2x2(x):
|
||||
return tf.nn.max_pool(x, ksize=[1, 2, 2, 1], strides=[1, 2, 2, 1], padding="VALID")
|
||||
|
||||
|
||||
# 第一层卷积核大小
|
||||
CONV1_KERNAL_SIZE = 5
|
||||
|
||||
# 第一层卷积输出通道数
|
||||
CONV1_OUTPUT_CHANNELS = 6
|
||||
|
||||
# 第二层卷积核大小
|
||||
CONV2_KERNAL_SIZE = 3
|
||||
|
||||
# 第二层卷积输出通道数
|
||||
CONV2_OUTPUT_CHANNELS = 10
|
||||
|
||||
# 第三层卷积核大小
|
||||
CONV3_KERNAL_SIZE = 3
|
||||
|
||||
# 第三层卷积输出通道数
|
||||
CONV3_OUTPUT_CHANNELS = 14
|
||||
|
||||
# 第一层全连接宽度
|
||||
FC1_OUTPUT_NODES = 60
|
||||
|
||||
# 第二层全连接宽度(输出标签类型数)
|
||||
FC2_OUTPUT_NODES = 15
|
||||
|
||||
# 输出标签类型数
|
||||
OUTPUT_NODES = FC2_OUTPUT_NODES
|
||||
|
||||
|
||||
def forward(x, regularizer=None, keep_rate=tf.constant(1.0)):
|
||||
vars = []
|
||||
vars_name = []
|
||||
nodes = []
|
||||
|
||||
conv1_w = get_weight(
|
||||
[CONV1_KERNAL_SIZE, CONV1_KERNAL_SIZE, int(x.shape[3]), CONV1_OUTPUT_CHANNELS]
|
||||
)
|
||||
conv1_b = get_bias([CONV1_OUTPUT_CHANNELS])
|
||||
conv1 = tf.nn.relu(tf.nn.bias_add(conv2d(x, conv1_w), conv1_b))
|
||||
pool1 = avg_pool_2x2(conv1)
|
||||
print("conv1: ", conv1.shape)
|
||||
print("pool1: ", pool1.shape)
|
||||
vars.extend([conv1_w, conv1_b])
|
||||
vars_name.extend(["conv1_w", "conv1_b"])
|
||||
nodes.extend([conv1, pool1])
|
||||
|
||||
conv2_w = get_weight(
|
||||
[CONV2_KERNAL_SIZE, CONV2_KERNAL_SIZE, CONV1_OUTPUT_CHANNELS, CONV2_OUTPUT_CHANNELS]
|
||||
)
|
||||
conv2_b = get_bias([CONV2_OUTPUT_CHANNELS])
|
||||
conv2 = tf.nn.relu(tf.nn.bias_add(conv2d(pool1, conv2_w), conv2_b))
|
||||
pool2 = avg_pool_2x2(conv2)
|
||||
print("conv2: ", conv2.shape)
|
||||
vars.extend([conv2_w, conv2_b])
|
||||
vars_name.extend(["conv2_w", "conv2_b"])
|
||||
nodes.extend([conv2, pool2])
|
||||
|
||||
conv3_w = get_weight(
|
||||
[CONV3_KERNAL_SIZE, CONV3_KERNAL_SIZE, CONV2_OUTPUT_CHANNELS, CONV3_OUTPUT_CHANNELS]
|
||||
)
|
||||
conv3_b = get_bias([CONV3_OUTPUT_CHANNELS])
|
||||
conv3 = tf.nn.relu(tf.nn.bias_add(conv2d(pool2, conv3_w), conv3_b))
|
||||
print("conv3: ", conv3.shape)
|
||||
vars.extend([conv3_w, conv3_b])
|
||||
vars_name.extend(["conv3_w", "conv3_b"])
|
||||
nodes.extend([conv3])
|
||||
|
||||
conv_shape = conv3.get_shape().as_list()
|
||||
node = conv_shape[1] * conv_shape[2] * conv_shape[3]
|
||||
reshaped = tf.reshape(conv3, [-1, node])
|
||||
reshaped = tf.nn.dropout(reshaped, keep_rate)
|
||||
print("reshaped: ", reshaped.shape)
|
||||
|
||||
fc1_w = get_weight([node, FC1_OUTPUT_NODES], regularizer)
|
||||
fc1_b = get_bias([FC1_OUTPUT_NODES])
|
||||
fc1 = tf.nn.relu(tf.matmul(reshaped, fc1_w) + fc1_b)
|
||||
vars.extend([fc1_w, fc1_b])
|
||||
vars_name.extend(["fc1_w", "fc1_b"])
|
||||
nodes.extend([fc1])
|
||||
|
||||
fc2_w = get_weight([FC1_OUTPUT_NODES, FC2_OUTPUT_NODES], regularizer)
|
||||
fc2_b = get_bias([FC2_OUTPUT_NODES])
|
||||
fc2 = tf.matmul(fc1, fc2_w) + fc2_b
|
||||
vars.extend([fc2_w, fc2_b])
|
||||
vars_name.extend(["fc2_w", "fc2_b"])
|
||||
nodes.extend([fc2])
|
||||
|
||||
return nodes, vars, vars_name
|
||||
104
tools/TrainCNN/generate.py
Normal file
104
tools/TrainCNN/generate.py
Normal file
@@ -0,0 +1,104 @@
|
||||
import numpy as np
|
||||
import os
|
||||
import cv2
|
||||
import random
|
||||
from tqdm import tqdm
|
||||
from forward import OUTPUT_NODES
|
||||
|
||||
# 原图像行数
|
||||
SRC_ROWS = 36
|
||||
|
||||
# 原图像列数
|
||||
SRC_COLS = 48
|
||||
|
||||
# 原图像通道数
|
||||
SRC_CHANNELS = 3
|
||||
|
||||
|
||||
class DataSet:
|
||||
def __init__(self, folder):
|
||||
self.train_samples = []
|
||||
self.train_labels = []
|
||||
self.test_samples = []
|
||||
self.test_labels = []
|
||||
self.generate_data_sets(folder)
|
||||
|
||||
def file2nparray(self, name):
|
||||
image = cv2.imread(name)
|
||||
image = cv2.resize(image, (SRC_COLS, SRC_ROWS))
|
||||
image = image.astype(np.float32)
|
||||
return image / 255.0
|
||||
|
||||
def id2label(self, id):
|
||||
a = np.zeros([OUTPUT_NODES])
|
||||
a[id] = 1
|
||||
return a[:]
|
||||
|
||||
def generate_data_sets(self, folder):
|
||||
sets = []
|
||||
for i in range(OUTPUT_NODES):
|
||||
dir = "%s/id%d" % (folder, i)
|
||||
files = os.listdir(dir)
|
||||
for file in tqdm(files, postfix={"loading id": i}, dynamic_ncols=True):
|
||||
if file[-3:] == "jpg":
|
||||
sample = self.file2nparray("%s/%s" % (dir, file))
|
||||
label = self.id2label(i)
|
||||
if random.random() < 0.7:
|
||||
self.train_samples.append(sample)
|
||||
self.train_labels.append(label)
|
||||
if i == 0:
|
||||
tmp = sample.copy()
|
||||
tmp = tmp[:, :, ::-1]
|
||||
self.train_samples.append(tmp)
|
||||
self.train_labels.append(label)
|
||||
else:
|
||||
tmp = sample.copy()
|
||||
tmp = 1.2 * tmp
|
||||
tmp = np.where(tmp > 1, 1, tmp)
|
||||
tmp = np.where(tmp < 0, 0, tmp)
|
||||
self.train_samples.append(tmp)
|
||||
self.train_labels.append(label)
|
||||
tmp = sample.copy()
|
||||
tmp = 0.8 * tmp
|
||||
tmp = np.where(tmp > 1, 1, tmp)
|
||||
tmp = np.where(tmp < 0, 0, tmp)
|
||||
self.train_samples.append(tmp)
|
||||
self.train_labels.append(label)
|
||||
else:
|
||||
self.test_samples.append(sample)
|
||||
self.test_labels.append(label)
|
||||
self.train_samples = np.array(self.train_samples)
|
||||
self.train_labels = np.array(self.train_labels)
|
||||
self.test_samples = np.array(self.test_samples)
|
||||
self.test_labels = np.array(self.test_labels)
|
||||
return sets
|
||||
|
||||
def sample_train_sets(self, length, std=0.0):
|
||||
samples = []
|
||||
labels = []
|
||||
for i in range(length):
|
||||
id = random.randint(0, len(self.train_samples) - 1)
|
||||
samples.append(self.train_samples[id])
|
||||
labels.append(self.train_labels[id])
|
||||
samples = np.array(samples).copy()
|
||||
samples += np.random.normal(0, std, samples.shape)
|
||||
labels = np.array(labels)
|
||||
return samples, labels
|
||||
|
||||
def sample_test_sets(self, length, std=0.0):
|
||||
samples = []
|
||||
labels = []
|
||||
for i in range(length):
|
||||
id = random.randint(0, len(self.test_samples) - 1)
|
||||
samples.append(self.test_samples[id])
|
||||
labels.append(self.test_labels[id])
|
||||
samples = np.array(samples).copy()
|
||||
samples += np.random.normal(0, std, samples.shape)
|
||||
labels = np.array(labels)
|
||||
return samples, labels
|
||||
|
||||
def all_train_sets(self, std=0.0):
|
||||
return self.train_samples[:], self.train_labels[:]
|
||||
|
||||
def all_test_sets(self, std=0.0):
|
||||
return self.test_samples[:], self.test_labels[:]
|
||||
111
tools/TrainCNN/grab.py
Normal file
111
tools/TrainCNN/grab.py
Normal file
@@ -0,0 +1,111 @@
|
||||
#coding=utf-8
|
||||
import mvsdk
|
||||
|
||||
def main():
|
||||
# 枚举相机
|
||||
DevList = mvsdk.CameraEnumerateDevice()
|
||||
nDev = len(DevList)
|
||||
if nDev < 1:
|
||||
print("No camera was found!")
|
||||
return
|
||||
|
||||
for i, DevInfo in enumerate(DevList):
|
||||
print("{}: {} {}".format(i, DevInfo.GetFriendlyName(), DevInfo.GetPortType()))
|
||||
i = 0 if nDev == 1 else int(input("Select camera: "))
|
||||
DevInfo = DevList[i]
|
||||
print(DevInfo)
|
||||
|
||||
# 打开相机
|
||||
hCamera = 0
|
||||
try:
|
||||
hCamera = mvsdk.CameraInit(DevInfo, -1, -1)
|
||||
except mvsdk.CameraException as e:
|
||||
print("CameraInit Failed({}): {}".format(e.error_code, e.message) )
|
||||
return
|
||||
|
||||
# 获取相机特性描述
|
||||
cap = mvsdk.CameraGetCapability(hCamera)
|
||||
PrintCapbility(cap)
|
||||
|
||||
# 判断是黑白相机还是彩色相机
|
||||
monoCamera = (cap.sIspCapacity.bMonoSensor != 0)
|
||||
|
||||
# 黑白相机让ISP直接输出MONO数据,而不是扩展成R=G=B的24位灰度
|
||||
if monoCamera:
|
||||
mvsdk.CameraSetIspOutFormat(hCamera, mvsdk.CAMERA_MEDIA_TYPE_MONO8)
|
||||
|
||||
# 相机模式切换成连续采集
|
||||
mvsdk.CameraSetTriggerMode(hCamera, 0)
|
||||
|
||||
# 手动曝光,曝光时间30ms
|
||||
mvsdk.CameraSetAeState(hCamera, 0)
|
||||
mvsdk.CameraSetExposureTime(hCamera, 30 * 1000)
|
||||
|
||||
# 让SDK内部取图线程开始工作
|
||||
mvsdk.CameraPlay(hCamera)
|
||||
|
||||
# 计算RGB buffer所需的大小,这里直接按照相机的最大分辨率来分配
|
||||
FrameBufferSize = cap.sResolutionRange.iWidthMax * cap.sResolutionRange.iHeightMax * (1 if monoCamera else 3)
|
||||
|
||||
# 分配RGB buffer,用来存放ISP输出的图像
|
||||
# 备注:从相机传输到PC端的是RAW数据,在PC端通过软件ISP转为RGB数据(如果是黑白相机就不需要转换格式,但是ISP还有其它处理,所以也需要分配这个buffer)
|
||||
pFrameBuffer = mvsdk.CameraAlignMalloc(FrameBufferSize, 16)
|
||||
|
||||
# 从相机取一帧图片
|
||||
try:
|
||||
pRawData, FrameHead = mvsdk.CameraGetImageBuffer(hCamera, 2000)
|
||||
mvsdk.CameraImageProcess(hCamera, pRawData, pFrameBuffer, FrameHead)
|
||||
mvsdk.CameraReleaseImageBuffer(hCamera, pRawData)
|
||||
|
||||
# 此时图片已经存储在pFrameBuffer中,对于彩色相机pFrameBuffer=RGB数据,黑白相机pFrameBuffer=8位灰度数据
|
||||
# 该示例中我们只是把图片保存到硬盘文件中
|
||||
status = mvsdk.CameraSaveImage(hCamera, "./grab.bmp", pFrameBuffer, FrameHead, mvsdk.FILE_BMP, 100)
|
||||
if status == mvsdk.CAMERA_STATUS_SUCCESS:
|
||||
print("Save image successfully. image_size = {}X{}".format(FrameHead.iWidth, FrameHead.iHeight) )
|
||||
else:
|
||||
print("Save image failed. err={}".format(status) )
|
||||
except mvsdk.CameraException as e:
|
||||
print("CameraGetImageBuffer failed({}): {}".format(e.error_code, e.message) )
|
||||
|
||||
# 关闭相机
|
||||
mvsdk.CameraUnInit(hCamera)
|
||||
|
||||
# 释放帧缓存
|
||||
mvsdk.CameraAlignFree(pFrameBuffer)
|
||||
|
||||
def PrintCapbility(cap):
|
||||
for i in range(cap.iTriggerDesc):
|
||||
desc = cap.pTriggerDesc[i]
|
||||
print("{}: {}".format(desc.iIndex, desc.GetDescription()) )
|
||||
for i in range(cap.iImageSizeDesc):
|
||||
desc = cap.pImageSizeDesc[i]
|
||||
print("{}: {}".format(desc.iIndex, desc.GetDescription()) )
|
||||
for i in range(cap.iClrTempDesc):
|
||||
desc = cap.pClrTempDesc[i]
|
||||
print("{}: {}".format(desc.iIndex, desc.GetDescription()) )
|
||||
for i in range(cap.iMediaTypeDesc):
|
||||
desc = cap.pMediaTypeDesc[i]
|
||||
print("{}: {}".format(desc.iIndex, desc.GetDescription()) )
|
||||
for i in range(cap.iFrameSpeedDesc):
|
||||
desc = cap.pFrameSpeedDesc[i]
|
||||
print("{}: {}".format(desc.iIndex, desc.GetDescription()) )
|
||||
for i in range(cap.iPackLenDesc):
|
||||
desc = cap.pPackLenDesc[i]
|
||||
print("{}: {}".format(desc.iIndex, desc.GetDescription()) )
|
||||
for i in range(cap.iPresetLut):
|
||||
desc = cap.pPresetLutDesc[i]
|
||||
print("{}: {}".format(desc.iIndex, desc.GetDescription()) )
|
||||
for i in range(cap.iAeAlmSwDesc):
|
||||
desc = cap.pAeAlmSwDesc[i]
|
||||
print("{}: {}".format(desc.iIndex, desc.GetDescription()) )
|
||||
for i in range(cap.iAeAlmHdDesc):
|
||||
desc = cap.pAeAlmHdDesc[i]
|
||||
print("{}: {}".format(desc.iIndex, desc.GetDescription()) )
|
||||
for i in range(cap.iBayerDecAlmSwDesc):
|
||||
desc = cap.pBayerDecAlmSwDesc[i]
|
||||
print("{}: {}".format(desc.iIndex, desc.GetDescription()) )
|
||||
for i in range(cap.iBayerDecAlmHdDesc):
|
||||
desc = cap.pBayerDecAlmHdDesc[i]
|
||||
print("{}: {}".format(desc.iIndex, desc.GetDescription()) )
|
||||
|
||||
main()
|
||||
2344
tools/TrainCNN/mvsdk.py
Normal file
2344
tools/TrainCNN/mvsdk.py
Normal file
File diff suppressed because it is too large
Load Diff
52
tools/analysis.py
Normal file
52
tools/analysis.py
Normal file
@@ -0,0 +1,52 @@
|
||||
import matplotlib.pyplot as plt
|
||||
import numpy as np
|
||||
|
||||
fsend = open("send.info")
|
||||
frecv = open("recv.info")
|
||||
|
||||
send_lines = fsend.readlines()[:-1]
|
||||
recv_lines = frecv.readlines()[:-1]
|
||||
|
||||
send_infos = [line.split(" ") for line in send_lines]
|
||||
recv_infos = [line.split(" ") for line in recv_lines]
|
||||
|
||||
send_times = [float(info[0]) for info in send_infos]
|
||||
recv_times = [float(info[0]) for info in recv_infos]
|
||||
|
||||
send_yaw = [float(info[1]) for info in send_infos]
|
||||
TargetAngle= [float(info[1]) for info in recv_infos]
|
||||
RealAngle = [float(info[2]) for info in recv_infos]
|
||||
|
||||
length = min(len(send_times), len(recv_times))
|
||||
|
||||
send_times = send_times[:length]
|
||||
recv_times = recv_times[:length]
|
||||
send_yaw = send_yaw[:length]
|
||||
TargetAngle= TargetAngle[:length]
|
||||
RealAngle = RealAngle[:length]
|
||||
|
||||
time_base = min(send_times[0], recv_times[0])
|
||||
|
||||
send_times = np.array(send_times) - time_base
|
||||
recv_times = np.array(recv_times) - time_base
|
||||
|
||||
TargetAngle = TargetAngle[:300]
|
||||
RealAngle = RealAngle[:300]
|
||||
send_times = send_times[:300]
|
||||
recv_times = recv_times[:300]
|
||||
send_yaw = send_yaw[:300]
|
||||
|
||||
TargetAngle = np.array(TargetAngle)
|
||||
TargetAngle -= TargetAngle.mean()
|
||||
RealAngle = np.array(RealAngle)
|
||||
RealAngle -= RealAngle.mean()
|
||||
|
||||
plt.plot(send_times, send_yaw, label="send-yaw")
|
||||
plt.plot(recv_times, TargetAngle,label="TargetAngle")
|
||||
plt.plot(recv_times, RealAngle, label="RealAngle")
|
||||
plt.scatter(send_times, send_yaw, label="send-yaw")
|
||||
plt.scatter(recv_times, TargetAngle,label="TargetAngle")
|
||||
plt.scatter(recv_times, RealAngle, label="RealAngle")
|
||||
plt.legend()
|
||||
plt.show()
|
||||
|
||||
7
tools/auto-pull.sh
Executable file
7
tools/auto-pull.sh
Executable file
@@ -0,0 +1,7 @@
|
||||
#!/bin/bash
|
||||
|
||||
cd $(dirname $0)/../
|
||||
timeout 8 git pull
|
||||
cd cmake-build-debug
|
||||
cmake ..
|
||||
make -j4
|
||||
9
tools/create-startup.sh
Executable file
9
tools/create-startup.sh
Executable file
@@ -0,0 +1,9 @@
|
||||
#!/bin/bash
|
||||
|
||||
echo "#!/bin/bash" > $2/startup-run
|
||||
echo "echo sjturm | sudo -S cpufreq-set -g performance" >> $2/startup-run
|
||||
echo "mkdir $1/Mark" >> $2/startup-run
|
||||
echo "mkdir $1/gimbal_video" >> $2/startup-run
|
||||
echo "mkdir $1/armor_box_photo" >> $2/startup-run
|
||||
echo "gnome-terminal -- bash -c \"echo sjturm | sudo -S $1/tools/monitor.sh \\\"$2/run --run-with-camera --save-video --save-mark --show-armor-box --wait-uart --save-labelled-boxes\\\"\"" >> $2/startup-run
|
||||
chmod +x $2/startup-run
|
||||
8
tools/logger.hpp
Normal file
8
tools/logger.hpp
Normal file
@@ -0,0 +1,8 @@
|
||||
#pragma once
|
||||
// Minimal logger stub — no external logging library required.
|
||||
// Replace with a real logger (e.g. spdlog) if needed.
|
||||
#include <iostream>
|
||||
#define LOG_INFO(...) (void)0
|
||||
#define LOG_WARN(...) (void)0
|
||||
#define LOG_ERROR(...) (void)0
|
||||
#define LOG_DEBUG(...) (void)0
|
||||
68
tools/math_tools.hpp
Normal file
68
tools/math_tools.hpp
Normal file
@@ -0,0 +1,68 @@
|
||||
#pragma once
|
||||
// math_tools.hpp
|
||||
// 内联实现 solver.cpp 所需的全部数学工具函数,无外部依赖。
|
||||
|
||||
#include <cmath>
|
||||
#include <Eigen/Dense>
|
||||
|
||||
namespace tools
|
||||
{
|
||||
|
||||
// ──────────────────────────────────────────────────────────────────────────────
|
||||
// square(x): 返回 x 的平方
|
||||
// ──────────────────────────────────────────────────────────────────────────────
|
||||
inline double square(double x) { return x * x; }
|
||||
|
||||
// ──────────────────────────────────────────────────────────────────────────────
|
||||
// limit_rad(angle): 将弧度角限制在 (-π, π] 范围内
|
||||
// ──────────────────────────────────────────────────────────────────────────────
|
||||
inline double limit_rad(double angle)
|
||||
{
|
||||
constexpr double two_pi = 2.0 * M_PI;
|
||||
angle = std::fmod(angle + M_PI, two_pi);
|
||||
if (angle < 0.0) angle += two_pi;
|
||||
return angle - M_PI;
|
||||
}
|
||||
|
||||
// ──────────────────────────────────────────────────────────────────────────────
|
||||
// eulers(R, ax0, ax1, ax2): 从旋转矩阵 R 提取欧拉角(内禀旋转,按 ax0->ax1->ax2 顺序)
|
||||
//
|
||||
// 常用调用方式:eulers(R, 2, 1, 0) 对应 ZYX(Yaw-Pitch-Roll)顺序。
|
||||
// 返回 Vector3d { angle_ax0, angle_ax1, angle_ax2 }
|
||||
// ──────────────────────────────────────────────────────────────────────────────
|
||||
inline Eigen::Vector3d eulers(const Eigen::Matrix3d & R, int ax0, int ax1, int ax2)
|
||||
{
|
||||
// 使用 Eigen 内置的欧拉角接口(内禀旋转)
|
||||
return R.eulerAngles(ax0, ax1, ax2);
|
||||
}
|
||||
|
||||
// ──────────────────────────────────────────────────────────────────────────────
|
||||
// xyz2ypd(xyz): 将三维空间坐标转换为 [yaw, pitch, distance]
|
||||
//
|
||||
// 坐标系约定(与云台/世界坐标系一致):
|
||||
// x 轴:前方(射击方向)
|
||||
// y 轴:左方
|
||||
// z 轴:上方
|
||||
//
|
||||
// 返回 Vector3d { yaw, pitch, distance }(单位:弧度,弧度,米)
|
||||
// ──────────────────────────────────────────────────────────────────────────────
|
||||
inline Eigen::Vector3d xyz2ypd(const Eigen::Vector3d & xyz)
|
||||
{
|
||||
double distance = xyz.norm();
|
||||
double yaw = std::atan2(xyz.y(), xyz.x());
|
||||
double pitch = std::atan2(xyz.z(), std::sqrt(xyz.x() * xyz.x() + xyz.y() * xyz.y()));
|
||||
return Eigen::Vector3d(yaw, pitch, distance);
|
||||
}
|
||||
|
||||
// ──────────────────────────────────────────────────────────────────────────────
|
||||
// get_abs_angle(a, b): 返回两个二维向量夹角的绝对值(弧度)
|
||||
// ──────────────────────────────────────────────────────────────────────────────
|
||||
inline double get_abs_angle(const Eigen::Vector2d & a, const Eigen::Vector2d & b)
|
||||
{
|
||||
double cos_angle = a.normalized().dot(b.normalized());
|
||||
// 数值钳位避免 acos 域错误
|
||||
cos_angle = std::max(-1.0, std::min(1.0, cos_angle));
|
||||
return std::acos(cos_angle);
|
||||
}
|
||||
|
||||
} // namespace tools
|
||||
53
tools/monitor.bat
Normal file
53
tools/monitor.bat
Normal file
@@ -0,0 +1,53 @@
|
||||
@echo off
|
||||
|
||||
rem <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>س<EFBFBD><D8B3><EFBFBD><EFBFBD>Ľ<EFBFBD><C4BD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ͳ<EFBFBD><CDB3><EFBFBD>·<EFBFBD><C2B7><EFBFBD><EFBFBD><EFBFBD>ɸ<EFBFBD><C9B8><EFBFBD><EFBFBD><EFBFBD>Ҫ<EFBFBD><D2AA><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
|
||||
set AppName=run.exe
|
||||
|
||||
set AppArgs= --run-with-camera --wait-uart --show-armor-box
|
||||
|
||||
set AppPath=C:\Users\sjturm\Desktop\AutoAim\build\Release\
|
||||
|
||||
title <20><><EFBFBD>̼<EFBFBD><CCBC><EFBFBD>
|
||||
|
||||
cls
|
||||
|
||||
echo.
|
||||
|
||||
echo <20><><EFBFBD>̼<EFBFBD><CCBC>ؿ<EFBFBD>ʼ<EFBFBD><CABC><EFBFBD><EFBFBD>
|
||||
|
||||
echo.
|
||||
|
||||
rem <20><><EFBFBD><EFBFBD>ѭ<EFBFBD><D1AD><EFBFBD><EFBFBD>
|
||||
|
||||
:startjc
|
||||
|
||||
rem <20>ӽ<EFBFBD><D3BD><EFBFBD><EFBFBD>б<EFBFBD><D0B1>в<EFBFBD><D0B2><EFBFBD>ָ<EFBFBD><D6B8><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
|
||||
rem <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ҳ<EFBFBD><D2B2>д<EFBFBD><D0B4> qprocess %AppName% >nul <20><><EFBFBD><EFBFBD><EFBFBD>鷢<EFBFBD><E9B7A2><EFBFBD>䣩
|
||||
|
||||
qprocess|findstr /i %AppName% >nul
|
||||
|
||||
rem <20><><EFBFBD><EFBFBD>errorlevel<65><6C>ֵ<EFBFBD><D6B5><EFBFBD><EFBFBD>0<EFBFBD><30>ʾ<EFBFBD><CABE><EFBFBD>ҵ<EFBFBD><D2B5><EFBFBD><EFBFBD>̣<EFBFBD><CCA3><EFBFBD><EFBFBD><EFBFBD>û<EFBFBD>в<EFBFBD><D0B2>ҵ<EFBFBD><D2B5><EFBFBD><EFBFBD><EFBFBD>
|
||||
|
||||
if %errorlevel%==0 (
|
||||
|
||||
echo ^>%date:~0,10% %time:~0,8% <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>С<EFBFBD><D0A1><EFBFBD>
|
||||
|
||||
)else (
|
||||
|
||||
echo ^>%date:~0,10% %time:~0,8% û<>з<EFBFBD><D0B7>ֳ<EFBFBD><D6B3><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
|
||||
echo ^>%date:~0,10% %time:~0,8% <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
|
||||
|
||||
start %AppPath%%AppName%%AppArgs% 2>nul && echo ^>%date:~0,10% %time:~0,8% <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ɹ<EFBFBD>
|
||||
|
||||
)
|
||||
|
||||
rem <20><>ping<6E><67><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʵ<EFBFBD><CAB5><EFBFBD><EFBFBD>ʱ<EFBFBD><CAB1><EFBFBD><EFBFBD>
|
||||
|
||||
ping -n 2 -w 1000 1.1.1.1>nul
|
||||
|
||||
goto startjc
|
||||
|
||||
echo on
|
||||
14
tools/monitor.sh
Executable file
14
tools/monitor.sh
Executable file
@@ -0,0 +1,14 @@
|
||||
#!/bin/sh
|
||||
|
||||
# usage: monitor.sh "<the exe file's absolute path and its shell parameter>"
|
||||
# And then when ever the exe shutdown it will be automatically restart
|
||||
|
||||
exe=$1
|
||||
while true; do
|
||||
state=`ps aux | grep "$1" | grep -v grep | grep -v $0`
|
||||
if [ ! "$state" ]; then
|
||||
exec $exe &
|
||||
echo "restart $exe"
|
||||
fi
|
||||
sleep 0.5
|
||||
done
|
||||
7
tools/para/conv1_b
Normal file
7
tools/para/conv1_b
Normal file
@@ -0,0 +1,7 @@
|
||||
6
|
||||
-0.13957113
|
||||
0.06878903
|
||||
0.031124229
|
||||
1.4302016
|
||||
-0.1433692
|
||||
1.1473336
|
||||
454
tools/para/conv1_w
Normal file
454
tools/para/conv1_w
Normal file
@@ -0,0 +1,454 @@
|
||||
3
|
||||
6
|
||||
5
|
||||
5
|
||||
0.026539411
|
||||
0.42253798
|
||||
0.6257618
|
||||
0.7803654
|
||||
0.56751746
|
||||
0.26718912
|
||||
0.7051625
|
||||
0.71628624
|
||||
0.7642506
|
||||
0.49248695
|
||||
0.16620474
|
||||
0.3780306
|
||||
0.7110501
|
||||
0.6030068
|
||||
0.4948883
|
||||
0.24835615
|
||||
0.33591226
|
||||
0.43040946
|
||||
0.5077497
|
||||
0.5212336
|
||||
-0.027971355
|
||||
0.2103128
|
||||
0.25356093
|
||||
0.07722227
|
||||
0.18559895
|
||||
0.32333145
|
||||
0.345134
|
||||
0.4201757
|
||||
0.6501012
|
||||
0.71342164
|
||||
0.27166557
|
||||
0.4905165
|
||||
0.6236048
|
||||
0.7930295
|
||||
0.7500772
|
||||
0.17779675
|
||||
0.56028295
|
||||
0.74555326
|
||||
0.5372084
|
||||
0.70782083
|
||||
0.27072752
|
||||
0.50543845
|
||||
0.57856107
|
||||
0.65362686
|
||||
0.53758156
|
||||
0.20370956
|
||||
0.38661864
|
||||
0.5690749
|
||||
0.24994203
|
||||
0.42308953
|
||||
-0.05610049
|
||||
0.0263962
|
||||
0.16409136
|
||||
-0.12595575
|
||||
-0.28413054
|
||||
-0.08711743
|
||||
0.3854187
|
||||
0.18076564
|
||||
0.08114622
|
||||
-0.31865782
|
||||
-0.10122112
|
||||
0.17201129
|
||||
0.116371
|
||||
0.13443075
|
||||
-0.3267171
|
||||
-0.23860133
|
||||
-0.092047565
|
||||
0.09856403
|
||||
-0.15966126
|
||||
-0.42780057
|
||||
-0.27054727
|
||||
-0.17382775
|
||||
-0.19402348
|
||||
-0.50262624
|
||||
-0.6701677
|
||||
0.021166094
|
||||
-0.15367271
|
||||
-0.3535248
|
||||
-0.3223209
|
||||
-0.3930027
|
||||
-0.012587458
|
||||
-0.2514576
|
||||
-0.028994415
|
||||
-0.23040394
|
||||
-0.22344537
|
||||
-0.28225404
|
||||
-0.12920779
|
||||
-0.084865615
|
||||
-0.079808
|
||||
-0.24189578
|
||||
-0.077354565
|
||||
-0.1364608
|
||||
-0.08271066
|
||||
0.015865652
|
||||
-0.17308144
|
||||
-0.016932748
|
||||
-0.10400943
|
||||
-0.15847488
|
||||
-0.19929907
|
||||
-0.024590252
|
||||
-0.305961
|
||||
0.41650155
|
||||
0.71885103
|
||||
0.5064972
|
||||
0.2556136
|
||||
-0.2217093
|
||||
0.3904318
|
||||
0.679353
|
||||
0.41345686
|
||||
0.1750823
|
||||
-0.07011908
|
||||
0.21723142
|
||||
0.36451343
|
||||
0.2734496
|
||||
-0.1827238
|
||||
-0.2640027
|
||||
-0.07665969
|
||||
-0.07281056
|
||||
-0.17140535
|
||||
-0.506126
|
||||
-0.39344314
|
||||
-0.19199198
|
||||
-0.43100312
|
||||
-0.5216478
|
||||
-0.8140914
|
||||
-0.22539687
|
||||
-0.1332064
|
||||
-0.18383063
|
||||
-0.3015942
|
||||
-0.3543749
|
||||
-0.07875634
|
||||
-0.046881627
|
||||
-0.17341466
|
||||
-0.17210038
|
||||
-0.16427462
|
||||
-0.12995729
|
||||
-0.09128473
|
||||
-0.07223676
|
||||
-0.05202489
|
||||
-0.17732152
|
||||
0.032028172
|
||||
0.022708599
|
||||
-0.07037333
|
||||
-0.24315825
|
||||
-0.3907585
|
||||
0.09521279
|
||||
-0.07241904
|
||||
-0.15533188
|
||||
-0.030434519
|
||||
-0.262898
|
||||
0.796653
|
||||
0.9267637
|
||||
0.93120253
|
||||
0.9917096
|
||||
0.9490124
|
||||
0.8625081
|
||||
1.0733354
|
||||
1.1211755
|
||||
1.1176518
|
||||
0.9001717
|
||||
0.7897956
|
||||
1.1967996
|
||||
1.1863062
|
||||
1.0460231
|
||||
0.86984694
|
||||
0.7440283
|
||||
0.88651806
|
||||
0.9017338
|
||||
0.81466335
|
||||
0.6403854
|
||||
0.50749934
|
||||
0.5359783
|
||||
0.54264694
|
||||
0.5598802
|
||||
0.41759288
|
||||
0.21787402
|
||||
0.42994195
|
||||
0.5423997
|
||||
0.46424487
|
||||
0.4637137
|
||||
0.4655036
|
||||
0.5988346
|
||||
0.5442244
|
||||
0.71659744
|
||||
0.6306643
|
||||
0.52392393
|
||||
0.66216165
|
||||
0.57559747
|
||||
0.50626665
|
||||
0.53091234
|
||||
0.50743634
|
||||
0.57716715
|
||||
0.7824497
|
||||
0.41367468
|
||||
0.55546504
|
||||
0.3030582
|
||||
0.6136134
|
||||
0.36521676
|
||||
0.43919942
|
||||
0.33232304
|
||||
0.51073956
|
||||
0.9655301
|
||||
1.0148821
|
||||
0.8726425
|
||||
0.30961013
|
||||
0.747004
|
||||
1.1461548
|
||||
1.3142052
|
||||
0.889127
|
||||
0.45464084
|
||||
0.5808323
|
||||
1.0770975
|
||||
1.3939735
|
||||
0.9165097
|
||||
0.6586972
|
||||
0.57355326
|
||||
0.9547619
|
||||
0.9447146
|
||||
0.66483366
|
||||
0.30041847
|
||||
0.3404827
|
||||
0.5929992
|
||||
0.7068603
|
||||
0.41881943
|
||||
-0.11529228
|
||||
-0.06013718
|
||||
0.029292889
|
||||
0.2176899
|
||||
0.14616063
|
||||
0.14816451
|
||||
0.13036805
|
||||
0.1793373
|
||||
0.3953
|
||||
0.51387286
|
||||
0.35285914
|
||||
0.06709124
|
||||
0.2171802
|
||||
0.6583215
|
||||
0.5220034
|
||||
0.44539294
|
||||
0.054360673
|
||||
0.18225458
|
||||
0.47989392
|
||||
0.5178179
|
||||
0.4576618
|
||||
0.16889913
|
||||
0.27844474
|
||||
0.32638916
|
||||
0.39993882
|
||||
0.119894765
|
||||
0.67456526
|
||||
1.4996389
|
||||
1.7681378
|
||||
1.6962894
|
||||
1.266272
|
||||
0.73875403
|
||||
1.6141837
|
||||
1.7386745
|
||||
1.671539
|
||||
1.1571932
|
||||
0.546496
|
||||
1.1523583
|
||||
1.2499596
|
||||
1.2602416
|
||||
0.7421503
|
||||
0.19625238
|
||||
0.6587611
|
||||
0.66948915
|
||||
0.43528196
|
||||
-0.008682725
|
||||
0.05109705
|
||||
0.13888682
|
||||
0.24387836
|
||||
-0.13002548
|
||||
-0.3703551
|
||||
0.06102093
|
||||
0.0076322197
|
||||
-0.035532437
|
||||
-0.029681634
|
||||
-0.057815406
|
||||
0.20116982
|
||||
0.27798048
|
||||
0.22556874
|
||||
0.3058461
|
||||
0.039763346
|
||||
0.10804575
|
||||
0.42170766
|
||||
0.3397586
|
||||
0.44702667
|
||||
0.19944976
|
||||
0.12492277
|
||||
0.2690411
|
||||
0.31178012
|
||||
0.307435
|
||||
0.09525637
|
||||
0.31001845
|
||||
0.20959602
|
||||
0.30736595
|
||||
0.2639023
|
||||
0.07473994
|
||||
-0.20428133
|
||||
0.123462535
|
||||
0.08172282
|
||||
0.0273528
|
||||
0.012557347
|
||||
-0.050085112
|
||||
0.15972462
|
||||
0.4576377
|
||||
0.26537335
|
||||
0.05294297
|
||||
0.1920879
|
||||
0.43903905
|
||||
0.44806978
|
||||
0.24177204
|
||||
0.15497287
|
||||
0.004198166
|
||||
0.24119955
|
||||
0.23940569
|
||||
0.30403528
|
||||
0.10443368
|
||||
-0.03242823
|
||||
-0.009877937
|
||||
-0.056617204
|
||||
-0.034309167
|
||||
-0.30718032
|
||||
-0.21831672
|
||||
-0.33697575
|
||||
-0.06903099
|
||||
-0.21208347
|
||||
-0.26106125
|
||||
-0.03470626
|
||||
-0.17156434
|
||||
-0.034266062
|
||||
-0.11911982
|
||||
-0.06517054
|
||||
-0.0014468514
|
||||
0.13053921
|
||||
-0.021993743
|
||||
0.08158244
|
||||
-0.048275527
|
||||
0.073179156
|
||||
0.11620164
|
||||
0.18908599
|
||||
0.090895034
|
||||
-0.13516097
|
||||
-0.041694365
|
||||
0.19145414
|
||||
0.06233252
|
||||
-0.015241079
|
||||
-0.08720653
|
||||
0.27016148
|
||||
0.68275934
|
||||
0.9259101
|
||||
0.87553996
|
||||
0.6730488
|
||||
0.5436024
|
||||
0.93307287
|
||||
1.284303
|
||||
1.215596
|
||||
0.7024047
|
||||
0.6535529
|
||||
1.0312322
|
||||
1.2054113
|
||||
1.1569601
|
||||
0.78507113
|
||||
0.46270427
|
||||
0.96070755
|
||||
1.0094548
|
||||
0.8725796
|
||||
0.584176
|
||||
0.2608554
|
||||
0.68085426
|
||||
0.6351991
|
||||
0.5974386
|
||||
0.44071475
|
||||
-0.14620513
|
||||
-0.051413815
|
||||
0.123140134
|
||||
0.3022954
|
||||
0.3937261
|
||||
0.14715014
|
||||
0.14558095
|
||||
0.37810993
|
||||
0.6081454
|
||||
0.4194721
|
||||
-0.048754267
|
||||
0.08287452
|
||||
0.5189599
|
||||
0.62214893
|
||||
0.7360417
|
||||
-0.06856284
|
||||
0.1070881
|
||||
0.296386
|
||||
0.6012432
|
||||
0.60254496
|
||||
-0.24324551
|
||||
0.14447688
|
||||
0.18799835
|
||||
0.46327543
|
||||
0.45924807
|
||||
0.20411673
|
||||
1.1002504
|
||||
1.4868475
|
||||
1.5346047
|
||||
1.0632775
|
||||
0.33373544
|
||||
1.1446538
|
||||
1.4786532
|
||||
1.4592378
|
||||
0.9056299
|
||||
0.22967416
|
||||
1.0249681
|
||||
1.2026587
|
||||
1.0556481
|
||||
0.6419271
|
||||
0.16762647
|
||||
0.475342
|
||||
0.64084166
|
||||
0.45603147
|
||||
0.19102122
|
||||
-0.17340069
|
||||
0.14535804
|
||||
0.13595402
|
||||
0.09039172
|
||||
-0.185116
|
||||
0.11963739
|
||||
0.3589415
|
||||
0.3841168
|
||||
0.5203414
|
||||
0.20129839
|
||||
0.20421675
|
||||
0.22073998
|
||||
0.4301539
|
||||
0.6149839
|
||||
0.42226243
|
||||
0.31898078
|
||||
0.31484243
|
||||
0.34544006
|
||||
0.5597543
|
||||
0.4067382
|
||||
0.12620181
|
||||
0.39053708
|
||||
0.38691083
|
||||
0.5219121
|
||||
0.62844783
|
||||
0.3108787
|
||||
0.46809235
|
||||
0.39197984
|
||||
0.38944077
|
||||
0.4951729
|
||||
11
tools/para/conv2_b
Normal file
11
tools/para/conv2_b
Normal file
@@ -0,0 +1,11 @@
|
||||
10
|
||||
-0.6072942
|
||||
1.0412933
|
||||
-0.34075898
|
||||
1.2761911
|
||||
0.16558713
|
||||
-0.11275745
|
||||
-0.20701186
|
||||
1.0942192
|
||||
0.511572
|
||||
0.07464832
|
||||
544
tools/para/conv2_w
Normal file
544
tools/para/conv2_w
Normal file
@@ -0,0 +1,544 @@
|
||||
6
|
||||
10
|
||||
3
|
||||
3
|
||||
-0.18567735
|
||||
0.31230295
|
||||
0.10601954
|
||||
-0.14635935
|
||||
0.17529164
|
||||
0.23833705
|
||||
-0.07737787
|
||||
-0.26470512
|
||||
-0.016763074
|
||||
0.0732159
|
||||
0.15613954
|
||||
0.24339953
|
||||
0.21809842
|
||||
0.10773516
|
||||
0.40015697
|
||||
0.08531675
|
||||
0.25792578
|
||||
0.29302046
|
||||
-0.14973466
|
||||
-0.13794622
|
||||
-0.3174705
|
||||
0.06396363
|
||||
-0.1582382
|
||||
-0.2843077
|
||||
-0.25538033
|
||||
-0.23979947
|
||||
-0.2003432
|
||||
-0.067921035
|
||||
0.008744139
|
||||
-0.12954548
|
||||
0.07350555
|
||||
0.016850626
|
||||
-0.13139062
|
||||
0.07412223
|
||||
-0.07210239
|
||||
-0.042953018
|
||||
-0.3169445
|
||||
0.009288535
|
||||
0.30465534
|
||||
-0.4208047
|
||||
0.07115591
|
||||
0.26925838
|
||||
-0.38791
|
||||
0.06488703
|
||||
0.400365
|
||||
-0.5090438
|
||||
-0.05041841
|
||||
0.28737134
|
||||
-0.32649037
|
||||
0.2732965
|
||||
0.3234882
|
||||
-0.14768949
|
||||
0.19571733
|
||||
0.46035185
|
||||
-0.1308439
|
||||
-0.28924602
|
||||
-0.4150856
|
||||
-0.1394865
|
||||
-0.14277102
|
||||
-0.028665107
|
||||
0.063959725
|
||||
-0.08086398
|
||||
-0.42271927
|
||||
-1.0998808
|
||||
-1.7531674
|
||||
-0.6868419
|
||||
-0.4679067
|
||||
-1.1683141
|
||||
-0.3862623
|
||||
0.1865768
|
||||
-0.7758855
|
||||
0.18598925
|
||||
-0.2777104
|
||||
-0.5689085
|
||||
-0.53544736
|
||||
0.06992068
|
||||
0.09683173
|
||||
-0.05572889
|
||||
0.497631
|
||||
0.5235087
|
||||
0.412554
|
||||
0.35491413
|
||||
0.20174716
|
||||
0.14414282
|
||||
0.21999303
|
||||
0.14763339
|
||||
0.15525024
|
||||
0.13345838
|
||||
-0.07630705
|
||||
-0.007321237
|
||||
-0.17791471
|
||||
0.067984045
|
||||
0.07404319
|
||||
-0.2620913
|
||||
-0.020879569
|
||||
-0.09856246
|
||||
-0.27126157
|
||||
-0.19668914
|
||||
-0.45068544
|
||||
0.06535956
|
||||
0.19665721
|
||||
0.4605025
|
||||
0.0834005
|
||||
0.26365396
|
||||
0.42590958
|
||||
0.041509036
|
||||
0.28209603
|
||||
0.23930955
|
||||
-0.16162594
|
||||
-0.22635049
|
||||
-0.26243812
|
||||
-0.12631208
|
||||
-0.22097321
|
||||
-0.20312756
|
||||
-0.1772115
|
||||
-0.33603805
|
||||
-0.30561772
|
||||
0.008207564
|
||||
0.07136626
|
||||
-0.216243
|
||||
0.16515563
|
||||
0.04111277
|
||||
-0.1260301
|
||||
0.14099488
|
||||
0.10370603
|
||||
-0.010030857
|
||||
-0.27448004
|
||||
-0.011123834
|
||||
0.22102898
|
||||
-0.25228068
|
||||
0.039984487
|
||||
0.24022454
|
||||
-0.12004822
|
||||
0.10729556
|
||||
0.22277792
|
||||
-0.2681527
|
||||
0.1929927
|
||||
0.35833898
|
||||
-0.1897413
|
||||
0.2386225
|
||||
0.59820104
|
||||
-0.27273512
|
||||
0.1098645
|
||||
0.36686987
|
||||
-0.43986773
|
||||
-0.18380699
|
||||
-0.43966547
|
||||
-0.009675484
|
||||
-0.25631252
|
||||
-0.29056635
|
||||
0.0712151
|
||||
-0.18025662
|
||||
-0.48891056
|
||||
-0.47694656
|
||||
-0.88816905
|
||||
-0.06483537
|
||||
0.013368553
|
||||
-0.70404077
|
||||
0.28231522
|
||||
0.33836752
|
||||
-0.22945245
|
||||
0.25680065
|
||||
-0.0012361507
|
||||
-0.52792823
|
||||
-0.2579657
|
||||
0.3255992
|
||||
-0.0019560119
|
||||
-0.046853587
|
||||
0.24827203
|
||||
0.34998816
|
||||
0.27723187
|
||||
0.31715482
|
||||
0.34362832
|
||||
0.12269884
|
||||
0.13557787
|
||||
-0.114973396
|
||||
0.07401403
|
||||
0.069110855
|
||||
-0.187023
|
||||
-0.036038406
|
||||
0.012674593
|
||||
0.36098468
|
||||
0.42171153
|
||||
0.048450485
|
||||
0.28105047
|
||||
0.4715788
|
||||
-0.023357779
|
||||
-0.057762705
|
||||
-0.073359944
|
||||
-0.16736583
|
||||
0.12476493
|
||||
0.0062710703
|
||||
-0.021589287
|
||||
-0.13475952
|
||||
0.030259239
|
||||
-0.036233522
|
||||
0.06367138
|
||||
-0.07908364
|
||||
0.36171123
|
||||
0.056995805
|
||||
0.26451215
|
||||
0.18291938
|
||||
0.06195444
|
||||
0.23869722
|
||||
0.10497623
|
||||
0.09330571
|
||||
0.29085782
|
||||
-0.2596862
|
||||
-0.031500176
|
||||
-0.013901459
|
||||
0.023374349
|
||||
0.016828336
|
||||
0.11964698
|
||||
0.026195215
|
||||
0.035629973
|
||||
0.12736408
|
||||
-0.42047524
|
||||
-0.045428358
|
||||
0.4764139
|
||||
-0.594475
|
||||
-0.14393432
|
||||
0.3904298
|
||||
-0.18805574
|
||||
-0.08113497
|
||||
0.5267287
|
||||
-0.4067696
|
||||
-0.32341024
|
||||
-0.29679683
|
||||
-0.10745416
|
||||
0.08389849
|
||||
0.14507549
|
||||
-0.024750415
|
||||
0.4222244
|
||||
0.16702761
|
||||
-0.008214667
|
||||
0.03591805
|
||||
0.08528825
|
||||
0.12195521
|
||||
0.41446808
|
||||
0.46344396
|
||||
0.37176162
|
||||
0.40626523
|
||||
0.08781661
|
||||
-0.8886079
|
||||
-1.0024366
|
||||
-0.86886346
|
||||
-0.49839306
|
||||
-0.8621685
|
||||
-0.642396
|
||||
-0.13097173
|
||||
-0.7362578
|
||||
-0.22594142
|
||||
-0.07626368
|
||||
-0.5901063
|
||||
-0.3290703
|
||||
0.14976943
|
||||
-0.06745293
|
||||
-0.0820076
|
||||
0.5327264
|
||||
0.4384248
|
||||
0.6160922
|
||||
0.24003918
|
||||
0.24436
|
||||
0.22210835
|
||||
0.21770608
|
||||
0.124687046
|
||||
0.0470902
|
||||
-0.14859878
|
||||
-0.321342
|
||||
-0.08767322
|
||||
0.20693085
|
||||
0.42665282
|
||||
0.33726025
|
||||
-0.020886194
|
||||
0.44385502
|
||||
0.01808433
|
||||
-0.118666425
|
||||
-0.15688846
|
||||
-0.31219846
|
||||
0.20918387
|
||||
0.021502182
|
||||
0.33103526
|
||||
0.24867874
|
||||
0.21629289
|
||||
0.013217075
|
||||
0.08715608
|
||||
0.054708257
|
||||
-0.15127313
|
||||
0.1508026
|
||||
0.24620876
|
||||
0.44316766
|
||||
0.17231683
|
||||
0.1236346
|
||||
0.26164678
|
||||
-0.08726074
|
||||
-0.052426733
|
||||
0.33535057
|
||||
0.36311948
|
||||
0.41015378
|
||||
0.34961388
|
||||
0.09574385
|
||||
0.5627171
|
||||
0.4841079
|
||||
0.36436325
|
||||
0.62349635
|
||||
0.651723
|
||||
-0.4531835
|
||||
0.15029465
|
||||
0.57511115
|
||||
-0.45798486
|
||||
0.19631258
|
||||
0.3225775
|
||||
-0.103153236
|
||||
0.19025934
|
||||
0.48245525
|
||||
-0.09091705
|
||||
-0.094119325
|
||||
-0.38689196
|
||||
0.14930637
|
||||
0.09523474
|
||||
-0.04373269
|
||||
0.3126633
|
||||
0.08655161
|
||||
-0.082390875
|
||||
-0.053303
|
||||
0.31841794
|
||||
0.3719926
|
||||
0.15074554
|
||||
0.40985286
|
||||
0.33657342
|
||||
0.20797513
|
||||
0.24987732
|
||||
0.39347094
|
||||
0.83306986
|
||||
0.86048186
|
||||
0.5689052
|
||||
0.72829825
|
||||
0.89263994
|
||||
0.8195005
|
||||
0.61129767
|
||||
0.78122336
|
||||
0.61171514
|
||||
-0.319987
|
||||
-0.25968623
|
||||
-0.11498821
|
||||
0.23861922
|
||||
0.088788316
|
||||
0.2950782
|
||||
0.62382466
|
||||
0.8079981
|
||||
0.61313707
|
||||
0.077279635
|
||||
-0.032932185
|
||||
0.0890238
|
||||
0.029694919
|
||||
0.12197181
|
||||
-0.042123534
|
||||
-0.29403502
|
||||
-0.36851963
|
||||
0.09636119
|
||||
0.04346845
|
||||
0.43912384
|
||||
0.3536572
|
||||
0.066943154
|
||||
0.4024961
|
||||
0.47593385
|
||||
0.0759621
|
||||
0.39561898
|
||||
0.22179781
|
||||
-0.35304305
|
||||
-0.20236854
|
||||
-0.008968132
|
||||
-0.09802803
|
||||
0.054423235
|
||||
0.23025425
|
||||
-0.015376655
|
||||
0.008936614
|
||||
0.2355261
|
||||
0.0014180358
|
||||
0.17833155
|
||||
0.19288565
|
||||
0.28466016
|
||||
-0.02708328
|
||||
0.05748906
|
||||
0.115661204
|
||||
-0.08906293
|
||||
0.06937998
|
||||
-0.12015559
|
||||
-0.11914039
|
||||
-0.15230455
|
||||
-0.30971813
|
||||
0.12253699
|
||||
-0.1287006
|
||||
-0.11642937
|
||||
-0.03524333
|
||||
0.106573164
|
||||
-0.46892896
|
||||
0.048909124
|
||||
0.35770398
|
||||
-0.48432148
|
||||
0.06230857
|
||||
0.35268116
|
||||
-0.6384595
|
||||
0.054048087
|
||||
0.33101568
|
||||
-0.7891181
|
||||
-0.5678995
|
||||
-0.32257825
|
||||
-0.30838996
|
||||
-0.019490078
|
||||
0.20418139
|
||||
0.2235779
|
||||
0.43282986
|
||||
0.33755836
|
||||
-0.43536973
|
||||
-0.18715984
|
||||
-0.017235223
|
||||
-0.22174615
|
||||
0.009737464
|
||||
0.18385953
|
||||
0.3702021
|
||||
0.1722581
|
||||
0.31182298
|
||||
-1.5388889
|
||||
-1.4710528
|
||||
-0.9808655
|
||||
-1.2328979
|
||||
-1.391655
|
||||
-0.9775159
|
||||
-0.53418314
|
||||
-1.0619466
|
||||
-0.14114031
|
||||
-0.38471037
|
||||
-0.91709787
|
||||
-0.6730362
|
||||
-0.3246664
|
||||
-0.50130564
|
||||
-0.29241592
|
||||
0.2488604
|
||||
0.29896885
|
||||
0.42214942
|
||||
0.23901664
|
||||
0.071325876
|
||||
0.0730879
|
||||
0.3215266
|
||||
0.37580463
|
||||
0.17601205
|
||||
0.082663685
|
||||
-0.14512439
|
||||
-0.02447424
|
||||
0.036292106
|
||||
0.190385
|
||||
0.24941531
|
||||
-0.15101732
|
||||
0.16009882
|
||||
0.022328991
|
||||
-0.13642876
|
||||
-0.2557106
|
||||
-0.23009326
|
||||
-0.2648493
|
||||
0.035393387
|
||||
0.058671933
|
||||
-0.06313441
|
||||
0.085322335
|
||||
0.037474677
|
||||
-0.09684385
|
||||
0.021198915
|
||||
-0.23987578
|
||||
0.49218395
|
||||
0.45345736
|
||||
0.4600616
|
||||
0.27070585
|
||||
0.23068464
|
||||
0.37693858
|
||||
0.32365304
|
||||
0.2629329
|
||||
0.38881606
|
||||
0.25656843
|
||||
0.3796918
|
||||
0.45741585
|
||||
0.08370856
|
||||
0.29546905
|
||||
0.55899864
|
||||
0.16390188
|
||||
0.43054807
|
||||
0.6232953
|
||||
-0.6125586
|
||||
0.042835608
|
||||
0.42402682
|
||||
-0.4055307
|
||||
-0.039988685
|
||||
0.42992234
|
||||
-0.26697057
|
||||
0.10284304
|
||||
0.4822276
|
||||
-0.32137555
|
||||
-0.38547745
|
||||
-0.33756226
|
||||
0.12396629
|
||||
0.018000755
|
||||
0.0040020915
|
||||
0.09871851
|
||||
0.19964874
|
||||
-0.049439877
|
||||
-0.054510776
|
||||
0.20413962
|
||||
0.49790758
|
||||
0.3678443
|
||||
0.47925648
|
||||
0.5145687
|
||||
0.46790117
|
||||
0.4268048
|
||||
0.23691703
|
||||
0.7796671
|
||||
0.6537224
|
||||
0.6620804
|
||||
0.6199029
|
||||
0.6739477
|
||||
0.5245343
|
||||
0.7053961
|
||||
0.5178989
|
||||
0.678157
|
||||
0.015971098
|
||||
-0.09368621
|
||||
-0.1418303
|
||||
0.2623539
|
||||
0.27078906
|
||||
0.26214978
|
||||
0.450224
|
||||
0.5519793
|
||||
0.589996
|
||||
0.0695408
|
||||
0.11883035
|
||||
0.16186124
|
||||
-0.00019518172
|
||||
-0.10749374
|
||||
-0.07061164
|
||||
-0.37467608
|
||||
-0.33476043
|
||||
-0.19680664
|
||||
15
tools/para/conv3_b
Normal file
15
tools/para/conv3_b
Normal file
@@ -0,0 +1,15 @@
|
||||
14
|
||||
0.55702305
|
||||
1.1578506
|
||||
0.4233094
|
||||
1.0468913
|
||||
0.102127574
|
||||
-0.11887622
|
||||
0.7552765
|
||||
0.8270396
|
||||
-0.037355777
|
||||
0.863297
|
||||
0.42967162
|
||||
0.36658964
|
||||
0.751224
|
||||
0.5695708
|
||||
1264
tools/para/conv3_w
Normal file
1264
tools/para/conv3_w
Normal file
File diff suppressed because it is too large
Load Diff
61
tools/para/fc1_b
Normal file
61
tools/para/fc1_b
Normal file
@@ -0,0 +1,61 @@
|
||||
60
|
||||
-0.193765
|
||||
-0.23972291
|
||||
0.07138973
|
||||
0.32630488
|
||||
-0.12837179
|
||||
0.15837212
|
||||
-0.171342
|
||||
0.15245913
|
||||
0.2655143
|
||||
0.5132081
|
||||
-0.36182725
|
||||
0.5721853
|
||||
1.1356937
|
||||
0.478751
|
||||
-0.19061308
|
||||
-0.4349855
|
||||
-0.037231974
|
||||
0.82266986
|
||||
0.021297721
|
||||
0.27819484
|
||||
-0.3700498
|
||||
-0.080103956
|
||||
0.118309975
|
||||
-0.120765805
|
||||
-0.21436372
|
||||
0.38247055
|
||||
0.9884826
|
||||
-0.4042391
|
||||
-0.21405952
|
||||
-1.1451919
|
||||
-0.07339987
|
||||
0.63600576
|
||||
0.39354753
|
||||
-0.14708714
|
||||
0.5753427
|
||||
-0.06053154
|
||||
0.6068468
|
||||
-0.24616803
|
||||
-0.18896966
|
||||
-0.06904445
|
||||
-0.137959
|
||||
-0.75066173
|
||||
-0.20227952
|
||||
0.17195949
|
||||
-0.13245444
|
||||
-0.10060697
|
||||
0.40073013
|
||||
-0.9563751
|
||||
0.031663556
|
||||
0.38514042
|
||||
-0.061627824
|
||||
0.14056061
|
||||
0.7515243
|
||||
0.7903934
|
||||
0.8401122
|
||||
0.29314804
|
||||
0.2987165
|
||||
0.39764544
|
||||
0.3022464
|
||||
-0.29335007
|
||||
33602
tools/para/fc1_w
Normal file
33602
tools/para/fc1_w
Normal file
File diff suppressed because it is too large
Load Diff
16
tools/para/fc2_b
Normal file
16
tools/para/fc2_b
Normal file
@@ -0,0 +1,16 @@
|
||||
15
|
||||
-0.68187517
|
||||
-0.013023868
|
||||
-0.012667711
|
||||
0.12630615
|
||||
-0.24749278
|
||||
-0.4987089
|
||||
0.3616302
|
||||
0.23901181
|
||||
0.32909712
|
||||
-0.25681627
|
||||
0.21683879
|
||||
0.72209626
|
||||
-0.2969338
|
||||
0.35322607
|
||||
0.6401797
|
||||
902
tools/para/fc2_w
Normal file
902
tools/para/fc2_w
Normal file
@@ -0,0 +1,902 @@
|
||||
60
|
||||
15
|
||||
0.023721257
|
||||
-0.056767184
|
||||
-0.02482725
|
||||
-0.056625195
|
||||
-0.013108621
|
||||
0.16314533
|
||||
-0.04853894
|
||||
-0.029597584
|
||||
-0.046683975
|
||||
-0.02246394
|
||||
-0.037572507
|
||||
-0.03316914
|
||||
0.17073579
|
||||
0.1816684
|
||||
-0.04529307
|
||||
-0.0248803
|
||||
-0.030885592
|
||||
-0.04743719
|
||||
0.10407687
|
||||
-0.027138393
|
||||
0.1133468
|
||||
-0.024212182
|
||||
-0.0057777944
|
||||
-0.05431293
|
||||
-0.02986296
|
||||
0.11789993
|
||||
-0.051923934
|
||||
0.09167429
|
||||
-0.045342486
|
||||
-0.043118663
|
||||
-0.098115616
|
||||
-0.006691878
|
||||
0.022823932
|
||||
0.016394816
|
||||
-0.0134537015
|
||||
-0.0060206857
|
||||
-0.008312101
|
||||
0.015749821
|
||||
0.016666552
|
||||
-0.007961423
|
||||
0.0130552165
|
||||
0.051745173
|
||||
0.086891346
|
||||
-0.061654568
|
||||
-0.022857342
|
||||
-0.045601845
|
||||
-0.024637094
|
||||
-0.025579434
|
||||
0.024080817
|
||||
-0.035525665
|
||||
0.084735304
|
||||
0.008145681
|
||||
-0.048479345
|
||||
-0.01107538
|
||||
0.0043653576
|
||||
-0.02404582
|
||||
-0.0046611303
|
||||
-0.018547907
|
||||
0.13898253
|
||||
-0.0071163056
|
||||
0.027239176
|
||||
0.019990532
|
||||
0.00575406
|
||||
0.067195065
|
||||
0.057361092
|
||||
-0.027234674
|
||||
0.0034042448
|
||||
0.07240855
|
||||
-0.014622719
|
||||
-0.021772297
|
||||
-0.018955652
|
||||
-0.016349709
|
||||
-0.033501316
|
||||
-0.012791992
|
||||
0.009489657
|
||||
-0.0040843496
|
||||
-0.06548852
|
||||
-0.0027336648
|
||||
-0.02771641
|
||||
0.003105313
|
||||
-0.022985559
|
||||
-0.027811378
|
||||
0.13901976
|
||||
-0.069822796
|
||||
-0.015901526
|
||||
-0.017430564
|
||||
0.008845486
|
||||
0.015278092
|
||||
-0.0567094
|
||||
0.1451618
|
||||
0.10175247
|
||||
-0.0145240985
|
||||
0.019893676
|
||||
0.00060109375
|
||||
0.0022912938
|
||||
0.07441637
|
||||
-0.044775177
|
||||
-0.02982467
|
||||
-0.0090249935
|
||||
0.015784694
|
||||
-0.0151947895
|
||||
-0.026377525
|
||||
0.07452386
|
||||
-0.057595294
|
||||
-0.033931956
|
||||
0.018042305
|
||||
-0.04521402
|
||||
-0.014217054
|
||||
0.010033828
|
||||
0.009846576
|
||||
0.0018628535
|
||||
-0.030086106
|
||||
-0.0017332508
|
||||
-0.005574078
|
||||
-0.00023017552
|
||||
-0.006606218
|
||||
0.13216685
|
||||
-0.010639397
|
||||
-0.026569739
|
||||
-0.04215086
|
||||
0.04924681
|
||||
-0.043633044
|
||||
0.1018429
|
||||
0.0021304227
|
||||
-0.056588713
|
||||
-0.058658466
|
||||
-0.059565447
|
||||
-0.042487074
|
||||
0.06225856
|
||||
-0.027270265
|
||||
0.0450222
|
||||
0.07110802
|
||||
0.049895298
|
||||
0.042784434
|
||||
0.05563622
|
||||
-0.050112586
|
||||
-0.047793083
|
||||
-0.06338001
|
||||
0.07364919
|
||||
-0.054492526
|
||||
0.08631582
|
||||
-0.036124628
|
||||
0.05227145
|
||||
-0.037520196
|
||||
-0.062319368
|
||||
0.08841054
|
||||
-0.032051668
|
||||
0.08331706
|
||||
-0.043635234
|
||||
0.04112745
|
||||
0.06212643
|
||||
0.007388739
|
||||
-0.020659756
|
||||
0.02230651
|
||||
0.086097695
|
||||
0.005100613
|
||||
-0.064036496
|
||||
0.017601727
|
||||
-0.05984531
|
||||
0.011942104
|
||||
0.008610117
|
||||
0.086421125
|
||||
-0.01637438
|
||||
-0.055868283
|
||||
-0.05516202
|
||||
-0.047032513
|
||||
0.121512815
|
||||
-0.05508921
|
||||
-0.012337177
|
||||
0.0035218787
|
||||
-0.022240747
|
||||
0.11666904
|
||||
-0.06353826
|
||||
0.060320225
|
||||
-0.047669224
|
||||
0.017966691
|
||||
-0.04024401
|
||||
-0.025529524
|
||||
0.069724366
|
||||
-0.053703915
|
||||
-0.034110505
|
||||
-0.029960383
|
||||
-0.06600948
|
||||
0.13501477
|
||||
-0.053031318
|
||||
0.012389384
|
||||
-0.022873297
|
||||
-0.009194736
|
||||
-0.029105553
|
||||
-0.045856915
|
||||
0.12856278
|
||||
-0.021943325
|
||||
0.010748578
|
||||
0.006589677
|
||||
0.003752689
|
||||
0.02887515
|
||||
0.10008096
|
||||
0.03216688
|
||||
-0.039296247
|
||||
-0.047470577
|
||||
-0.035232235
|
||||
0.08135979
|
||||
-0.04116884
|
||||
0.09727354
|
||||
0.044263303
|
||||
-0.05627888
|
||||
-0.018874492
|
||||
-0.07279877
|
||||
0.09413788
|
||||
-0.036279287
|
||||
-0.036115322
|
||||
0.083222285
|
||||
-0.035373613
|
||||
-0.002076556
|
||||
-0.034073725
|
||||
-0.058003467
|
||||
-0.011753285
|
||||
0.064566836
|
||||
0.1351894
|
||||
-0.018176533
|
||||
0.0045275176
|
||||
-0.0394347
|
||||
-0.053792067
|
||||
-0.060081203
|
||||
0.06741035
|
||||
0.06952082
|
||||
-0.070167564
|
||||
-0.11953224
|
||||
-0.093335666
|
||||
-0.092176
|
||||
-0.06279851
|
||||
-0.08698778
|
||||
-0.09178264
|
||||
0.06140479
|
||||
0.073674716
|
||||
0.060297325
|
||||
0.072911836
|
||||
0.07054657
|
||||
0.053970445
|
||||
0.06798171
|
||||
-0.013621602
|
||||
-0.011862524
|
||||
-0.02278563
|
||||
0.08397386
|
||||
-0.029510925
|
||||
-0.006828416
|
||||
0.008962611
|
||||
-0.0060842847
|
||||
0.057862744
|
||||
-0.014851122
|
||||
0.035502855
|
||||
-0.027666172
|
||||
-0.01099776
|
||||
-0.013816966
|
||||
-0.018422294
|
||||
-0.07163931
|
||||
0.011755499
|
||||
-0.016132606
|
||||
-0.06628269
|
||||
0.0060495273
|
||||
-0.004684206
|
||||
0.091115616
|
||||
0.07032679
|
||||
-0.022980448
|
||||
-0.027459152
|
||||
-0.04107013
|
||||
-0.005020775
|
||||
-0.0050464333
|
||||
0.036403414
|
||||
0.043938298
|
||||
0.004868387
|
||||
0.09904006
|
||||
0.07008151
|
||||
0.025196165
|
||||
-0.024412407
|
||||
-0.041503318
|
||||
-0.023655541
|
||||
-0.021237679
|
||||
0.0059536123
|
||||
0.07900436
|
||||
-0.066426545
|
||||
-0.058976896
|
||||
-0.042309746
|
||||
-0.0044052647
|
||||
0.011788804
|
||||
-0.06437558
|
||||
0.050667755
|
||||
0.003000085
|
||||
-0.026545258
|
||||
0.035834778
|
||||
0.02146158
|
||||
-0.025112923
|
||||
-0.013572935
|
||||
0.07372157
|
||||
-0.02082975
|
||||
-0.034076523
|
||||
0.05821599
|
||||
0.042366743
|
||||
-0.06394822
|
||||
-0.019507725
|
||||
0.07289588
|
||||
0.04123546
|
||||
-0.0401289
|
||||
-0.028429616
|
||||
-0.04741946
|
||||
-0.036297556
|
||||
0.024062768
|
||||
-0.03628923
|
||||
0.076255724
|
||||
-0.007795125
|
||||
0.012530167
|
||||
-0.026342789
|
||||
-0.029241074
|
||||
0.032052062
|
||||
-0.017812248
|
||||
0.02970647
|
||||
0.08998527
|
||||
-0.05396118
|
||||
0.023024661
|
||||
0.0052098245
|
||||
0.016553843
|
||||
-0.10519745
|
||||
0.037710346
|
||||
0.009732182
|
||||
-0.027681515
|
||||
-0.03822997
|
||||
-0.012670474
|
||||
0.07280391
|
||||
-0.029706435
|
||||
0.0014060438
|
||||
-0.030424576
|
||||
0.056327637
|
||||
-0.03691004
|
||||
0.100075796
|
||||
0.059969947
|
||||
-0.009466309
|
||||
-0.04053178
|
||||
-0.07394839
|
||||
0.017282715
|
||||
-0.038851976
|
||||
0.07533885
|
||||
0.022888316
|
||||
-0.005222714
|
||||
-0.051790617
|
||||
-0.039949816
|
||||
0.045010787
|
||||
-0.05255461
|
||||
0.028021902
|
||||
-0.051901788
|
||||
0.030317541
|
||||
-0.016183384
|
||||
-0.000669922
|
||||
0.06513011
|
||||
-0.07717841
|
||||
-0.020836962
|
||||
-0.012460537
|
||||
0.002608653
|
||||
0.015867954
|
||||
0.05845073
|
||||
-0.0021784795
|
||||
0.07890689
|
||||
-0.022973057
|
||||
0.092426814
|
||||
-0.054843165
|
||||
0.044392575
|
||||
-0.021421066
|
||||
-0.094741575
|
||||
-0.065930516
|
||||
-0.022157872
|
||||
0.12326591
|
||||
0.014883588
|
||||
0.026948972
|
||||
-0.016465168
|
||||
-0.064375505
|
||||
-0.023275383
|
||||
-0.0070997463
|
||||
-0.033101372
|
||||
0.09446811
|
||||
0.10115626
|
||||
-0.04225017
|
||||
-0.0007481162
|
||||
-0.056021266
|
||||
-0.04811929
|
||||
-0.051491253
|
||||
0.068353504
|
||||
0.08718989
|
||||
-0.05749272
|
||||
-0.010089683
|
||||
-0.046433568
|
||||
-0.016778694
|
||||
-0.025272565
|
||||
-0.013132711
|
||||
-0.039840337
|
||||
-0.02110915
|
||||
-0.03557828
|
||||
-0.0014030484
|
||||
0.01924547
|
||||
0.0789074
|
||||
0.06009254
|
||||
-0.025958415
|
||||
0.020134918
|
||||
-0.03148343
|
||||
-0.009884057
|
||||
0.0061013266
|
||||
0.08806658
|
||||
0.0656854
|
||||
0.009727492
|
||||
-0.03322069
|
||||
-0.019033067
|
||||
0.0035772354
|
||||
-0.02508404
|
||||
0.007561759
|
||||
-0.03869725
|
||||
0.06390332
|
||||
0.026551774
|
||||
0.050207905
|
||||
-0.043208126
|
||||
-0.019934112
|
||||
0.06602689
|
||||
-0.02860308
|
||||
-0.0115318475
|
||||
-0.050741002
|
||||
-0.012525999
|
||||
-0.03984677
|
||||
0.025553342
|
||||
-0.007472711
|
||||
-0.03354731
|
||||
0.120088056
|
||||
-0.049436986
|
||||
-0.020271834
|
||||
-0.036656402
|
||||
0.01050952
|
||||
-0.040384356
|
||||
-0.013354367
|
||||
0.15239534
|
||||
0.061574545
|
||||
-0.0038912655
|
||||
0.0015946868
|
||||
-0.0033184527
|
||||
0.0044296803
|
||||
-0.026376294
|
||||
-0.02409796
|
||||
-0.033598542
|
||||
-0.038278487
|
||||
0.0022965355
|
||||
0.032300834
|
||||
0.013073122
|
||||
-0.016868252
|
||||
0.030710598
|
||||
0.042514037
|
||||
-0.017287938
|
||||
-0.052982263
|
||||
-0.0025038382
|
||||
0.04258102
|
||||
-0.037782636
|
||||
0.08912471
|
||||
-0.041155506
|
||||
-0.020055389
|
||||
-0.036539547
|
||||
-0.008155307
|
||||
0.095901586
|
||||
-0.045066398
|
||||
0.07589279
|
||||
-0.0008031097
|
||||
-0.042826444
|
||||
-0.066662736
|
||||
0.035725113
|
||||
0.07053888
|
||||
-0.003361896
|
||||
0.010324781
|
||||
0.057961073
|
||||
-0.060475152
|
||||
-0.059718084
|
||||
-0.011133738
|
||||
0.038670868
|
||||
0.0045008264
|
||||
0.00011081969
|
||||
0.011725977
|
||||
-0.06017393
|
||||
-0.037521508
|
||||
-0.041834593
|
||||
-0.018241858
|
||||
0.016014917
|
||||
-0.022131182
|
||||
0.09944455
|
||||
-0.053095143
|
||||
-0.00742253
|
||||
-0.03147508
|
||||
0.018483965
|
||||
0.00743996
|
||||
-0.026868168
|
||||
0.121405125
|
||||
-0.030068455
|
||||
-0.020201726
|
||||
-0.025969878
|
||||
0.04350136
|
||||
-0.0021948342
|
||||
0.06245924
|
||||
0.027152391
|
||||
-0.00056066626
|
||||
-0.009253849
|
||||
0.012065811
|
||||
-0.018439502
|
||||
-0.010880174
|
||||
0.058823567
|
||||
0.011996477
|
||||
-0.040978447
|
||||
-0.011799242
|
||||
-0.0050421795
|
||||
-0.0367865
|
||||
0.047042668
|
||||
-0.12227256
|
||||
0.031531557
|
||||
0.008638815
|
||||
-0.021561243
|
||||
-0.02409996
|
||||
0.08065916
|
||||
-0.03862787
|
||||
-0.069201544
|
||||
0.035517152
|
||||
0.025776947
|
||||
-0.019695587
|
||||
-0.00736174
|
||||
0.097198814
|
||||
-0.0031088917
|
||||
0.0056593325
|
||||
-0.06007171
|
||||
-0.035134632
|
||||
0.028565645
|
||||
-0.012346341
|
||||
-0.022452231
|
||||
0.14388211
|
||||
-0.016372552
|
||||
-0.026357366
|
||||
-0.011106448
|
||||
0.0031650758
|
||||
-0.010229361
|
||||
-0.025584642
|
||||
0.07345942
|
||||
-0.024771154
|
||||
-0.036477014
|
||||
-0.06983555
|
||||
0.06293779
|
||||
0.10976889
|
||||
0.016566912
|
||||
-0.03319916
|
||||
-0.03126182
|
||||
-0.042317595
|
||||
-0.029041866
|
||||
0.05726187
|
||||
0.11515596
|
||||
-0.0073280144
|
||||
-0.025612779
|
||||
-0.01186883
|
||||
-0.046921965
|
||||
-0.011384405
|
||||
0.13430771
|
||||
-0.025325155
|
||||
-0.027509108
|
||||
-0.008541601
|
||||
-0.044411432
|
||||
0.0004181579
|
||||
-0.037252396
|
||||
0.12108238
|
||||
-0.007830119
|
||||
-0.020841695
|
||||
-0.0061824056
|
||||
-0.0424927
|
||||
-0.014388491
|
||||
-0.0126006035
|
||||
0.026058633
|
||||
0.07131681
|
||||
-0.03908185
|
||||
-0.0034570813
|
||||
0.011785356
|
||||
0.006566377
|
||||
-0.07555411
|
||||
0.024073388
|
||||
0.11404315
|
||||
-0.052582927
|
||||
-0.01964203
|
||||
0.012207591
|
||||
0.003144945
|
||||
-0.08745947
|
||||
0.020775186
|
||||
-0.0035174368
|
||||
-0.008068929
|
||||
-0.020500282
|
||||
0.058456566
|
||||
0.030612053
|
||||
-0.022996115
|
||||
-0.02936319
|
||||
-0.030847497
|
||||
0.021455627
|
||||
-0.059063505
|
||||
0.05697014
|
||||
0.010187005
|
||||
0.06089469
|
||||
-0.04353769
|
||||
-0.009652151
|
||||
0.03238445
|
||||
-0.0010035908
|
||||
-0.052168515
|
||||
-0.029284708
|
||||
0.003263534
|
||||
-0.044448454
|
||||
-0.052631732
|
||||
-0.07391317
|
||||
0.038685244
|
||||
0.036219478
|
||||
0.035986923
|
||||
-0.0010210739
|
||||
0.04722957
|
||||
0.022612667
|
||||
0.06024814
|
||||
0.06373478
|
||||
0.05212275
|
||||
0.048431445
|
||||
0.069127135
|
||||
0.05499899
|
||||
0.052656386
|
||||
0.05041688
|
||||
0.014507067
|
||||
-0.06100631
|
||||
-0.10755678
|
||||
-0.10481951
|
||||
-0.090853445
|
||||
-0.021902813
|
||||
-0.08386116
|
||||
0.006706923
|
||||
-0.0064033153
|
||||
-0.012173957
|
||||
-0.0036868856
|
||||
0.095132016
|
||||
-0.021994542
|
||||
-0.004649494
|
||||
-0.026794076
|
||||
-0.01632169
|
||||
-0.010126181
|
||||
-0.01677234
|
||||
-0.013022024
|
||||
-0.005384277
|
||||
-0.0054797633
|
||||
0.00015999126
|
||||
0.013708873
|
||||
0.09010221
|
||||
0.11247074
|
||||
0.0702876
|
||||
0.07355304
|
||||
0.07295774
|
||||
0.09754597
|
||||
0.079869345
|
||||
0.11162802
|
||||
-0.09146599
|
||||
-0.06617916
|
||||
-0.05427548
|
||||
0.012102348
|
||||
-0.11461164
|
||||
-0.1239081
|
||||
-0.09864961
|
||||
0.08521436
|
||||
-0.0010414277
|
||||
0.024066186
|
||||
0.042577848
|
||||
0.06795371
|
||||
0.0033148052
|
||||
-0.04981378
|
||||
-0.002585282
|
||||
-0.0003937899
|
||||
-0.003339654
|
||||
0.008448152
|
||||
-0.035717778
|
||||
-0.021917287
|
||||
-0.020991681
|
||||
-0.016192002
|
||||
0.03761725
|
||||
0.034530357
|
||||
-0.06626378
|
||||
0.0014098238
|
||||
-0.076238416
|
||||
0.029416975
|
||||
0.018664703
|
||||
0.03343811
|
||||
0.038841713
|
||||
-0.05282685
|
||||
-0.008477915
|
||||
-0.050246432
|
||||
0.04036034
|
||||
0.03782437
|
||||
0.04491213
|
||||
0.0031788559
|
||||
0.026595125
|
||||
0.05203974
|
||||
-0.011356884
|
||||
0.043487385
|
||||
-0.055312343
|
||||
0.03458062
|
||||
0.040055893
|
||||
-0.039015166
|
||||
-0.022881871
|
||||
0.0063166018
|
||||
-0.038738396
|
||||
0.00589617
|
||||
-0.020359939
|
||||
-0.012527778
|
||||
0.064004995
|
||||
0.010790943
|
||||
-0.01802895
|
||||
-0.056990944
|
||||
-0.051393062
|
||||
-0.023789257
|
||||
0.0030616294
|
||||
0.051064275
|
||||
0.04010207
|
||||
0.03371209
|
||||
0.060095347
|
||||
0.015607021
|
||||
0.010104986
|
||||
0.020415762
|
||||
0.0019168631
|
||||
0.04336732
|
||||
-0.039259564
|
||||
0.055087548
|
||||
0.025899537
|
||||
0.018325731
|
||||
-0.031002747
|
||||
-0.033109486
|
||||
-0.035237692
|
||||
-0.060989216
|
||||
0.055961084
|
||||
0.02822797
|
||||
0.027010137
|
||||
-0.025959654
|
||||
-0.035303224
|
||||
-0.039628804
|
||||
-0.05582998
|
||||
-0.03959532
|
||||
0.1256905
|
||||
-0.027060708
|
||||
-0.05580327
|
||||
-0.03622858
|
||||
0.12780237
|
||||
-0.018839851
|
||||
-0.03447354
|
||||
0.08838121
|
||||
-0.03136378
|
||||
-0.05799618
|
||||
-0.023935076
|
||||
0.078720175
|
||||
-0.02881707
|
||||
0.00847261
|
||||
-0.02233137
|
||||
-0.013755523
|
||||
0.014816273
|
||||
0.004065502
|
||||
0.11188121
|
||||
-0.014230934
|
||||
-0.0056429356
|
||||
-0.0045665978
|
||||
-0.00498333
|
||||
-0.012701793
|
||||
-0.0019023885
|
||||
-0.030901533
|
||||
-0.007683906
|
||||
-0.020062435
|
||||
-0.04124341
|
||||
0.024057284
|
||||
-0.09335823
|
||||
-0.03777578
|
||||
-0.014056007
|
||||
-0.008580212
|
||||
0.11240235
|
||||
0.002323658
|
||||
0.016537955
|
||||
-0.07825424
|
||||
-0.016088892
|
||||
-0.025930585
|
||||
0.027807685
|
||||
0.1700214
|
||||
-0.019626008
|
||||
-0.07721867
|
||||
-0.04162061
|
||||
0.052601207
|
||||
0.02577326
|
||||
-0.040874712
|
||||
-0.03728593
|
||||
-0.012193351
|
||||
0.13011028
|
||||
-0.041224383
|
||||
0.057561
|
||||
-0.010276193
|
||||
-0.024530202
|
||||
-0.03962346
|
||||
-0.040800393
|
||||
0.13106227
|
||||
-0.02382709
|
||||
-0.06445572
|
||||
0.1744702
|
||||
-0.047365215
|
||||
-0.0107749
|
||||
0.017781138
|
||||
0.05427503
|
||||
-0.04871042
|
||||
-0.010184613
|
||||
0.14689082
|
||||
-0.06170824
|
||||
-0.040328942
|
||||
-0.050108895
|
||||
0.07433148
|
||||
-0.035749625
|
||||
-0.05033758
|
||||
-0.034158345
|
||||
-0.01407411
|
||||
-0.03855565
|
||||
0.118630916
|
||||
0.015975745
|
||||
-0.025617888
|
||||
-0.027871372
|
||||
0.020677658
|
||||
-0.060416315
|
||||
-0.011996592
|
||||
0.15613428
|
||||
-0.039205384
|
||||
-0.017144002
|
||||
-0.016228413
|
||||
0.01726939
|
||||
0.11926382
|
||||
-0.029930148
|
||||
-0.015833873
|
||||
-0.036014646
|
||||
-0.021936195
|
||||
-0.027379872
|
||||
-0.006858447
|
||||
0.036611702
|
||||
-0.06453845
|
||||
0.017900916
|
||||
-0.017864183
|
||||
0.016977126
|
||||
0.00013984025
|
||||
-0.011365406
|
||||
-0.02641995
|
||||
0.05642642
|
||||
-0.02021149
|
||||
-0.016630339
|
||||
0.024355782
|
||||
-0.014129852
|
||||
0.103316136
|
||||
-0.041531242
|
||||
-0.00224662
|
||||
-0.026749535
|
||||
-0.01905401
|
||||
0.0026879937
|
||||
-0.008229434
|
||||
0.017593939
|
||||
-0.018483022
|
||||
0.019348662
|
||||
-0.056839425
|
||||
0.043575108
|
||||
0.07768085
|
||||
0.030608702
|
||||
-0.05727275
|
||||
0.10484878
|
||||
-0.06496533
|
||||
-0.05744542
|
||||
0.05217385
|
||||
0.011118693
|
||||
-0.008622026
|
||||
-0.02919702
|
||||
0.031088505
|
||||
-0.051129196
|
||||
0.027191278
|
||||
-0.048688192
|
||||
0.04744573
|
||||
-0.054880034
|
||||
0.07251054
|
||||
0.017558554
|
||||
-0.06281788
|
||||
0.0071332487
|
||||
-0.05200442
|
||||
0.08113713
|
||||
-0.043849833
|
||||
0.07000845
|
||||
-0.003035843
|
||||
-0.035914857
|
||||
-0.0068447613
|
||||
0.029527344
|
||||
-0.060751688
|
||||
-0.022351053
|
||||
-0.025395205
|
||||
0.033314105
|
||||
0.09969347
|
||||
-0.03596114
|
||||
0.007367574
|
||||
-0.07811931
|
||||
-0.015391812
|
||||
-0.010692302
|
||||
0.02191812
|
||||
0.06635398
|
||||
-0.04495509
|
||||
0.0008100525
|
||||
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