├── doc ├── 哨兵视觉部分技术报告.docx ├── can-bus.md ├── qt5.md └── init.md ├── can-bus-test ├── build │ ├── can-bus-test │ └── .qmake.stash ├── main.cpp ├── can-bus-test.pro ├── mainwindow.h ├── mainwindow.ui └── mainwindow.cpp ├── .gitattributes ├── include ├── config.h ├── commprotocol.h ├── imageshow.h ├── taskmanager.h ├── energydetector.h ├── capturethread.h ├── anglesolver.h ├── armordetector.h ├── processthread.h ├── common.h ├── CameraStatus.h └── CameraDefine.h ├── .gitignore ├── config ├── camera.xml ├── long_camera.xml └── config.json ├── LICENSE ├── DUT0BUG-RM-CV-2021.pro ├── src ├── main.cpp ├── imageshow.cpp ├── taskmanager.cpp ├── capturethread.cpp ├── config.cpp ├── processthread.cpp ├── commprotocol.cpp ├── anglesolver.cpp ├── energydetector.cpp └── armordetector.cpp ├── README.md ├── log └── log.txt └── imageshow.ui /doc/哨兵视觉部分技术报告.docx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/tbh111/DUT0BUG-RM-CV-2021/HEAD/doc/哨兵视觉部分技术报告.docx -------------------------------------------------------------------------------- /can-bus-test/build/can-bus-test: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/tbh111/DUT0BUG-RM-CV-2021/HEAD/can-bus-test/build/can-bus-test -------------------------------------------------------------------------------- /.gitattributes: -------------------------------------------------------------------------------- 1 | # Auto detect text files and perform LF normalization 2 | * text=auto 3 | *.h linguist-language=C++ 4 | *.cpp linguist-language=C++ 5 | *.hpp linguist-language=C++ 6 | -------------------------------------------------------------------------------- /can-bus-test/main.cpp: -------------------------------------------------------------------------------- 1 | #include "mainwindow.h" 2 | #include 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | 11 | int main(int argc, char *argv[]) 12 | { 13 | QApplication a(argc, argv); 14 | 15 | 16 | // qDebug() << "closed"; 17 | MainWindow w; 18 | w.show(); 19 | return a.exec(); 20 | } 21 | -------------------------------------------------------------------------------- /doc/can-bus.md: -------------------------------------------------------------------------------- 1 | ## 设置manifold的can总线 2 | 3 | #### 1.设置can 4 | 5 | manifold共有两个can接口,分别为can0和can1。使用下面的命令将can0比特率设置为250kbps,注意官方文档中给出的maniflod的can总线最大传输速率为2Mbps,且不能向外设供电。 6 | 7 | ``` 8 | sudo ip link set up can0 type can bitrate 250000 9 | ``` 10 | 11 | 为了在出现"bus error"错误之后的100毫秒内恢复原先状态,使用下面的命令设置。 12 | 13 | ``` 14 | sudo ip link set up can0 type can bitrate 250000 restart-ms 100 15 | ``` 16 | 17 | #### 2.建立can总线设备 18 | 19 | 首先检查QCanBus类是否存在,在qmake中加入 20 | 21 | ``` 22 | QT += serialbus 23 | ``` 24 | 25 | 在can通信类的头文件中加入 26 | 27 | ``` 28 | #include 29 | ``` 30 | 31 | -------------------------------------------------------------------------------- /include/config.h: -------------------------------------------------------------------------------- 1 | #ifndef CONFIG_H 2 | #define CONFIG_H 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | 12 | class Config 13 | { 14 | public: 15 | Config(); 16 | ~Config(); 17 | QString ReadJsonFile(QString function, QString key); 18 | QString ReadYamlFile(); 19 | int InitJsonFile(); 20 | int WriteJsonFile(); 21 | int WriteYamlFile(); 22 | 23 | private: 24 | QFile fp_json; 25 | }; 26 | 27 | #endif // CONFIG_H 28 | -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | # C++ objects and libs 2 | *.slo 3 | *.lo 4 | *.o 5 | *.a 6 | *.la 7 | *.lai 8 | *.so 9 | *.dll 10 | *.dylib 11 | 12 | # Qt-es 13 | object_script.*.Release 14 | object_script.*.Debug 15 | *_plugin_import.cpp 16 | /.qmake.cache 17 | /.qmake.stash 18 | *.pro.user 19 | *.pro.user.* 20 | *.qbs.user 21 | *.qbs.user.* 22 | *.moc 23 | moc_*.cpp 24 | moc_*.h 25 | qrc_*.cpp 26 | ui_*.h 27 | *.qmlc 28 | *.jsc 29 | Makefile* 30 | *build-* 31 | 32 | # Qt unit tests 33 | target_wrapper.* 34 | 35 | # QtCreator 36 | *.autosave 37 | 38 | # QtCreator Qml 39 | *.qmlproject.user 40 | *.qmlproject.user.* 41 | 42 | # QtCreator CMake 43 | CMakeLists.txt.user* 44 | -------------------------------------------------------------------------------- /can-bus-test/can-bus-test.pro: -------------------------------------------------------------------------------- 1 | QT += core gui 2 | QT += serialbus 3 | 4 | greaterThan(QT_MAJOR_VERSION, 4): QT += widgets 5 | 6 | CONFIG += c++11 7 | 8 | # You can make your code fail to compile if it uses deprecated APIs. 9 | # In order to do so, uncomment the following line. 10 | #DEFINES += QT_DISABLE_DEPRECATED_BEFORE=0x060000 # disables all the APIs deprecated before Qt 6.0.0 11 | 12 | SOURCES += \ 13 | main.cpp \ 14 | mainwindow.cpp 15 | 16 | HEADERS += \ 17 | mainwindow.h 18 | 19 | FORMS += \ 20 | mainwindow.ui 21 | 22 | # Default rules for deployment. 23 | qnx: target.path = /tmp/$${TARGET}/bin 24 | else: unix:!android: target.path = /opt/$${TARGET}/bin 25 | !isEmpty(target.path): INSTALLS += target 26 | -------------------------------------------------------------------------------- /can-bus-test/mainwindow.h: -------------------------------------------------------------------------------- 1 | #ifndef MAINWINDOW_H 2 | #define MAINWINDOW_H 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | 12 | QT_BEGIN_NAMESPACE 13 | namespace Ui { class MainWindow; } 14 | QT_END_NAMESPACE 15 | 16 | class MainWindow : public QMainWindow 17 | { 18 | Q_OBJECT 19 | 20 | public: 21 | MainWindow(QWidget *parent = nullptr); 22 | ~MainWindow(); 23 | 24 | private slots: 25 | void updateText(); 26 | 27 | void on_send_pushButton_clicked(); 28 | 29 | void on_connect_pushButton_clicked(); 30 | 31 | void on_disconnect_pushButton_clicked(); 32 | 33 | private: 34 | Ui::MainWindow *ui; 35 | QCanBusDevice *device; 36 | }; 37 | #endif // MAINWINDOW_H 38 | -------------------------------------------------------------------------------- /include/commprotocol.h: -------------------------------------------------------------------------------- 1 | #ifndef COMMPROTOCOL_H 2 | #define COMMPROTOCOL_H 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include 12 | #include 13 | #include 14 | #include "common.h" 15 | 16 | class CommProtocol 17 | { 18 | public: 19 | CommProtocol(int t_protocol, QString t_port); 20 | bool initConnect(); 21 | void disConnect(); 22 | bool writeData(common_utils::TranPkg tx_pkg); 23 | int getFrameNumber(); 24 | common_utils::RecvPkg readData(); 25 | QCanBusDevice* device; 26 | private: 27 | int protocol; 28 | QString port; 29 | const int bitrate = 1000000; 30 | const int dbitrate = 2000000; 31 | }; 32 | 33 | #endif // COMMPROTOCOL_H 34 | -------------------------------------------------------------------------------- /can-bus-test/build/.qmake.stash: -------------------------------------------------------------------------------- 1 | QMAKE_CXX.QT_COMPILER_STDCXX = 201402L 2 | QMAKE_CXX.QMAKE_GCC_MAJOR_VERSION = 7 3 | QMAKE_CXX.QMAKE_GCC_MINOR_VERSION = 4 4 | QMAKE_CXX.QMAKE_GCC_PATCH_VERSION = 0 5 | QMAKE_CXX.COMPILER_MACROS = \ 6 | QT_COMPILER_STDCXX \ 7 | QMAKE_GCC_MAJOR_VERSION \ 8 | QMAKE_GCC_MINOR_VERSION \ 9 | QMAKE_GCC_PATCH_VERSION 10 | QMAKE_CXX.INCDIRS = \ 11 | /usr/include/c++/7 \ 12 | /usr/include/aarch64-linux-gnu/c++/7 \ 13 | /usr/include/c++/7/backward \ 14 | /usr/lib/gcc/aarch64-linux-gnu/7/include \ 15 | /usr/local/include \ 16 | /usr/lib/gcc/aarch64-linux-gnu/7/include-fixed \ 17 | /usr/include/aarch64-linux-gnu \ 18 | /usr/include 19 | QMAKE_CXX.LIBDIRS = \ 20 | /usr/lib/gcc/aarch64-linux-gnu/7 \ 21 | /usr/lib/aarch64-linux-gnu \ 22 | /usr/lib \ 23 | /lib/aarch64-linux-gnu \ 24 | /lib 25 | -------------------------------------------------------------------------------- /include/imageshow.h: -------------------------------------------------------------------------------- 1 | #ifndef IMAGESHOW_H 2 | #define IMAGESHOW_H 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include "common.h" 9 | 10 | namespace Ui { 11 | class ImageShow; 12 | } 13 | 14 | class ImageShow : public QWidget 15 | { 16 | Q_OBJECT 17 | 18 | public: 19 | explicit ImageShow(QWidget *parent = nullptr); 20 | explicit ImageShow(QString window_name, QWidget *parent = nullptr); 21 | ~ImageShow(); 22 | public slots: 23 | void draw(QImage qimg); 24 | void showFps(int fps); 25 | void showTx(common_utils::TranPkg new_tx); 26 | void showRx(common_utils::RecvPkg new_rx); 27 | private slots: 28 | void on_closeButton_clicked(); 29 | signals: 30 | void end_signal(); 31 | 32 | private: 33 | Ui::ImageShow *ui; 34 | int sample_count = 0; 35 | }; 36 | 37 | #endif // IMAGESHOW_H 38 | -------------------------------------------------------------------------------- /config/camera.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 60 4 | 34 5 | 6 | 3 7 | 3 8 |
d
9 | 1039.4865625391900000 0.0000000000000000 316.4180899304880000 10 | 0.0000000000000000 1039.353157786020000 259.8881988114650000 11 | 0.0000000000000000 0.0000000000000000 1.0000000000000000 12 | 13 |
14 | 15 | 5 16 | 1 17 |
d
18 | -0.103621005222992 0.132444751012341 0.0000000000000000 0.0000000000000000 0.0000000000000000 19 |
20 |
21 | -------------------------------------------------------------------------------- /config/long_camera.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 60 4 | 34 5 | 6 | 3 7 | 3 8 |
d
9 | 3095.7988087967900000 0.0000000000000000 362.6308164616070000 10 | 0.0000000000000000 3096.139011072400000 258.2973430928710000 11 | 0.0000000000000000 0.0000000000000000 1.0000000000000000 12 | 13 |
14 | 15 | 5 16 | 1 17 |
d
18 | -0.0646331324139052 0.0852361998596593 0.0000000000000000 0.0000000000000000 0.0000000000000000 19 |
20 |
21 | -------------------------------------------------------------------------------- /include/taskmanager.h: -------------------------------------------------------------------------------- 1 | #ifndef TASKMANAGER_H 2 | #define TASKMANAGER_H 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include "capturethread.h" 11 | #include "processthread.h" 12 | #include "commprotocol.h" 13 | #include "imageshow.h" 14 | #include "common.h" 15 | 16 | class TaskManager:public QObject 17 | { 18 | Q_OBJECT 19 | public: 20 | explicit TaskManager(int mode, QObject *parent = nullptr); 21 | signals: 22 | void new_rx(common_utils::RecvPkg rx); 23 | public slots: 24 | void end_show(); 25 | void updateTx(common_utils::TranPkg tx); 26 | void updateRx(); 27 | private: 28 | CaptureThread* capture_thread; 29 | ProcessThread* process_thread; 30 | ImageShow* image_show; 31 | CommProtocol *comm; 32 | common_utils::RecvPkg current_rx; 33 | QMutex mutex; 34 | int task_mode; 35 | }; 36 | 37 | #endif // TASKMANAGER_H 38 | -------------------------------------------------------------------------------- /include/energydetector.h: -------------------------------------------------------------------------------- 1 | #ifndef ENERGYDETECTOR_H 2 | #define ENERGYDETECTOR_H 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include "common.h" 9 | 10 | using namespace std; 11 | 12 | using namespace cv; 13 | using namespace cv::ml; 14 | 15 | vector ARMOR; 16 | int16_t yawErr,pitchErr; 17 | 18 | class EnergyBox 19 | { 20 | public: 21 | EnergyBox() = default; 22 | EnergyBox(const cv::Rect &t_rect): 23 | armor_rect(t_rect), isValid(true){} 24 | cv::Rect armor_rect; 25 | bool isValid = false; 26 | int armor_type = common_utils::ARMOR_ENERGY; 27 | 28 | }; 29 | 30 | class EnergyDetector 31 | { 32 | public: 33 | EnergyDetector(); 34 | bool run(const cv::Mat &src_img, cv::Mat &dst_img, EnergyBox &target, int &self_color); 35 | private: 36 | double getDistance(Point A,Point B); 37 | std::vector stander(Mat im); 38 | cv::Mat get(Mat input); 39 | 40 | cv::Ptr svm; 41 | 42 | }; 43 | 44 | 45 | 46 | 47 | #endif // ENERGYDETECTOR_H 48 | -------------------------------------------------------------------------------- /config/config.json: -------------------------------------------------------------------------------- 1 | { 2 | "armor": { 3 | "blue_binary_threshold": 200, 4 | "red_binary_threshold": 150 5 | }, 6 | "energy": { 7 | "energy_armor_area_max_threshold": 5000, 8 | "energy_armor_area_min_threshold": 3500, 9 | "hsv_blue_hmax": 150, 10 | "hsv_blue_hmin": 80, 11 | "hsv_blue_smax": 255, 12 | "hsv_blue_smin": 40, 13 | "hsv_blue_vmax": 255, 14 | "hsv_blue_vmin": 100, 15 | "hsv_red_hmax": 180, 16 | "hsv_red_hmax_2": 40, 17 | "hsv_red_hmin": 250, 18 | "hsv_red_hmin_2": 0, 19 | "hsv_red_smax": 255, 20 | "hsv_red_smin": 40, 21 | "hsv_red_vmax": 225, 22 | "hsv_red_vmin": 100 23 | }, 24 | "mode": { 25 | "function": "full", 26 | "source": "video" 27 | }, 28 | "paths": { 29 | "camera_param_path": "../config/camera.xml", 30 | "energy_svm_path": "../config/SVM_MODEL.xml", 31 | "test_video_path": "../config/1.avi" 32 | }, 33 | "serial": { 34 | "baud_rate": 115200, 35 | "port": "/dev/ttyTHS2" 36 | } 37 | } 38 | -------------------------------------------------------------------------------- /include/capturethread.h: -------------------------------------------------------------------------------- 1 | #ifndef CAPTURETHREAD_H 2 | #define CAPTURETHREAD_H 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include "CameraApi.h" 11 | #include "CameraDefine.h" 12 | #include "CameraStatus.h" 13 | 14 | class CaptureThread : public QThread 15 | { 16 | Q_OBJECT 17 | public: 18 | explicit CaptureThread(QObject *parent = nullptr); 19 | int cameraOpen(); 20 | void cameraClose(); 21 | void getFrame(); 22 | // int GetFps(); 23 | protected: 24 | void run(); 25 | signals: 26 | void camera_opened(); 27 | void capture_done(cv::Mat img); 28 | void send_capture_fps(int send_fps); 29 | public slots: 30 | void setCameraOff(); 31 | private: 32 | cv::Mat grabbed_frame; 33 | QMutex stopped_mutex, data_mutex; 34 | int frame_number = 0; 35 | double time_strap = 0.0; 36 | double fps = 0.0; 37 | volatile bool stop_flag = false; 38 | 39 | CameraHandle h_camera; 40 | tSdkCameraCapbility camera_capability; 41 | BYTE *pbyBuffer = NULL; 42 | BYTE *g_pRgbBuffer = NULL; 43 | }; 44 | 45 | #endif // CAPTURETHREAD_H 46 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | This is free and unencumbered software released into the public domain. 2 | 3 | Anyone is free to copy, modify, publish, use, compile, sell, or 4 | distribute this software, either in source code form or as a compiled 5 | binary, for any purpose, commercial or non-commercial, and by any 6 | means. 7 | 8 | In jurisdictions that recognize copyright laws, the author or authors 9 | of this software dedicate any and all copyright interest in the 10 | software to the public domain. We make this dedication for the benefit 11 | of the public at large and to the detriment of our heirs and 12 | successors. We intend this dedication to be an overt act of 13 | relinquishment in perpetuity of all present and future rights to this 14 | software under copyright law. 15 | 16 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, 17 | EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF 18 | MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. 19 | IN NO EVENT SHALL THE AUTHORS BE LIABLE FOR ANY CLAIM, DAMAGES OR 20 | OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, 21 | ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR 22 | OTHER DEALINGS IN THE SOFTWARE. 23 | 24 | For more information, please refer to 25 | -------------------------------------------------------------------------------- /include/anglesolver.h: -------------------------------------------------------------------------------- 1 | #ifndef ANGLESOLVER_H 2 | #define ANGLESOLVER_H 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include "common.h" 10 | 11 | class AngleSolver 12 | { 13 | public: 14 | AngleSolver(); 15 | 16 | //初始化角度解算的参数 17 | bool init(); 18 | 19 | //利用小孔成像原理进行单点解算,只能得到相对于摄像头中心的转角,没有深度信息,仅需一个点 20 | void onePointSolution(const std::vector centerPoint); 21 | 22 | //利用solvePNP进行位置解算,包含深度信息,可以自定义中心,需要四个点 23 | std::vector p4pSolution(const cv::Rect &rect, int objectType); 24 | 25 | //重力补偿 26 | /* 27 | //air friction is considered 28 | float BulletModel(float x, float v, float angle); 29 | 30 | //x:distance , y: height 31 | float GetPitch(float x, float y, float v); 32 | 33 | void Transform(cv::Point3f &postion, float &pitch, float &yaw); 34 | */ 35 | private: 36 | 37 | cv::Mat CameraIntrinsicMatrix; //相机内参矩阵 38 | cv::Mat DistortionCoefficient; //相机畸变系数 39 | //单位为mm 40 | std::vector POINT_3D_OF_ARMOR_BIG; 41 | std::vector POINT_3D_OF_ARMOR_SMALL; 42 | float Y_DISTANCE_BETWEEN_GUN_AND_CAM;//如果摄像头在枪管的上面,这个变量为正 43 | float Z_DISTANCE_BETWEEN_MUZZLE_AND_CAM;//如果摄像头在枪口的后面,这个变量为正 44 | 45 | 46 | float _euclideanDistance;//x坐标下的差值,y坐标下的差值,欧氏距离 47 | float yawErr = 0; 48 | float pitchErr = 0; //yaw轴的误差,pitch轴的误差 49 | 50 | const float GRAVITY = 9.78; 51 | 52 | }; 53 | 54 | #endif // ANGLESOLVER_H 55 | -------------------------------------------------------------------------------- /include/armordetector.h: -------------------------------------------------------------------------------- 1 | #ifndef ARMORDETECTOR_H 2 | #define ARMORDETECTOR_H 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include 12 | #include "common.h" 13 | 14 | class ArmorBox 15 | { 16 | public: 17 | ArmorBox() = default; 18 | ArmorBox(const cv::Rect &t_rect, const cv::RotatedRect &t_rotate_rect, const cv::Mat &t_img, int t_armor_type): 19 | armor_rect(t_rect), armor_rotated_rect(t_rotate_rect), armor_img(t_img), armor_type(t_armor_type), isValid(true) 20 | { 21 | // armor_rect.points(armor_points); 22 | } 23 | static bool areaComparator(const ArmorBox &a, const ArmorBox &b); 24 | static bool ratioComparator(const ArmorBox &a, const ArmorBox &b); 25 | // cv::Point2f armor_points[4]; 26 | cv::Rect armor_rect; 27 | cv::RotatedRect armor_rotated_rect; 28 | cv::Mat armor_img; 29 | bool isValid = false; 30 | int armor_type = common_utils::ARMOR_SMALL; 31 | }; 32 | 33 | class ArmorDetector 34 | { 35 | public: 36 | ArmorDetector(); 37 | bool run(const cv::Mat &src_img, cv::Mat &dst_img, ArmorBox &armor_target, int &self_color); 38 | private: 39 | void preProcess(const cv::Mat &src_img, cv::Mat &bin_img, int &self_color); 40 | void findLightbars(const cv::Mat &bin_img, cv::Mat &dst_img); 41 | void matchArmorBoxes(const cv::Mat &src_img, cv::Mat &dst_img); 42 | bool getTarget(); 43 | cv::Mat warpTransform(const cv::Mat &src_img, cv::RotatedRect rect, double height, double width); 44 | cv::Point2i getCenterPoint(cv::Rect rect); 45 | cv::Mat bin_img; 46 | std::vector lightbars; 47 | std::vector armor_boxes; 48 | ArmorBox armor_target; 49 | 50 | int frame_count = 0; 51 | }; 52 | 53 | #endif // ARMORDETECTOR_H 54 | -------------------------------------------------------------------------------- /include/processthread.h: -------------------------------------------------------------------------------- 1 | #ifndef PROCESSTHREAD_H 2 | #define PROCESSTHREAD_H 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include "armordetector.h" 12 | //#include "energydetector.h" 13 | #include "anglesolver.h" 14 | #include "common.h" 15 | 16 | class ProcessThread : public QThread 17 | { 18 | Q_OBJECT 19 | public: 20 | explicit ProcessThread(QObject *parent = nullptr); 21 | protected: 22 | void run(); 23 | public slots: 24 | void getImage(cv::Mat image); 25 | void setProcessOn(); 26 | void setProcessOff(); 27 | void getRx(common_utils::RecvPkg new_rx); 28 | // void switch_mode(int change_mode); 29 | signals: 30 | void update_show_image(QImage img); 31 | void send_process_fps(int fps); 32 | void send_tx_pkg(common_utils::TranPkg tx_pkg); 33 | private: 34 | void preProcess(); 35 | void process(); 36 | 37 | cv::Mat src_img, bin_img, dst_img; 38 | QMutex stop_mutex; 39 | QMutex data_mutex; 40 | double time_strap = 0.0; 41 | double fps = 0.0; 42 | int process_mode = 0; 43 | 44 | // received data from stm32 45 | int color = common_utils::SELF_RED; 46 | int process_target = common_utils::TARGET_ARMOR; 47 | int energy_mode = common_utils::ENERGY_SMALL; 48 | int video_switch = common_utils::VIDEO_OFF; 49 | double pitch_rx = 0.0; 50 | double speed_rx = 0.0; 51 | 52 | //transmit data to stm32 53 | common_utils::TranPkg tx_pkg; 54 | void packTx(); 55 | int detect_flag = common_utils::DETECT_NONE; 56 | double yaw_tx = 0.0; 57 | double pitch_tx = 0.0; 58 | int cmd_tx = common_utils::SHOOT_DISABLED; 59 | 60 | bool image_update_flag = false; 61 | volatile bool stop_flag = false; 62 | volatile bool start_flag = false; 63 | }; 64 | 65 | #endif // PROCESSTHREAD_H 66 | -------------------------------------------------------------------------------- /DUT0BUG-RM-CV-2021.pro: -------------------------------------------------------------------------------- 1 | QT += core gui 2 | QT += widgets 3 | QT += serialbus 4 | CONFIG += c++11 console 5 | CONFIG -= app_bundle 6 | 7 | # The following define makes your compiler emit warnings if you use 8 | # any Qt feature that has been marked deprecated (the exact warnings 9 | # depend on your compiler). Please consult the documentation of the 10 | # deprecated API in order to know how to port your code away from it. 11 | DEFINES += QT_DEPRECATED_WARNINGS 12 | 13 | # You can also make your code fail to compile if it uses deprecated APIs. 14 | # In order to do so, uncomment the following line. 15 | # You can also select to disable deprecated APIs only up to a certain version of Qt. 16 | #DEFINES += QT_DISABLE_DEPRECATED_BEFORE=0x060000 # disables all the APIs deprecated before Qt 6.0.0 17 | 18 | message("infantry v0.1") 19 | 20 | SOURCES += \ 21 | src/anglesolver.cpp \ 22 | src/commprotocol.cpp \ 23 | # src/energydetector.cpp \ 24 | src/imageshow.cpp \ 25 | src/config.cpp \ 26 | src/main.cpp \ 27 | src/taskmanager.cpp \ 28 | src/processthread.cpp \ 29 | src/capturethread.cpp \ 30 | src/armordetector.cpp 31 | 32 | HEADERS += \ 33 | include/anglesolver.h \ 34 | include/common.h \ 35 | include/commprotocol.h \ 36 | # include/energydetector.h \ 37 | include/imageshow.h \ 38 | include/config.h \ 39 | include/CameraApi.h \ 40 | include/CameraDefine.h \ 41 | include/CameraStatus.h \ 42 | include/taskmanager.h \ 43 | include/processthread.h \ 44 | include/capturethread.h \ 45 | include/armordetector.h 46 | 47 | COMPILER = $$system($$QMAKE_CC -v 2>&1) 48 | contains(COMPILER, x86_64-linux-gnu){ 49 | message("compile on linux, x86_64-linux-gnu") 50 | LIBS += /home/tbh/DUT0BUG-RM-CV-2021/lib/x64/libMVSDK.so 51 | } 52 | contains(COMPILER, aarch64-linux-gnu){ 53 | message("compile on linux, aarch64-linux-gnu") 54 | LIBS += /home/dji/DUT0BUG-RM-CV-2021/lib/arm64/libMVSDK.so 55 | } 56 | 57 | INCLUDEPATH += /usr/local/include/opencv4/ 58 | INCLUDEPATH += /usr/local/include/eigen3 59 | INCLUDEPATH += ./include/ 60 | LIBS += /usr/local/lib/libopencv_*.so 61 | 62 | # Default rules for deployment. 63 | qnx: target.path = /tmp/$${TARGET}/bin 64 | else: unix:!android: target.path = /opt/$${TARGET}/bin 65 | !isEmpty(target.path): INSTALLS += target 66 | 67 | FORMS += \ 68 | imageshow.ui 69 | -------------------------------------------------------------------------------- /can-bus-test/mainwindow.ui: -------------------------------------------------------------------------------- 1 | 2 | 3 | MainWindow 4 | 5 | 6 | Qt::ApplicationModal 7 | 8 | 9 | 10 | 0 11 | 0 12 | 345 13 | 582 14 | 15 | 16 | 17 | Can Bus Debugger 18 | 19 | 20 | 21 | 22 | 23 | 40 24 | 170 25 | 256 26 | 311 27 | 28 | 29 | 30 | 31 | 32 | 33 | 190 34 | 30 35 | 78 36 | 22 37 | 38 | 39 | 40 | disconnect 41 | 42 | 43 | 44 | 45 | 46 | 50 47 | 80 48 | 231 49 | 22 50 | 51 | 52 | 53 | 54 | 55 | 56 | 60 57 | 30 58 | 78 59 | 22 60 | 61 | 62 | 63 | connect 64 | 65 | 66 | 67 | 68 | 69 | 120 70 | 120 71 | 80 72 | 22 73 | 74 | 75 | 76 | send 77 | 78 | 79 | 80 | 81 | 82 | 83 | 0 84 | 0 85 | 345 86 | 19 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | 95 | -------------------------------------------------------------------------------- /src/main.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | 10 | #include "taskmanager.h" 11 | #include "common.h" 12 | #include "config.h" 13 | 14 | void logger(QtMsgType type,const QMessageLogContext &context,const QString &msg); 15 | unsigned long GetTickCount(); 16 | 17 | int main(int argc, char *argv[]) 18 | { 19 | qInstallMessageHandler(logger); // 全局日志功能 20 | QApplication a(argc, argv); 21 | qDebug() << "STARTING MAIN CLIENT..."; 22 | TaskManager manager(common_utils::SHOW_ON); // 线程调度 23 | 24 | // 从文件读取参数,未使用 25 | //Config config; 26 | 27 | //config.InitJsonFile(); 28 | //QString test = config.ReadJsonFile("serial", "baud_rate"); 29 | //qDebug() << test; 30 | // QString test1 = config.ReadJsonFile("serial", "port"); 31 | // qDebug() << test1; 32 | // QString test2 = config.ReadJsonFile("energy", "energy_armor_area_max_threshold"); 33 | // qDebug() << test2; 34 | return a.exec(); 35 | 36 | } 37 | 38 | unsigned long GetTickCount() 39 | { 40 | struct timespec ts; 41 | clock_gettime(CLOCK_MONOTONIC, &ts); 42 | return (ts.tv_sec * 1000 + ts.tv_nsec / 1000000); 43 | } 44 | 45 | void logger(QtMsgType type, const QMessageLogContext &context, const QString &msg) 46 | { 47 | // 加锁 48 | static QMutex mutex; 49 | mutex.lock(); 50 | 51 | QByteArray localMsg = msg.toLocal8Bit(); 52 | 53 | QString strMsg(""); 54 | switch(type) 55 | { 56 | case QtDebugMsg: 57 | strMsg = QString("Debug"); 58 | break; 59 | case QtWarningMsg: 60 | strMsg = QString("Warning"); 61 | break; 62 | case QtCriticalMsg: 63 | strMsg = QString("Critical"); 64 | break; 65 | case QtFatalMsg: 66 | strMsg = QString("Fatal"); 67 | break; 68 | default: 69 | break; 70 | } 71 | 72 | // 设置输出信息格式 73 | QString strDateTime = QDateTime::currentDateTime().toString("yyyy-MM-dd hh:mm:ss ddd"); 74 | QString strMessage = QString("[%1][%2] File:%3 Line:%4 %5") 75 | .arg(strDateTime).arg(strMsg).arg(context.file).arg(context.line).arg(localMsg.constData()); 76 | // 输出信息至文件中(读写、追加形式) 77 | QFile file("../log/log.txt"); 78 | file.open(QIODevice::ReadWrite | QIODevice::Append); 79 | QTextStream stream(&file); 80 | stream << strMessage << "\r\n"; 81 | file.flush(); 82 | file.close(); 83 | 84 | // 解锁 85 | mutex.unlock(); 86 | } 87 | -------------------------------------------------------------------------------- /include/common.h: -------------------------------------------------------------------------------- 1 | #ifndef GENERAL_H 2 | #define GENERAL_H 3 | 4 | #include 5 | 6 | namespace common_utils 7 | { 8 | // flags for transmit data 9 | // no detect: 0x00, detected: 0x01 10 | enum DETECT_STATE {DETECT_NONE = 0x00, DETECT_YES = 0x01}; 11 | // disabled: 0x00, single: 0x01, auto: 0x02 12 | enum SHOOT_MODE {SHOOT_DISABLED = 0x00, SHOOT_SINGLE = 0x01, SHOOT_AUTO = 0x02}; 13 | 14 | // function codes 15 | enum FUNC_CODE {FUNC_COLOR = 0x01, FUNC_TARGET = 0x02, FUNC_ENERGY = 0x03, 16 | FUNC_VIDEO = 0x09, FUNC_ANGLE = 0x11, FUNC_SPEED = 0x12, 17 | FUNC_INVALID = 0xFF}; 18 | 19 | // flags for receive data 20 | // self red: 0x00, self blue: 0x01 21 | enum SELF_COLOR {SELF_RED = 0x00, SELF_BLUE = 0x01}; 22 | // armor: 0x00, energy: 0x01, guard: undefined 23 | enum TARGET_MODE {TARGET_ARMOR = 0x00, TARGET_ENERGY = 0x01, TARGET_GUARD = 0x02}; 24 | // small energy: 0x00, big energy: 0x01 25 | enum ENERGY_MODE {ENERGY_SMALL = 0x00, ENERGY_BIG = 0x01}; 26 | // video on: 0x01, video off: 0x00 27 | enum VIDEO_MODE {VIDEO_OFF = 0x00, VIDEO_ON = 0x01}; 28 | 29 | // flags for other control 30 | enum ARMOR_TYPE {ARMOR_SMALL = 0, ARMOR_BIG = 1, ARMOR_ENERGY = 2}; 31 | enum PROTOCOL {CAN = 0, SERIAL = 1}; 32 | // enum COMM_MODE {RX = 0, TX = 1}; 33 | enum EXEC_MODE {SHOW_ON = 0, SHOW_OFF = 1}; 34 | enum FRAME_STATE {VALID = true, INVALID = false}; 35 | 36 | struct RecvPkg 37 | { 38 | int func_code = FUNC_INVALID; 39 | int recv_color = FUNC_INVALID; 40 | int recv_target = FUNC_INVALID; 41 | int recv_energy = FUNC_INVALID; 42 | int recv_video = FUNC_INVALID; 43 | // qint16 yaw = 0; 44 | qint16 pitch = 0; 45 | qint16 speed = 0; 46 | RecvPkg() = default; 47 | // RecvPkg(int t_color, int t_mode, int t_energy, int t_video, 48 | // qint16 t_yaw, qint16 t_pitch, qint8 t_speed): 49 | // recv_color(t_color), recv_mode(t_mode), recv_energy(t_energy), recv_video(t_video), 50 | // yaw(t_yaw), pitch(t_pitch), speed(t_speed){} 51 | }; 52 | 53 | struct TranPkg 54 | { 55 | int check_mode = FUNC_INVALID; 56 | int check_color = FUNC_INVALID; 57 | int check_video = FUNC_INVALID; 58 | int detect_state = FUNC_INVALID; 59 | qint16 yaw = 0; 60 | qint16 pitch = 0; 61 | int cmd = FUNC_INVALID; 62 | TranPkg() = default; 63 | TranPkg(int t_mode, int t_color, int t_video, int t_state, 64 | qint16 t_yaw, qint16 t_pitch, int t_cmd): 65 | check_mode(t_mode), check_color(t_color), check_video(t_video), detect_state(t_state), 66 | yaw(t_yaw), pitch(t_pitch), cmd(t_cmd){} 67 | }; 68 | 69 | } 70 | 71 | #endif // GENERAL_H 72 | -------------------------------------------------------------------------------- /doc/qt5.md: -------------------------------------------------------------------------------- 1 | ## 在manifold上安装qt5开发环境 2 | 3 | ### 使用源码方式安装 4 | 5 | #### 1.安装相应的库 6 | 7 | ``` 8 | sudo apt-get install libxcb-xinerama0-dev 9 | sudo apt-get install '^libxcb.*-dev' libx11-xcb-dev libglu1-mesa-dev libxrender-dev libxi-dev libxkbcommon-dev libxkbcommon-x11-dev 10 | ``` 11 | 12 | 直接使用apt安装。 13 | 14 | #### 2.配置configure 15 | 16 | ``` 17 | cd /home/dji/data/qt-everywhere-src-5.15.2 18 | ./configure -opensource -nomake examples -nomake tests -skip qtwebengine 19 | ``` 20 | 21 | 由于移植系统时,只会复制emmc中的内容,硬盘中的内容不会复制,此处选择的安装路径为默认的/usr/local,编译路径在/home/dji/data,即硬盘挂载的目录下,以防止emmc内存不足。注意不要加入-developer-build选项 22 | 23 | 注意若不跳过webengine模块,会遇到一堆bug,且耗费时间极长,源码大小为2.1G。 24 | 25 | 参考:[](https://wiki.qt.io/Building_Qt_5_from_Git) 26 | 27 | #### 3.build&install 28 | 29 | ``` 30 | make -j6 31 | sudo make install 32 | cd /usr/local/Qt-5.15.2/bin 33 | ./qmake -v 34 | ``` 35 | 36 | 经过漫长的等待之后,编译完成。使用-v参数输出为: 37 | 38 | QMake version 3.1 Using Qt version 5.15.2 in /usr/local/Qt-5.15.2/lib 39 | 40 | #### 4.安装Qt creator 41 | 42 | 上述完成了Qt 5.15.2的编译安装,可以使用命令行方式进行编译,但是我们需要给它套一个壳:sweat_smile:,即安装IDE:Qt creator。参考:https://wiki.qt.io/Building_Qt_Creator_from_Git/zh 43 | 44 | 首先需要将3中安装的qmake设置为环境变量,manifold原系统中装有qmake4.8.7,在终端中输入qmake时,输出的版本信息为4.8.7,需要将/usr/bin中的软连接qmake删除,将安装的qmake 5.15.2 创建一个软链接。 45 | 46 | ``` 47 | cd /usr/bin 48 | sudo rm qmake qmake-qt4 qml* qt* 49 | sudo ln -s /usr/local/Qt-5.15.2/bin/qmake ./qmake 50 | ``` 51 | 52 | Qt creator源码的文档里面要求最好安装ninja和LLVM,这里只安装了ninja。下面开始编译: 53 | 54 | ``` 55 | sudo apt-get install ninja-build 56 | cd /home/dji/data/ 57 | mkdir qt-creator-build 58 | cd qt-creator-build 59 | qmake -r ../qtcreator.pro 60 | make -j6 61 | ``` 62 | 63 | 接下来又是漫长的等待(连个进度条或者类似cmake的百分比都没,折磨) 64 | 65 | 编译结束之后,将qtcreator安装至目录/bin下,并添加到环境变量 66 | 67 | ``` 68 | sudo make install 69 | sudo ln -s /bin/qtcreator /usr/bin/qtcreator 70 | sudo qtcreator 71 | ``` 72 | 73 | 可以看到qtcreator的界面,接下来就可以使用qt写程序了:happy:(不使用sudo,初始化会报错,待解决) 74 | 75 | #### 5.配置工程 76 | 77 | 打开qtcreator之后,新建命令行工程:Projects-New-Application-Qt Console Application,修改工程名称和路径,Build system选择默认qmake,跳过翻译文件,在Kit Selection选项下选择系统检测到的默认Desktop,不添加版本控制,完成即可。 78 | 79 | PS:安装完qt和qtcreator后,emmc使用率为10.7/29.5GB,还有约17.3GB剩余。编译qt时一定要先看官方文档!!!不要先看csdn上的博客!!!Total time wasted on building qt and qt creator : 2 days. 80 | 81 | ### 使用apt安装(不推荐) 82 | 83 | ``` 84 | sudo apt-get install qt5-default 85 | sudo apt-get install aptitude 86 | sudo aptitude install qtcreator 87 | sudo apt-get install qtdeclarative5-dev 88 | ``` 89 | 90 | 使用apt-get安装qtcreator时,可能会有libclang1-3.6的依赖错误,因此选择aptitude解决该问题,在跳出第一个选项时选择N,在第二个选项选择Y,(会把一大堆东西都删了,如果没有移除预装的ros等环境),等待几分钟后安装完成。 91 | 92 | 使用apt方式安装的qt版本为5.5过旧,不使用。 93 | 94 | ### Bug 记录 95 | 96 | #### 1.Parse error at “std“ 97 | 98 | 删除build目录下的.qmake.stash文件即可 99 | 100 | ``` 101 | rm ./build/.qmake.stash 102 | ``` 103 | 104 | #### 2.Cannot load library socketcan 105 | 106 | 安装libsocketcan-dev 107 | 108 | ``` 109 | sudo apt-get install libsocketcan-dev 110 | ``` 111 | 112 | -------------------------------------------------------------------------------- /src/imageshow.cpp: -------------------------------------------------------------------------------- 1 | #include "imageshow.h" 2 | #include "ui_imageshow.h" 3 | 4 | ImageShow::ImageShow(QWidget *parent) : 5 | QWidget(parent), 6 | ui(new Ui::ImageShow) 7 | { 8 | ui->setupUi(this); 9 | } 10 | 11 | ImageShow::ImageShow(QString window_name, QWidget *parent) : 12 | QWidget(parent), 13 | ui(new Ui::ImageShow) 14 | { 15 | ui->setupUi(this); 16 | this->setWindowTitle(window_name); 17 | } 18 | 19 | ImageShow::~ImageShow() 20 | { 21 | delete ui; 22 | } 23 | 24 | void ImageShow::showTx(common_utils::TranPkg new_tx) 25 | { 26 | if(new_tx.detect_state == common_utils::DETECT_YES) 27 | { 28 | ui->state_tx->setText("detected"); 29 | } 30 | else 31 | { 32 | ui->state_tx->setText("none"); 33 | } 34 | if(new_tx.cmd == common_utils::SHOOT_AUTO) 35 | { 36 | ui->cmd_tx->setText("auto"); 37 | } 38 | else if(new_tx.cmd == common_utils::SHOOT_SINGLE) 39 | { 40 | ui->cmd_tx->setText("single"); 41 | } 42 | else if(new_tx.cmd == common_utils::SHOOT_DISABLED) 43 | { 44 | ui->cmd_tx->setText("disabled"); 45 | } 46 | ui->pitch_tx->setText(QString::number(new_tx.pitch)); 47 | ui->yaw_tx->setText(QString::number(new_tx.yaw)); 48 | } 49 | 50 | void ImageShow::showRx(common_utils::RecvPkg new_rx) 51 | { 52 | if(new_rx.recv_color == common_utils::SELF_BLUE) 53 | { 54 | ui->color_rx->setText("blue"); 55 | } 56 | else if(new_rx.recv_color == common_utils::SELF_RED) 57 | { 58 | ui->color_rx->setText("red"); 59 | } 60 | if(new_rx.recv_target == common_utils::TARGET_ARMOR) 61 | { 62 | ui->target_rx->setText("armor"); 63 | } 64 | else if(new_rx.recv_target == common_utils::TARGET_ENERGY) 65 | { 66 | ui->target_rx->setText("energy"); 67 | } 68 | if(new_rx.recv_energy == common_utils::ENERGY_SMALL) 69 | { 70 | ui->energy_rx->setText("small"); 71 | } 72 | else if(new_rx.recv_energy == common_utils::ENERGY_BIG) 73 | { 74 | ui->energy_rx->setText("big"); 75 | } 76 | if(new_rx.recv_video == common_utils::VIDEO_OFF) 77 | { 78 | ui->video_rx->setText("off"); 79 | } 80 | else if(new_rx.recv_video == common_utils::VIDEO_ON) 81 | { 82 | ui->video_rx->setText("on"); 83 | } 84 | ui->pitch_rx->setText(QString::number(new_rx.pitch)); 85 | ui->speed_rx->setText(QString::number(new_rx.speed)); 86 | } 87 | 88 | void ImageShow::draw(QImage qimg) 89 | { 90 | sample_count++; 91 | if(sample_count == 1) 92 | { 93 | ui->image->setPixmap(QPixmap::fromImage(qimg.scaled(ui->image->size(),Qt::KeepAspectRatio))); 94 | sample_count = 0; 95 | } 96 | } 97 | 98 | void ImageShow::showFps(int fps) 99 | { 100 | QString fpsText = QString("FPS: %1").arg(fps); 101 | ui->fpsLabel->setText(fpsText); 102 | } 103 | 104 | 105 | void ImageShow::on_closeButton_clicked() 106 | { 107 | emit end_signal(); 108 | this->close(); 109 | } 110 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # DUT0BUG-RM-CV-2021 2 | 3 | ## 项目简介 4 | 5 | 本仓库为2021年大连理工大学凌BUG战队视觉组代码(非战队官方开源),仅为纪念本人于2021.5.1-2021.8.6与王飞龙老师及各位队友在大福楼、北京分区赛以及深圳国赛期间度过的短暂RMer时光。 6 | 7 | ### 开发环境 8 | 9 | ``` 10 | DJI Manifold 2-G, Ubuntu 16.04 11 | 迈德威视工业相机SDK, OpenCV + OpenCV_contrib 4.5.2 12 | Qt 5.15.2 + Qt creator 4.15.1(自主源码编译) 13 | ``` 14 | 15 | 由于在北部分区赛中,使用Linux系统中的多线程框架容易导致程序在运行一段时间后崩溃(core dumped),且使用妙算2(DJI的智商税及劝退产品)上的串口与下位机通信的效率较低,因此在深圳国赛中,我们使用了自主源码编译(折腾了好久)的Qt 5.15.2 LTS + Qt creator 4.15.1 + OpenCV 4.5.2 进行项目构建,并使用Can总线以及 Qt中集成的QCanBus模块与下位机进行通信。所有算法均使用OpenCV传统方法构建,于是我在深圳,在赛场炫酷(花里胡哨)的场地灯光中,同很多战队中坚守传统的视觉人度过了破防的一周。 16 | 17 | ### 开发者 18 | 19 | Tongbh, Myron & Fly Dragon 20 | 21 | ## 系统功能 22 | 23 | | 功能 | 描述 | 国赛应用情况 | 24 | |:------ |:--------------------- |:------ | 25 | | 全局日志 | 使用Qt内置日志功能实现 | ❎ | 26 | | 统一配置文件 | 使用Qt.Json和xml实现配置文件读写 | ❎ / ✅ | 27 | | 多线程 | 使用Qt.Thread管理多线程 | ✅ | 28 | | 装甲板检测 | 灯条检测+数字识别 | ✅ | 29 | | 能量机关 | 区域框选+SVM识别 | ❎ | 30 | | 下位机通信 | 使用Uart/Can与下位机通信 | ❎ / ✅ | 31 | | 角度解算 | PnP/激光测距 | ✅ / ❎ | 32 | | 运动预测 | 预测+防抖 | ❎ | 33 | 34 | ## 项目结构 35 | 36 | ``` 37 | ├── DUT0BUG-RM-CV-2021.pro 38 | ├── LICENSE 39 | ├── README.md 40 | ├── build 41 | ├── can-bus-test // 一个用于测试系统can总线的小工具 42 | │   ├── build 43 | │   ├── can-bus-test.pro 44 | │   ├── main.cpp 45 | │   ├── mainwindow.cpp 46 | │   ├── mainwindow.h 47 | │   └── mainwindow.ui 48 | ├── config 49 | │   ├── SVM_MODEL.xml // 能量机关装甲板识别模型 50 | │   ├── camera.xml // 哨兵下云台/步兵镜头标定数据 51 | │   ├── config.json // 系统参数 52 | │   └── long_camera.xml // 哨兵上云台长焦镜头标定数据 53 | ├── imageshow.ui // 摄像头图像GUI显示(可关闭) 54 | ├── include 55 | │   ├── CameraApi.h 56 | │   ├── CameraDefine.h 57 | │   ├── CameraStatus.h 58 | │   ├── anglesolver.h 59 | │   ├── armordetector.h 60 | │   ├── capturethread.h 61 | │   ├── common.h 62 | │   ├── commprotocol.h 63 | │   ├── config.h 64 | │   ├── energydetector.h 65 | │   ├── imageshow.h 66 | │   ├── processthread.h 67 | │   └── taskmanager.h 68 | ├── lib 69 | │   ├── arm 70 | │   │   └── libMVSDK.s 71 | │   ├── arm64 72 | │   │   └── libMVSDK.so 73 | │   ├── arm_softfp 74 | │   │   └── libMVSDK.so 75 | │   ├── x64 76 | │   │   └── libMVSDK.so 77 | │   └── x86 78 | │   └── libMVSDK.so 79 | ├── log 80 | │   └── log.txt 81 | └── src 82 | ├── anglesolver.cpp // pnp角度解算 83 | ├── armordetector.cpp // 识别装甲板 84 | ├── capturethread.cpp // 相机图像获取线程 85 | ├── commprotocol.cpp // 通信协议 86 | ├── config.cpp // 参数读取 87 | ├── energydetector.cpp // 能量机关识别 88 | ├── imageshow.cpp // GUI图窗 89 | ├── main.cpp // 程序入口 90 | ├── processthread.cpp // 图像处理线程 91 | └── taskmanager.cpp // 线程调度 92 | ``` 93 | 94 | ## 系统实现思路 95 | 96 | 由于篇幅过长,请移步至本项目中的doc文件夹:[传送门](https://github.com/tbh111/DUT0BUG-RM-CV-2021/tree/main/doc) 97 | 98 | ## 写在后面 99 | 100 | 2021年,我经历了太多,3月独自完成大创结项与专利申请,4月底临危受命在凌BUG战队中负责视觉工作,5月在北京某地下仓库度过了不见天日的一周,8月在深圳某别墅地下室度过了同样艰辛的一周,再到9月保研失败,12月并不顺利的头铁考研。感谢一直支持鼓励我的朋友们,感谢2021年拼命的自己。 101 | -------------------------------------------------------------------------------- /src/taskmanager.cpp: -------------------------------------------------------------------------------- 1 | #include "taskmanager.h" 2 | 3 | // structure: TaskManager --- CaptureThread 4 | // --- ProcessThread --- Armor/Energy 5 | // --- CanBus 6 | // 7 | // pitch, roll, yaw 8 | // work flow: Camera ---------------> process -----------------> canbus 9 | // (thread1) (thread2) 10 | // | image 11 | // armor/energy/video mode -------> show image 12 | // (TaskManager(Main) thread) 13 | // 14 | 15 | TaskManager::TaskManager(int mode, QObject *parent) : 16 | task_mode(mode), QObject(parent) 17 | { 18 | capture_thread = new CaptureThread; 19 | process_thread = new ProcessThread; 20 | comm = new CommProtocol(common_utils::CAN, "can0"); 21 | comm->initConnect(); 22 | qRegisterMetaType("common_utils::TranPkg"); 23 | qRegisterMetaType("common_utils::RecvPkg"); 24 | qRegisterMetaType("cv::Mat"); 25 | 26 | // set process thread on after camera opened 27 | connect(capture_thread, SIGNAL(camera_opened()), process_thread, SLOT(setProcessOn())); 28 | // send frame to process thread after capture get a frame(update slot in capture thread) 29 | connect(capture_thread, SIGNAL(capture_done(cv::Mat)), process_thread, SLOT(getImage(cv::Mat)), Qt::DirectConnection); 30 | // transfer the data frame to can device, and send to stm32 31 | connect(process_thread, SIGNAL(send_tx_pkg(common_utils::TranPkg)), this, SLOT(updateTx(common_utils::TranPkg))); 32 | // if can device detected new frame, read frame data into current_rx 33 | connect(comm->device, SIGNAL(framesReceived()), this, SLOT(updateRx())); 34 | // send current_rx to process thread 35 | connect(this, SIGNAL(new_rx(common_utils::RecvPkg)), process_thread, SLOT(getRx(common_utils::RecvPkg))); 36 | 37 | if(mode == common_utils::SHOW_ON) 38 | { 39 | image_show = new ImageShow; 40 | // send frame to image show window after process is done 41 | connect(process_thread, SIGNAL(update_show_image(QImage)), image_show, SLOT(draw(QImage)), Qt::BlockingQueuedConnection); 42 | connect(image_show, SIGNAL(end_signal()), this, SLOT(end_show())); 43 | connect(process_thread, SIGNAL(send_process_fps(int)), image_show, SLOT(showFps(int))); 44 | connect(this, SIGNAL(new_rx(common_utils::RecvPkg)), image_show, SLOT(showRx(common_utils::RecvPkg))); 45 | connect(process_thread, SIGNAL(send_tx_pkg(common_utils::TranPkg)), image_show, SLOT(showTx(common_utils::TranPkg))); 46 | image_show->show(); 47 | } 48 | capture_thread->start(); 49 | process_thread->start(); 50 | } 51 | 52 | void TaskManager::updateRx() 53 | { 54 | current_rx = comm->readData(); 55 | emit new_rx(current_rx); 56 | } 57 | 58 | void TaskManager::updateTx(common_utils::TranPkg tx) 59 | { 60 | comm->writeData(tx); 61 | } 62 | 63 | void TaskManager::end_show() 64 | { 65 | image_show->close(); 66 | capture_thread->setCameraOff(); 67 | process_thread->setProcessOff(); 68 | comm->disConnect(); 69 | // capture_thread->wait(); 70 | // process_thread->wait(); 71 | qDebug() << "end"; 72 | } 73 | -------------------------------------------------------------------------------- /can-bus-test/mainwindow.cpp: -------------------------------------------------------------------------------- 1 | #include "mainwindow.h" 2 | #include "ui_mainwindow.h" 3 | 4 | MainWindow::MainWindow(QWidget *parent) 5 | : QMainWindow(parent) 6 | , ui(new Ui::MainWindow) 7 | { 8 | ui->setupUi(this); 9 | // if(QCanBus::instance()->plugins().contains(QStringLiteral("socketcan"))) 10 | // { 11 | // qDebug() << "plugin available"; 12 | // } 13 | // QString error_string; 14 | // QCanBusDevice *device = QCanBus::instance() 15 | } 16 | 17 | MainWindow::~MainWindow() 18 | { 19 | delete ui; 20 | } 21 | 22 | 23 | void MainWindow::updateText() 24 | { 25 | while(device->framesAvailable()) 26 | { 27 | const QCanBusFrame frame = device->readFrame(); 28 | QCanBusFrame::TimeStamp time = frame.timeStamp(); 29 | qint64 time_strap = time.seconds(); 30 | QString frame_str; 31 | if(frame.frameType() == QCanBusFrame::ErrorFrame) 32 | { 33 | frame_str = device->interpretErrorFrame(frame); 34 | } 35 | else if(frame.frameType() == QCanBusFrame::DataFrame) 36 | { 37 | frame_str = frame.toString(); 38 | } 39 | qDebug() << time_strap; 40 | QString show_str = frame_str + "\n"; 41 | ui->textBrowser->append(show_str); 42 | device->clear(); 43 | } 44 | } 45 | 46 | void MainWindow::on_send_pushButton_clicked() 47 | { 48 | QCanBusFrame frame; 49 | frame.setFrameId(1); 50 | QString data = ui->input_lineEdit->text(); 51 | if(!data.isEmpty()) 52 | { 53 | QByteArray payload = QByteArray::fromHex(data.toUtf8()); 54 | frame.setPayload(payload); 55 | device->writeFrame(frame); 56 | qDebug() << "write"; 57 | } 58 | else 59 | { 60 | qDebug() << "empty"; 61 | } 62 | } 63 | 64 | void MainWindow::on_connect_pushButton_clicked() 65 | { 66 | if(QCanBus::instance()->plugins().contains(QStringLiteral("socketcan"))) 67 | { 68 | qDebug() << "plugin available"; 69 | } 70 | QString error_string; 71 | const QList can_info = QCanBus::instance()->availableDevices(QStringLiteral("socketcan"), &error_string); 72 | if(can_info.empty()) 73 | { 74 | qDebug() << "empty"; 75 | qDebug() << error_string; 76 | } 77 | else 78 | { 79 | qDebug() << can_info.begin()->name(); 80 | } 81 | 82 | device = QCanBus::instance()->createDevice( 83 | QStringLiteral("socketcan"), QStringLiteral("can0"), &error_string); 84 | if(!device) 85 | { 86 | qDebug() << "error on create device"; 87 | qDebug() << error_string; 88 | } 89 | else 90 | { 91 | const int bitrate = 1000000; 92 | const int data_bitrate = 2000000; 93 | device->setConfigurationParameter(QCanBusDevice::BitRateKey, QVariant(bitrate)); 94 | device->setConfigurationParameter(QCanBusDevice::DataBitRateKey, QVariant(data_bitrate)); 95 | bool connect_status = device->connectDevice(); 96 | if(connect_status) 97 | { 98 | qDebug() << "connect success"; 99 | connect(device, SIGNAL(framesReceived()), 100 | this, SLOT(updateText())); 101 | // device->disconnectDevice(); 102 | } 103 | else 104 | { 105 | qDebug() << "connect failed"; 106 | } 107 | } 108 | } 109 | 110 | void MainWindow::on_disconnect_pushButton_clicked() 111 | { 112 | if(device->state() == QCanBusDevice::ConnectedState) 113 | { 114 | device->disconnectDevice(); 115 | delete device; 116 | qDebug() << "disconnect"; 117 | } 118 | } 119 | -------------------------------------------------------------------------------- /doc/init.md: -------------------------------------------------------------------------------- 1 | ## 初始化manifold 2 | 3 | #### 1.刷机 4 | 5 | 见刷机教程 6 | 7 | [https://dl.djicdn.com/downloads/manifold-2/20190528/Manifold_2_User_Guide_v1.0_CHS.pdf](https://dl.djicdn.com/downloads/manifold-2/20190528/Manifold_2_User_Guide_v1.0_CHS.pdf) 8 | 9 | 使用安装Ubuntu 16.04的物理机或虚拟机皆可,约半小时 10 | 11 | #### 2.卸载预装ros、OpenCV、Qt、LibreOffice 12 | 13 | Manifold预装有ros,旧版本OpenCV,Qt4和5、LibreOffice,为了防止多个版本共存,进行卸载,可以省下一大堆空间:smile:,需要时手动安装。 14 | 15 | ``` 16 | # 卸载ros,open,qt,libreoffice 17 | sudo apt-get purge ros-* 18 | sudo apt-get purge libopencv* 19 | sudo apt-get purge libreoffice-common 20 | sudo apt-get autoremove 21 | sudo apt-get update 22 | sudo apt-get install apt-transport-https 23 | ``` 24 | 25 | 运行最后一行命令报错:Data from such a repository can't be authenticated and is therefore potentially dangerous to use. 26 | 27 | ``` 28 | sudo chmod 777 /tmp 29 | sudo apt-get update --allow-unauthenticated 30 | sudo apt-get install apt-transport-https 31 | ``` 32 | 33 | ``` 34 | # 卸载qt4和5 35 | # 查看现在安装的qt版本 36 | qt chooser -list-versions 37 | # 卸载qt4 38 | sudo apt-get autoremove --purge libqt4-[a-z]* 39 | # 卸载qt5(卸不干净) 40 | sudo apt-get remove qt* 41 | ``` 42 | 43 | #### 3.更换apt源 44 | 45 | 将/etc/apt/sources.list.d/ 目录下的本地源cuda-9-0-list-local.list,ros-latest.list,visionworks-repo.list等文件中的deb行注释 46 | 47 | 使用清华源 48 | 49 | ``` 50 | sudo gedit /etc/apt/sources.list 51 | ``` 52 | 53 | 清空原有内容,输入: 54 | 55 | ``` 56 | # 默认注释了源码镜像以提高 apt update 速度,如有需要可自行取消注释 57 | deb https://mirrors.tuna.tsinghua.edu.cn/ubuntu-ports/ xenial main restricted universe multiverse 58 | # deb-src https://mirrors.tuna.tsinghua.edu.cn/ubuntu-ports/ xenial main restricted universe multiverse 59 | deb https://mirrors.tuna.tsinghua.edu.cn/ubuntu-ports/ xenial-updates main restricted universe multiverse 60 | # deb-src https://mirrors.tuna.tsinghua.edu.cn/ubuntu-ports/ xenial-updates main restricted universe multiverse 61 | deb https://mirrors.tuna.tsinghua.edu.cn/ubuntu-ports/ xenial-backports main restricted universe multiverse 62 | # deb-src https://mirrors.tuna.tsinghua.edu.cn/ubuntu-ports/ xenial-backports main restricted universe multiverse 63 | deb https://mirrors.tuna.tsinghua.edu.cn/ubuntu-ports/ xenial-security main restricted universe multiverse 64 | # deb-src https://mirrors.tuna.tsinghua.edu.cn/ubuntu-ports/ xenial-security main restricted universe multiverse 65 | ``` 66 | 67 | 或直接去 [清华镜像](mirror.tuna.tsinghua.edu.cn),相关链接 -- 使用帮助 -- Ubuntu Ports(ARM系统) -- 16.04LTS复制。 68 | 69 | #### 4.开机自动挂载硬盘 70 | 71 | manifold中emmc大小为32G,实际为29.5G,安装完系统后约剩余18G。使用内置的硬盘,开机时自动挂载,以保存录制的视频等文件。 72 | 73 | ``` 74 | # 查看分区 75 | sudo fdisk -lu 76 | # 对硬盘分区 77 | sudo fdisk /dev/sda 78 | ``` 79 | 80 | 此时输入d,删除已有的分区,输入n新建分区,所有参数均选择默认,最后输入w保存退出。再次查看分区,硬盘sda下,有一个为sda1的分区。 81 | 82 | ``` 83 | # 格式化分区 84 | sudo mkfs -t ext4 /dev/sda1 85 | sudo mount -t ext4 /dev/sda1 /home/dji/data 86 | ``` 87 | 88 | 设置开机挂载(用户读写权限设置可以在fstab中设置,但不太管用 :confused:) 89 | 90 | https://help.ubuntu.com/community/Fstab 91 | 92 | ``` 93 | sudo gedit /etc/fstab 94 | 末尾添加 /dev/sda1/ /home/dji/data ext4 defaluts 0 1 95 | sudo chown dji:dji /home/dji/data/ 96 | reboot 97 | ``` 98 | 99 | #### 5.配置工业相机 100 | 101 | 使用的工业相机型号为MindVision MV-SUA33GC,linux SDK下载地址:[http://mindvision.com.cn/rjxz/list_12.aspx?lcid=138](http://mindvision.com.cn/rjxz/list_12.aspx?lcid=138) 102 | 103 | 安装: 104 | 105 | ``` 106 | cd ~/dji/linuxSDK_V2.1.0.25 107 | ./install.sh 108 | reboot 109 | ``` 110 | 111 | 编译GTK demo 112 | 113 | ``` 114 | sudo apt-get install libglib2.0-dev 115 | sudo cp /usr/lib/aarch64-linux-gnu/glib-2.0/include/glibconfig.h /usr/include/ 116 | sudo cp /usr/lib/aarch64-linux-gnu/gtk-2.0/include/gdkconfig.h /usr/include/ 117 | ``` 118 | 119 | #### 6.更换gcc和g++版本 120 | 121 | 系统默认的gcc/g++版本为5.5.0,这里更新至7.4.0,根据提示输入数字切换版本,只需切换gcc。 122 | 123 | ``` 124 | # 查看版本 125 | gcc -v 126 | g++ -v 127 | # 更改版本 128 | sudo update-alternatives --config gcc 129 | ``` 130 | -------------------------------------------------------------------------------- /src/capturethread.cpp: -------------------------------------------------------------------------------- 1 | #include "capturethread.h" 2 | 3 | CaptureThread::CaptureThread(QObject *parent): 4 | QThread(parent) 5 | { 6 | 7 | } 8 | 9 | void CaptureThread::run() 10 | { 11 | qDebug() << "capture thread id: " << currentThreadId(); 12 | cameraOpen(); 13 | while(true) 14 | { 15 | stopped_mutex.lock(); 16 | // exit thread if stop flag is true 17 | if(stop_flag) 18 | { 19 | stop_flag = false; 20 | data_mutex.unlock(); 21 | stopped_mutex.unlock(); 22 | cameraClose(); 23 | qDebug() << "capture thread exit"; 24 | break; 25 | } 26 | stopped_mutex.unlock(); 27 | 28 | // data_mutex.lock(); 29 | // capture a frame from image buffer 30 | getFrame(); 31 | // data_mutex.unlock(); 32 | } 33 | } 34 | 35 | int CaptureThread::cameraOpen() 36 | { 37 | CameraSdkStatus camera_status; 38 | tSdkCameraDevInfo camera_enum_list; 39 | int camera_count = 1; 40 | qDebug() << "camera SDK initializing"; 41 | CameraSdkInit(0); 42 | qDebug() << "camera SDK init done"; 43 | CameraEnumerateDevice(&camera_enum_list, &camera_count); 44 | if(camera_count == 0) 45 | { 46 | qDebug() << "ERROR: no camera connected"; 47 | return -1; 48 | } 49 | else 50 | { 51 | qDebug() << "connected camera numbers:" << camera_count; 52 | } 53 | camera_status = CameraInit(&camera_enum_list, -1, -1, &h_camera); 54 | if(camera_status != CAMERA_STATUS_SUCCESS) 55 | { 56 | qDebug() << "camera initialize failed"; 57 | return -1; 58 | } 59 | else 60 | { 61 | qDebug() << "camera initialize success"; 62 | } 63 | CameraGetCapability(h_camera, &camera_capability); 64 | g_pRgbBuffer = (unsigned char*)malloc(camera_capability.sResolutionRange.iHeightMax*camera_capability.sResolutionRange.iWidthMax*3); 65 | 66 | // set param 67 | CameraSetIspOutFormat(h_camera, CAMERA_MEDIA_TYPE_BGR8); 68 | CameraSetAeState(h_camera, false); 69 | CameraSetExposureTime(h_camera, 1000); 70 | // run 71 | CameraPlay(h_camera); 72 | qDebug() << "camera playing"; 73 | emit camera_opened(); 74 | return 1; 75 | } 76 | 77 | void CaptureThread::getFrame() 78 | { 79 | // time_strap = static_cast(cv::getTickCount()); 80 | tSdkFrameHead frame_info; 81 | if(CameraGetImageBuffer(h_camera, &frame_info, &pbyBuffer, 1000) == CAMERA_STATUS_SUCCESS) 82 | { 83 | CameraImageProcess(h_camera, pbyBuffer, g_pRgbBuffer, &frame_info); 84 | cv::Mat frame(cv::Size(frame_info.iWidth, frame_info.iHeight), CV_8UC3, g_pRgbBuffer); 85 | grabbed_frame = frame; 86 | // qDebug() << "get frame: " << frame_number++; 87 | // cv::cvtColor(grabbed_frame, grabbed_frame, cv::COLOR_BGR2RGB); 88 | emit capture_done(grabbed_frame); 89 | CameraReleaseImageBuffer(h_camera, pbyBuffer); 90 | } 91 | else 92 | { 93 | qDebug() << "timeout"; 94 | usleep(1000); 95 | } 96 | // time_strap = static_cast(cv::getTickCount() - time_strap) / cv::getTickFrequency(); 97 | // fps = 1.0 / time_strap; 98 | // qDebug() << "fps: " << fps; 99 | // emit send_capture_fps(fps); 100 | } 101 | 102 | void CaptureThread::setCameraOff() 103 | { 104 | stopped_mutex.lock(); 105 | stop_flag = true; 106 | stopped_mutex.unlock(); 107 | } 108 | 109 | void CaptureThread::cameraClose() 110 | { 111 | CameraSdkStatus camera_status; 112 | qDebug() << "try close camera"; 113 | camera_status = CameraUnInit(h_camera); 114 | if(camera_status != CAMERA_STATUS_SUCCESS) 115 | { 116 | qDebug() << "can not close camera"; 117 | } 118 | else 119 | { 120 | if(g_pRgbBuffer != NULL) 121 | { 122 | free(g_pRgbBuffer); 123 | } 124 | qDebug() << "close camera success"; 125 | } 126 | } 127 | -------------------------------------------------------------------------------- /src/config.cpp: -------------------------------------------------------------------------------- 1 | #include "config.h" 2 | 3 | Config::Config() 4 | { 5 | fp_json.setFileName("../config/config.json"); 6 | } 7 | 8 | Config::~Config() 9 | { 10 | fp_json.close(); 11 | } 12 | 13 | int Config::InitJsonFile() 14 | { 15 | if(!fp_json.open(QIODevice::ReadWrite)) 16 | { 17 | qDebug() << "config file open error"; 18 | } 19 | else 20 | { 21 | qDebug() << "config file open success"; 22 | } 23 | 24 | fp_json.resize(0); 25 | QJsonObject json_object; 26 | 27 | QJsonObject json_object_mode; 28 | json_object_mode.insert("source", "video"); 29 | json_object_mode.insert("function", "full"); 30 | json_object.insert("mode", json_object_mode); 31 | 32 | QJsonObject json_object_path; 33 | json_object_path.insert("test_video_path", "../config/1.avi"); 34 | json_object_path.insert("camera_param_path", "../config/camera.xml"); 35 | json_object_path.insert("energy_svm_path", "../config/SVM_MODEL.xml"); 36 | json_object.insert("paths", json_object_path); 37 | 38 | QJsonObject json_object_armor; 39 | json_object_armor.insert("blue_binary_threshold", 200); 40 | json_object_armor.insert("red_binary_threshold", 150); 41 | json_object.insert("armor", json_object_armor); 42 | 43 | QJsonObject json_object_serial; 44 | json_object_serial.insert("port", "/dev/ttyTHS2"); 45 | json_object_serial.insert("baud_rate", 115200); 46 | json_object.insert("serial", json_object_serial); 47 | 48 | QJsonObject json_object_energy; 49 | // blue 50 | json_object_energy.insert("hsv_blue_hmin", 80); 51 | json_object_energy.insert("hsv_blue_hmax", 150); 52 | json_object_energy.insert("hsv_blue_smin", 40); 53 | json_object_energy.insert("hsv_blue_smax", 255); 54 | json_object_energy.insert("hsv_blue_vmin", 100); 55 | json_object_energy.insert("hsv_blue_vmax", 255); 56 | // red 57 | json_object_energy.insert("hsv_red_hmin", 250); 58 | json_object_energy.insert("hsv_red_hmax", 180); 59 | json_object_energy.insert("hsv_red_hmin_2", 0); 60 | json_object_energy.insert("hsv_red_hmax_2", 40); 61 | json_object_energy.insert("hsv_red_smin", 40); 62 | json_object_energy.insert("hsv_red_smax", 255); 63 | json_object_energy.insert("hsv_red_vmin", 100); 64 | json_object_energy.insert("hsv_red_vmax", 225); 65 | json_object_energy.insert("hsv_red_vmax", 225); 66 | json_object_energy.insert("hsv_red_vmax", 225); 67 | // area threshold 68 | json_object_energy.insert("energy_armor_area_min_threshold", 3500); 69 | json_object_energy.insert("energy_armor_area_max_threshold", 5000); 70 | json_object.insert("energy",json_object_energy); 71 | 72 | QJsonDocument jsonDoc(json_object); 73 | fp_json.write(jsonDoc.toJson()); 74 | fp_json.close(); 75 | qDebug() << "initialize config file success"; 76 | return 0; 77 | } 78 | 79 | QString Config::ReadJsonFile(QString function, QString key) 80 | { 81 | if(!fp_json.open(QIODevice::ReadOnly)) 82 | { 83 | qDebug() << "config file open error"; 84 | } 85 | else 86 | { 87 | qDebug() << "config file open success"; 88 | } 89 | QJsonParseError jsonParserError; 90 | QJsonDocument jsonDocument = QJsonDocument::fromJson(fp_json.readAll(), &jsonParserError); 91 | QJsonObject json_object, json_object_key; 92 | if(!jsonDocument.isNull() && jsonParserError.error == QJsonParseError::NoError) 93 | { 94 | qDebug() << "read config file success"; 95 | json_object = jsonDocument.object(); 96 | if(json_object.contains(function) && json_object.value(function).isObject()) 97 | { 98 | json_object_key = json_object.value(function).toObject(); 99 | if(json_object_key.contains(key) && json_object_key.value(key).isString()) 100 | { 101 | qDebug() << "read: " << json_object_key.value(key).toString(); 102 | fp_json.close(); 103 | return json_object_key.value(key).toString(); 104 | } 105 | else if(json_object_key.contains(key) && json_object_key.value(key).isDouble()) 106 | { 107 | qDebug() << "read: " << json_object_key.value(key).toDouble(); 108 | fp_json.close(); 109 | return QString::number(json_object_key.value(key).toDouble()); 110 | } 111 | else 112 | { 113 | qDebug() << "err: no key called " << key; 114 | fp_json.close(); 115 | return ""; 116 | } 117 | } 118 | else 119 | { 120 | qDebug() << "err: no function called " << function; 121 | fp_json.close(); 122 | return ""; 123 | } 124 | } 125 | qDebug() << "err: " << jsonParserError.error; 126 | fp_json.close(); 127 | return ""; 128 | } 129 | -------------------------------------------------------------------------------- /include/CameraStatus.h: -------------------------------------------------------------------------------- 1 | 2 | #ifndef __CAMERA_STATUS_DEF__ 3 | #define __CAMERA_STATUS_DEF__ 4 | 5 | typedef int CameraSdkStatus; 6 | 7 | 8 | /*常用的宏*/ 9 | #define SDK_SUCCESS(_FUC_) ((_FUC_) == CAMERA_STATUS_SUCCESS) 10 | 11 | #define SDK_UNSUCCESS(_FUC_) ((_FUC_) != CAMERA_STATUS_SUCCESS) 12 | 13 | #define SDK_UNSUCCESS_RETURN(_FUC_,RET) if((RET = (_FUC_)) != CAMERA_STATUS_SUCCESS)\ 14 | {\ 15 | return RET;\ 16 | } 17 | 18 | #define SDK_UNSUCCESS_BREAK(_FUC_) if((_FUC_) != CAMERA_STATUS_SUCCESS)\ 19 | {\ 20 | break;\ 21 | } 22 | 23 | 24 | /* 常用错误 */ 25 | 26 | #define CAMERA_STATUS_SUCCESS 0 // 操作成功 27 | #define CAMERA_STATUS_FAILED -1 // 操作失败 28 | #define CAMERA_STATUS_INTERNAL_ERROR -2 // 内部错误 29 | #define CAMERA_STATUS_UNKNOW -3 // 未知错误 30 | #define CAMERA_STATUS_NOT_SUPPORTED -4 // 不支持该功能 31 | #define CAMERA_STATUS_NOT_INITIALIZED -5 // 初始化未完成 32 | #define CAMERA_STATUS_PARAMETER_INVALID -6 // 参数无效 33 | #define CAMERA_STATUS_PARAMETER_OUT_OF_BOUND -7 // 参数越界 34 | #define CAMERA_STATUS_UNENABLED -8 // 未使能 35 | #define CAMERA_STATUS_USER_CANCEL -9 // 用户手动取消了,比如roi面板点击取消,返回 36 | #define CAMERA_STATUS_PATH_NOT_FOUND -10 // 注册表中没有找到对应的路径 37 | #define CAMERA_STATUS_SIZE_DISMATCH -11 // 获得图像数据长度和定义的尺寸不匹配 38 | #define CAMERA_STATUS_TIME_OUT -12 // 超时错误 39 | #define CAMERA_STATUS_IO_ERROR -13 // 硬件IO错误 40 | #define CAMERA_STATUS_COMM_ERROR -14 // 通讯错误 41 | #define CAMERA_STATUS_BUS_ERROR -15 // 总线错误 42 | #define CAMERA_STATUS_NO_DEVICE_FOUND -16 // 没有发现设备 43 | #define CAMERA_STATUS_NO_LOGIC_DEVICE_FOUND -17 // 未找到逻辑设备 44 | #define CAMERA_STATUS_DEVICE_IS_OPENED -18 // 设备已经打开 45 | #define CAMERA_STATUS_DEVICE_IS_CLOSED -19 // 设备已经关闭 46 | #define CAMERA_STATUS_DEVICE_VEDIO_CLOSED -20 // 没有打开设备视频,调用录像相关的函数时,如果相机视频没有打开,则回返回该错误。 47 | #define CAMERA_STATUS_NO_MEMORY -21 // 没有足够系统内存 48 | #define CAMERA_STATUS_FILE_CREATE_FAILED -22 // 创建文件失败 49 | #define CAMERA_STATUS_FILE_INVALID -23 // 文件格式无效 50 | #define CAMERA_STATUS_WRITE_PROTECTED -24 // 写保护,不可写 51 | #define CAMERA_STATUS_GRAB_FAILED -25 // 数据采集失败 52 | #define CAMERA_STATUS_LOST_DATA -26 // 数据丢失,不完整 53 | #define CAMERA_STATUS_EOF_ERROR -27 // 未接收到帧结束符 54 | #define CAMERA_STATUS_BUSY -28 // 正忙(上一次操作还在进行中),此次操作不能进行 55 | #define CAMERA_STATUS_WAIT -29 // 需要等待(进行操作的条件不成立),可以再次尝试trf 56 | #define CAMERA_STATUS_IN_PROCESS -30 // 正在进行,已经被操作过 57 | #define CAMERA_STATUS_IIC_ERROR -31 // IIC传输错误 58 | #define CAMERA_STATUS_SPI_ERROR -32 // SPI传输错误 59 | #define CAMERA_STATUS_USB_CONTROL_ERROR -33 // USB控制传输错误 60 | #define CAMERA_STATUS_USB_BULK_ERROR -34 // USB BULK传输错误 61 | #define CAMERA_STATUS_SOCKET_INIT_ERROR -35 // 网络传输套件初始化失败 62 | #define CAMERA_STATUS_GIGE_FILTER_INIT_ERROR -36 // 网络相机内核过滤驱动初始化失败,请检查是否正确安装了驱动,或者重新安装。 63 | #define CAMERA_STATUS_NET_SEND_ERROR -37 // 网络数据发送错误 64 | #define CAMERA_STATUS_DEVICE_LOST -38 // 与网络相机失去连接,心跳检测超时 65 | #define CAMERA_STATUS_DATA_RECV_LESS -39 // 接收到的字节数比请求的少 66 | #define CAMERA_STATUS_FUNCTION_LOAD_FAILED -40 // 从文件中加载程序失败 67 | #define CAMERA_STATUS_CRITICAL_FILE_LOST -41 // 程序运行所必须的文件丢失。 68 | #define CAMERA_STATUS_SENSOR_ID_DISMATCH -42 // 固件和程序不匹配,原因是下载了错误的固件。 69 | #define CAMERA_STATUS_OUT_OF_RANGE -43 // 参数超出有效范围。 70 | #define CAMERA_STATUS_REGISTRY_ERROR -44 // 安装程序注册错误。请重新安装程序,或者运行安装目录Setup/Installer.exe 71 | #define CAMERA_STATUS_ACCESS_DENY -45 // 禁止访问。指定相机已经被其他程序占用时,再申请访问该相机,会返回该状态。(一个相机不能被多个程序同时访问) 72 | #define CAMERA_STATUS_CAMERA_NEED_RESET -46 // 表示相机需要复位后才能正常使用,此时请让相机断电重启,或者重启操作系统后,便可正常使用。 73 | #define CAMERA_STATUS_ISP_MOUDLE_NOT_INITIALIZED -47 // ISP模块未初始化 74 | #define CAMERA_STATUS_ISP_DATA_CRC_ERROR -48 // 数据校验错误 75 | #define CAMERA_STATUS_MV_TEST_FAILED -49 // 数据测试失败 76 | #define CAMERA_STATUS_INTERNAL_ERR1 -50 // 内部错误1 77 | #define CAMERA_STATUS_U3V_NO_CONTROL_EP -51 // U3V控制端点未找到 78 | #define CAMERA_STATUS_U3V_CONTROL_ERROR -52 // U3V控制通讯错误 79 | 80 | 81 | 82 | 83 | //和AIA制定的标准相同 84 | /*#define CAMERA_AIA_SUCCESS 0x0000 */ 85 | #define CAMERA_AIA_PACKET_RESEND 0x0100 //该帧需要重传 86 | #define CAMERA_AIA_NOT_IMPLEMENTED 0x8001 //设备不支持的命令 87 | #define CAMERA_AIA_INVALID_PARAMETER 0x8002 //命令参数非法 88 | #define CAMERA_AIA_INVALID_ADDRESS 0x8003 //不可访问的地址 89 | #define CAMERA_AIA_WRITE_PROTECT 0x8004 //访问的对象不可写 90 | #define CAMERA_AIA_BAD_ALIGNMENT 0x8005 //访问的地址没有按照要求对齐 91 | #define CAMERA_AIA_ACCESS_DENIED 0x8006 //没有访问权限 92 | #define CAMERA_AIA_BUSY 0x8007 //命令正在处理中 93 | #define CAMERA_AIA_DEPRECATED 0x8008 //0x8008-0x0800B 0x800F 该指令已经废弃 94 | #define CAMERA_AIA_PACKET_UNAVAILABLE 0x800C //包无效 95 | #define CAMERA_AIA_DATA_OVERRUN 0x800D //数据溢出,通常是收到的数据比需要的多 96 | #define CAMERA_AIA_INVALID_HEADER 0x800E //数据包头部中某些区域与协议不匹配 97 | #define CAMERA_AIA_PACKET_NOT_YET_AVAILABLE 0x8010 //图像分包数据还未准备好,多用于触发模式,应用程序访问超时 98 | #define CAMERA_AIA_PACKET_AND_PREV_REMOVED_FROM_MEMORY 0x8011 //需要访问的分包已经不存在。多用于重传时数据已经不在缓冲区中 99 | #define CAMERA_AIA_PACKET_REMOVED_FROM_MEMORY 0x8012 //CAMERA_AIA_PACKET_AND_PREV_REMOVED_FROM_MEMORY 100 | #define CAMERA_AIA_NO_REF_TIME 0x0813 //没有参考时钟源。多用于时间同步的命令执行时 101 | #define CAMERA_AIA_PACKET_TEMPORARILY_UNAVAILABLE 0x0814 //由于信道带宽问题,当前分包暂时不可用,需稍后进行访问 102 | #define CAMERA_AIA_OVERFLOW 0x0815 //设备端数据溢出,通常是队列已满 103 | #define CAMERA_AIA_ACTION_LATE 0x0816 //命令执行已经超过有效的指定时间 104 | #define CAMERA_AIA_ERROR 0x8FFF //错误 105 | 106 | 107 | 108 | 109 | 110 | #endif 111 | -------------------------------------------------------------------------------- /src/processthread.cpp: -------------------------------------------------------------------------------- 1 | #include "processthread.h" 2 | 3 | ProcessThread::ProcessThread(QObject *parent): 4 | QThread(parent) 5 | { 6 | 7 | } 8 | 9 | void ProcessThread::run() 10 | { 11 | qDebug() << "process thread id: " << currentThreadId(); 12 | ArmorDetector armor_detector; 13 | EnergyDetector energy_detector; //未测试 14 | AngleSolver pnp; 15 | int sample_count = 0; 16 | int armor_type; 17 | while(true) 18 | { 19 | stop_mutex.lock(); 20 | if(stop_flag) 21 | { 22 | stop_flag = false; 23 | stop_mutex.unlock(); 24 | qDebug() << "process thread exit"; 25 | break; 26 | } 27 | stop_mutex.unlock(); 28 | 29 | data_mutex.lock(); 30 | if(start_flag && image_update_flag) 31 | { 32 | time_strap = static_cast(cv::getTickCount()); 33 | if(video_switch == common_utils::VIDEO_ON) 34 | { 35 | if(sample_count++ == 10) 36 | { 37 | sample_count = 0; 38 | cv::imwrite("/home/dji/data/photo/" + std::to_string(cv::getTickCount()) + ".png", src_img); 39 | } 40 | } 41 | if(process_target == common_utils::TARGET_ARMOR) 42 | { 43 | ArmorBox target; 44 | armor_detector.run(src_img, dst_img, target, color); 45 | if(target.isValid) 46 | { 47 | // std::vector target_vec(target.armor_points, target.armor_points+4); 48 | 49 | std::vector result = pnp.p4pSolution(target.armor_rect, target.armor_type); 50 | detect_flag = common_utils::DETECT_YES; 51 | yaw_tx = result[0]; 52 | pitch_tx = result[1]; 53 | cmd_tx = common_utils::SHOOT_AUTO; 54 | packTx(); 55 | result.clear(); 56 | // std::cout << "color: " << color << " target: " << process_target << std::endl; 57 | // std::cout << "energy_mode: " << energy_mode << "video_switch: " << video_switch << std::endl; 58 | // std::cout << "yaw: " << yaw_rx << " pitch: " << pitch_rx << " speed: " << speed_rx << std::endl; 59 | } 60 | else 61 | { 62 | detect_flag = common_utils::DETECT_NONE; 63 | yaw_tx = 0.0; 64 | pitch_tx = 0.0; 65 | cmd_tx = common_utils::SHOOT_DISABLED; 66 | packTx(); 67 | } 68 | } 69 | else if(process_target == common_utils::TARGET_ENERGY) 70 | { 71 | EnergyBox target; 72 | energy_detector.run(src_img, dst_img, target, color); 73 | if(target.isValid) 74 | { 75 | std::vector result = pnp.p4pSolution(target.armor_rect, target.armor_type); 76 | detect_flag = common_utils::DETECT_YES; 77 | yaw_tx = result[0]; 78 | pitch_tx = result[1]; 79 | cmd_tx = common_utils::SHOOT_SINGLE; 80 | packTx(); 81 | result.clear(); 82 | } 83 | } 84 | else 85 | { 86 | detect_flag = common_utils::DETECT_NONE; 87 | yaw_tx = 0.0; 88 | pitch_tx = 0.0; 89 | cmd_tx = common_utils::SHOOT_DISABLED; 90 | // packTx(); 91 | } 92 | // std::cout << "energy" << std::endl; 93 | 94 | // preProcess(); 95 | // process(); 96 | // dst_img = bin_img; 97 | // cv::cvtColor(dst_img, dst_img, cv::COLOR_BGR2RGB); 98 | if(dst_img.channels() == 3) 99 | { 100 | QImage image(dst_img.data, dst_img.cols, dst_img.rows, static_cast(dst_img.step), QImage::Format_RGB888); 101 | emit update_show_image(image); 102 | } 103 | else 104 | { 105 | QImage image(dst_img.data, dst_img.cols, dst_img.rows, static_cast(dst_img.step), QImage::Format_Indexed8); 106 | emit update_show_image(image); 107 | } 108 | image_update_flag = false; 109 | time_strap = static_cast(cv::getTickCount() - time_strap) / cv::getTickFrequency(); 110 | fps = 1.0 / time_strap; 111 | // qDebug() << "fps: " << fps; 112 | emit send_process_fps(fps); 113 | } 114 | 115 | data_mutex.unlock(); 116 | } 117 | } 118 | 119 | void ProcessThread::getRx(common_utils::RecvPkg new_rx) 120 | { 121 | // data_mutex.lock(); 122 | if(new_rx.func_code == common_utils::FUNC_TARGET) 123 | { 124 | process_target = new_rx.recv_target; 125 | } 126 | else if(new_rx.func_code == common_utils::FUNC_COLOR) 127 | { 128 | color = new_rx.recv_color; 129 | } 130 | else if(new_rx.func_code == common_utils::FUNC_VIDEO) 131 | { 132 | video_switch = new_rx.recv_video; 133 | } 134 | else if(new_rx.func_code == common_utils::FUNC_ENERGY) 135 | { 136 | energy_mode = new_rx.recv_energy; 137 | } 138 | else if(new_rx.func_code == common_utils::FUNC_ANGLE) 139 | { 140 | pitch_rx = new_rx.pitch / 100; 141 | } 142 | else if(new_rx.func_code == common_utils::FUNC_SPEED) 143 | { 144 | speed_rx = new_rx.speed / 100; 145 | } 146 | // data_mutex.unlock(); 147 | } 148 | 149 | void ProcessThread::packTx() 150 | { 151 | // data_mutex.lock(); 152 | tx_pkg.check_mode = process_target; 153 | tx_pkg.check_color = color; 154 | tx_pkg.check_video = video_switch; 155 | tx_pkg.detect_state = detect_flag; 156 | tx_pkg.yaw = yaw_tx * 100; 157 | tx_pkg.pitch = pitch_tx * 100; 158 | tx_pkg.cmd = cmd_tx; 159 | emit send_tx_pkg(tx_pkg); 160 | // data_mutex.unlock(); 161 | } 162 | 163 | void ProcessThread::setProcessOn() 164 | { 165 | data_mutex.lock(); 166 | qDebug() << "process start"; 167 | start_flag = true; 168 | data_mutex.unlock(); 169 | } 170 | 171 | void ProcessThread::setProcessOff() 172 | { 173 | stop_mutex.lock(); 174 | stop_flag = true; 175 | stop_mutex.unlock(); 176 | } 177 | 178 | void ProcessThread::getImage(cv::Mat image) 179 | { 180 | data_mutex.lock(); 181 | if(!image.empty()) 182 | { 183 | image.copyTo(src_img); 184 | } 185 | image_update_flag = true; 186 | data_mutex.unlock(); 187 | } 188 | -------------------------------------------------------------------------------- /src/commprotocol.cpp: -------------------------------------------------------------------------------- 1 | #include "commprotocol.h" 2 | 3 | CommProtocol::CommProtocol(int t_protocol, QString t_port): 4 | protocol(t_protocol), port(t_port) 5 | { 6 | if(t_protocol == common_utils::CAN) 7 | { 8 | // system("echo dji | sudo -S ip link set down can0"); 9 | // system("echo dji | sudo ip link set can0 type can bitrate 1000000 dbitrate 2000000 berr-reporting on fd on restart-ms 100"); 10 | // system("echo dji | sudo ip link set up can0"); 11 | 12 | qDebug() << "use socketcan interface"; 13 | if(QCanBus::instance()->plugins().contains(QStringLiteral("socketcan"))) 14 | { 15 | qDebug() << "socketcan plugin available"; 16 | } 17 | QString err_string; 18 | const QList can_info = QCanBus::instance()-> 19 | availableDevices(QStringLiteral("socketcan"), &err_string); 20 | if(can_info.isEmpty()) 21 | { 22 | qDebug() << "can not detect can-bus device"; 23 | } 24 | else 25 | { 26 | if(can_info.begin()->name() == port) 27 | { 28 | qDebug() << "successfully detect device can0"; 29 | } 30 | } 31 | } 32 | } 33 | 34 | bool CommProtocol::initConnect() 35 | { 36 | QString err_string; 37 | device = QCanBus::instance()->createDevice(QStringLiteral("socketcan"), port, &err_string); 38 | device->setConfigurationParameter(QCanBusDevice::BitRateKey, QVariant(bitrate)); 39 | device->setConfigurationParameter(QCanBusDevice::DataBitRateKey, QVariant(dbitrate)); 40 | 41 | QCanBusDevice::Filter filter; 42 | QList filterlist; 43 | filter.frameId = 0x400u; 44 | filter.frameIdMask = 0x7FFu; 45 | filter.format = QCanBusDevice::Filter::MatchBaseFormat; 46 | filter.type = QCanBusFrame::DataFrame; 47 | filterlist.append(filter); 48 | device->setConfigurationParameter(QCanBusDevice::RawFilterKey, QVariant::fromValue(filterlist)); 49 | 50 | bool connect_status = device->connectDevice(); 51 | if(connect_status) 52 | { 53 | qDebug() << "connect succeess"; 54 | return true; 55 | } 56 | else 57 | { 58 | qDebug() << "connect failed"; 59 | return false; 60 | } 61 | } 62 | 63 | void CommProtocol::disConnect() 64 | { 65 | if(device->state() == QCanBusDevice::ConnectedState) 66 | { 67 | device->disconnectDevice(); 68 | delete device; 69 | qDebug() << "disconnect"; 70 | } 71 | } 72 | 73 | bool CommProtocol::writeData(common_utils::TranPkg tx_pkg) 74 | { 75 | // qDebug() << "write state: " << device->state() << " status: " << device->busStatus(); 76 | 77 | QCanBusFrame tx_frame; 78 | tx_frame.setFrameId(0x401); 79 | QByteArray payload; 80 | payload.resize(8); 81 | 82 | // byte 0: ckeck state 0000_0xxx 83 | payload[0] = 0x07 & ((tx_pkg.check_video & common_utils::VIDEO_ON) << 2 ^ 84 | (tx_pkg.check_color & common_utils::SELF_BLUE) << 1 ^ 85 | (tx_pkg.check_mode & common_utils::TARGET_ARMOR)); 86 | // qDebug() << payload[0]; 87 | // qDebug() << " 1: " << tx_pkg.check_video << " 2: " << tx_pkg.check_color << " 3: " << tx_pkg.check_mode; 88 | 89 | // byte 1: whether detect valid 90 | payload[1] = tx_pkg.detect_state; 91 | 92 | // byte 2-3: yaw offset 93 | payload[2] = (0xff00 & tx_pkg.yaw) >> 8; 94 | payload[3] = 0x00ff & tx_pkg.yaw; 95 | 96 | // byte 4-5: pitch offset 97 | payload[4] = (0xff00 & tx_pkg.pitch) >> 8; 98 | payload[5] = 0x00ff & tx_pkg.pitch; 99 | 100 | // byte 6: shoot command 101 | payload[6] = tx_pkg.cmd; 102 | 103 | // byte 7: undefined 104 | payload[7] = 0x00; 105 | 106 | tx_frame.setPayload(payload); 107 | bool write_status = device->writeFrame(tx_frame); 108 | if(write_status) 109 | { 110 | // qDebug() << "write"; 111 | return true; 112 | } 113 | else 114 | { 115 | qDebug() << "write failed"; 116 | return false; 117 | } 118 | } 119 | 120 | int CommProtocol::getFrameNumber() 121 | { 122 | return device->framesAvailable(); 123 | } 124 | 125 | common_utils::RecvPkg CommProtocol::readData() 126 | { 127 | // qDebug() << "read state: " << device->state() << " status: " << device->busStatus(); 128 | 129 | common_utils::RecvPkg rx_pkg; 130 | while(device->framesAvailable()) 131 | { 132 | const QCanBusFrame frame = device->readFrame(); 133 | QString frame_str; 134 | if(frame.frameType() == QCanBusFrame::DataFrame) 135 | { 136 | frame_str = frame.toString(); 137 | // qDebug() << frame_str; 138 | 139 | // frame: 7FF [8] 00 01 02 03 04 05 06 07 140 | QStringList list = frame_str.split(QLatin1Char(' '), Qt::SkipEmptyParts); 141 | // ensure frame length 142 | if(list.at(1) == "[8]") 143 | { 144 | bool ok; 145 | rx_pkg.func_code = list.at(2).toInt(&ok, 16); 146 | if(rx_pkg.func_code == common_utils::FUNC_COLOR) 147 | { 148 | rx_pkg.recv_color = list.at(3).toInt(&ok, 16); 149 | } 150 | else if(rx_pkg.func_code == common_utils::FUNC_TARGET) 151 | { 152 | rx_pkg.recv_target = list.at(3).toInt(&ok, 16); 153 | } 154 | else if(rx_pkg.func_code == common_utils::FUNC_ENERGY) 155 | { 156 | rx_pkg.recv_energy = list.at(3).toInt(&ok, 16); 157 | } 158 | else if(rx_pkg.func_code == common_utils::FUNC_VIDEO) 159 | { 160 | rx_pkg.recv_video = list.at(3).toInt(&ok, 16); 161 | } 162 | else if(rx_pkg.func_code == common_utils::FUNC_ANGLE) 163 | { 164 | QString pitch_str; 165 | pitch_str = list.at(3) + list.at(4); 166 | rx_pkg.pitch = pitch_str.toInt(&ok, 16); 167 | 168 | } 169 | else if(rx_pkg.func_code == common_utils::FUNC_SPEED) 170 | { 171 | QString speed_str = list.at(3) + list.at(4); 172 | rx_pkg.speed = speed_str.toInt(&ok, 16); 173 | } 174 | else 175 | { 176 | qDebug() << rx_pkg.func_code; 177 | qDebug() << "package error"; 178 | } 179 | } 180 | } 181 | else 182 | { 183 | qDebug() << device->interpretErrorFrame(frame); 184 | } 185 | } 186 | return rx_pkg; 187 | } 188 | -------------------------------------------------------------------------------- /src/anglesolver.cpp: -------------------------------------------------------------------------------- 1 | #include "anglesolver.h" 2 | 3 | 4 | //AngleSolverParam::AngleSolverParam() 5 | //{ 6 | 7 | //} 8 | 9 | //void AngleSolverParam::read_XMLFile(void) 10 | //{ 11 | // FileStorage fsRead("../config/camera.xml", FileStorage::READ); 12 | 13 | // if(!fsRead.isOpened()) 14 | // { 15 | // cout << "failed to open xml" << endl; 16 | // return; 17 | // } 18 | 19 | // fsRead["Y_DISTANCE_BETWEEN_GUN_AND_CAM"] >> Y_DISTANCE_BETWEEN_GUN_AND_CAM; 20 | // fsRead["Z_DISTANCE_BETWEEN_MUZZLE_AND_CAM"] >> Z_DISTANCE_BETWEEN_MUZZLE_AND_CAM; 21 | // fsRead["Camera_Matrix"] >> CameraIntrinsicMatrix; 22 | // fsRead["Distortion_Coefficients"] >> DistortionCoefficient; 23 | // return; 24 | //} 25 | 26 | AngleSolver::AngleSolver() 27 | { 28 | init(); 29 | } 30 | 31 | bool AngleSolver::init() 32 | { 33 | 34 | 35 | //装甲板世界坐标,把装甲板的中心对准定义的图像中心 36 | POINT_3D_OF_ARMOR_BIG.push_back(cv::Point3f(-117.5f, -63.5f, 0.0f)); // top left 37 | POINT_3D_OF_ARMOR_BIG.push_back(cv::Point3f( 117.5f, -63.5f, 0.0f)); // top right 38 | POINT_3D_OF_ARMOR_BIG.push_back(cv::Point3f( 117.5f, 63.5f, 0.0f)); // bottom right 39 | POINT_3D_OF_ARMOR_BIG.push_back(cv::Point3f(-117.5f, 63.5f, 0.0f)); // bottom left 40 | 41 | POINT_3D_OF_ARMOR_SMALL.push_back(cv::Point3f(-70.0f, -28.0f, 0.0f)); 42 | POINT_3D_OF_ARMOR_SMALL.push_back(cv::Point3f( 70.0f, -28.0f, 0.0f)); 43 | POINT_3D_OF_ARMOR_SMALL.push_back(cv::Point3f( 70.0f, 28.0f, 0.0f)); 44 | POINT_3D_OF_ARMOR_SMALL.push_back(cv::Point3f(-70.0f, 28.0f, 0.0f)); 45 | 46 | cv::FileStorage fsRead("../config/camera.xml", cv::FileStorage::READ); 47 | 48 | if(!fsRead.isOpened()) 49 | { 50 | std::cout << "failed to open xml" << std::endl; 51 | return false; 52 | } 53 | 54 | fsRead["Y_DISTANCE_BETWEEN_GUN_AND_CAM"] >> Y_DISTANCE_BETWEEN_GUN_AND_CAM; 55 | fsRead["Z_DISTANCE_BETWEEN_MUZZLE_AND_CAM"] >> Z_DISTANCE_BETWEEN_MUZZLE_AND_CAM; 56 | fsRead["Camera_Matrix"] >> CameraIntrinsicMatrix; 57 | fsRead["Distortion_Coefficients"] >> DistortionCoefficient; 58 | // std::cout << CameraIntrinsicMatrix << std::endl; 59 | return true; 60 | 61 | } 62 | 63 | void AngleSolver::onePointSolution(const std::vector centerPoint) 64 | { 65 | double fx = CameraIntrinsicMatrix.at(0,0); 66 | double fy = CameraIntrinsicMatrix.at(1,1); 67 | double cx = CameraIntrinsicMatrix.at(0,2); 68 | double cy = CameraIntrinsicMatrix.at(1,2); 69 | 70 | std::vector dstPoint; 71 | //单点矫正 72 | cv::undistortPoints(centerPoint, dstPoint, CameraIntrinsicMatrix, 73 | DistortionCoefficient, cv::noArray(), CameraIntrinsicMatrix); 74 | cv::Point2f pnt = dstPoint.front();//返回dstPoint中的第一个元素 75 | //去畸变后的比值,根据像素坐标系与世界坐标系的关系得出,pnt的坐标就是在整幅图像中的坐标 76 | double rxNew=(pnt.x-cx)/fx; 77 | double ryNew=(pnt.y-cy)/fy; 78 | 79 | yawErr = atan(rxNew)/CV_PI*180; 80 | pitchErr = atan(ryNew)/CV_PI*180; 81 | } 82 | 83 | std::vector AngleSolver::p4pSolution(const cv::Rect &rect, int objectType) 84 | { 85 | cv::Point2f rect_points[4]; 86 | // cv::Point2f left_up, left_down, right_up, right_down; 87 | std::vector rect_points_vec; 88 | // rect.points(rect_points); 89 | 90 | // std::cout << "rect_point0: " << rect_points[0] << std::endl; 91 | // std::cout << "rect_point1: " << rect_points[1] << std::endl; 92 | // std::cout << "rect_point2: " << rect_points[2] << std::endl; 93 | // std::cout << "rect_point3: " << rect_points[3] << std::endl; 94 | 95 | 96 | 97 | rect_points_vec.clear(); 98 | rect_points_vec.emplace_back(cv::Point(std::max(rect.x, 0), std::max(rect.y, 0))); 99 | rect_points_vec.emplace_back(cv::Point(std::min(rect.x+rect.width, 640), std::max(rect.y, 0))); 100 | rect_points_vec.emplace_back(cv::Point(std::min(rect.x+rect.width, 640), std::min(rect.y+rect.height, 480))); 101 | rect_points_vec.emplace_back(cv::Point(std::max(rect.x, 0), std::min(rect.y+rect.height, 480))); 102 | // std::cout << rect_points_vec << std::endl; 103 | cv::Mat raux, taux; 104 | 105 | float yawErr_current; 106 | float pitchErr_current; 107 | if(objectType == common_utils::ARMOR_BIG) 108 | { 109 | std::cout << "big" << std::endl; 110 | cv::solvePnP(POINT_3D_OF_ARMOR_BIG, rect_points_vec, CameraIntrinsicMatrix, 111 | DistortionCoefficient, raux, taux, false, cv::SOLVEPNP_ITERATIVE); 112 | 113 | } 114 | else 115 | { 116 | std::cout << "small" << std::endl; 117 | cv::solvePnP(POINT_3D_OF_ARMOR_SMALL, rect_points_vec, CameraIntrinsicMatrix, 118 | DistortionCoefficient, raux, taux, false, cv::SOLVEPNP_ITERATIVE); 119 | } 120 | 121 | // tVec.at(1, 0) -= _params.Y_DISTANCE_BETWEEN_GUN_AND_CAM; 122 | // tVec.at(2, 0) -= _params.Z_DISTANCE_BETWEEN_MUZZLE_AND_CAM; 123 | 124 | yawErr_current = atan(taux.at(0, 0)/taux.at(2, 0))/CV_PI*180; 125 | pitchErr_current = atan(taux.at(1, 0)/taux.at(2, 0))/CV_PI*180; 126 | //计算三维空间下的欧氏距离 127 | _euclideanDistance = sqrt(taux.at(0, 0) * taux.at(0, 0) + taux.at(1, 0) * 128 | taux.at(1, 0) + taux.at(2, 0) * taux.at(2, 0)); 129 | std::vector result; 130 | 131 | result.resize(3); //指定容器的大小为3 132 | result[0] = yawErr_current; 133 | result[1] = pitchErr_current; 134 | result[2] =_euclideanDistance; 135 | std::cout << "yaw:" << result[0] << " pitch: " << result[1] << " dis: " << result[2] << std::endl; 136 | return result; 137 | } 138 | 139 | 140 | 141 | /* 142 | //air friction is considered 143 | float BulletModel(float x, float v, float angle) { //x:m,v:m/s,angle:rad 144 | float t, y; 145 | float init_k_; 146 | t = (float)((exp(init_k_ * x) - 1) / (init_k_ * v * cos(angle))); 147 | y = (float)(v * sin(angle) * t - GRAVITY * t * t / 2); 148 | return y; 149 | } 150 | 151 | //x:distance , y: height 152 | float GetPitch(float x, float y, float v) { 153 | float y_temp, y_actual, dy; 154 | float a; 155 | y_temp = y; 156 | // by iteration 157 | for (int i = 0; i < 20; i++) { 158 | a = (float) atan2(y_temp, x); 159 | y_actual = BulletModel(x, v, a); 160 | dy = y - y_actual; 161 | y_temp = y_temp + dy; 162 | if (fabsf(dy) < 0.001) { 163 | break; 164 | } 165 | //printf("iteration num %d: angle %f,temp target y:%f,err of y:%f\n",i+1,a*180/3.1415926535,yTemp,dy); 166 | } 167 | return a; 168 | 169 | } 170 | 171 | void Transform(vector result, float &pitch, float v, float angle) { 172 | pitch = 173 | -GetPitch(result[2] / 100, -BulletModel(result[2], v, angle) / 100, v) + result[1]; 174 | 175 | } 176 | 177 | */ 178 | -------------------------------------------------------------------------------- /log/log.txt: -------------------------------------------------------------------------------- 1 | [2021-06-16 00:01:12 Wed][Debug] File:../main.cpp Line:17 STARTING MAIN CLIENT... 2 | [2021-06-16 00:01:12 Wed][Debug] File:../src/config.cpp Line:12 config file open success 3 | [2021-06-16 00:01:12 Wed][Debug] File:../src/config.cpp Line:78 read config file success 4 | [2021-06-16 00:01:12 Wed][Debug] File:../src/config.cpp Line:85 read: "/dev/ttyTHS2" 5 | [2021-06-16 00:01:12 Wed][Debug] File:../main.cpp Line:23 "/dev/ttyTHS2" 6 | [2021-06-16 00:01:12 Wed][Debug] File:../src/config.cpp Line:105 err: 5 7 | [2021-06-16 00:01:12 Wed][Debug] File:../main.cpp Line:25 "" 8 | [2021-06-16 00:02:29 Wed][Debug] File:../main.cpp Line:17 STARTING MAIN CLIENT... 9 | [2021-06-16 00:02:29 Wed][Debug] File:../src/config.cpp Line:80 config file open success 10 | [2021-06-16 00:02:29 Wed][Debug] File:../src/config.cpp Line:87 read config file success 11 | [2021-06-16 00:02:29 Wed][Debug] File:../src/config.cpp Line:94 read: "/dev/ttyTHS2" 12 | [2021-06-16 00:02:29 Wed][Debug] File:../main.cpp Line:23 "/dev/ttyTHS2" 13 | [2021-06-16 00:02:29 Wed][Warning] File: Line:0 QFile::open: File (../config/config.json) already open 14 | [2021-06-16 00:02:29 Wed][Debug] File:../src/config.cpp Line:76 config file open error 15 | [2021-06-16 00:02:29 Wed][Debug] File:../src/config.cpp Line:114 err: 5 16 | [2021-06-16 00:02:29 Wed][Debug] File:../main.cpp Line:25 "" 17 | [2021-06-16 00:03:59 Wed][Debug] File:../main.cpp Line:17 STARTING MAIN CLIENT... 18 | [2021-06-16 00:03:59 Wed][Debug] File:../src/config.cpp Line:80 config file open success 19 | [2021-06-16 00:03:59 Wed][Debug] File:../src/config.cpp Line:87 read config file success 20 | [2021-06-16 00:03:59 Wed][Debug] File:../src/config.cpp Line:94 read: "/dev/ttyTHS2" 21 | [2021-06-16 00:03:59 Wed][Debug] File:../main.cpp Line:23 "/dev/ttyTHS2" 22 | [2021-06-16 00:03:59 Wed][Debug] File:../src/config.cpp Line:80 config file open success 23 | [2021-06-16 00:03:59 Wed][Debug] File:../src/config.cpp Line:87 read config file success 24 | [2021-06-16 00:03:59 Wed][Debug] File:../src/config.cpp Line:100 read: 5000 25 | [2021-06-16 00:03:59 Wed][Debug] File:../main.cpp Line:25 "5000" 26 | [2021-06-16 00:12:51 Wed][Debug] File:../main.cpp Line:19 STARTING MAIN CLIENT... 27 | [2021-06-16 00:12:51 Wed][Debug] File:../src/config.cpp Line:80 config file open success 28 | [2021-06-16 00:12:51 Wed][Debug] File:../src/config.cpp Line:87 read config file success 29 | [2021-06-16 00:12:51 Wed][Debug] File:../src/config.cpp Line:94 read: "/dev/ttyTHS2" 30 | [2021-06-16 00:12:51 Wed][Debug] File:../main.cpp Line:26 "/dev/ttyTHS2" 31 | [2021-06-16 00:12:51 Wed][Debug] File:../src/config.cpp Line:80 config file open success 32 | [2021-06-16 00:12:51 Wed][Debug] File:../src/config.cpp Line:87 read config file success 33 | [2021-06-16 00:12:51 Wed][Debug] File:../src/config.cpp Line:100 read: 5000 34 | [2021-06-16 00:12:51 Wed][Debug] File:../main.cpp Line:28 "5000" 35 | [2021-06-16 00:12:51 Wed][Debug] File:../main.cpp Line:30 0 36 | [2021-06-16 00:13:14 Wed][Debug] File:../main.cpp Line:19 STARTING MAIN CLIENT... 37 | [2021-06-16 00:13:14 Wed][Debug] File:../src/config.cpp Line:80 config file open success 38 | [2021-06-16 00:13:14 Wed][Debug] File:../src/config.cpp Line:87 read config file success 39 | [2021-06-16 00:13:14 Wed][Debug] File:../src/config.cpp Line:94 read: "/dev/ttyTHS2" 40 | [2021-06-16 00:13:14 Wed][Debug] File:../main.cpp Line:26 "/dev/ttyTHS2" 41 | [2021-06-16 00:13:14 Wed][Debug] File:../src/config.cpp Line:80 config file open success 42 | [2021-06-16 00:13:14 Wed][Debug] File:../src/config.cpp Line:87 read config file success 43 | [2021-06-16 00:13:14 Wed][Debug] File:../src/config.cpp Line:100 read: 5000 44 | [2021-06-16 00:13:14 Wed][Debug] File:../main.cpp Line:28 "5000" 45 | [2021-06-16 00:13:14 Wed][Debug] File:../main.cpp Line:30 6341673 46 | [2021-06-16 00:13:30 Wed][Debug] File:../main.cpp Line:19 STARTING MAIN CLIENT... 47 | [2021-06-16 00:13:30 Wed][Debug] File:../src/config.cpp Line:80 config file open success 48 | [2021-06-16 00:13:30 Wed][Debug] File:../src/config.cpp Line:87 read config file success 49 | [2021-06-16 00:13:30 Wed][Debug] File:../src/config.cpp Line:94 read: "/dev/ttyTHS2" 50 | [2021-06-16 00:13:30 Wed][Debug] File:../main.cpp Line:26 "/dev/ttyTHS2" 51 | [2021-06-16 00:13:30 Wed][Debug] File:../src/config.cpp Line:80 config file open success 52 | [2021-06-16 00:13:30 Wed][Debug] File:../src/config.cpp Line:87 read config file success 53 | [2021-06-16 00:13:30 Wed][Debug] File:../src/config.cpp Line:100 read: 5000 54 | [2021-06-16 00:13:30 Wed][Debug] File:../main.cpp Line:28 "5000" 55 | [2021-06-16 00:13:30 Wed][Debug] File:../main.cpp Line:30 6358360 6358361 56 | [2021-06-16 00:21:30 Wed][Debug] File:../main.cpp Line:19 STARTING MAIN CLIENT... 57 | [2021-06-16 00:21:30 Wed][Debug] File:../src/config.cpp Line:21 config file open success 58 | [2021-06-16 00:21:30 Wed][Debug] File:../src/config.cpp Line:75 initialize config file success 59 | [2021-06-16 00:37:26 Wed][Debug] File:../main.cpp Line:19 STARTING MAIN CLIENT... 60 | [2021-06-16 00:37:26 Wed][Debug] File:../src/config.cpp Line:21 config file open success 61 | [2021-06-16 00:37:26 Wed][Debug] File:../src/config.cpp Line:75 initialize config file success 62 | [2021-06-16 00:37:47 Wed][Debug] File:../main.cpp Line:19 STARTING MAIN CLIENT... 63 | [2021-06-16 00:37:47 Wed][Debug] File:../src/config.cpp Line:21 config file open success 64 | [2021-06-16 00:37:47 Wed][Debug] File:../src/config.cpp Line:75 initialize config file success 65 | [2021-06-16 00:44:34 Wed][Debug] File:../main.cpp Line:19 STARTING MAIN CLIENT... 66 | [2021-06-16 00:44:34 Wed][Debug] File:../src/config.cpp Line:21 config file open success 67 | [2021-06-16 00:44:34 Wed][Debug] File:../src/config.cpp Line:75 initialize config file success 68 | [2021-06-16 00:46:12 Wed][Debug] File:../main.cpp Line:19 STARTING MAIN CLIENT... 69 | [2021-06-16 00:46:12 Wed][Debug] File:../src/config.cpp Line:21 config file open success 70 | [2021-06-16 00:46:12 Wed][Debug] File:../src/config.cpp Line:75 initialize config file success 71 | [2021-06-16 00:46:22 Wed][Debug] File:../main.cpp Line:19 STARTING MAIN CLIENT... 72 | [2021-06-16 00:46:22 Wed][Debug] File:../src/config.cpp Line:21 config file open success 73 | [2021-06-16 00:46:22 Wed][Debug] File:../src/config.cpp Line:75 initialize config file success 74 | [2021-06-28 16:24:44 Mon][Debug] File:../main.cpp Line:19 STARTING MAIN CLIENT... 75 | [2021-06-28 16:24:44 Mon][Debug] File:../src/config.cpp Line:21 config file open success 76 | [2021-06-28 16:24:44 Mon][Debug] File:../src/config.cpp Line:75 initialize config file success 77 | [2021-06-28 16:30:18 Mon][Debug] File:../main.cpp Line:19 STARTING MAIN CLIENT... 78 | [2021-06-28 16:30:18 Mon][Debug] File:../src/config.cpp Line:21 config file open success 79 | [2021-06-28 16:30:18 Mon][Debug] File:../src/config.cpp Line:75 initialize config file success 80 | [2021-06-29 09:34:45 Tue][Debug] File:../main.cpp Line:20 STARTING MAIN CLIENT... 81 | [2021-06-29 09:34:45 Tue][Debug] File:../src/config.cpp Line:21 config file open success 82 | [2021-06-29 09:34:45 Tue][Debug] File:../src/config.cpp Line:75 initialize config file success 83 | [2021-06-29 13:41:06 Tue][Debug] File:../main.cpp Line:23 STARTING MAIN CLIENT... 84 | [2021-06-29 13:41:06 Tue][Debug] File:../src/can.cpp Line:21 find can device success 85 | [2021-06-29 13:41:06 Tue][Warning] File: Line:0 Cannot apply parameter: 4 with value: 500000. 86 | [2021-06-29 13:41:06 Tue][Debug] File:../src/can.cpp Line:36 connect can bus success 87 | [2021-06-29 13:48:41 Tue][Debug] File:../main.cpp Line:23 STARTING MAIN CLIENT... 88 | [2021-06-29 13:48:41 Tue][Debug] File:../src/can.cpp Line:21 find can device success 89 | [2021-06-29 13:48:41 Tue][Warning] File: Line:0 Cannot apply parameter: 4 with value: 500000. 90 | [2021-06-29 13:48:41 Tue][Debug] File:../src/can.cpp Line:36 connect can bus success 91 | [2021-06-29 13:48:47 Tue][Debug] File:../main.cpp Line:23 STARTING MAIN CLIENT... 92 | [2021-06-29 13:48:47 Tue][Debug] File:../src/can.cpp Line:21 find can device success 93 | [2021-06-29 13:48:47 Tue][Warning] File: Line:0 Cannot apply parameter: 4 with value: 500000. 94 | [2021-06-29 13:48:47 Tue][Debug] File:../src/can.cpp Line:36 connect can bus success 95 | -------------------------------------------------------------------------------- /imageshow.ui: -------------------------------------------------------------------------------- 1 | 2 | 3 | ImageShow 4 | 5 | 6 | 7 | 0 8 | 0 9 | 887 10 | 530 11 | 12 | 13 | 14 | ImageShow 15 | 16 | 17 | 18 | 19 | 10 20 | 10 21 | 640 22 | 480 23 | 24 | 25 | 26 | QFrame::Panel 27 | 28 | 29 | QFrame::Sunken 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 560 39 | 500 40 | 80 41 | 22 42 | 43 | 44 | 45 | Close 46 | 47 | 48 | 49 | 50 | 51 | 406 52 | 500 53 | 111 54 | 22 55 | 56 | 57 | 58 | FPS: 59 | 60 | 61 | 62 | 63 | 64 | 700 65 | 40 66 | 57 67 | 14 68 | 69 | 70 | 71 | Rx: 72 | 73 | 74 | 75 | 76 | 77 | 700 78 | 60 79 | 57 80 | 14 81 | 82 | 83 | 84 | color 85 | 86 | 87 | 88 | 89 | 90 | 790 91 | 60 92 | 57 93 | 14 94 | 95 | 96 | 97 | QFrame::Panel 98 | 99 | 100 | QFrame::Sunken 101 | 102 | 103 | 104 | 105 | 106 | 107 | 108 | 109 | 700 110 | 280 111 | 57 112 | 14 113 | 114 | 115 | 116 | Tx: 117 | 118 | 119 | 120 | 121 | 122 | 790 123 | 80 124 | 57 125 | 14 126 | 127 | 128 | 129 | QFrame::Panel 130 | 131 | 132 | QFrame::Sunken 133 | 134 | 135 | 136 | 137 | 138 | 139 | 140 | 141 | 700 142 | 80 143 | 57 144 | 14 145 | 146 | 147 | 148 | target 149 | 150 | 151 | 152 | 153 | 154 | 790 155 | 120 156 | 57 157 | 14 158 | 159 | 160 | 161 | QFrame::Panel 162 | 163 | 164 | QFrame::Sunken 165 | 166 | 167 | 168 | 169 | 170 | 171 | 172 | 173 | 700 174 | 120 175 | 57 176 | 14 177 | 178 | 179 | 180 | video 181 | 182 | 183 | 184 | 185 | 186 | 790 187 | 100 188 | 57 189 | 14 190 | 191 | 192 | 193 | QFrame::Panel 194 | 195 | 196 | QFrame::Sunken 197 | 198 | 199 | 200 | 201 | 202 | 203 | 204 | 205 | 700 206 | 100 207 | 57 208 | 14 209 | 210 | 211 | 212 | energy 213 | 214 | 215 | 216 | 217 | 218 | 790 219 | 320 220 | 57 221 | 14 222 | 223 | 224 | 225 | QFrame::Panel 226 | 227 | 228 | QFrame::Sunken 229 | 230 | 231 | 232 | 233 | 234 | 235 | 236 | 237 | 700 238 | 320 239 | 57 240 | 14 241 | 242 | 243 | 244 | pitch 245 | 246 | 247 | 248 | 249 | 250 | 790 251 | 300 252 | 57 253 | 14 254 | 255 | 256 | 257 | QFrame::Panel 258 | 259 | 260 | QFrame::Sunken 261 | 262 | 263 | 264 | 265 | 266 | 267 | 268 | 269 | 700 270 | 300 271 | 57 272 | 14 273 | 274 | 275 | 276 | yaw 277 | 278 | 279 | 280 | 281 | 282 | 790 283 | 340 284 | 57 285 | 14 286 | 287 | 288 | 289 | QFrame::Panel 290 | 291 | 292 | QFrame::Sunken 293 | 294 | 295 | 296 | 297 | 298 | 299 | 300 | 301 | 700 302 | 340 303 | 57 304 | 14 305 | 306 | 307 | 308 | state 309 | 310 | 311 | 312 | 313 | 314 | 790 315 | 360 316 | 57 317 | 14 318 | 319 | 320 | 321 | QFrame::Panel 322 | 323 | 324 | QFrame::Sunken 325 | 326 | 327 | 328 | 329 | 330 | 331 | 332 | 333 | 700 334 | 360 335 | 57 336 | 14 337 | 338 | 339 | 340 | cmd 341 | 342 | 343 | 344 | 345 | 346 | 790 347 | 140 348 | 57 349 | 14 350 | 351 | 352 | 353 | QFrame::Panel 354 | 355 | 356 | QFrame::Sunken 357 | 358 | 359 | 360 | 361 | 362 | 363 | 364 | 365 | 700 366 | 140 367 | 57 368 | 14 369 | 370 | 371 | 372 | pitch 373 | 374 | 375 | 376 | 377 | 378 | 700 379 | 160 380 | 57 381 | 14 382 | 383 | 384 | 385 | speed 386 | 387 | 388 | 389 | 390 | 391 | 790 392 | 160 393 | 57 394 | 14 395 | 396 | 397 | 398 | QFrame::Panel 399 | 400 | 401 | QFrame::Sunken 402 | 403 | 404 | 405 | 406 | 407 | 408 | 409 | 410 | 411 | -------------------------------------------------------------------------------- /src/energydetector.cpp: -------------------------------------------------------------------------------- 1 | #include "energydetector.h" 2 | #include "anglesolver.h" 3 | 4 | double EnergyDetector::getDistance(Point A,Point B) 5 | { 6 | double dis; 7 | dis=pow((A.x-B.x),2)+pow((A.y-B.y),2); 8 | return sqrt(dis); 9 | } 10 | //标准化并计算hog 11 | vector EnergyDetector::stander(Mat im) 12 | { 13 | 14 | if(im.empty()==1) 15 | { 16 | cout<<"filed open"< result; 21 | 22 | HOGDescriptor hog(cvSize(48,48),cvSize(16,16),cvSize(8,8),cvSize(8,8),9,1,-1, 23 | HOGDescriptor::L2Hys,0.2,false,HOGDescriptor::DEFAULT_NLEVELS); //初始化HOG描述符 24 | hog.compute(im,result); 25 | return result; 26 | } 27 | //将图片转换为svm所需格式 28 | Mat EnergyDetector::get(Mat input) 29 | { 30 | vector vec=stander(input); 31 | if(vec.size()!=900) cout<<"wrong not 900"< p=output; 35 | int jj=0; 36 | for(vector::iterator iter=vec.begin();iter!=vec.end();iter++,jj++) 37 | { 38 | p(0,jj)=*(iter); 39 | } 40 | return output; 41 | } 42 | 43 | EnergyDetector::EnergyDetector() 44 | { 45 | svm = cv::ml::SVM::create(); 46 | svm->load("/home/dji/energy/camera_param/SVM_mode.xml"); 47 | } 48 | 49 | bool EnergyDetector::run(const cv::Mat &src_img, cv::Mat &dst_img, EnergyBox &target, int &self_color){ 50 | 51 | Point centerP; 52 | Point centerR; 53 | Point centerP_pre; 54 | int angle = 0; 55 | int count_ture = 0; 56 | int flag = 0; 57 | // double V; 58 | // double ptz_pitch; 59 | // double theta = 0.0; 60 | // double pitch_theta = 0.0; 61 | 62 | //分割颜色通道 63 | vector imgChannels; 64 | split(src_img,imgChannels); 65 | Mat midImage2; 66 | //获得目标颜色图像的二值图 67 | if(self_color == common_utils::SELF_BLUE) 68 | { 69 | midImage2=imgChannels.at(0)-imgChannels.at(2); 70 | } 71 | else if(sekf_color == common_utils::SELF_RED) 72 | { 73 | midImage2=imgChannels.at(2)-imgChannels.at(0); 74 | } 75 | else 76 | { 77 | dst_img = src_img; 78 | return false; 79 | } 80 | 81 | 82 | //二值化,背景为黑色,图案为白色 83 | //用于查找扇叶 84 | threshold(midImage2,midImage2,100,255,CV_THRESH_BINARY); 85 | int structElementSize=1; 86 | Mat element=getStructuringElement(MORPH_RECT,Size(2*structElementSize+3,2*structElementSize+3),Point(structElementSize,structElementSize)); 87 | //膨胀 88 | dilate(midImage2,midImage2,element); 89 | //开运算,消除扇叶上可能存在的小洞 90 | structElementSize=1; 91 | element=getStructuringElement(MORPH_RECT,Size(2*structElementSize+1,2*structElementSize+1),Point(structElementSize,structElementSize)); 92 | morphologyEx(midImage2,midImage2, MORPH_CLOSE, element); 93 | 94 | //查找轮廓 95 | vector> contours2; 96 | vector hierarchy2; 97 | findContours(midImage2,contours2,hierarchy2,RETR_CCOMP,CHAIN_APPROX_SIMPLE); 98 | 99 | RotatedRect rect_tmp2; 100 | bool findTarget=0; 101 | 102 | //遍历轮廓 103 | if(hierarchy2.size()) 104 | for(int i=hierarchy2.size()-1;i>=0;i--) 105 | { 106 | rect_tmp2=minAreaRect(contours2[i]); 107 | Point2f P[4]; 108 | rect_tmp2.points(P); 109 | 110 | Point2f srcRect[4]; 111 | Point2f dstRect[4]; 112 | Point2f rRect[4]; 113 | 114 | double width; 115 | double height; 116 | 117 | //矫正提取的叶片的宽高 118 | width=getDistance(P[0],P[1]); 119 | height=getDistance(P[1],P[2]); 120 | if(width>height) 121 | { 122 | srcRect[0]=P[0]; 123 | srcRect[1]=P[1]; 124 | srcRect[2]=P[2]; 125 | srcRect[3]=P[3]; 126 | } 127 | else 128 | { 129 | swap(width,height); 130 | srcRect[0]=P[1]; 131 | srcRect[1]=P[2]; 132 | srcRect[2]=P[3]; 133 | srcRect[3]=P[0]; 134 | } 135 | //通过面积筛选 136 | double area=height*width; 137 | //cout<<"area "<100 && area<180){ 139 | rRect[0]=Point2f(0,0); 140 | rRect[1]=Point2f(width,0); 141 | rRect[2]=Point2f(width,height); 142 | rRect[3]=Point2f(0,height); 143 | // 应用透视变换,矫正成规则矩形 144 | Mat transform_r = getPerspectiveTransform(srcRect,rRect); 145 | Mat perspectMat_r; 146 | warpPerspective(midImage2,perspectMat_r,transform_r,midImage2.size()); 147 | 148 | Mat testR; 149 | testR = perspectMat_r(Rect(0,0,width,height)); 150 | 151 | RotatedRect rect_R=minAreaRect(contours2[i]); 152 | //cout<<"beggg"<2000){ 158 | dstRect[0]=Point2f(0,0); 159 | dstRect[1]=Point2f(width,0); 160 | dstRect[2]=Point2f(width,height); 161 | dstRect[3]=Point2f(0,height); 162 | // 应用透视变换,矫正成规则矩形 163 | Mat transform = getPerspectiveTransform(srcRect,dstRect); 164 | Mat perspectMat; 165 | warpPerspective(midImage2,perspectMat,transform,midImage2.size()); 166 | 167 | // 提取扇叶图片 168 | Mat testim; 169 | testim = perspectMat(Rect(0,0,width,height)); 170 | 171 | if(testim.empty()) 172 | { 173 | cout<<"filed open"<predict(test)>=0.9) 182 | { 183 | findTarget=true; 184 | //查找装甲板 185 | if(hierarchy2[i][2]>=0) 186 | { 187 | RotatedRect rect_tmp=minAreaRect(contours2[hierarchy2[i][2]]); 188 | Point2f Pnt[4]; 189 | rect_tmp.points(Pnt); 190 | const float maxHWRatio=0.7153846; 191 | const float maxArea=1000; 192 | const float minArea=250; 193 | 194 | float width=rect_tmp.size.width; 195 | float height=rect_tmp.size.height; 196 | if(height>width) 197 | swap(height,width); 198 | float area=width*height; 199 | 200 | if(height/width>maxHWRatio||area>maxArea ||area6 && count_ture<50) << endl; 220 | cout << "value " << count_ture << endl; 221 | cout << "value_xp " << centerP_pre.x << endl; 222 | cout << "value_x " << centerP.x << endl; 223 | */ 224 | 225 | 226 | if((count_ture>4 && count_ture<50) && (centerP.y40 && count_ture<50) && (centerP.y>centerR.y && centerP_pre.x>centerP.x)) 231 | { 232 | flag = 1; 233 | } 234 | else if(count_ture>40 && count_ture<50) 235 | { 236 | flag = -1; 237 | } 238 | 239 | if(centerP_pre.x != centerP.x){ 240 | count_ture++; 241 | centerP_pre = centerP; 242 | } 243 | 244 | Rect r(centerP.x, centerP.y, width, height); 245 | // target = EnergyBox(r); 246 | // return true; 247 | Point2f tl = r.tl(); 248 | Point2f br = r.br(); 249 | //cout << "width" << width << endl; 250 | //cout << "height" << height << endl; 251 | float min_x, min_y, max_x, max_y; 252 | min_x = tl.x; 253 | max_x = br.x; 254 | min_y = tl.y; 255 | max_y = br.y; 256 | ARMOR = { 257 | cv::Point2f(min_x, min_y), //tl 258 | cv::Point2f(max_x, min_y), //tr 259 | cv::Point2f(max_x, max_y), //br 260 | cv::Point2f(min_x, max_y) //bl 261 | }; 262 | AngleSolverParam pnp; 263 | pnp.read_XMLFile(); 264 | AngleSolver PNP(pnp); 265 | vectorresult = PNP.trajectorySolve_energy(ARMOR ,4,float target_fan_angle, 266 | Point centerR); 267 | /* 268 | for(int i = 0; iresult1 = PNP.trajectorySolve(result); 274 | 275 | 276 | // yawErr = result[0]; 277 | // pitchErr = result[1]+pitch_theta; 278 | // char buff[9]; 279 | // buff[0]=0xAA; 280 | // buff[1]=0x00; 281 | // buff[2]=0x01; 282 | // buff[3]=yawErr>>8; 283 | // buff[4]=yawErr; 284 | // buff[5]=pitchErr>>8; 285 | // buff[6]=pitchErr; 286 | // buff[7]=0x01;//0x00- 287 | // buff[8]=buff[0]+buff[1]+buff[2]+buff[3]+buff[4]+buff[5]+buff[6]+buff[7]; 288 | // sel.writeData(buff, 9); 289 | } 290 | } 291 | 292 | } 293 | } 294 | } 295 | -------------------------------------------------------------------------------- /src/armordetector.cpp: -------------------------------------------------------------------------------- 1 | #include "armordetector.h" 2 | 3 | bool ArmorBox::areaComparator(const ArmorBox &a, const ArmorBox &b) 4 | { 5 | return a.armor_rotated_rect.size.area() > b.armor_rotated_rect.size.area(); 6 | } 7 | 8 | //bool ArmorBox::ratioComparator(const ArmorBox &a, const ArmorBox &b) 9 | //{ 10 | // return fabs(a.armor_rect.size.aspectRatio()-1) < fabs(b.armor_rect.size.aspectRatio()-1); 11 | //} 12 | 13 | ArmorDetector::ArmorDetector() 14 | { 15 | 16 | } 17 | 18 | bool ArmorDetector::run(const cv::Mat &src_img, cv::Mat &dst_img, ArmorBox &target, int &self_color) 19 | { 20 | preProcess(src_img, bin_img, self_color); 21 | findLightbars(bin_img, dst_img); 22 | matchArmorBoxes(src_img, dst_img); 23 | // dst_img = bin_img.clone(); 24 | if(getTarget()) 25 | { 26 | target = armor_target; 27 | 28 | lightbars.clear(); 29 | armor_boxes.clear(); 30 | cv::circle(dst_img, target.armor_rotated_rect.center, 7, cv::Scalar(255,0,255), -1); 31 | 32 | return true; 33 | } 34 | else 35 | { 36 | lightbars.clear(); 37 | armor_boxes.clear(); 38 | return false; 39 | } 40 | } 41 | 42 | void ArmorDetector::preProcess(const cv::Mat &src_img, cv::Mat &bin_img, int &self_color) 43 | { 44 | cv::Mat img = src_img.clone(); 45 | cv::Mat color_channel, color_channel_binary; 46 | std::vector channels; 47 | cv::split(img, channels); 48 | if(self_color == common_utils::SELF_RED) 49 | { 50 | color_channel = channels[0] - channels[2]; // enemy=blue 51 | } 52 | else 53 | { 54 | color_channel = channels[2] - channels[0]; // enemy=red 55 | } 56 | // cv::threshold(color_channel, color_channel_binary, 150, 255, cv::THRESH_BINARY); 57 | 58 | cv::threshold(color_channel, color_channel_binary, 150, 255, cv::THRESH_BINARY); 59 | cv::Mat kernel = cv::getStructuringElement(cv::MORPH_RECT, cv::Size(3,3)); 60 | // cv::morphologyEx(color_channel_binary, color_channel_binary, cv::MORPH_OPEN, kernel); 61 | cv::morphologyEx(color_channel_binary, bin_img, cv::MORPH_CLOSE, kernel); 62 | } 63 | 64 | void ArmorDetector::findLightbars(const cv::Mat &bin_img, cv::Mat &dst_img) 65 | { 66 | 67 | std::vector> lightbar_contours; 68 | std::vector hierarchy_lightbar; 69 | 70 | cv::RotatedRect rect_lightbar; 71 | cv::findContours(bin_img, lightbar_contours, hierarchy_lightbar, cv::RETR_EXTERNAL, cv::CHAIN_APPROX_NONE); 72 | for(uint i=0; i 0) 76 | // { 77 | // std::cout << "area: " << rect_lightbar.size.area() << std::endl; 78 | // } 79 | if(rect_lightbar.size.area() > 5.0) 80 | { 81 | if(rect_lightbar.size.width > rect_lightbar.size.height) 82 | { 83 | rect_lightbar = cv::RotatedRect(rect_lightbar.center, 84 | cv::Size2f(rect_lightbar.size.height, rect_lightbar.size.width),rect_lightbar.angle-90); 85 | } 86 | lightbars.emplace_back(rect_lightbar); 87 | } 88 | } 89 | dst_img = cv::Mat::zeros(480, 640, CV_8UC3); 90 | cv::drawContours(dst_img, lightbar_contours, -1, cv::Scalar(0,255,0), 1); 91 | } 92 | 93 | void ArmorDetector::matchArmorBoxes(const cv::Mat &src_img, cv::Mat &dst_img) 94 | { 95 | // armor's height, width, ratio between length of two lightbars, ratio between armor's height and width 96 | double armor_height, armor_width, length_ratio, aspect_ratio; 97 | 98 | // angle/height distance between two lightbars, angle of armor, angle distance between armor and lightbars 99 | double angle_distance, height_distance, armor_angle, armor_light_angle; 100 | 101 | std::vector armor_points_vec; 102 | cv::Point2f left_points[4], right_points[4], armor_points[4]; 103 | cv::RotatedRect armor_rotated_rect; 104 | cv::Rect armor_rect; 105 | cv::Mat armor_img; 106 | cv::Point2f target; 107 | 108 | armor_boxes.clear(); 109 | 110 | if(lightbars.size() < 2) 111 | { 112 | lightbars.clear(); 113 | return; 114 | } 115 | 116 | for(uint i=0; i0.5) && (length_ratio<1.5) && 139 | (height_distance<30) && ((angle_distance)<10 || (angle_distance>170)) && 140 | (aspect_ratio>2.0) && (aspect_ratio<7.0)) 141 | { 142 | lightbars.at(i).points(left_points); 143 | lightbars.at(j).points(right_points); 144 | for(int k=0; k<4; k++) 145 | { 146 | armor_points_vec.emplace_back(left_points[k]); 147 | armor_points_vec.emplace_back(right_points[k]); 148 | } 149 | armor_rotated_rect = cv::minAreaRect(armor_points_vec); 150 | armor_rect = cv::boundingRect(armor_points_vec); 151 | target = getCenterPoint(armor_rect); 152 | armor_rotated_rect.points(armor_points); 153 | 154 | cv::Point rect_top_left, rect_bottom_right; 155 | rect_top_left = armor_rect.tl(); 156 | rect_bottom_right = armor_rect.br(); 157 | // std::cout << int(rect_top_left.x) << " " << int(fmax(rect_top_left.y-armor_height*0.5, 0)) << " "; 158 | // std::cout << int(armor_width) << " " << int(armor_height*2) << std::endl; 159 | if(rect_top_left.x+armor_width*0.12 <= 0 || 160 | (int(rect_top_left.x+armor_width*0.12) + int(armor_width) > 640) || 161 | (int(fmax(rect_top_left.y-armor_height*0.5, 0)) + int(armor_height*2) > 480)) 162 | { 163 | continue; 164 | } 165 | cv::Rect armor_img_rect(int(rect_top_left.x+armor_width*0.12), 166 | int(fmax(rect_top_left.y-armor_height*0.5, 0)), 167 | int(armor_width*0.8), 168 | int(armor_height*2)); 169 | cv::Mat roi = src_img(armor_img_rect); 170 | cv::Mat roi_gray; 171 | cv::Mat roi_gamma; 172 | 173 | cv::cvtColor(roi, roi_gray, cv::COLOR_BGR2GRAY); 174 | roi_gray.convertTo(roi_gray, CV_64F, 1.0/255, 0); 175 | double gamma = 0.46; 176 | 177 | cv::pow(roi_gray, gamma, roi_gamma); 178 | roi_gamma.convertTo(roi_gamma, CV_8U, 255, 0); 179 | cv::threshold(roi_gamma, roi_gamma, 45, 255, cv::THRESH_BINARY); 180 | 181 | // armor_img = warpTransform(src_img, armor_rect, armor_height, armor_width); 182 | QString filename = "../dataset/" + QString::number(frame_count++) + ".png"; 183 | cv::imwrite(filename.toStdString(), roi_gamma); 184 | for(int m=0; m<4; m++) 185 | { 186 | cv::line(dst_img, armor_points[m], armor_points[(m+1)%4], cv::Scalar(0,255,255)); 187 | } 188 | if(aspect_ratio < 4.4) 189 | { 190 | armor_boxes.emplace_back(ArmorBox(armor_rect, armor_rotated_rect, 191 | roi_gamma, common_utils::ARMOR_SMALL)); 192 | } 193 | else 194 | { 195 | armor_boxes.emplace_back(ArmorBox(armor_rect, armor_rotated_rect, 196 | roi_gamma, common_utils::ARMOR_BIG)); 197 | } 198 | armor_points_vec.clear(); 199 | } 200 | } 201 | } 202 | } 203 | 204 | bool ArmorDetector::getTarget() 205 | { 206 | if(armor_boxes.empty()) 207 | { 208 | return false; 209 | } 210 | else if(armor_boxes.size() == 1) 211 | { 212 | // std::sort(armor_boxes.begin(), armor_boxes.end(), ArmorBox::ratioComparator); 213 | armor_target = armor_boxes[0]; 214 | return true; 215 | } 216 | else 217 | { 218 | std::cout << "size: " << armor_boxes.size() << std::endl; 219 | // for(int k=0; j armor_match_list; 224 | for(int i=0; i::iterator it = armor_boxes[i].armor_img.begin(); 227 | cv::Mat_::iterator it_end = armor_boxes[i].armor_img.end(); 228 | int count = 0; 229 | for(; it!=it_end; ++it) 230 | { 231 | if((*it) > 0) 232 | { 233 | count++; 234 | } 235 | } 236 | std::cout << "ratio: " << float(count) / float(armor_boxes[i].armor_img.cols * armor_boxes[i].armor_img.rows) << std::endl; 237 | if(float(count) / float(armor_boxes[i].armor_img.cols * armor_boxes[i].armor_img.rows) > 0.3) 238 | { 239 | armor_match_list.emplace_back(armor_boxes[i]); 240 | } 241 | } 242 | if(armor_match_list.size() == 0) 243 | { 244 | return false; 245 | } 246 | else 247 | { 248 | std::sort(armor_match_list.begin(), armor_match_list.end(), ArmorBox::areaComparator); 249 | armor_target = armor_match_list[0]; 250 | armor_match_list.clear(); 251 | return true; 252 | } 253 | } 254 | } 255 | cv::Mat ArmorDetector::warpTransform(const cv::Mat &src_img, cv::RotatedRect rect, double height, double width) 256 | { 257 | cv::Point2f rect_point[4], rect_point_src[4], rect_point_dst[4]; 258 | cv::Mat transform_mat, perspect_mat; 259 | rect.points(rect_point_src); 260 | 261 | // if(width < height) 262 | // { 263 | // double temp = 0; 264 | // rect_point_src[0] = rect_point[1]; 265 | // rect_point_src[1] = rect_point[2]; 266 | // rect_point_src[2] = rect_point[3]; 267 | // rect_point_src[3] = rect_point[0]; 268 | // } 269 | // else 270 | // { 271 | // rect_point_src[0] = rect_point[0]; 272 | // rect_point_src[1] = rect_point[1]; 273 | // rect_point_src[2] = rect_point[2]; 274 | // rect_point_src[3] = rect_point[3]; 275 | // } 276 | 277 | rect_point_src[0].y = fmax(rect_point_src[0].y - height/2, 0); 278 | rect_point_src[1].y = fmax(rect_point_src[1].y - height/2, 0); 279 | rect_point_src[2].y = fmin(rect_point_src[2].y + height/2, 480); 280 | rect_point_src[3].y = fmin(rect_point_src[3].y + height/2, 480); 281 | rect_point_dst[0] = cv::Point2f(0, 0); 282 | rect_point_dst[1] = cv::Point2f(width, 0); 283 | rect_point_dst[2] = cv::Point2f(width, 2*height); 284 | rect_point_dst[3] = cv::Point2f(0, 2*height); 285 | std::vector rect_point_src_vec(rect_point_src, rect_point_src+4); 286 | std::vector rect_point_dst_vec(rect_point_dst, rect_point_dst+4); 287 | // transform_mat = cv::getPerspectiveTransform(rect_point_src, rect_point_dst); 288 | transform_mat = cv::findHomography(rect_point_src_vec, rect_point_dst_vec); 289 | cv::warpPerspective(src_img, perspect_mat, transform_mat, cv::Size(width, 2*height)); 290 | return perspect_mat; 291 | } 292 | 293 | cv::Point2i ArmorDetector::getCenterPoint(cv::Rect rect) 294 | { 295 | cv::Point center; 296 | center.x = rect.x + cvRound(rect.width/2.0); 297 | center.y = rect.y + cvRound(rect.height/2.0); 298 | return center; 299 | } 300 | 301 | 302 | 303 | 304 | 305 | 306 | 307 | 308 | 309 | 310 | 311 | 312 | 313 | -------------------------------------------------------------------------------- /include/CameraDefine.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | #ifndef _CAMERA_DEFINE_H_ 3 | #define _CAMERA_DEFINE_H_ 4 | 5 | #include "CameraStatus.h" 6 | 7 | #define MAX_CROSS_LINE 9 8 | 9 | //相机的句柄类型定义 10 | typedef int CameraHandle; 11 | typedef int INT; 12 | typedef int LONG; 13 | typedef unsigned int UINT; 14 | typedef unsigned long long UINT64; 15 | typedef int BOOL; 16 | typedef unsigned char BYTE; 17 | typedef unsigned int DWORD; 18 | typedef void* PVOID; 19 | typedef void* HWND; 20 | typedef char* LPCTSTR; 21 | typedef unsigned short USHORT; 22 | typedef short SHORT; 23 | typedef unsigned char* LPBYTE; 24 | typedef char CHAR; 25 | typedef char TCHAR; 26 | typedef unsigned short WORD; 27 | typedef INT HANDLE; 28 | typedef void VOID; 29 | typedef unsigned int ULONG; 30 | typedef void* LPVOID; 31 | typedef unsigned char UCHAR; 32 | typedef void* HMODULE; 33 | 34 | #define TRUE 1 35 | #define FALSE 0 36 | //图像查表变换的方式 37 | typedef enum 38 | { 39 | LUTMODE_PARAM_GEN=0,//通过调节参数动态生成LUT表 40 | LUTMODE_PRESET, //使用预设的LUT表 41 | LUTMODE_USER_DEF //使用用户自定义的LUT表 42 | }emSdkLutMode; 43 | 44 | //相机的视频流控制 45 | typedef enum 46 | { 47 | RUNMODE_PLAY=0, //正常预览,捕获到图像就显示。(如果相机处于触发模式,则会等待触发帧的到来) 48 | RUNMODE_PAUSE, //暂停,会暂停相机的图像输出,同时也不会去捕获图像 49 | RUNMODE_STOP //停止相机工作。反初始化后,相机就处于停止模式 50 | }emSdkRunMode; 51 | 52 | //SDK内部显示接口的显示方式 53 | typedef enum 54 | { 55 | DISPLAYMODE_SCALE=0, //缩放显示模式,缩放到显示控件的尺寸 56 | DISPLAYMODE_REAL //1:1显示模式,当图像尺寸大于显示控件的尺寸时,只显示局部 57 | }emSdkDisplayMode; 58 | 59 | //录像状态 60 | typedef enum 61 | { 62 | RECORD_STOP = 0, //停止 63 | RECORD_START, //录像中 64 | RECORD_PAUSE //暂停 65 | }emSdkRecordMode; 66 | 67 | //图像的镜像操作 68 | typedef enum 69 | { 70 | MIRROR_DIRECTION_HORIZONTAL = 0,//水平镜像 71 | MIRROR_DIRECTION_VERTICAL //垂直镜像 72 | }emSdkMirrorDirection; 73 | 74 | /// @ingroup MV_ENUM_TYPE 75 | /// \~chinese 图像的旋转操作 76 | /// \~english Rotation of the image 77 | typedef enum 78 | { 79 | ROTATE_DIRECTION_0=0, ///< \~chinese 不旋转 \~english Do not rotate 80 | ROTATE_DIRECTION_90=1, ///< \~chinese 逆时针90度 \~english Counterclockwise 90 degrees 81 | ROTATE_DIRECTION_180=2, ///< \~chinese 逆时针180度 \~english Counterclockwise 180 degrees 82 | ROTATE_DIRECTION_270=3, ///< \~chinese 逆时针270度 \~english Counterclockwise 270 degrees 83 | }emSdkRotateDirection; 84 | 85 | //相机视频的帧率 86 | typedef enum 87 | { 88 | FRAME_SPEED_LOW = 0, //低速模式 89 | FRAME_SPEED_NORMAL, //普通模式 90 | FRAME_SPEED_HIGH, //高速模式(需要较高的传输带宽,多设备共享传输带宽时会对帧率的稳定性有影响) 91 | FRAME_SPEED_SUPER //超高速模式(需要较高的传输带宽,多设备共享传输带宽时会对帧率的稳定性有影响) 92 | }emSdkFrameSpeed; 93 | 94 | //保存文件的格式类型 95 | typedef enum 96 | { 97 | FILE_JPG = 1,//JPG 98 | FILE_BMP = 2,//BMP 99 | FILE_RAW = 4,//相机输出的bayer格式文件,对于不支持bayer格式输出相机,无法保存为该格式 100 | FILE_PNG = 8, //PNG 101 | FILE_BMP_8BIT = 16, ///< \~chinese BMP 8bit \~english BMP 8bit 102 | FILE_PNG_8BIT = 32, ///< \~chinese PNG 8bit \~english PNG 8bit 103 | FILE_RAW_16BIT = 64, ///< \~chinese RAW 16bit \~english RAW 16bit 104 | }emSdkFileType; 105 | 106 | //相机中的图像传感器的工作模式 107 | typedef enum 108 | { 109 | CONTINUATION = 0,//连续采集模式 110 | SOFT_TRIGGER, //软件触发模式,由软件发送指令后,传感器开始采集指定帧数的图像,采集完成后,停止输出 111 | EXTERNAL_TRIGGER //硬件触发模式,当接收到外部信号,传感器开始采集指定帧数的图像,采集完成后,停止输出 112 | } emSdkSnapMode; 113 | 114 | //自动曝光时抗频闪的频闪 115 | typedef enum 116 | { 117 | LIGHT_FREQUENCY_50HZ = 0,//50HZ,一般的灯光都是50HZ 118 | LIGHT_FREQUENCY_60HZ //60HZ,主要是指显示器的 119 | }emSdkLightFrequency; 120 | 121 | //相机的配置参数,分为A,B,C,D 4组进行保存。 122 | typedef enum 123 | { 124 | PARAMETER_TEAM_DEFAULT = 0xff, 125 | PARAMETER_TEAM_A = 0, 126 | PARAMETER_TEAM_B = 1, 127 | PARAMETER_TEAM_C = 2, 128 | PARAMETER_TEAM_D = 3 129 | }emSdkParameterTeam; 130 | 131 | 132 | /*emSdkParameterMode 相机参数加载模式,参数加载分为从文件和从设备加载两种方式 133 | 134 | PARAM_MODE_BY_MODEL:所有同型号的相机共用ABCD四组参数文件。修改 135 | 一台相机的参数文件,会影响到整个同型号的 136 | 相机参数加载。 137 | 138 | PARAM_MODE_BY_NAME:所有设备名相同的相机,共用ABCD四组参数文件。 139 | 默认情况下,当电脑上只接了某型号一台相机时, 140 | 设备名都是一样的,而您希望某一台相机能够加载 141 | 不同的参数文件,则可以通过修改其设备名的方式 142 | 来让其加载指定的参数文件。 143 | 144 | PARAM_MODE_BY_SN:相机按照自己的唯一序列号来加载ABCD四组参数文件, 145 | 序列号在出厂时已经固化在相机内,每台相机的序列号 146 | 都不相同,通过这种方式,每台相机的参数文件都是独立的。 147 | 148 | 您可以根据自己的使用环境,灵活使用以上几种方式加载参数。例如,以 149 | MV-U300为例,您希望多台该型号的相机在您的 电脑上都共用4组参数,那么就 150 | 使用PARAM_MODE_BY_MODEL方式;如果您希望其中某一台或者某几台MV-U300能 151 | 使用自己参数文件而其余的MV-U300又要使用相同的参数文件,那么使用 152 | PARAM_MODE_BY_NAME方式;如果您希望每台MV-U300都使用不同的参数文件,那么 153 | 使用PARAM_MODE_BY_SN方式。 154 | 参数文件存在安装目录的 \Camera\Configs 目录下,以config为后缀名的文件。 155 | */ 156 | typedef enum 157 | { 158 | PARAM_MODE_BY_MODEL = 0, //根据相机型号名从文件中加载参数,例如MV-U300 159 | PARAM_MODE_BY_NAME, //根据设备昵称(tSdkCameraDevInfo.acFriendlyName)从文件中加载参数,例如MV-U300,该昵称可自定义 160 | PARAM_MODE_BY_SN, //根据设备的唯一序列号从文件中加载参数,序列号在出厂时已经写入设备,每台相机拥有不同的序列号。 161 | PARAM_MODE_IN_DEVICE //从设备的固态存储器中加载参数。不是所有的型号都支持从相机中读写参数组,由tSdkCameraCapbility.bParamInDevice决定 162 | }emSdkParameterMode; 163 | 164 | 165 | //SDK生成的相机配置页面掩码值 166 | typedef enum 167 | { 168 | PROP_SHEET_INDEX_EXPOSURE = 0, 169 | PROP_SHEET_INDEX_ISP_COLOR, 170 | PROP_SHEET_INDEX_ISP_LUT, 171 | PROP_SHEET_INDEX_ISP_SHAPE, 172 | PROP_SHEET_INDEX_VIDEO_FORMAT, 173 | PROP_SHEET_INDEX_RESOLUTION, 174 | PROP_SHEET_INDEX_IO_CTRL, 175 | PROP_SHEET_INDEX_TRIGGER_SET, 176 | PROP_SHEET_INDEX_OVERLAY, 177 | PROP_SHEET_INDEX_DEVICE_INFO, 178 | PROP_SHEET_INDEX_WDR, 179 | PROP_SHEET_INDEX_MULTI_EXPOSURE 180 | }emSdkPropSheetMask; 181 | 182 | //SDK生成的相机配置页面的回调消息类型 183 | typedef enum 184 | { 185 | SHEET_MSG_LOAD_PARAM_DEFAULT = 0, //参数被恢复成默认后,触发该消息 186 | SHEET_MSG_LOAD_PARAM_GROUP, //加载指定参数组,触发该消息 187 | SHEET_MSG_LOAD_PARAM_FROMFILE, //从指定文件加载参数后,触发该消息 188 | SHEET_MSG_SAVE_PARAM_GROUP //当前参数组被保存时,触发该消息 189 | }emSdkPropSheetMsg; 190 | 191 | //可视化选择参考窗口的类型 192 | typedef enum 193 | { 194 | REF_WIN_AUTO_EXPOSURE = 0, 195 | REF_WIN_WHITE_BALANCE, 196 | }emSdkRefWinType; 197 | 198 | //可视化选择参考窗口的类型 199 | typedef enum 200 | { 201 | RES_MODE_PREVIEW = 0, 202 | RES_MODE_SNAPSHOT, 203 | }emSdkResolutionMode; 204 | 205 | //白平衡时色温模式 206 | typedef enum 207 | { 208 | CT_MODE_AUTO = 0, //自动识别色温 209 | CT_MODE_PRESET, //使用指定的预设色温 210 | CT_MODE_USER_DEF //自定义色温(增益和矩阵) 211 | }emSdkClrTmpMode; 212 | 213 | //LUT的颜色通道 214 | typedef enum 215 | { 216 | LUT_CHANNEL_ALL = 0,//R,B,G三通道同时调节 217 | LUT_CHANNEL_RED, //红色通道 218 | LUT_CHANNEL_GREEN, //绿色通道 219 | LUT_CHANNEL_BLUE, //蓝色通道 220 | }emSdkLutChannel; 221 | 222 | //ISP处理单元 223 | typedef enum 224 | { 225 | ISP_PROCESSSOR_PC = 0,//使用PC的软件ISP模块 226 | ISP_PROCESSSOR_DEVICE //使用相机自带的硬件ISP模块 227 | }emSdkIspProcessor; 228 | 229 | //闪光灯信号控制方式 230 | typedef enum 231 | { 232 | STROBE_SYNC_WITH_TRIG_AUTO = 0, //和触发信号同步,触发后,相机进行曝光时,自动生成STROBE信号。此时,有效极性可设置(CameraSetStrobePolarity)。 233 | STROBE_SYNC_WITH_TRIG_MANUAL, //和触发信号同步,触发后,STROBE延时指定的时间后(CameraSetStrobeDelayTime),再持续指定时间的脉冲(CameraSetStrobePulseWidth),有效极性可设置(CameraSetStrobePolarity)。 234 | STROBE_ALWAYS_HIGH, //始终为高,忽略STROBE信号的其他设置 235 | STROBE_ALWAYS_LOW //始终为低,忽略STROBE信号的其他设置 236 | }emStrobeControl; 237 | 238 | //硬件外触发的信号种类 239 | typedef enum 240 | { 241 | EXT_TRIG_LEADING_EDGE = 0, //上升沿触发,默认为该方式 242 | EXT_TRIG_TRAILING_EDGE, //下降沿触发 243 | EXT_TRIG_HIGH_LEVEL, //高电平触发,电平宽度决定曝光时间,仅部分型号的相机支持电平触发方式。 244 | EXT_TRIG_LOW_LEVEL //低电平触发, 245 | }emExtTrigSignal; 246 | 247 | //硬件外触发时的快门方式 248 | typedef enum 249 | { 250 | EXT_TRIG_EXP_STANDARD = 0, //标准方式,默认为该方式。 251 | EXT_TRIG_EXP_GRR, //全局复位方式,部分滚动快门的CMOS型号的相机支持该方式,配合外部机械快门,可以达到全局快门的效果,适合拍高速运动的物体 252 | }emExtTrigShutterMode; 253 | 254 | // GPIO模式 255 | typedef enum 256 | { 257 | IOMODE_TRIG_INPUT=0, ///< \~chinese 触发输入 \~english Trigger input 258 | IOMODE_STROBE_OUTPUT=1, ///< \~chinese 闪光灯输出 \~english Strobe output 259 | IOMODE_GP_INPUT=2, ///< \~chinese 通用型输入 \~english Universal input 260 | IOMODE_GP_OUTPUT=3, ///< \~chinese 通用型输出 \~english Universal output 261 | IOMODE_PWM_OUTPUT=4, ///< \~chinese PWM型输出 \~english PWM output 262 | IOMODE_ROTARYENC_INPUT=5, ///< \~chinese 编码器输入 \~english rotary input 263 | }emCameraGPIOMode; 264 | 265 | /// @ingroup MV_ENUM_TYPE 266 | /// \~chinese GPIO 格式 267 | /// \~english GPIO Format 268 | typedef enum 269 | { 270 | IOFORMAT_SINGLE=0, ///< \~chinese 单端 \~english single ended 271 | IOFORMAT_RS422=1, ///< \~chinese 差分RS422 \~english Differential RS422 272 | IOFORMAT_RS422_TERM=2, ///< \~chinese 差分RS422带终端电阻 \~english Differential RS422 and Termination Enable 273 | }emCameraGPIOFormat; 274 | 275 | /// @ingroup MV_ENUM_TYPE 276 | /// \~chinese 取图优先级 277 | /// \~english Get Image priority 278 | typedef enum 279 | { 280 | CAMERA_GET_IMAGE_PRIORITY_OLDEST=0, ///< \~chinese 获取缓存中最旧的一帧 \~english Get the oldest frame in the cache 281 | CAMERA_GET_IMAGE_PRIORITY_NEWEST=1, ///< \~chinese 获取缓存中最新的一帧(比此帧旧的将全部丢弃) \~english Get the latest frame in the cache (older than this frame will be discarded) 282 | 283 | /// \~chinese 丢弃缓存中的所有帧,并且如果此刻相机正在曝光或传输将会被立即打断,等待接收下一帧 284 | /// \note 某些型号的相机不支持此功能,对于不支持此功能的相机这个标志相当于@link #CAMERA_GET_IMAGE_PRIORITY_OLDEST @endlink 285 | /// \~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 286 | /// \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 287 | CAMERA_GET_IMAGE_PRIORITY_NEXT=2, 288 | }emCameraGetImagePriority; 289 | 290 | /// @ingroup MV_ENUM_TYPE 291 | /// \~chinese 软触发功能标志 292 | /// \~english Soft trigger function flag 293 | typedef enum 294 | { 295 | CAMERA_ST_CLEAR_BUFFER_BEFORE = 0x1, ///< \~chinese 在软触发之前先清空相机已缓存的帧 \~english Empty camera-cached frames before soft triggering 296 | }emCameraSoftTriggerExFlags; 297 | 298 | //相机的设备信息 299 | typedef struct 300 | { 301 | char acProductSeries[32]; // 产品系列 302 | char acProductName[32]; // 产品名称 303 | char acFriendlyName[32]; // 产品昵称,用户可自定义改昵称,保存在相机内,用于区分多个相机同时使用,可以用CameraSetFriendlyName接口改变该昵称,设备重启后生效。 304 | char acLinkName[32]; // 内核符号连接名,内部使用 305 | char acDriverVersion[32]; // 驱动版本 306 | char acSensorType[32]; // sensor类型 307 | char acPortType[32]; // 接口类型 308 | char acSn[32]; // 产品唯一序列号 309 | UINT uInstance; // 该型号相机在该电脑上的实例索引号,用于区分同型号多相机 310 | } tSdkCameraDevInfo; 311 | 312 | #define EXT_TRIG_MASK_GRR_SHUTTER 1 ///< \~chinese 快门支持GRR模式 \~english Shutter supports GRR mode 313 | #define EXT_TRIG_MASK_LEVEL_MODE 2 ///< \~chinese 支持电平触发 \~english Support level trigger 314 | #define EXT_TRIG_MASK_DOUBLE_EDGE 4 ///< \~chinese 支持双边沿触发 \~english Supports bilateral triggering 315 | 316 | //tSdkResolutionRange结构体中SKIP、 BIN、RESAMPLE模式的掩码值 317 | #define MASK_2X2_HD (1<<0) //硬件SKIP、BIN、重采样 2X2 318 | #define MASK_3X3_HD (1<<1) 319 | #define MASK_4X4_HD (1<<2) 320 | #define MASK_5X5_HD (1<<3) 321 | #define MASK_6X6_HD (1<<4) 322 | #define MASK_7X7_HD (1<<5) 323 | #define MASK_8X8_HD (1<<6) 324 | #define MASK_9X9_HD (1<<7) 325 | #define MASK_10X10_HD (1<<8) 326 | #define MASK_11X11_HD (1<<9) 327 | #define MASK_12X12_HD (1<<10) 328 | #define MASK_13X13_HD (1<<11) 329 | #define MASK_14X14_HD (1<<12) 330 | #define MASK_15X15_HD (1<<13) 331 | #define MASK_16X16_HD (1<<14) 332 | #define MASK_17X17_HD (1<<15) 333 | #define MASK_2X2_SW (1<<16) //硬件SKIP、BIN、重采样 2X2 334 | #define MASK_3X3_SW (1<<17) 335 | #define MASK_4X4_SW (1<<18) 336 | #define MASK_5X5_SW (1<<19) 337 | #define MASK_6X6_SW (1<<20) 338 | #define MASK_7X7_SW (1<<21) 339 | #define MASK_8X8_SW (1<<22) 340 | #define MASK_9X9_SW (1<<23) 341 | #define MASK_10X10_SW (1<<24) 342 | #define MASK_11X11_SW (1<<25) 343 | #define MASK_12X12_SW (1<<26) 344 | #define MASK_13X13_SW (1<<27) 345 | #define MASK_14X14_SW (1<<28) 346 | #define MASK_15X15_SW (1<<29) 347 | #define MASK_16X16_SW (1<<30) 348 | #define MASK_17X17_SW (1<<31) 349 | 350 | //相机的分辨率设定范围,用于构件UI 351 | typedef struct 352 | { 353 | INT iHeightMax; //图像最大高度 354 | INT iHeightMin; //图像最小高度 355 | INT iWidthMax; //图像最大宽度 356 | INT iWidthMin; //图像最小宽度 357 | UINT uSkipModeMask; //SKIP模式掩码,为0,表示不支持SKIP 。bit0为1,表示支持SKIP 2x2 ;bit1为1,表示支持SKIP 3x3.... 358 | UINT uBinSumModeMask; //BIN(求和)模式掩码,为0,表示不支持BIN 。bit0为1,表示支持BIN 2x2 ;bit1为1,表示支持BIN 3x3.... 359 | UINT uBinAverageModeMask; //BIN(求均值)模式掩码,为0,表示不支持BIN 。bit0为1,表示支持BIN 2x2 ;bit1为1,表示支持BIN 3x3.... 360 | UINT uResampleMask; //硬件重采样的掩码 361 | } tSdkResolutionRange; 362 | 363 | 364 | //相机的分辨率描述 365 | typedef struct 366 | { 367 | INT iIndex; // 索引号,[0,N]表示预设的分辨率(N 为预设分辨率的最大个数,一般不超过20),OXFF 表示自定义分辨率(ROI) 368 | char acDescription[32]; // 该分辨率的描述信息。仅预设分辨率时该信息有效。自定义分辨率可忽略该信息 369 | UINT uBinSumMode; // BIN(求和)的模式,范围不能超过tSdkResolutionRange中uBinSumModeMask 370 | UINT uBinAverageMode; // BIN(求均值)的模式,范围不能超过tSdkResolutionRange中uBinAverageModeMask 371 | UINT uSkipMode; // 是否SKIP的尺寸,为0表示禁止SKIP模式,范围不能超过tSdkResolutionRange中uSkipModeMask 372 | UINT uResampleMask; // 硬件重采样的掩码 373 | INT iHOffsetFOV; // 采集视场相对于Sensor最大视场左上角的垂直偏移 374 | INT iVOffsetFOV; // 采集视场相对于Sensor最大视场左上角的水平偏移 375 | INT iWidthFOV; // 采集视场的宽度 376 | INT iHeightFOV; // 采集视场的高度 377 | INT iWidth; // 相机最终输出的图像的宽度 378 | INT iHeight; // 相机最终输出的图像的高度 379 | INT iWidthZoomHd; // 硬件缩放的宽度,不需要进行此操作的分辨率,此变量设置为0. 380 | INT iHeightZoomHd; // 硬件缩放的高度,不需要进行此操作的分辨率,此变量设置为0. 381 | INT iWidthZoomSw; // 软件缩放的宽度,不需要进行此操作的分辨率,此变量设置为0. 382 | INT iHeightZoomSw; // 软件缩放的高度,不需要进行此操作的分辨率,此变量设置为0. 383 | } tSdkImageResolution; 384 | 385 | //相机白平衡色温模式描述信息 386 | typedef struct 387 | { 388 | INT iIndex; // 模式索引号 389 | char acDescription[32]; // 描述信息 390 | } tSdkColorTemperatureDes; 391 | 392 | //相机帧率描述信息 393 | typedef struct 394 | { 395 | INT iIndex; // 帧率索引号,一般0对应于低速模式,1对应于普通模式,2对应于高速模式 396 | char acDescription[32]; // 描述信息 397 | } tSdkFrameSpeed; 398 | 399 | //相机曝光功能范围定义 400 | typedef struct 401 | { 402 | UINT uiTargetMin; //自动曝光亮度目标最小值 403 | UINT uiTargetMax; //自动曝光亮度目标最大值 404 | UINT uiAnalogGainMin; //模拟增益的最小值,单位为fAnalogGainStep中定义 405 | UINT uiAnalogGainMax; //模拟增益的最大值,单位为fAnalogGainStep中定义 406 | float fAnalogGainStep; //模拟增益每增加1,对应的增加的放大倍数。例如,uiAnalogGainMin一般为16,fAnalogGainStep一般为0.125,那么最小放大倍数就是16*0.125 = 2倍 407 | UINT uiExposeTimeMin; //手动模式下,曝光时间的最小值,单位:行。根据CameraGetExposureLineTime可以获得一行对应的时间(微秒),从而得到整帧的曝光时间 408 | UINT uiExposeTimeMax; //手动模式下,曝光时间的最大值,单位:行 409 | } tSdkExpose; 410 | 411 | //触发模式描述 412 | typedef struct 413 | { 414 | INT iIndex; //模式索引号 415 | char acDescription[32]; //该模式的描述信息 416 | } tSdkTrigger; 417 | 418 | //传输分包大小描述(主要是针对网络相机有效) 419 | typedef struct 420 | { 421 | INT iIndex; //分包大小索引号 422 | char acDescription[32]; //对应的描述信息 423 | UINT iPackSize; 424 | } tSdkPackLength; 425 | 426 | //预设的LUT表描述 427 | typedef struct 428 | { 429 | INT iIndex; //编号 430 | char acDescription[32]; //描述信息 431 | } tSdkPresetLut; 432 | 433 | //AE算法描述 434 | typedef struct 435 | { 436 | INT iIndex; //编号 437 | char acDescription[32]; //描述信息 438 | } tSdkAeAlgorithm; 439 | 440 | //RAW转RGB算法描述 441 | typedef struct 442 | { 443 | INT iIndex; //编号 444 | char acDescription[32]; //描述信息 445 | } tSdkBayerDecodeAlgorithm; 446 | 447 | 448 | //帧率统计信息 449 | typedef struct 450 | { 451 | INT iTotal; //当前采集的总帧数(包括错误帧) 452 | INT iCapture; //当前采集的有效帧的数量 453 | INT iLost; //当前丢帧的数量 454 | } tSdkFrameStatistic; 455 | 456 | //相机输出的图像数据格式 457 | typedef struct 458 | { 459 | INT iIndex; //格式种类编号 460 | char acDescription[32]; //描述信息 461 | UINT iMediaType; //对应的图像格式编码,如CAMERA_MEDIA_TYPE_BAYGR8,在本文件中有定义。 462 | } tSdkMediaType; 463 | 464 | //伽马的设定范围 465 | typedef struct 466 | { 467 | INT iMin; //最小值 468 | INT iMax; //最大值 469 | } tGammaRange; 470 | 471 | //对比度的设定范围 472 | typedef struct 473 | { 474 | INT iMin; //最小值 475 | INT iMax; //最大值 476 | } tContrastRange; 477 | 478 | //RGB三通道数字增益的设定范围 479 | typedef struct 480 | { 481 | INT iRGainMin; //红色增益的最小值 482 | INT iRGainMax; //红色增益的最大值 483 | INT iGGainMin; //绿色增益的最小值 484 | INT iGGainMax; //绿色增益的最大值 485 | INT iBGainMin; //蓝色增益的最小值 486 | INT iBGainMax; //蓝色增益的最大值 487 | } tRgbGainRange; 488 | 489 | //饱和度设定的范围 490 | typedef struct 491 | { 492 | INT iMin; //最小值 493 | INT iMax; //最大值 494 | } tSaturationRange; 495 | 496 | //锐化的设定范围 497 | typedef struct 498 | { 499 | INT iMin; //最小值 500 | INT iMax; //最大值 501 | } tSharpnessRange; 502 | 503 | //ISP模块的使能信息 504 | typedef struct 505 | { 506 | BOOL bMonoSensor; //表示该型号相机是否为黑白相机,如果是黑白相机,则颜色相关的功能都无法调节 507 | BOOL bWbOnce; //表示该型号相机是否支持手动白平衡功能 508 | BOOL bAutoWb; //表示该型号相机是否支持自动白平衡功能 509 | BOOL bAutoExposure; //表示该型号相机是否支持自动曝光功能 510 | BOOL bManualExposure; //表示该型号相机是否支持手动曝光功能 511 | BOOL bAntiFlick; //表示该型号相机是否支持抗频闪功能 512 | BOOL bDeviceIsp; //表示该型号相机是否支持硬件ISP功能 513 | BOOL bForceUseDeviceIsp;//bDeviceIsp和bForceUseDeviceIsp同时为TRUE时,表示强制只用硬件ISP,不可取消。 514 | BOOL bZoomHD; //相机硬件是否支持图像缩放输出(只能是缩小)。 515 | } tSdkIspCapacity; 516 | 517 | /* 定义整合的设备描述信息,这些信息可以用于动态构建UI */ 518 | typedef struct 519 | { 520 | 521 | tSdkTrigger *pTriggerDesc; // 触发模式 522 | INT iTriggerDesc; // 触发模式的个数,即pTriggerDesc数组的大小 523 | 524 | tSdkImageResolution *pImageSizeDesc;// 预设分辨率选择 525 | INT iImageSizeDesc; // 预设分辨率的个数,即pImageSizeDesc数组的大小 526 | 527 | tSdkColorTemperatureDes *pClrTempDesc;// 预设色温模式,用于白平衡 528 | INT iClrTempDesc; 529 | 530 | tSdkMediaType *pMediaTypeDesc; // 相机输出图像格式 531 | INT iMediaTypdeDesc; // 相机输出图像格式的种类个数,即pMediaTypeDesc数组的大小。 532 | 533 | tSdkFrameSpeed *pFrameSpeedDesc; // 可调节帧速类型,对应界面上普通 高速 和超级三种速度设置 534 | INT iFrameSpeedDesc; // 可调节帧速类型的个数,即pFrameSpeedDesc数组的大小。 535 | 536 | tSdkPackLength *pPackLenDesc; // 传输包长度,一般用于网络设备 537 | INT iPackLenDesc; // 可供选择的传输分包长度的个数,即pPackLenDesc数组的大小。 538 | 539 | INT iOutputIoCounts; // 可编程输出IO的个数 540 | INT iInputIoCounts; // 可编程输入IO的个数 541 | 542 | tSdkPresetLut *pPresetLutDesc; // 相机预设的LUT表 543 | INT iPresetLut; // 相机预设的LUT表的个数,即pPresetLutDesc数组的大小 544 | 545 | INT iUserDataMaxLen; // 指示该相机中用于保存用户数据区的最大长度。为0表示无。 546 | BOOL bParamInDevice; // 指示该设备是否支持从设备中读写参数组。1为支持,0不支持。 547 | 548 | tSdkAeAlgorithm *pAeAlmSwDesc; // 软件自动曝光算法描述 549 | int iAeAlmSwDesc; // 软件自动曝光算法个数 550 | 551 | tSdkAeAlgorithm *pAeAlmHdDesc; // 硬件自动曝光算法描述,为NULL表示不支持硬件自动曝光 552 | int iAeAlmHdDesc; // 硬件自动曝光算法个数,为0表示不支持硬件自动曝光 553 | 554 | tSdkBayerDecodeAlgorithm *pBayerDecAlmSwDesc; // 软件Bayer转换为RGB数据的算法描述 555 | int iBayerDecAlmSwDesc; // 软件Bayer转换为RGB数据的算法个数 556 | 557 | tSdkBayerDecodeAlgorithm *pBayerDecAlmHdDesc; // 硬件Bayer转换为RGB数据的算法描述,为NULL表示不支持 558 | int iBayerDecAlmHdDesc; // 硬件Bayer转换为RGB数据的算法个数,为0表示不支持 559 | 560 | /* 图像参数的调节范围定义,用于动态构建UI*/ 561 | tSdkExpose sExposeDesc; // 曝光的范围值 562 | tSdkResolutionRange sResolutionRange; // 分辨率范围描述 563 | tRgbGainRange sRgbGainRange; // 图像数字增益范围描述 564 | tSaturationRange sSaturationRange; // 饱和度范围描述 565 | tGammaRange sGammaRange; // 伽马范围描述 566 | tContrastRange sContrastRange; // 对比度范围描述 567 | tSharpnessRange sSharpnessRange; // 锐化范围描述 568 | tSdkIspCapacity sIspCapacity; // ISP能力描述 569 | 570 | 571 | } tSdkCameraCapbility; 572 | 573 | 574 | //图像帧头信息 575 | typedef struct 576 | { 577 | UINT uiMediaType; // 图像格式,Image Format 578 | UINT uBytes; // 图像数据字节数,Total bytes 579 | INT iWidth; // 图像的宽度,调用图像处理函数后,该变量可能被动态修改,来指示处理后的图像尺寸 580 | INT iHeight; // 图像的高度,调用图像处理函数后,该变量可能被动态修改,来指示处理后的图像尺寸 581 | INT iWidthZoomSw; // 软件缩放的宽度,不需要进行软件裁剪的图像,此变量设置为0. 582 | INT iHeightZoomSw; // 软件缩放的高度,不需要进行软件裁剪的图像,此变量设置为0. 583 | BOOL bIsTrigger; // 指示是否为触发帧 is trigger 584 | UINT uiTimeStamp; // 该帧的采集时间,单位0.1毫秒 585 | UINT uiExpTime; // 当前图像的曝光值,单位为微秒us 586 | float fAnalogGain; // 当前图像的模拟增益倍数 587 | INT iGamma; // 该帧图像的伽马设定值,仅当LUT模式为动态参数生成时有效,其余模式下为-1 588 | INT iContrast; // 该帧图像的对比度设定值,仅当LUT模式为动态参数生成时有效,其余模式下为-1 589 | INT iSaturation; // 该帧图像的饱和度设定值,对于黑白相机无意义,为0 590 | float fRgain; // 该帧图像处理的红色数字增益倍数,对于黑白相机无意义,为1 591 | float fGgain; // 该帧图像处理的绿色数字增益倍数,对于黑白相机无意义,为1 592 | float fBgain; // 该帧图像处理的蓝色数字增益倍数,对于黑白相机无意义,为1 593 | }tSdkFrameHead; 594 | 595 | //图像帧描述 596 | typedef struct sCameraFrame 597 | { 598 | tSdkFrameHead head; //帧头 599 | BYTE * pBuffer; //数据区 600 | }tSdkFrame; 601 | 602 | //图像捕获的回调函数定义 603 | typedef void (*CAMERA_SNAP_PROC)(CameraHandle hCamera, BYTE *pFrameBuffer, tSdkFrameHead* pFrameHead,PVOID pContext); 604 | 605 | //SDK生成的相机配置页面的消息回调函数定义 606 | typedef void (*CAMERA_PAGE_MSG_PROC)(CameraHandle hCamera,UINT MSG,UINT uParam,PVOID pContext); 607 | 608 | /// @ingroup API_RECONNECT 609 | /// \~chinese 相机连接状态回调 610 | /// \param [in] hCamera 相机句柄 611 | /// \param [in] MSG 消息,0: 相机连接断开 1: 相机连接恢复 612 | /// \param [in] uParam 附加信息 613 | /// \param [in] pContext 用户数据 614 | /// \return 无 615 | /// \note USB相机uParam取值: 616 | /// \note 未定义 617 | /// \note 网口相机uParam取值: 618 | /// \note 当MSG=0时:未定义 619 | /// \note 当MSG=1时: 620 | /// \note 0:上次掉线原因,网络通讯失败 621 | /// \note 1:上次掉线原因,相机掉电 622 | /// \~english Camera connection status callback 623 | /// \param [in] hCamera Camera handle 624 | /// \param [in] MSG message, 0: Camera disconnected 1: Camera connection restored 625 | /// \param [in] uParam Additional Information 626 | /// \param [in] pContext user data 627 | /// \return None 628 | /// \note USB camera uParam value: 629 | /// \note Undefined 630 | /// \note network camera uParam value: 631 | /// \note When MSG=0: Undefined 632 | /// \note When MSG=1: 633 | /// \note 0: The last dropped reason, network communication failed 634 | /// \note 1: The last dropped reason, the camera lost power 635 | typedef void (*CAMERA_CONNECTION_STATUS_CALLBACK)(CameraHandle hCamera,UINT MSG,UINT uParam,PVOID pContext); 636 | 637 | 638 | //----------------------------IMAGE FORMAT DEFINE------------------------------------ 639 | //----------------------------图像格式定义------------------------------------------- 640 | #define CAMERA_MEDIA_TYPE_MONO 0x01000000 641 | #define CAMERA_MEDIA_TYPE_RGB 0x02000000 642 | #define CAMERA_MEDIA_TYPE_COLOR 0x02000000 643 | #define CAMERA_MEDIA_TYPE_CUSTOM 0x80000000 644 | #define CAMERA_MEDIA_TYPE_COLOR_MASK 0xFF000000 645 | #define CAMERA_MEDIA_TYPE_OCCUPY1BIT 0x00010000 646 | #define CAMERA_MEDIA_TYPE_OCCUPY2BIT 0x00020000 647 | #define CAMERA_MEDIA_TYPE_OCCUPY4BIT 0x00040000 648 | #define CAMERA_MEDIA_TYPE_OCCUPY8BIT 0x00080000 649 | #define CAMERA_MEDIA_TYPE_OCCUPY10BIT 0x000A0000 650 | #define CAMERA_MEDIA_TYPE_OCCUPY12BIT 0x000C0000 651 | #define CAMERA_MEDIA_TYPE_OCCUPY16BIT 0x00100000 652 | #define CAMERA_MEDIA_TYPE_OCCUPY24BIT 0x00180000 653 | #define CAMERA_MEDIA_TYPE_OCCUPY32BIT 0x00200000 654 | #define CAMERA_MEDIA_TYPE_OCCUPY36BIT 0x00240000 655 | #define CAMERA_MEDIA_TYPE_OCCUPY48BIT 0x00300000 656 | #define CAMERA_MEDIA_TYPE_OCCUPY64BIT 0x00400000 657 | 658 | #define CAMERA_MEDIA_TYPE_EFFECTIVE_PIXEL_SIZE_MASK 0x00FF0000 659 | #define CAMERA_MEDIA_TYPE_EFFECTIVE_PIXEL_SIZE_SHIFT 16 660 | 661 | #define CAMERA_MEDIA_TYPE_PIXEL_SIZE(type) (((type) & CAMERA_MEDIA_TYPE_EFFECTIVE_PIXEL_SIZE_MASK)>>CAMERA_MEDIA_TYPE_EFFECTIVE_PIXEL_SIZE_SHIFT) 662 | 663 | #define CAMERA_MEDIA_TYPE_ID_MASK 0x0000FFFF 664 | #define CAMERA_MEDIA_TYPE_COUNT 0x46 665 | 666 | /*mono*/ 667 | #define CAMERA_MEDIA_TYPE_MONO1P (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY1BIT | 0x0037) 668 | #define CAMERA_MEDIA_TYPE_MONO2P (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY2BIT | 0x0038) 669 | #define CAMERA_MEDIA_TYPE_MONO4P (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY4BIT | 0x0039) 670 | #define CAMERA_MEDIA_TYPE_MONO8 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x0001) 671 | #define CAMERA_MEDIA_TYPE_MONO8S (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x0002) 672 | #define CAMERA_MEDIA_TYPE_MONO10 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0003) 673 | #define CAMERA_MEDIA_TYPE_MONO10_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0004) 674 | #define CAMERA_MEDIA_TYPE_MONO12 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0005) 675 | #define CAMERA_MEDIA_TYPE_MONO12_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0006) 676 | #define CAMERA_MEDIA_TYPE_MONO14 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0025) 677 | #define CAMERA_MEDIA_TYPE_MONO16 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0007) 678 | 679 | /*Bayer */ 680 | #define CAMERA_MEDIA_TYPE_BAYGR8 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x0008) 681 | #define CAMERA_MEDIA_TYPE_BAYRG8 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x0009) 682 | #define CAMERA_MEDIA_TYPE_BAYGB8 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x000A) 683 | #define CAMERA_MEDIA_TYPE_BAYBG8 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x000B) 684 | 685 | #define CAMERA_MEDIA_TYPE_BAYGR10_MIPI (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY10BIT | 0x0026) 686 | #define CAMERA_MEDIA_TYPE_BAYRG10_MIPI (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY10BIT | 0x0027) 687 | #define CAMERA_MEDIA_TYPE_BAYGB10_MIPI (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY10BIT | 0x0028) 688 | #define CAMERA_MEDIA_TYPE_BAYBG10_MIPI (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY10BIT | 0x0029) 689 | 690 | 691 | #define CAMERA_MEDIA_TYPE_BAYGR10 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x000C) 692 | #define CAMERA_MEDIA_TYPE_BAYRG10 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x000D) 693 | #define CAMERA_MEDIA_TYPE_BAYGB10 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x000E) 694 | #define CAMERA_MEDIA_TYPE_BAYBG10 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x000F) 695 | 696 | #define CAMERA_MEDIA_TYPE_BAYGR12 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0010) 697 | #define CAMERA_MEDIA_TYPE_BAYRG12 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0011) 698 | #define CAMERA_MEDIA_TYPE_BAYGB12 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0012) 699 | #define CAMERA_MEDIA_TYPE_BAYBG12 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0013) 700 | 701 | 702 | #define CAMERA_MEDIA_TYPE_BAYGR10_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0026) 703 | #define CAMERA_MEDIA_TYPE_BAYRG10_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0027) 704 | #define CAMERA_MEDIA_TYPE_BAYGB10_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0028) 705 | #define CAMERA_MEDIA_TYPE_BAYBG10_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0029) 706 | 707 | #define CAMERA_MEDIA_TYPE_BAYGR12_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x002A) 708 | #define CAMERA_MEDIA_TYPE_BAYRG12_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x002B) 709 | #define CAMERA_MEDIA_TYPE_BAYGB12_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x002C) 710 | #define CAMERA_MEDIA_TYPE_BAYBG12_PACKED (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x002D) 711 | 712 | #define CAMERA_MEDIA_TYPE_BAYGR16 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x002E) 713 | #define CAMERA_MEDIA_TYPE_BAYRG16 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x002F) 714 | #define CAMERA_MEDIA_TYPE_BAYGB16 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0030) 715 | #define CAMERA_MEDIA_TYPE_BAYBG16 (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0031) 716 | 717 | /*RGB */ 718 | #define CAMERA_MEDIA_TYPE_RGB8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x0014) 719 | #define CAMERA_MEDIA_TYPE_BGR8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x0015) 720 | #define CAMERA_MEDIA_TYPE_RGBA8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY32BIT | 0x0016) 721 | #define CAMERA_MEDIA_TYPE_BGRA8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY32BIT | 0x0017) 722 | #define CAMERA_MEDIA_TYPE_RGB10 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0018) 723 | #define CAMERA_MEDIA_TYPE_BGR10 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0019) 724 | #define CAMERA_MEDIA_TYPE_RGB12 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x001A) 725 | #define CAMERA_MEDIA_TYPE_BGR12 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x001B) 726 | #define CAMERA_MEDIA_TYPE_RGB16 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0033) 727 | #define CAMERA_MEDIA_TYPE_BGR16 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x004B) 728 | #define CAMERA_MEDIA_TYPE_RGBA16 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY64BIT | 0x0064) 729 | #define CAMERA_MEDIA_TYPE_BGRA16 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY64BIT | 0x0051) 730 | #define CAMERA_MEDIA_TYPE_RGB10V1_PACKED (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY32BIT | 0x001C) 731 | #define CAMERA_MEDIA_TYPE_RGB10P32 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY32BIT | 0x001D) 732 | #define CAMERA_MEDIA_TYPE_RGB12V1_PACKED (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY36BIT | 0X0034) 733 | #define CAMERA_MEDIA_TYPE_RGB565P (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0035) 734 | #define CAMERA_MEDIA_TYPE_BGR565P (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0X0036) 735 | 736 | /*YUV and YCbCr*/ 737 | #define CAMERA_MEDIA_TYPE_YUV411_8_UYYVYY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x001E) 738 | #define CAMERA_MEDIA_TYPE_YUV422_8_UYVY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x001F) 739 | #define CAMERA_MEDIA_TYPE_YUV422_8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0032) 740 | #define CAMERA_MEDIA_TYPE_YUV8_UYV (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x0020) 741 | #define CAMERA_MEDIA_TYPE_YCBCR8_CBYCR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x003A) 742 | //CAMERA_MEDIA_TYPE_YCBCR422_8 : YYYYCbCrCbCr 743 | #define CAMERA_MEDIA_TYPE_YCBCR422_8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x003B) 744 | #define CAMERA_MEDIA_TYPE_YCBCR422_8_CBYCRY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0043) 745 | #define CAMERA_MEDIA_TYPE_YCBCR411_8_CBYYCRYY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x003C) 746 | #define CAMERA_MEDIA_TYPE_YCBCR601_8_CBYCR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x003D) 747 | #define CAMERA_MEDIA_TYPE_YCBCR601_422_8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x003E) 748 | #define CAMERA_MEDIA_TYPE_YCBCR601_422_8_CBYCRY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0044) 749 | #define CAMERA_MEDIA_TYPE_YCBCR601_411_8_CBYYCRYY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x003F) 750 | #define CAMERA_MEDIA_TYPE_YCBCR709_8_CBYCR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x0040) 751 | #define CAMERA_MEDIA_TYPE_YCBCR709_422_8 (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0041) 752 | #define CAMERA_MEDIA_TYPE_YCBCR709_422_8_CBYCRY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0045) 753 | #define CAMERA_MEDIA_TYPE_YCBCR709_411_8_CBYYCRYY (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0042) 754 | 755 | /*RGB Planar */ 756 | #define CAMERA_MEDIA_TYPE_RGB8_PLANAR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x0021) 757 | #define CAMERA_MEDIA_TYPE_RGB10_PLANAR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0022) 758 | #define CAMERA_MEDIA_TYPE_RGB12_PLANAR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0023) 759 | #define CAMERA_MEDIA_TYPE_RGB16_PLANAR (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0024) 760 | 761 | 762 | 763 | /*MindVision 12bit packed bayer*/ 764 | #define CAMERA_MEDIA_TYPE_BAYGR12_PACKED_MV (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0060) 765 | #define CAMERA_MEDIA_TYPE_BAYRG12_PACKED_MV (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0061) 766 | #define CAMERA_MEDIA_TYPE_BAYGB12_PACKED_MV (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0062) 767 | #define CAMERA_MEDIA_TYPE_BAYBG12_PACKED_MV (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0063) 768 | 769 | /*MindVision 12bit packed monochome*/ 770 | #define CAMERA_MEDIA_TYPE_MONO12_PACKED_MV (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0064) 771 | #define CAMERA_MEDIA_TYPE_YUV420P_MV (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0065) 772 | #endif 773 | --------------------------------------------------------------------------------