Преглед на файлове

1、添加识别子模块;

LiuZe преди 1 година
родител
ревизия
024645279d

+ 25 - 67
communication/mqtt/mqtt_communication.cpp

@@ -13,20 +13,14 @@ void Tof3DMqttAsyncClient::init(const std::string &file) {
 }
 
 // 识别结果数据包含识别结果、时间序号、具体识别信息
-int Tof3DMqttAsyncClient::CloudDataArrived(MqttAsyncClient *client, char *topicName, int topicLen,
+int Tof3DMqttAsyncClient::CloudDataArrived(void *client, char *topicName, int topicLen,
                                              MQTTAsync_message *message) {
-    // 1、查看识别结果
-
-    // 2、队列取数据
-//    cv::Mat merge_mat = cv::Mat::zeros(480 * 2, 640 * 2, CV_8UC1);
-//    memcpy(merge_mat.data, message->payload, message->payloadlen);
-//    cv::imshow("receive", merge_mat);
-    LOG(INFO) << topicName;
-
-    // 3、分离出四份点云
-
-    // 4、发送对应队列
-
+    std::string topic = topicName;
+    if (topic == "tof/seg") {
+        JetStream::LabelYolo seg_results;
+        seg_results.ParseFromArray(message->payload, message->payloadlen);
+        LabelYoloDataBuffer::iter()->lock_exe(&LabelYoloDataBuffer::set, seg_results);
+    }
     return 1;
 }
 
@@ -43,61 +37,25 @@ void Tof3DMqttAsyncClient::run() {
         t_start_time = std::chrono::steady_clock::now();
 
         if (condit->is_alive()) {
-//            // 1、获取图片并合并
-//            cv::Mat merge_mat = cv::Mat::zeros(480 * 2, 640 * 2, CV_8UC1);
-//            DeviceTof3D::DeviceTof3DSaveInfo devices_info[DeviceAzimuth::DEVICE_AZIMUTH_MAX];
-//            for (int device_index = 0; device_index < DeviceAzimuth::DEVICE_AZIMUTH_MAX; device_index++) {
-//                devices_info[device_index] = DeviceTof3D::iter()->getDeviceSaveInfo((DeviceAzimuth) device_index);
-//                devices_info[device_index].irMat.copyTo(merge_mat(cv::Rect((device_index & 0x1) * 640,
-//                                                                           ((device_index & 0x2) >> 1) * 480, 640, 480)));
-//            }
-//            cv::imshow("merge_mat", merge_mat);
-//            cv::waitKey(1);
-
-//            // 2、信息放入队列
-//            m_cloud_mutex.lock();
-//            for (auto iter = m_lf_info.begin(); iter != m_lf_info.end();) {
-//                long save_time = std::chrono::steady_clock::now().time_since_epoch().count() - iter->first;
-//                if (save_time > 1000000000) {
-//                    m_rf_info.erase(iter->first);
-//                    m_lr_info.erase(iter->first);
-//                    m_rr_info.erase(iter->first);
-//                    iter = m_lf_info.erase(m_lf_info.find(iter->first));
-//                } else {
-//                    iter++;
-//                }
-//            }
-//            long time_point = std::chrono::steady_clock::now().time_since_epoch().count();
-//            m_lf_info.insert(std::pair<long, DeviceTof3D::DeviceTof3DSaveInfo>(
-//                    time_point, devices_info[DeviceAzimuth::DEVICE_AZIMUTH_LF]));
-//            m_rf_info.insert(std::pair<long, DeviceTof3D::DeviceTof3DSaveInfo>(
-//                    time_point, devices_info[DeviceAzimuth::DEVICE_AZIMUTH_RF]));
-//            m_lr_info.insert(std::pair<long, DeviceTof3D::DeviceTof3DSaveInfo>(
-//                    time_point, devices_info[DeviceAzimuth::DEVICE_AZIMUTH_LR]));
-//            m_rr_info.insert(std::pair<long, DeviceTof3D::DeviceTof3DSaveInfo>(
-//                    time_point, devices_info[DeviceAzimuth::DEVICE_AZIMUTH_RR]));
-//            m_cloud_mutex.unlock();
-
-            // 3、将ir图打包发送mqtt
-//            std::vector<unsigned char> message;
-////            message.push_back(time_point);
-//
-////            for (int rows = 0; rows < merge_mat.rows - 0; rows++) {
-////                for (int cols = 0; cols < merge_mat.cols - 0; cols++) {
-////                    message.push_back(merge_mat.at<uchar>(rows, cols));
-////                }
-////            }
-//            for (auto iter = merge_mat.datastart; iter != merge_mat.dataend; iter++) {
-//                message.push_back(*iter);
-//            }
-//            cv::Mat merge_mat_2 = cv::Mat::zeros(480 * 2, 640 * 2, CV_8UC1);
-//            memcpy(merge_mat_2.data, message.data(), message.size());
-            std::vector<unsigned char > test;
-            for (int i = 0; i < 640*480*2*1; i++) {
-                test.push_back('a');
+            static int lable = 0;
+            if (lable++ > 1000) {
+                lable = 0;
+            }
+            // 1、获取图片并合并
+            cv::Mat merge_mat = cv::Mat::zeros(480 * 2, 640 * 2, CV_8UC1);
+            DeviceTof3D::DeviceTof3DSaveInfo devices_info[DeviceAzimuth::DEVICE_AZIMUTH_MAX];
+            for (int device_index = 0; device_index < DeviceAzimuth::DEVICE_AZIMUTH_MAX; device_index++) {
+                devices_info[device_index] = DeviceTof3D::iter()->getDeviceSaveInfo((DeviceAzimuth) device_index);
+                MatDataBuffer::iter()->lock_exe(&MatDataBuffer::set, device_index, lable, devices_info[device_index].pointMat);
+                devices_info[device_index].irMat.copyTo(merge_mat(cv::Rect((device_index & 0x1) * 640,
+                                                                           ((device_index & 0x2) >> 1) * 480, 640, 480)));
             }
-            LOG(INFO) << "message size " << test.size();
-            SendMessage("tof/ir", test.data(), test.size());
+            JetStream::LabelImage testimage;
+            NetMessageTrans::lableMat2Proto(lable, merge_mat, testimage);
+            int size_1 = testimage.ByteSizeLong();
+            unsigned char data[size_1];
+            testimage.SerializeToArray((void *)data, size_1);
+            SendMessage("tof/ir", data, size_1);
         }
     }
 }

+ 7 - 7
communication/mqtt/mqtt_communication.h

@@ -6,8 +6,12 @@
 #include "pahoc/mqtt_async.h"
 #include "tool/log.hpp"
 #include "vzense/device_tof3d.h"
+#include "net_message_trans.h"
+
+#include "detect/data_buf_lable.hpp"
 
 class Tof3DMqttAsyncClient : public MqttAsyncClient {
+    friend class MqttAsyncClient;
 public:
     static Tof3DMqttAsyncClient *iter() {
         static Tof3DMqttAsyncClient *instance = nullptr;
@@ -20,21 +24,17 @@ public:
     void init(const std::string &file);
 
 protected:
-    Tof3DMqttAsyncClient() = default;
 
 private:
+    Tof3DMqttAsyncClient() = default;
+
     void run();
 
-    static int CloudDataArrived(MqttAsyncClient *client, char *topicName, int topicLen, MQTTAsync_message *message);
+    static int CloudDataArrived(void *client, char *topicName, int topicLen, MQTTAsync_message *message);
 
 public:
 
 private:
-    std::mutex m_cloud_mutex;
-    std::map<long, DeviceTof3D::DeviceTof3DSaveInfo> m_lf_info;
-    std::map<long, DeviceTof3D::DeviceTof3DSaveInfo> m_rf_info;
-    std::map<long, DeviceTof3D::DeviceTof3DSaveInfo> m_lr_info;
-    std::map<long, DeviceTof3D::DeviceTof3DSaveInfo> m_rr_info;
 
     std::thread *t = nullptr;
     Thread_condition *condit = nullptr;

+ 5 - 0
communication/mqtt/net_message_trans.cpp

@@ -0,0 +1,5 @@
+//
+// Created by zx on 2023/12/12.
+//
+
+#include "net_message_trans.h"

+ 32 - 0
communication/mqtt/net_message_trans.h

@@ -0,0 +1,32 @@
+#pragma once
+
+#include "proto/def.grpc.pb.h"
+#include <opencv2/opencv.hpp>
+#include "tool/log.hpp"
+
+class NetMessageTrans {
+public:
+    static void lableMat2Proto(int lable, cv::Mat &mat, JetStream::LabelImage &image) {
+        image.set_label(lable);
+        image.mutable_ir()->set_width(mat.cols);
+        image.mutable_ir()->set_height(mat.rows);
+        image.mutable_ir()->set_channel(mat.type());
+        image.mutable_ir()->set_data(mat.data, mat.dataend - mat.datastart);
+        // LOG(INFO) << "mat.dataend - mat.datastart = " << mat.dataend - mat.datastart;
+    }
+
+    static void Proto2lableMat(JetStream::LabelImage &image, int &lable, cv::Mat &mat) {
+        lable = image.label();
+        mat = cv::Mat(image.ir().height(), image.ir().width(), image.ir().channel(), (void*)image.ir().data().data());
+    }
+
+    static void getSegBoxData() {
+
+    }
+
+    static void data2SegBox() {
+
+    }
+};
+
+

+ 122 - 0
detect/data_buf_lable.hpp

@@ -0,0 +1,122 @@
+#pragma once
+#include <iostream>
+#include <map>
+#include <chrono>
+#include <thread>
+#include <mutex>
+#include <opencv2/opencv.hpp>
+
+#include "proto/def.grpc.pb.h"
+
+template <class Type>
+class lockFunc {
+public:
+    template<class Func, class ... Args>
+    int lock_exe(Func func, Args&&... args) {
+        lock.lock();
+        bool ret = ((Type* )this->*func)(args...);
+        lock.unlock();
+        return ret;
+    }
+
+    template<class Func, class ... Args>
+    int lock_exe(Func func, Type* p, Args&&... args) {
+        lock.lock();
+        bool ret = (p->*func)(args...);
+        lock.unlock();
+        return ret;
+    }
+
+private:
+    std::mutex lock;
+};
+
+class MatDataBuffer : public lockFunc<MatDataBuffer>{
+public:
+    static MatDataBuffer *iter() {
+        static MatDataBuffer *instance = nullptr;
+        if (instance == nullptr) {
+            instance = new MatDataBuffer();
+        }
+        return instance;
+    }
+
+    bool set(int azimuth, int lable, cv::Mat &mat) {
+        if (azimuth >= DeviceAzimuth::DEVICE_AZIMUTH_MAX) {
+            return false;
+        }
+        if (data[azimuth].size() > 100) {
+            data[azimuth].erase(data[azimuth].begin());
+        }
+        data[azimuth].emplace_back(lable, mat);
+        return true;
+    }
+
+    bool get(int azimuth, int lable, cv::Mat &mat, double timeout = 10) {
+        if (azimuth >= DeviceAzimuth::DEVICE_AZIMUTH_MAX) {
+            LOG(INFO) << "azimuth: " << azimuth << " < " << DeviceAzimuth::DEVICE_AZIMUTH_MAX;
+            return false;
+        }
+         for (auto & iter : data[azimuth]) {
+             if (iter.lable != lable) {
+                 LOG(INFO) << lable << " != " << iter.lable;
+                 continue;
+             } else {
+                 std::chrono::duration<double> cost = std::chrono::steady_clock::now() - iter.t;
+                 if (cost.count() > timeout) {
+                     LOG(INFO) << "data is too old : " << cost.count() << "s";
+                     return false;
+                 } else {
+                     mat = iter.pointsMat.clone();
+                     return true;
+                 }
+             }
+         }
+        LOG(INFO) << "Not found data: " << lable << " in device " << azimuth;
+        return false;
+    }
+
+private:
+    struct DataBufferInfo {
+        std::chrono::steady_clock::time_point t;
+        int lable;
+        cv::Mat pointsMat;
+
+        DataBufferInfo(int lable_, cv::Mat &mat_) : lable(lable_), pointsMat(mat_.clone()) {
+            t = std::chrono::steady_clock::now();
+        }
+    };
+private:
+    std::vector<DataBufferInfo> data[DeviceAzimuth::DEVICE_AZIMUTH_MAX];
+};
+
+class LabelYoloDataBuffer : public lockFunc<LabelYoloDataBuffer> {
+public:
+    static LabelYoloDataBuffer *iter() {
+        static LabelYoloDataBuffer *instance = nullptr;
+        if (instance == nullptr) {
+            instance = new LabelYoloDataBuffer();
+        }
+        return instance;
+    }
+
+    bool set(JetStream::LabelYolo &yolo) {
+        if (data.size() > 10) {
+            data.pop();
+        }
+        data.push(yolo);
+        return true;
+    }
+
+    bool get(JetStream::LabelYolo &yolo, double timeout = 10) {
+        if (data.empty()) {
+            return false;
+        }
+        yolo = data.front();
+        data.pop();
+        return true;
+    }
+
+private:
+    std::queue<JetStream::LabelYolo> data;
+};

+ 26 - 72
detect/detect_manager.cpp

@@ -5,13 +5,6 @@
 #include "detect_manager.h"
 
 Error_manager DetectManager::Init() {
-
-#ifdef ENABLE_TENSORRT_DETECT
-    detector = new TensorrtWheelDetector(ETC_PATH PROJECT_NAME "/model.engine", ETC_PATH PROJECT_NAME "/class.txt");
-#else
-    detector = new TensorrtWheelDetector(ETC_PATH PROJECT_NAME "/model.onnx", ETC_PATH PROJECT_NAME "/class.txt");
-#endif
-
     m_thread = new std::thread(&DetectManager::run, this);
     m_condit.notify_all(true);
 
@@ -20,8 +13,6 @@ Error_manager DetectManager::Init() {
 
 Error_manager DetectManager::Release() {
     stop();
-    delete detector;
-    detector = nullptr;
     return {};
 }
 
@@ -45,75 +36,39 @@ void DetectManager::run() {
         t_start_time = std::chrono::steady_clock::now();
 
         if (m_condit.is_alive()) {
+            std::vector<int> have_cloud;
             DetectResult detect_result;
-            cv::Mat merge_mat = cv::Mat::zeros(480 * 2, 640 * 2, CV_8UC1);
-            DeviceTof3D::DeviceTof3DSaveInfo t_device_mat[DeviceAzimuth::DEVICE_AZIMUTH_MAX];
-            for (int device_index = 0; device_index < DeviceAzimuth::DEVICE_AZIMUTH_MAX; device_index++) {
-                vct_wheel_cloud[device_index]->clear();
-                t_device_mat[device_index] = DeviceTof3D::iter()->getDeviceSaveInfo((DeviceAzimuth)device_index);
-                t_device_mat[device_index].irMat.copyTo(merge_mat(cv::Rect((device_index & 0x1) * 640,
-                                                                           ((device_index & 0x2) >> 1) * 480, 640, 480)));
-            }
-
-            cost = std::chrono::steady_clock::now() - t_start_time;
-            DLOG(INFO) << "cost time is " << cost.count() * 1000 << " ms";
-
-            // 模型识别
-            std::vector<Object> objs;
-            cv::cvtColor(merge_mat, merge_mat, cv::COLOR_GRAY2RGB);
-//            detector->detect(merge_mat, objs, merge_mat);
-            cv::imshow("merge_mat", merge_mat);
-            cv::waitKey(1);
-            if (objs.empty()) {
-                detect_statu = MeasureStatu::Measure_Empty_Clouds;
-                m_detect_result_record.reset();
+            JetStream::LabelYolo seg_results;
+            if (!LabelYoloDataBuffer::iter()->lock_exe(&LabelYoloDataBuffer::get, seg_results, 10)) {
                 continue;
             }
-
-            cost = std::chrono::steady_clock::now() - t_start_time;
-            DLOG(INFO) << "cost time is " << cost.count() * 1000 << " ms";
-
-            // 标记识别点云
-            for (auto iter = objs.begin(); iter != objs.end(); iter++) {
-                auto seg_points = detector->getPointsFromObj(*iter);
-                int device_index = (int(iter->rect.x / 640) * 0x01) | (int(iter->rect.y / 480) << 1);
-                // 校验识别矩形框是否越界
-                int device_index_check = (int((iter->rect.x + iter->rect.width) / 640) * 0x01) | (int((iter->rect.y + iter->rect.height) / 480) << 1);
-                if (device_index != device_index_check) {
-                    // TODO:存图
-                    LOG(INFO) << "device_index_check " << device_index_check << " != device_index " << device_index;
-                    LOG(INFO) << "obj.rect.x: " << iter->rect.x << ", iter->rect.y: " << iter->rect.x << ", obj.rect.width: " << iter->rect.width << ", obj.rect.height: " << iter->rect.height;
-                    objs.erase(iter);
-                    iter--;
+            LOG(INFO) << seg_results.label() << " " << seg_results.boxes(0).lines_size();
+            for (int device_index = 0; device_index < DeviceAzimuth::DEVICE_AZIMUTH_MAX; device_index++) {
+                if (seg_results.boxes(device_index).lines().empty()) {
+                    LOG(INFO) << device_index << " empty";
                     continue;
                 }
-                detect_result.wheel[device_index].confidence = iter->prob;
-
-                if (iter->prob > 0.9) {
-                    detect_result.wheel[device_index].detectOk = true;
-                    float d = MAX(iter->rect.height, iter->rect.width) / 2;
-                    pcl::PointXYZ point;
-                    int x_alpha = (device_index & 0x1);
-                    int y_alpha = ((device_index & 0x2) >> 1);
-                    for (auto &pt: seg_points) {    // use 7.5~9ms
-                        pt.x -= x_alpha * t_device_mat[device_index].irMat.cols;
-                        pt.y -= y_alpha * t_device_mat[device_index].irMat.rows;
-                        t_device_mat[device_index].pointMat.at<cv::Vec4f>(pt)[3] = iter->prob;
-                        point.x = t_device_mat[device_index].pointMat.at<cv::Vec4f>(pt)[0];
-                        point.y = t_device_mat[device_index].pointMat.at<cv::Vec4f>(pt)[1];
-                        point.z = t_device_mat[device_index].pointMat.at<cv::Vec4f>(pt)[2];
-                        vct_wheel_cloud[device_index]->push_back(point);
+                cv::Mat pointMat;
+                LOG(INFO) << "b get data" << " empty";
+                if (MatDataBuffer::iter()->lock_exe(&MatDataBuffer::get, device_index, seg_results.label(), pointMat, 10)) {
+                    cv::imshow(std::to_string(device_index), pointMat);
+                    cv::waitKey(1);
+                }
+                LOG(INFO) << "e get data" << " empty";
+                continue;
+                have_cloud.push_back(device_index);
+                for (int row = 0; row < 480; row++) {
+                    for (int col = seg_results.boxes(device_index).lines(row).begin(); col < seg_results.boxes(device_index).lines(row).end(); col++) {
+                        vct_wheel_cloud[device_index]->emplace_back(pointMat.at<cv::Vec3f>(row, col)[0],
+                                                                    pointMat.at<cv::Vec3f>(row, col)[1],
+                                                                    pointMat.at<cv::Vec3f>(row, col)[2]);
                     }
-
-                    TransitData::get_instance_pointer()->setMask(seg_points, device_index);
                 }
             }
-
-            cost = std::chrono::steady_clock::now() - t_start_time;
-            DLOG(INFO) << "cost time is " << cost.count() * 1000 << " ms";
+            continue;
 
             // 点云处理
-            if (!objs.empty()) {
+            if (!have_cloud.empty()) {
                 WheelCloudOptimize(vct_wheel_cloud, detect_result);
                 cost = std::chrono::steady_clock::now() - t_start_time;
                 DLOG(INFO) << "cost time is " << cost.count() * 1000 << " ms";
@@ -137,17 +92,16 @@ void DetectManager::run() {
                                           detect_result.car.wheel_width,detect_result.car.front_wheels_theta, detect_result.car.loss);
                 // 根据车轮数采用不同的优化方式
                 if (m_detect_result_record.car.wheel_width < 1.0 || m_detect_result_record.car.wheel_base < 2.0 ||
-                    objs.size() > 2) {
+                        have_cloud.size() > 2) {
                     ceres_detect_ret = wheel_detect->detect_2Step(vct_wheel_cloud[DeviceAzimuth::DEVICE_AZIMUTH_LF], vct_wheel_cloud[DeviceAzimuth::DEVICE_AZIMUTH_RF],
                                     vct_wheel_cloud[DeviceAzimuth::DEVICE_AZIMUTH_LR], vct_wheel_cloud[DeviceAzimuth::DEVICE_AZIMUTH_RR],
                                     detect_result.car.wheels_center_x, detect_result.car.wheels_center_y,
                                     detect_result.car.theta, detect_result.car.wheel_base,
                                     detect_result.car.wheel_width,detect_result.car.front_wheels_theta, detect_result.car.loss);
-                    if ((m_detect_result_record.car.wheel_width < 1.0 && m_detect_result_record.car.wheel_base < 1.0 && objs.size() == 2) || objs.size() < 2) {
+                    if ((m_detect_result_record.car.wheel_width < 1.0 && m_detect_result_record.car.wheel_base < 1.0 && have_cloud.size() == 2) || have_cloud.size() < 2) {
                         detect_result.car.wheel_width = m_detect_result_record.car.wheel_width;
                         detect_result.car.wheel_base = m_detect_result_record.car.wheel_base;
-                    } else if (objs.size() == 2) {
-                        std::vector<int> have_cloud;
+                    } else if (have_cloud.size() == 2) {
                         for (int device_index = 0; device_index < DeviceAzimuth::DEVICE_AZIMUTH_MAX; device_index++) {
                             if (!vct_wheel_cloud[device_index]->empty()) {
                                 have_cloud.push_back(device_index);

+ 2 - 6
detect/detect_manager.h

@@ -9,15 +9,12 @@
 #include "thread/thread_condition.h"
 #include "vzense/device_tof3d.h"
 
-#ifdef ENABLE_TENSORRT_DETECT
-#include "detect/tensorrt_detect/wheel-detector.h"
-#else
-#include "detect/onnx_detect/wheel-detector.h"
-#endif
 #include "detect/ceres_detect/car_pose_detector.h"
 #include "detect/ceres_detect/wheel_detector.h"
 #include "detect/ceres_detect/detect_wheel_ceres.h"
+#include "detect/data_buf_lable.hpp"
 #include "communication/transitData.h"
+#include "proto/def.grpc.pb.h"
 
 class DetectManager {
 public:
@@ -73,7 +70,6 @@ private:
 
     TimedLockData<bool> move_statu;
     TimedLockData<MeasureStatu> detect_statu;
-    TensorrtWheelDetector *detector;
     TimedLockData<DetectResult> m_detect_result_time_lock_data;
 };
 

+ 0 - 183
detect/onnx_detect/inference.cpp

@@ -1,183 +0,0 @@
-#include "inference.h"
-
-Inference::Inference(const std::string &onnxModelPath, const cv::Size &modelInputShape, const std::string &classesTxtFile, const bool &runWithCuda)
-{
-    modelPath = onnxModelPath;
-    modelShape = modelInputShape;
-    classesPath = classesTxtFile;
-    cudaEnabled = runWithCuda;
-
-    loadOnnxNetwork();
-    // loadClassesFromFile(); The classes are hard-coded for this example
-}
-
-std::vector<Detection> Inference::runInference(const cv::Mat &input)
-{
-    cv::Mat modelInput = input;
-    if (letterBoxForSquare && modelShape.width == modelShape.height)
-        modelInput = formatToSquare(modelInput);
-
-    cv::Mat blob;
-    cv::dnn::blobFromImage(modelInput, blob, 1.0/255.0, modelShape, cv::Scalar(), true, false);
-    net.setInput(blob);
-
-    std::vector<cv::Mat> outputs;
-    net.forward(outputs, net.getUnconnectedOutLayersNames());
-
-    int rows = outputs[0].size[1];
-    int dimensions = outputs[0].size[2];
-
-    bool yolov8 = false;
-    // yolov5 has an output of shape (batchSize, 25200, 85) (Num classes + box[x,y,w,h] + confidence[c])
-    // yolov8 has an output of shape (batchSize, 84,  8400) (Num classes + box[x,y,w,h])
-    if (dimensions > rows) // Check if the shape[2] is more than shape[1] (yolov8)
-    {
-        yolov8 = true;
-        rows = outputs[0].size[2];
-        dimensions = outputs[0].size[1];
-
-        outputs[0] = outputs[0].reshape(1, dimensions);
-        cv::transpose(outputs[0], outputs[0]);
-    }
-    float *data = (float *)outputs[0].data;
-
-    float x_factor = modelInput.cols / modelShape.width;
-    float y_factor = modelInput.rows / modelShape.height;
-
-    std::vector<int> class_ids;
-    std::vector<float> confidences;
-    std::vector<cv::Rect> boxes;
-
-    for (int i = 0; i < rows; ++i)
-    {
-        if (yolov8)
-        {
-            float *classes_scores = data+4;
-
-            cv::Mat scores(1, classes.size(), CV_32FC1, classes_scores);
-            cv::Point class_id;
-            double maxClassScore;
-
-            minMaxLoc(scores, 0, &maxClassScore, 0, &class_id);
-
-            if (maxClassScore > modelScoreThreshold)
-            {
-                confidences.push_back(maxClassScore);
-                class_ids.push_back(class_id.x);
-
-                float x = data[0];
-                float y = data[1];
-                float w = data[2];
-                float h = data[3];
-
-                int left = int((x - 0.5 * w) * x_factor);
-                int top = int((y - 0.5 * h) * y_factor);
-
-                int width = int(w * x_factor);
-                int height = int(h * y_factor);
-
-                boxes.push_back(cv::Rect(left, top, width, height));
-            }
-        }
-        else // yolov5
-        {
-            float confidence = data[4];
-
-            if (confidence >= modelConfidenceThreshold)
-            {
-                float *classes_scores = data+5;
-
-                cv::Mat scores(1, classes.size(), CV_32FC1, classes_scores);
-                cv::Point class_id;
-                double max_class_score;
-
-                minMaxLoc(scores, 0, &max_class_score, 0, &class_id);
-
-                if (max_class_score > modelScoreThreshold)
-                {
-                    confidences.push_back(confidence);
-                    class_ids.push_back(class_id.x);
-
-                    float x = data[0];
-                    float y = data[1];
-                    float w = data[2];
-                    float h = data[3];
-
-                    int left = int((x - 0.5 * w) * x_factor);
-                    int top = int((y - 0.5 * h) * y_factor);
-
-                    int width = int(w * x_factor);
-                    int height = int(h * y_factor);
-
-                    boxes.push_back(cv::Rect(left, top, width, height));
-                }
-            }
-        }
-
-        data += dimensions;
-    }
-
-    std::vector<int> nms_result;
-    cv::dnn::NMSBoxes(boxes, confidences, modelScoreThreshold, modelNMSThreshold, nms_result);
-
-    std::vector<Detection> detections{};
-    for (unsigned long i = 0; i < nms_result.size(); ++i)
-    {
-        int idx = nms_result[i];
-
-        Detection result;
-        result.class_id = class_ids[idx];
-        result.confidence = confidences[idx];
-
-        std::random_device rd;
-        std::mt19937 gen(rd());
-        std::uniform_int_distribution<int> dis(100, 255);
-        result.color = cv::Scalar(dis(gen),
-                                  dis(gen),
-                                  dis(gen));
-
-        result.className = classes[result.class_id];
-        result.box = boxes[idx];
-
-        detections.push_back(result);
-    }
-
-    return detections;
-}
-
-void Inference::loadClassesFromFile()
-{
-    std::ifstream inputFile(classesPath);
-    if (inputFile.is_open())
-    {
-        std::string classLine;
-        while (std::getline(inputFile, classLine))
-            classes.push_back(classLine);
-        inputFile.close();
-    }
-}
-
-void Inference::loadOnnxNetwork()
-{
-    net = cv::dnn::readNetFromONNX(modelPath);
-    if (cudaEnabled)
-    {
-        net.setPreferableBackend(cv::dnn::DNN_BACKEND_CUDA);
-        net.setPreferableTarget(cv::dnn::DNN_TARGET_CUDA);
-    }
-    else
-    {
-        net.setPreferableBackend(cv::dnn::DNN_BACKEND_OPENCV);
-        net.setPreferableTarget(cv::dnn::DNN_TARGET_CPU);
-    }
-}
-
-cv::Mat Inference::formatToSquare(const cv::Mat &source)
-{
-    int col = source.cols;
-    int row = source.rows;
-    int _max = MAX(col, row);
-    cv::Mat result = cv::Mat::zeros(_max, _max, CV_8UC3);
-    source.copyTo(result(cv::Rect(0, 0, col, row)));
-    return result;
-}

+ 0 - 50
detect/onnx_detect/inference.h

@@ -1,50 +0,0 @@
-#pragma once
-
-// Cpp native
-#include <fstream>
-#include <vector>
-#include <string>
-#include <random>
-
-// OpenCV / DNN / Inference
-#include <opencv2/imgproc.hpp>
-#include <opencv2/opencv.hpp>
-#include <opencv2/dnn.hpp>
-
-struct Detection
-{
-    int class_id{0};
-    std::string className{};
-    float confidence{0.0};
-    cv::Scalar color{};
-    cv::Rect box{};
-};
-
-class Inference
-{
-public:
-    Inference(const std::string &onnxModelPath, const cv::Size &modelInputShape = {640, 640}, const std::string &classesTxtFile = "", const bool &runWithCuda = false);
-    std::vector<Detection> runInference(const cv::Mat &input);
-
-private:
-    void loadClassesFromFile();
-    void loadOnnxNetwork();
-    cv::Mat formatToSquare(const cv::Mat &source);
-
-    std::string modelPath{};
-    std::string classesPath{};
-    bool cudaEnabled{};
-
-    std::vector<std::string> classes{"car", "wheel"};
-
-    cv::Size2f modelShape{};
-
-    float modelConfidenceThreshold {0.25};
-    float modelScoreThreshold      {0.45};
-    float modelNMSThreshold        {0.50};
-
-    bool letterBoxForSquare = true;
-
-    cv::dnn::Net net;
-};
-

+ 0 - 66
detect/onnx_detect/wheel-detector.cpp

@@ -1,66 +0,0 @@
-#include "wheel-detector.h"
-
-TensorrtWheelDetector::TensorrtWheelDetector(const std::string &model_file, const std::string &class_file){
-    yolov8_ = new Inference(model_file, cv::Size{640, 640}, class_file, false);
-}
-
-TensorrtWheelDetector::~TensorrtWheelDetector(){
-}
-
-bool TensorrtWheelDetector::detect(cv::Mat& img,std::vector<Object>& objs){
-    std::vector<Detection> rets = yolov8_->runInference(img);
-
-    for (auto &ret: rets) {
-        Object obj;
-       obj.rect = ret.box;
-        obj.label = ret.class_id;
-        obj.prob = ret.confidence;
-        objs.push_back(obj);
-    }
-    return true;
-}
-
-bool TensorrtWheelDetector::detect(cv::Mat& img,std::vector<Object>& objs,cv::Mat& res){
-    std::vector<Detection> rets = yolov8_->runInference(img);
-
-    for (auto &ret: rets) {
-        Object obj;
-        obj.rect = ret.box;
-        obj.label = ret.class_id;
-        obj.prob = ret.confidence;
-        obj.boxMask = img;
-        objs.push_back(obj);
-
-        cv::Rect box = ret.box;
-        cv::Scalar color = ret.color;
-
-        // Detection box
-        cv::rectangle(res, box, color, 2);
-
-        // Detection box text
-        std::string classString = ret.className + ' ' + std::to_string(ret.confidence).substr(0, 4);
-        cv::Size textSize = cv::getTextSize(classString, cv::FONT_HERSHEY_DUPLEX, 1, 2, 0);
-        cv::Rect textBox(box.x, box.y - 40, textSize.width + 10, textSize.height + 20);
-
-        cv::rectangle(res, textBox, color, cv::FILLED);
-        cv::putText(res, classString, cv::Point(box.x + 5, box.y - 10), cv::FONT_HERSHEY_DUPLEX, 1, cv::Scalar(0, 0, 0), 2, 0);
-    }
-    return true;
-}
-
-std::vector<cv::Point> TensorrtWheelDetector::getPointsFromObj(const Object &obj){
-    std::vector<cv::Point> ret;
-
-    int x=int(obj.rect.x+0.5);
-    int y=int(obj.rect.y+0.5);
-    int width=int(obj.rect.width);
-    int height=int(obj.rect.height);
-
-    for(int i=0;i<height;++i){
-        for(int j=0;j<width;++j){
-            ret.emplace_back(x+j,y+i);
-        }
-    }
-
-    return ret;
-}

+ 0 - 29
detect/onnx_detect/wheel-detector.h

@@ -1,29 +0,0 @@
-#pragma once
-
-#include "inference.h"
-
-struct Object {
-    cv::Rect_<float> rect;
-    int              label = 0;
-    float            prob  = 0.0;
-    cv::Mat          boxMask;
-};
-    
-class TensorrtWheelDetector{
-public:
-    TensorrtWheelDetector(const std::string &model_file, const std::string &class_file);
-    ~TensorrtWheelDetector();
-
-    bool detect(cv::Mat& img,std::vector<Object>& objs);
-    bool detect(cv::Mat& img,std::vector<Object>& objs,cv::Mat& res);
-
-    static std::vector<cv::Point> getPointsFromObj(const Object &obj);
-
-private:
-    Inference*  yolov8_;
-    cv::Size     imgsz_;
-    int      seg_h_        = 120;
-    int      seg_w_        = 160;
-    int      seg_channels_ = 32;
-};
-

+ 0 - 142
detect/tensorrt_detect/common.hpp

@@ -1,142 +0,0 @@
-//
-// Created by ubuntu on 3/16/23.
-//
-
-#ifndef JETSON_SEGMENT_COMMON_HPP
-#define JETSON_SEGMENT_COMMON_HPP
-#include "NvInfer.h"
-#include "opencv2/opencv.hpp"
-#include <sys/stat.h>
-#include <unistd.h>
-
-#define CHECK(call)                                                                                                    \
-    do {                                                                                                               \
-        const cudaError_t error_code = call;                                                                           \
-        if (error_code != cudaSuccess) {                                                                               \
-            printf("CUDA Error:\n");                                                                                   \
-            printf("    File:       %s\n", __FILE__);                                                                  \
-            printf("    Line:       %d\n", __LINE__);                                                                  \
-            printf("    Error code: %d\n", error_code);                                                                \
-            printf("    Error text: %s\n", cudaGetErrorString(error_code));                                            \
-            exit(1);                                                                                                   \
-        }                                                                                                              \
-    } while (0)
-
-class Logger: public nvinfer1::ILogger {
-public:
-    nvinfer1::ILogger::Severity reportableSeverity;
-
-    explicit Logger(nvinfer1::ILogger::Severity severity = nvinfer1::ILogger::Severity::kINFO):
-        reportableSeverity(severity)
-    {
-    }
-
-    void log(nvinfer1::ILogger::Severity severity, const char* msg) noexcept override
-    {
-        if (severity > reportableSeverity) {
-            return;
-        }
-        switch (severity) {
-            case nvinfer1::ILogger::Severity::kINTERNAL_ERROR:
-                std::cerr << "INTERNAL_ERROR: ";
-                break;
-            case nvinfer1::ILogger::Severity::kERROR:
-                std::cerr << "ERROR: ";
-                break;
-            case nvinfer1::ILogger::Severity::kWARNING:
-                std::cerr << "WARNING: ";
-                break;
-            case nvinfer1::ILogger::Severity::kINFO:
-                std::cerr << "INFO: ";
-                break;
-            default:
-                std::cerr << "VERBOSE: ";
-                break;
-        }
-        std::cerr << msg << std::endl;
-    }
-};
-
-inline int get_size_by_dims(const nvinfer1::Dims& dims)
-{
-    int size = 1;
-    for (int i = 0; i < dims.nbDims; i++) {
-        size *= dims.d[i];
-    }
-    return size;
-}
-
-inline int type_to_size(const nvinfer1::DataType& dataType)
-{
-    switch (dataType) {
-        case nvinfer1::DataType::kFLOAT:
-            return 4;
-        case nvinfer1::DataType::kHALF:
-            return 2;
-        case nvinfer1::DataType::kINT32:
-            return 4;
-        case nvinfer1::DataType::kINT8:
-            return 1;
-        case nvinfer1::DataType::kBOOL:
-            return 1;
-        default:
-            return 4;
-    }
-}
-
-inline static float clamp(float val, float min, float max)
-{
-    return val > min ? (val < max ? val : max) : min;
-}
-
-inline bool IsPathExist(const std::string& path)
-{
-    if (access(path.c_str(), 0) == F_OK) {
-        return true;
-    }
-    return false;
-}
-
-inline bool IsFile(const std::string& path)
-{
-    if (!IsPathExist(path)) {
-        printf("%s:%d %s not exist\n", __FILE__, __LINE__, path.c_str());
-        return false;
-    }
-    struct stat buffer;
-    return (stat(path.c_str(), &buffer) == 0 && S_ISREG(buffer.st_mode));
-}
-
-inline bool IsFolder(const std::string& path)
-{
-    if (!IsPathExist(path)) {
-        return false;
-    }
-    struct stat buffer;
-    return (stat(path.c_str(), &buffer) == 0 && S_ISDIR(buffer.st_mode));
-}
-
-namespace seg {
-struct Binding {
-    size_t         size  = 1;
-    size_t         dsize = 1;
-    nvinfer1::Dims dims;
-    std::string    name;
-};
-
-struct Object {
-    cv::Rect_<float> rect;
-    int              label = 0;
-    float            prob  = 0.0;
-    cv::Mat          boxMask;
-};
-
-struct PreParam {
-    float ratio  = 1.0f;
-    float dw     = 0.0f;
-    float dh     = 0.0f;
-    float height = 0;
-    float width  = 0;
-};
-}  // namespace seg
-#endif  // JETSON_SEGMENT_COMMON_HPP

+ 0 - 65
detect/tensorrt_detect/wheel-detector.cpp

@@ -1,65 +0,0 @@
-#include "wheel-detector.h"
-
-TensorrtWheelDetector::TensorrtWheelDetector(const std::string &model_file, const std::string &class_file){
-    cudaSetDevice(0);
-    
-    yolov8_ = new YOLOv8_seg(model_file);
-    yolov8_->make_pipe(false);
-    imgsz_=cv::Size{640, 480};
-    seg_h_        = 120;
-    seg_w_        = 160;
-    seg_channels_ = 32;
-}
-
-TensorrtWheelDetector::~TensorrtWheelDetector(){
-    if(yolov8_!=nullptr){
-        delete yolov8_;
-        yolov8_=nullptr;
-    }
-
-}
-
-bool TensorrtWheelDetector::detect(cv::Mat& img,std::vector<Object>& objs){
-    if(yolov8_==nullptr){
-        return false;
-    }
-    
-    yolov8_->copy_from_Mat(img, imgsz_);
-    yolov8_->infer();
-    float score_thres=0.9;
-    float iou_thres=0.65;
-    int topk=10;
-    yolov8_->postprocess(objs, score_thres, iou_thres, topk, seg_channels_, seg_h_, seg_w_);
-    return true;
-
-}
-
-bool TensorrtWheelDetector::detect(cv::Mat& img,std::vector<Object>& objs,cv::Mat& res){
-    if(detect(img,objs))
-    {
-        const std::vector<std::string> classes={"none","wheel"};
-        const std::vector<std::vector<unsigned int>> colors = {{0, 114, 189},   {0, 255, 0}};
-        const std::vector<std::vector<unsigned int>> mask_colors = {{255, 56, 56},  {255, 0, 0}};
-        yolov8_->draw_objects(img, res, objs, classes, colors, mask_colors);
-        return true;
-    }else{
-        return false;
-    }
-}
-
-std::vector<cv::Point> TensorrtWheelDetector::getPointsFromObj(Object obj){
-    std::vector<cv::Point> ret;
-    int x=int(obj.rect.x+0.5);
-    int y=int(obj.rect.y+0.5);
-    int width=int(obj.rect.width);
-    int height=int(obj.rect.height);
-    
-    for(int i=0;i<height;++i){
-        for(int j=0;j<width;++j){
-            if(obj.boxMask.at<uchar>(i,j)!=0){
-                ret.push_back(cv::Point((x+j),y+i));
-            }
-        }
-    }
-    return ret;
-}

+ 0 - 25
detect/tensorrt_detect/wheel-detector.h

@@ -1,25 +0,0 @@
-#ifndef WHELL_DETECTOR__HH___
-#define WWHELL_DETECTOR__HH___
-#include "yolov8-seg.h"
-
-class TensorrtWheelDetector{
-public:
-    TensorrtWheelDetector(const std::string &model_file, const std::string &class_file);
-    ~TensorrtWheelDetector();
-
-
-    bool detect(cv::Mat& img,std::vector<Object>& objs);
-    bool detect(cv::Mat& img,std::vector<Object>& objs,cv::Mat& res);
-
-    static std::vector<cv::Point> getPointsFromObj(Object obj);
-
-private:
-    YOLOv8_seg*  yolov8_;
-    cv::Size     imgsz_;
-    int      seg_h_        = 120;
-    int      seg_w_        = 160;
-    int      seg_channels_ = 32;
-
-};
-
-#endif

+ 0 - 319
detect/tensorrt_detect/yolov8-seg.cpp

@@ -1,319 +0,0 @@
-//
-// Created by ubuntu on 3/16/23.
-//
-
-#include "yolov8-seg.h"
-
-
-using namespace seg;
-
-YOLOv8_seg::YOLOv8_seg(const std::string& engine_file_path)
-{
-    std::ifstream file(engine_file_path, std::ios::binary);
-    assert(file.good());
-    file.seekg(0, std::ios::end);
-    auto size = file.tellg();
-    file.seekg(0, std::ios::beg);
-    char* trtModelStream = new char[size];
-    assert(trtModelStream);
-    file.read(trtModelStream, size);
-    file.close();
-    initLibNvInferPlugins(&this->gLogger, "");
-    this->runtime = nvinfer1::createInferRuntime(this->gLogger);
-    assert(this->runtime != nullptr);
-
-    this->engine = this->runtime->deserializeCudaEngine(trtModelStream, size);
-    assert(this->engine != nullptr);
-    delete[] trtModelStream;
-    this->context = this->engine->createExecutionContext();
-
-    assert(this->context != nullptr);
-    cudaStreamCreate(&this->stream);
-    this->num_bindings = this->engine->getNbBindings();
-
-    for (int i = 0; i < this->num_bindings; ++i) {
-        Binding            binding;
-        nvinfer1::Dims     dims;
-        nvinfer1::DataType dtype = this->engine->getBindingDataType(i);
-        std::string        name  = this->engine->getBindingName(i);
-        binding.name             = name;
-        binding.dsize            = type_to_size(dtype);
-
-        bool IsInput = engine->bindingIsInput(i);
-        if (IsInput) {
-            this->num_inputs += 1;
-            dims         = this->engine->getProfileDimensions(i, 0, nvinfer1::OptProfileSelector::kMAX);
-            binding.size = get_size_by_dims(dims);
-            binding.dims = dims;
-            this->input_bindings.push_back(binding);
-            // set max opt shape
-            this->context->setBindingDimensions(i, dims);
-        }
-        else {
-            dims         = this->context->getBindingDimensions(i);
-            binding.size = get_size_by_dims(dims);
-            binding.dims = dims;
-            this->output_bindings.push_back(binding);
-            this->num_outputs += 1;
-        }
-        // printf("name: %s, size: %ld, dims: %d %d %d %d %d\n", 
-        //         name.c_str(), binding.dsize, dims.nbDims, dims.d[0], dims.d[1], dims.d[2], dims.d[3]);
-    }
-}
-
-YOLOv8_seg::~YOLOv8_seg()
-{
-    this->context->destroy();
-    this->engine->destroy();
-    this->runtime->destroy();
-    cudaStreamDestroy(this->stream);
-    for (auto& ptr : this->device_ptrs) {
-        CHECK(cudaFree(ptr));
-    }
-
-    for (auto& ptr : this->host_ptrs) {
-        CHECK(cudaFreeHost(ptr));
-    }
-}
-
-void YOLOv8_seg::make_pipe(bool warmup)
-{
-
-    for (auto& bindings : this->input_bindings) {
-        void* d_ptr;
-        CHECK(cudaMalloc(&d_ptr, bindings.size * bindings.dsize));
-        this->device_ptrs.push_back(d_ptr);
-    }
-
-    for (auto& bindings : this->output_bindings) {
-        void * d_ptr, *h_ptr;
-        size_t size = bindings.size * bindings.dsize;
-        CHECK(cudaMalloc(&d_ptr, size));
-        CHECK(cudaHostAlloc(&h_ptr, size, 0));
-        this->device_ptrs.push_back(d_ptr);
-        this->host_ptrs.push_back(h_ptr);
-    }
-
-    if (warmup) {
-        for (int i = 0; i < 10; i++) {
-            for (auto& bindings : this->input_bindings) {
-                size_t size  = bindings.size * bindings.dsize;
-                void*  h_ptr = malloc(size);
-                memset(h_ptr, 0, size);
-                CHECK(cudaMemcpyAsync(this->device_ptrs[0], h_ptr, size, cudaMemcpyHostToDevice, this->stream));
-                free(h_ptr);
-            }
-            this->infer();
-        }
-        printf("model warmup 10 times\n");
-    }
-}
-
-void YOLOv8_seg::letterbox(const cv::Mat& image, cv::Mat& out, cv::Size& size)
-{
-    const float inp_h  = size.height;
-    const float inp_w  = size.width;
-    float       height = image.rows;
-    float       width  = image.cols;
-
-    float r    = std::min(inp_h / height, inp_w / width);
-    int   padw = std::round(width * r);
-    int   padh = std::round(height * r);
-
-    cv::Mat tmp;
-    if ((int)width != padw || (int)height != padh) {
-        cv::resize(image, tmp, cv::Size(padw, padh));
-    }
-    else {
-        tmp = image.clone();
-    }
-
-    float dw = inp_w - padw;
-    float dh = inp_h - padh;
-
-    dw /= 2.0f;
-    dh /= 2.0f;
-    int top    = int(std::round(dh - 0.1f));
-    int bottom = int(std::round(dh + 0.1f));
-    int left   = int(std::round(dw - 0.1f));
-    int right  = int(std::round(dw + 0.1f));
-
-    cv::copyMakeBorder(tmp, tmp, top, bottom, left, right, cv::BORDER_CONSTANT, {114, 114, 114});
-
-    cv::dnn::blobFromImage(tmp, out, 1 / 255.f, cv::Size(), cv::Scalar(0, 0, 0), true, false, CV_32F);
-    this->pparam.ratio  = 1 / r;
-    this->pparam.dw     = dw;
-    this->pparam.dh     = dh;
-    this->pparam.height = height;
-    this->pparam.width  = width;
-}
-
-void YOLOv8_seg::copy_from_Mat(const cv::Mat& image)
-{
-    cv::Mat  nchw;
-    auto&    in_binding = this->input_bindings[0];
-    auto     width      = in_binding.dims.d[3];
-    auto     height     = in_binding.dims.d[2];
-    cv::Size size{width, height};
-    this->letterbox(image, nchw, size);
-
-    this->context->setBindingDimensions(0, nvinfer1::Dims{4, {1, 3, height, width}});
-
-    CHECK(cudaMemcpyAsync(
-        this->device_ptrs[0], nchw.ptr<float>(), nchw.total() * nchw.elemSize(), cudaMemcpyHostToDevice, this->stream));
-}
-
-void YOLOv8_seg::copy_from_Mat(const cv::Mat& image, cv::Size& size)
-{
-    cv::Mat nchw;
-    this->letterbox(image, nchw, size);
-    this->context->setBindingDimensions(0, nvinfer1::Dims{4, {1, 3, size.height, size.width}});
-    CHECK(cudaMemcpyAsync(
-        this->device_ptrs[0], nchw.ptr<float>(), nchw.total() * nchw.elemSize(), cudaMemcpyHostToDevice, this->stream));
-}
-
-void YOLOv8_seg::infer()
-{
-
-    this->context->enqueueV2(this->device_ptrs.data(), this->stream, nullptr);
-    for (int i = 0; i < this->num_outputs; i++) {
-        size_t osize = this->output_bindings[i].size * this->output_bindings[i].dsize;
-        CHECK(cudaMemcpyAsync(
-            this->host_ptrs[i], this->device_ptrs[i + this->num_inputs], osize, cudaMemcpyDeviceToHost, this->stream));
-    }
-    cudaStreamSynchronize(this->stream);
-}
-
-void YOLOv8_seg::postprocess(
-    std::vector<Object>& objs, float score_thres, float iou_thres, int topk, int seg_channels, int seg_h, int seg_w)
-{
-    objs.clear();
-    auto input_h      = this->input_bindings[0].dims.d[2];
-    auto input_w      = this->input_bindings[0].dims.d[3];
-    auto num_anchors  = this->output_bindings[0].dims.d[1];
-    auto num_channels = this->output_bindings[0].dims.d[2];
-
-    auto& dw     = this->pparam.dw;
-    auto& dh     = this->pparam.dh;
-    auto& width  = this->pparam.width;
-    auto& height = this->pparam.height;
-    auto& ratio  = this->pparam.ratio;
-
-    auto*   output = static_cast<float*>(this->host_ptrs[0]);
-    cv::Mat protos = cv::Mat(seg_channels, seg_h * seg_w, CV_32F, static_cast<float*>(this->host_ptrs[1]));
-
-    std::vector<int>      labels;
-    std::vector<float>    scores;
-    std::vector<cv::Rect> bboxes;
-    std::vector<cv::Mat>  mask_confs;
-    std::vector<int>      indices;
-
-    for (int i = 0; i < num_anchors; i++) {
-        float* ptr   = output + i * num_channels;
-        float  score = *(ptr + 4);
-		
-         /*if (score > score_thres) {
-             printf("num_channels: %d, score: %f\n", num_channels, score);
-         }*/
-	
-        if (score > score_thres) {
-            float x0 = *ptr++ - dw;
-            float y0 = *ptr++ - dh;
-            float x1 = *ptr++ - dw;
-            float y1 = *ptr++ - dh;
-
-            x0 = clamp(x0 * ratio, 0.f, width);
-            y0 = clamp(y0 * ratio, 0.f, height);
-            x1 = clamp(x1 * ratio, 0.f, width);
-            y1 = clamp(y1 * ratio, 0.f, height);
-
-            int     label     = *(++ptr);
-            cv::Mat mask_conf = cv::Mat(1, seg_channels, CV_32F, ++ptr);
-            mask_confs.push_back(mask_conf);
-            labels.push_back(label);
-            scores.push_back(score);
-            bboxes.push_back(cv::Rect_<float>(x0, y0, x1 - x0, y1 - y0));
-        }
-    }
-
-#if defined(BATCHED_NMS)
-    cv::dnn::NMSBoxesBatched(bboxes, scores, labels, score_thres, iou_thres, indices);
-#else
-    cv::dnn::NMSBoxes(bboxes, scores, score_thres, iou_thres, indices);
-#endif
-
-    cv::Mat masks;
-    int     cnt = 0;
-    for (auto& i : indices) {
-        if (cnt >= topk) {
-            break;
-        }
-        cv::Rect tmp = bboxes[i];
-        Object   obj;
-        obj.label = labels[i];
-        obj.rect  = tmp;
-        obj.prob  = scores[i];
-        masks.push_back(mask_confs[i]);
-        objs.push_back(obj);
-        cnt += 1;
-    }
-    if (masks.empty()) {
-        // masks is empty
-    }
-    else {
-        cv::Mat matmulRes = (masks * protos).t();
-        cv::Mat maskMat   = matmulRes.reshape(indices.size(), {seg_h, seg_w});
-
-        std::vector<cv::Mat> maskChannels;
-        cv::split(maskMat, maskChannels);
-        int scale_dw = dw / input_w * seg_w;
-        int scale_dh = dh / input_h * seg_h;
-
-        cv::Rect roi(scale_dw, scale_dh, seg_w - 2 * scale_dw, seg_h - 2 * scale_dh);
-
-        for (int i = 0; i < indices.size(); i++) {
-            cv::Mat dest, mask;
-            cv::exp(-maskChannels[i], dest);
-            dest = 1.0 / (1.0 + dest);
-            dest = dest(roi);
-            cv::resize(dest, mask, cv::Size((int)width, (int)height), cv::INTER_LINEAR);
-            objs[i].boxMask = mask(objs[i].rect) > 0.5f;
-        }
-    }
-}
-
-void YOLOv8_seg::draw_objects(const cv::Mat&                                image,
-                              cv::Mat&                                      res,
-                              const std::vector<Object>&                    objs,
-                              const std::vector<std::string>&               CLASS_NAMES,
-                              const std::vector<std::vector<unsigned int>>& COLORS,
-                              const std::vector<std::vector<unsigned int>>& MASK_COLORS)
-{
-    res          = image.clone();
-    cv::Mat mask = image.clone();
-    for (auto& obj : objs) {
-        int        idx   = obj.label;
-        cv::Scalar color = cv::Scalar(COLORS[idx][0], COLORS[idx][1], COLORS[idx][2]);
-        cv::Scalar mask_color =
-            cv::Scalar(MASK_COLORS[idx % 20][0], MASK_COLORS[idx % 20][1], MASK_COLORS[idx % 20][2]);
-        cv::rectangle(res, obj.rect, color, 2);
-
-        char text[256];
-        sprintf(text, "%s %.1f%%", CLASS_NAMES[idx].c_str(), obj.prob * 100);
-        mask(obj.rect).setTo(mask_color, obj.boxMask);
-
-        int      baseLine   = 0;
-        cv::Size label_size = cv::getTextSize(text, cv::FONT_HERSHEY_SIMPLEX, 0.4, 1, &baseLine);
-
-        int x = (int)obj.rect.x;
-        int y = (int)obj.rect.y + 1;
-
-        if (y > res.rows)
-            y = res.rows;
-
-        cv::rectangle(res, cv::Rect(x, y, label_size.width, label_size.height + baseLine), {0, 0, 255}, -1);
-
-        cv::putText(res, text, cv::Point(x, y + label_size.height), cv::FONT_HERSHEY_SIMPLEX, 0.4, {255, 255, 255}, 1);
-    }
-    cv::addWeighted(res, 0.5, mask, 0.8, 1, res);
-}

+ 0 - 53
detect/tensorrt_detect/yolov8-seg.h

@@ -1,53 +0,0 @@
-//
-// Created by ubuntu on 3/16/23.
-//
-#ifndef JETSON_SEGMENT_YOLOV8_SEG_HPP
-#define JETSON_SEGMENT_YOLOV8_SEG_HPP
-#include "NvInferPlugin.h"
-#include "common.hpp"
-#include <fstream>
-
-using namespace seg;
-
-class YOLOv8_seg {
-public:
-    explicit YOLOv8_seg(const std::string& engine_file_path);
-    ~YOLOv8_seg();
-
-    void                 make_pipe(bool warmup = true);
-    void                 copy_from_Mat(const cv::Mat& image);
-    void                 copy_from_Mat(const cv::Mat& image, cv::Size& size);
-    void                 letterbox(const cv::Mat& image, cv::Mat& out, cv::Size& size);
-    void                 infer();
-    void                 postprocess(std::vector<Object>& objs,
-                                     float                score_thres  = 0.25f,
-                                     float                iou_thres    = 0.65f,
-                                     int                  topk         = 100,
-                                     int                  seg_channels = 32,
-                                     int                  seg_h        = 160,
-                                     int                  seg_w        = 160);
-    static void          draw_objects(const cv::Mat&                                image,
-                                      cv::Mat&                                      res,
-                                      const std::vector<Object>&                    objs,
-                                      const std::vector<std::string>&               CLASS_NAMES,
-                                      const std::vector<std::vector<unsigned int>>& COLORS,
-                                      const std::vector<std::vector<unsigned int>>& MASK_COLORS);
-    int                  num_bindings;
-    int                  num_inputs  = 0;
-    int                  num_outputs = 0;
-    std::vector<Binding> input_bindings;
-    std::vector<Binding> output_bindings;
-    std::vector<void*>   host_ptrs;
-    std::vector<void*>   device_ptrs;
-
-    PreParam pparam;
-
-private:
-    nvinfer1::ICudaEngine*       engine  = nullptr;
-    nvinfer1::IRuntime*          runtime = nullptr;
-    nvinfer1::IExecutionContext* context = nullptr;
-    cudaStream_t                 stream  = nullptr;
-    Logger                       gLogger{nvinfer1::ILogger::Severity::kERROR};
-};
-
-#endif  // JETSON_SEGMENT_YOLOV8_SEG_HPP

+ 16 - 9
proto/def.grpc.proto

@@ -1,28 +1,38 @@
 syntax = "proto3";
 package JetStream;
-
 message RequestCmd
 {
   int32 Id=1;  // 对于获取对应id的相机数据。1,2,3,4,其他表示所有
   //对于打开视频流
 }
-
 message Response{
   string info=2;
 }
-
 message Image{
   int32 width=1;
   int32 height=2;
   int32 channel=3;
   bytes data=4;
 }
-
 message PointCloud{
   int32 size=1;
   bytes data=2;
 }
-
+message LabelImage{
+  int32 label=1;
+  Image ir=2;
+}
+message Line{
+  int32 begin=1;
+  int32 end=2;
+}
+message SegBox{
+  repeated Line lines=1;
+}
+message LabelYolo{
+  int32 label=1;
+  repeated SegBox boxes=2;
+}
 message ResImage{
   Image img1=1;
   Image img2=2;
@@ -55,7 +65,6 @@ message ResFrame{
   ResImage images=1;
   ResCloud clouds=2;
   MeasureInfo measure_info=3;
-
 }
 service StreamServer{
   rpc OpenImageStream(RequestCmd) returns(stream ResImage){}
@@ -79,6 +88,4 @@ message Limit{
   Boundary display_limit=2;
   float maxWidth=3;
   float maxWheelBase=4;
-}
-
-
+}

+ 6 - 6
tof3DMain.cpp

@@ -16,8 +16,8 @@ int main(int argc, char * argv[]) {
     // 初始化相机处理程序
     tof3dManagerParams tof3d_etc;
     if (loadProtobufFile(ETC_PATH PROJECT_NAME "/tof3d_manager.json", tof3d_etc) == SUCCESS) {
-        // auto ret = DeviceTof3D::iter()->Init(tof3d_etc.vzense_tof3d_devices());
-        Error_manager ret;
+         auto ret = DeviceTof3D::iter()->Init(tof3d_etc.vzense_tof3d_devices());
+//        Error_manager ret;
         if (ret != SUCCESS) {
             LOG(ERROR) << ret.to_string();
             return EXIT_FAILURE;
@@ -27,11 +27,11 @@ int main(int argc, char * argv[]) {
         return EXIT_FAILURE;
     }
 
-    // 初始化测量程序
-    // DetectManager::iter()->Init();
-
     // 通信
-     CommunicationManager::iter()->Init(tof3d_etc.communication());
+    CommunicationManager::iter()->Init(tof3d_etc.communication());
+
+    // 初始化测量程序
+    DetectManager::iter()->Init();
 
     // 加载看门狗 TODO:添加看门狗,监视线程
     LOG(INFO) << "---------- all init complate ----------";