客製作模型部署(以機器車應用為例)
-
待完成
-
模型部署基本操作流程
按照以下路徑將nb檔放入對應任務的資料夾中

在這個資料夾內只能放一個nb檔

開啟ObjectDetectionLoop的程式碼

將以下程式碼貼至ObjectDetectionLoop的.ino檔內
#include "StreamIO.h" #include "VideoStream.h" #include "NNObjectDetection.h" #include "VideoStreamOverlay.h" #include "ObjectClassList.h" #include "AmebaServo.h" #define CHANNEL 0 #define CHANNELNN 3 #define NNWIDTH 640 #define NNHEIGHT 640 VideoSetting config(VIDEO_FHD, 30, VIDEO_H264, 0); VideoSetting configNN(NNWIDTH, NNHEIGHT, 10, VIDEO_RGB, 0); NNObjectDetection ObjDet; StreamIO videoStreamer(1, 1); StreamIO videoStreamerNN(1, 1); // PWM 腳位 int a = 1; int b = 2; int c = 3; int d = 4; // PWM 控制參數 const int maxPWM = 180; const int turnMaxPWM = 90; void setup() { Serial.begin(115200); pinMode(a, OUTPUT); pinMode(b, OUTPUT); pinMode(c, OUTPUT); pinMode(d, OUTPUT); config.setBitrate(2 * 1024 * 1024); Camera.configVideoChannel(CHANNEL, config); Camera.configVideoChannel(CHANNELNN, configNN); Camera.videoInit(); ObjDet.configVideo(configNN); ObjDet.modelSelect(OBJECT_DETECTION, CUSTOMIZED_YOLOV7TINY, NA_MODEL, NA_MODEL); ObjDet.configThreshold(0.2, 0.2); ObjDet.begin(); videoStreamer.registerInput(Camera.getStream(CHANNEL)); if (videoStreamer.begin() != 0) { Serial.println("StreamIO link start failed"); } Camera.channelBegin(CHANNEL); videoStreamerNN.registerInput(Camera.getStream(CHANNELNN)); videoStreamerNN.setStackSize(); videoStreamerNN.setTaskPriority(); videoStreamerNN.registerOutput(ObjDet); if (videoStreamerNN.begin() != 0) { Serial.println("StreamIO link start failed"); } Camera.channelBegin(CHANNELNN); } void loop() { std::vector<ObjectDetectionResult> results = ObjDet.getResult(); uint16_t im_w = config.width(); if (ObjDet.getResultCount() > 0) { int bestIndex = -1; float highestScore = -1.0; for (int i = 0; i < ObjDet.getResultCount(); i++) { if (results[i].score() > highestScore) { highestScore = results[i].score(); bestIndex = i; } } if (bestIndex != -1) { int obj_type = results[bestIndex].type(); if (itemList[obj_type].filter) { ObjectDetectionResult item = results[bestIndex]; int xmin = (int)(item.xMin() * im_w); int xmax = (int)(item.xMax() * im_w); int xcenter = (xmin + xmax) / 2; const char* position; if (xcenter < im_w / 3) { position = "左半部"; } else if (xcenter > 2 * im_w / 3) { position = "右半部"; } else { position = "中間"; } if (position == "中間") { // 前進 analogWrite(a, 0); // 右後停 analogWrite(b, maxPWM); // 右前轉 analogWrite(c, 0); // 左後停 analogWrite(d, maxPWM); // 左前轉 } else if (position == "右半部") { // 右轉 analogWrite(a, 0); analogWrite(b, turnMaxPWM); // 右前較慢 analogWrite(c, 0); analogWrite(d, maxPWM); // 左前較快 } else if (position == "左半部") { // 左轉 analogWrite(a, 0); analogWrite(b, maxPWM); // 右前較快 analogWrite(c, 0); analogWrite(d, turnMaxPWM); // 左前較慢 } else { analogWrite(a, 0); analogWrite(b, 0); analogWrite(c, 0); analogWrite(d, 0); } delay(200); // 保持動作一段時間 // 停車 analogWrite(a, 0); analogWrite(b, 0); analogWrite(c, 0); analogWrite(d, 0); } } } delay(100); }最後將.h檔內的itemList改成你要偵測的物品數量和物品名稱就可以執行了 (多的刪掉)

電路連接方式

-
模型部署基本操作流程