4 Commits
train2 ... main

Author SHA1 Message Date
Rhys
f7eb63473f New control code with different setpoint handling 2025-05-11 17:13:26 -07:00
1eba3e9ab2 Delete Final/test.txt 2025-04-01 00:03:48 +00:00
engr-ugaif engr-ugaif
29a0f4ef5f Hopefully Final Control Update...minus esp bug 2025-03-31 20:03:16 -04:00
82affd033b Add Final/test.txt 2025-03-31 23:54:05 +00:00
47 changed files with 655 additions and 373 deletions

128
Final/MQTTdigitalPot.ino Normal file
View File

@@ -0,0 +1,128 @@
#include <M5StickCPlus2.h> // Correct library header for M5StickC Plus2 // Include M5StickCPlus2 library
#include <SPI.h>
#include <WiFi.h>
#include <PubSubClient.h>
#define CS_PIN 32 // Chip Select (CS) for MCP4231
#define SCK_PIN 33
#define MISO_PIN 25
#define MOSI_PIN 26
#define SPI_SPEED 1000000 // 1MHz SPI speed
byte addressPot = B00000000;
const char* ssid = "IOT-pecan";
const char* password = "aaaaaaaa";
const char* mqtt_server = "192.168.1.110";
const char* topic = "jc/status/light:0";
WiFiClient espClient;
PubSubClient client(espClient);
void setPot(uint8_t value) {
digitalWrite(CS_PIN, LOW); // Select MCP4231
SPI.transfer(addressPot); // Command: Write to Wiper 0
SPI.transfer(value); // Set wiper position (0-255)
digitalWrite(CS_PIN, HIGH); // Deselect MCP4231
}
void callback(char* topic, byte* payload, unsigned int length) {
char payloadStr[10];
if (length >= sizeof(payloadStr)) length = sizeof(payloadStr) - 1;
strncpy(payloadStr, (char*)payload, length);
payloadStr[length] = '\0';
int potValue = atoi(payloadStr);
setPot(potValue);
Serial.print("Wiper set to: ");
Serial.println(potValue);
// Display on the M5StickC Plus2 screen
M5.Lcd.fillScreen(TFT_BLACK);
M5.Lcd.setCursor(0, 20);
M5.Lcd.println("Output:");
M5.Lcd.print(potValue);
}
void setup() {
M5.begin(); // Initialize M5StickC Plus2
SPI.begin(SCK_PIN, MISO_PIN, MOSI_PIN, CS_PIN); // SCK, MISO (not used), MOSI, CS
pinMode(CS_PIN, OUTPUT);
digitalWrite(CS_PIN, HIGH);
Serial.begin(115200);
Serial.println("MCP4231 Digital Potentiometer Test");
M5.Lcd.setRotation(0);
M5.Lcd.fillScreen(TFT_BLACK);
M5.Lcd.setTextColor(TFT_WHITE);
M5.Lcd.setTextSize(2.5);
// Set potentiometer to mid-range (127)
setPot(60);
WiFi.begin(ssid, password);
Serial.print("Connecting to WiFi");
unsigned long startTime = millis();
while (WiFi.status() != WL_CONNECTED && millis() - startTime < 10000) {
delay(500);
Serial.print(".");
}
if (WiFi.status() == WL_CONNECTED) {
Serial.println("\nConnected to WiFi");
} else {
Serial.println("\nWiFi Connection Failed!");
return;
}
client.setServer(mqtt_server, 1883);
client.setCallback(callback);
while (!client.connected()) {
Serial.print("Connecting to MQTT...");
if (client.connect("M5StickCPlus2")) {
Serial.println("Connected!");
client.subscribe(topic);
} else {
Serial.print("Failed, rc=");
Serial.println(client.state());
delay(2000);
}
}
}
void reconnect() {
while (!client.connected()) {
Serial.print("Reconnecting to MQTT...");
if (client.connect("M5StickCPlus2")) {
Serial.println("Reconnected!");
client.subscribe(topic);
} else {
Serial.print("Failed, rc=");
Serial.println(client.state());
delay(5000); // Wait before retrying
}
}
}
void loop() {
if (!client.connected()) {
reconnect(); // Reconnect to MQTT if disconnected
}
client.loop();
}

View File

@@ -0,0 +1,14 @@
# Ultralytics 🚀 AGPL-3.0 License - https://ultralytics.com/license
# Default Ultralytics settings for ByteTrack tracker when using mode="track"
# For documentation and examples see https://docs.ultralytics.com/modes/track/
# For ByteTrack source code see https://github.com/ifzhang/ByteTrack
tracker_type: bytetrack # tracker type, ['botsort', 'bytetrack']
track_high_thresh: 0.45 # threshold for the first association
track_low_thresh: 0.05 # threshold for the second association
new_track_thresh: 0.45 # threshold for init new track if the detection does not match any tracks
track_buffer: 15 # buffer to calculate the time when to remove tracks
match_thresh: 0.75 # threshold for matching tracks
fuse_score: True # Whether to fuse confidence scores with the iou distances before matching
# min_box_area: 10 # threshold for min box areas(for tracker evaluation, not used for now)

262
Final/jcControl.py Normal file
View File

@@ -0,0 +1,262 @@
####################################################################################
# Load Libraries
from ultralytics import YOLO
import cvzone
import cv2
import threading
import queue
import paho.mqtt.client as mqtt
import time
from filterpy.kalman import UnscentedKalmanFilter as UKF
from filterpy.kalman import MerweScaledSigmaPoints
import numpy as np
import pandas as pd
####################################################################################
# Initialize Variables
# Load YOLOv11 model
device = 'cuda'
model = YOLO("yolo11n-pecan.pt") # Update with correct model path
cy1 = 475 # Count Threshold (Center Y-coordinate)
offset = 60 # Offset for Center Y-coordinate
ids = set()
pecanCount = 0
samplePeriod = 0.1 # seconds
refThroughput = 0 # Count / Second
switchState = 0 # 0 = Off, 1 = On
prevSwitchState = 0 # 0 = Off, 1 = On
####################################################################################
# Initialize Camera
cap = cv2.VideoCapture(0) # Ensure that you have the correct camera index
# Set the resolution and other properties for each camera
cap.set(cv2.CAP_PROP_FRAME_WIDTH, 1280)
cap.set(cv2.CAP_PROP_FRAME_HEIGHT, 720)
cap.set(cv2.CAP_PROP_FPS, 120)
####################################################################################
# Unscented Kalman Filter
# State transition function (identity - no control input)
def fx(x, dt):
""" State transition function (no external control) """
return x # No change in state without an input
# Measurement function (identity)
def hx(x):
""" Measurement function (direct observation) """
return x # We measure the state directly
points = MerweScaledSigmaPoints(n=1, alpha=0.1, beta=2, kappa=0)# Define sigma points
ukf = UKF(dim_x=1, dim_z=1, fx=fx, hx=hx, points=points, dt=samplePeriod) # Initial State Estimate
ukf.x = np.array([refThroughput]) # Initial state estimate
ukf.Q = np.array([[0.02]]) # Process noise covariance (Q) - controls how much the state changes naturally
ukf.R = np.array([[0.5]]) # Measurement noise covariance (R) - how noisy the measurements are
ukf.P = np.eye(1) * 0.1 # Initial state covariance (P) - initial uncertainty
####################################################################################
# PI Controller
class PIController:
def __init__(self, Kp, Ki, Ts):
self.Kp = Kp
self.Ki = Ki
self.Ts = Ts
self.prevError = 0
self.prevOutput = 55
self.error = 0
def compute(self, setpoint, measurement):
"""Compute PI control output."""
self.error = setpoint - measurement
output = self.prevOutput + self.Kp * self.error + (self.Ki * self.Ts - self.Kp) * self.prevError # Z domain
self.prevError = self.error
# Apply saturation limits (0 to 90)
if output > 90:
output = 90
elif output < 0:
output = 0
self.prevOutput = output
return output
# PI Initialization
controller = PIController(0.063, 0.5, samplePeriod) # Kp, Ki, Ts
####################################################################################
# MQTT
# Mqtt Configuration
MQTT_BROKER = "192.168.1.110"
MQTT_PORT = 1883
MQTT_REF_TOPIC = "/jc/feedrate/"
MQTT_COUNT_TOPIC = "/jc/feedrate/count/"
MQTT_CONTROL_TOPIC = "jc/status/light:0"
MQTT_CONTROL_VISUAL_TOPIC = "/pi_controller/output"
# MQTT Handling
def on_connect(client, userdata, flags, rc, properties=None):
print("Connected with result code " + str(rc))
client.subscribe(MQTT_REF_TOPIC)
def on_message(client, userdata, message):
global refThroughput, switchState, prevSwitchState, controller
with refThroughput_lock:
refThroughput = float(message.payload.decode())
with ukf_lock:
ukf.x = np.array([refThroughput])
with switchState_lock:
if refThroughput == 0:
switchState = 0
elif prevSwitchState == 0 and refThroughput != 0:
switchState = 1
with controller_lock:
controller.prevError = 0
controller.prevOutput = 60
else:
switchState = 1
prevSwitchState = switchState
# Initialize MQTT client
mqtt_client = mqtt.Client()
mqtt_client.on_connect = on_connect
mqtt_client.on_message = on_message
mqtt_client.connect(MQTT_BROKER, MQTT_PORT, 60)
mqtt_client.loop_start() # Starts the loop in the background
####################################################################################
# Thread Initialization
# Queue to hold frames captured by the capture thread
frame_queue = queue.Queue(maxsize=1) # Limit to 1 frames in the queue
# Locks for thread synchronization
refThroughput_lock = threading.Lock()
ukf_lock = threading.Lock()
switchState_lock = threading.Lock()
controller_lock = threading.Lock()
####################################################################################
# Camera Thread
def capture_thread():
while True:
ret, frame = cap.read()
if not ret:
break
# Define the black box position (adjust as needed)
top_left = (0, 600)
bottom_right = (1280, 720)
# Draw a black rectangle (filled)
cv2.rectangle(frame, top_left, bottom_right, (0, 0, 0), thickness=-1)
# Flip Frame
frame = cv2.flip(frame, 0)
# Put the frame into the queue
if not frame_queue.full():
frame_queue.put(frame)
####################################################################################
# Processing Thread
def processing_thread():
global pecanCount, ids
sampleStart = time.time()
while True:
# Check if there are any frames in the queue
if not frame_queue.empty():
frame = frame_queue.get()
results = model.track(frame, persist=True, classes=0, device=device, stream=True, tracker='bytetrack_custom.yaml', iou = 0.6)
for result in results:
# Check if there are any boxes in the result
if result.boxes is not None and result.boxes.id is not None:
# Get the boxes (x, y, w, h), class IDs, track IDs, and confidences
boxes = result.boxes.xyxy.int().tolist() # Bounding boxes
track_ids = result.boxes.id.int().tolist() # Track IDs
# Iterate over each detected object
for box, track_id in zip(boxes, track_ids):
x1, y1, x2, y2 = box
cy = int((y1 + y2) // 2) # Center Y-coordinate
if cy < (cy1 + offset) and cy > (cy1 - offset) and track_id not in ids:
pecanCount += 1
ids.add(track_id)
sampleEnd = time.time()
if (sampleEnd - sampleStart) > samplePeriod:
measuredCount = pecanCount / samplePeriod
with ukf_lock:
ukf.predict()
ukf.update(np.array([measuredCount]))
filteredCount = ukf.x[0]
if switchState == 1:
with controller_lock:
controllerOutput = (controller.compute(refThroughput, filteredCount))
mqtt_client.publish(MQTT_CONTROL_TOPIC, str(int((controllerOutput) / 90 * 129)))
mqtt_client.publish(MQTT_CONTROL_VISUAL_TOPIC, str(controllerOutput))
mqtt_client.publish(MQTT_COUNT_TOPIC, str(filteredCount))
pecanCount = 0 # Reset count for next sample period
sampleStart = time.time() # Reset start time for next sample period
####################################################################################
# Threading
# Start capture and processing threads
capture_thread = threading.Thread(target=capture_thread)
capture_thread.daemon = True # Ensures the thread exits when the main program exits
capture_thread.start()
processing_thread = threading.Thread(target=processing_thread)
processing_thread.daemon = True # Ensures the thread exits when the main program exits
processing_thread.start()
####################################################################################
# Clean Up
try:
while True:
# Keep the main loop alive
if cv2.waitKey(1) & 0xFF == ord('q'): # Press 'q' to quit
break
except KeyboardInterrupt:
print("Process interrupted")
# Release resources when exiting
cap.release()
cv2.destroyAllWindows()
mqtt_client.loop_stop()
mqtt_client.disconnect()
print("Capture Released")
####################################################################################

BIN
Final/yolo11n-pecan.pt Normal file

Binary file not shown.

View File

251
jcControlRevised.py Executable file
View File

@@ -0,0 +1,251 @@
####################################################################################
# Load Libraries
from ultralytics import YOLO
import cvzone
import cv2
import threading
import queue
import paho.mqtt.client as mqtt
import time
from filterpy.kalman import UnscentedKalmanFilter as UKF
from filterpy.kalman import MerweScaledSigmaPoints
import numpy as np
import pandas as pd
####################################################################################
# Initialize Variables
# Load YOLOv11 model
device = 'cuda'
model = YOLO("yolo11n-pecan.pt") # Update with correct model path
cy1 = 475 # Count Threshold (Center Y-coordinate)
offset = 60 # Offset for Center Y-coordinate
ids = set()
pecanCount = 0
samplePeriod = 0.1 # seconds
refThroughput = 0 # Count / Second
####################################################################################
# Initialize Camera
cap = cv2.VideoCapture(0) # Ensure that you have the correct camera index
# Set the resolution and other properties for each camera
cap.set(cv2.CAP_PROP_FRAME_WIDTH, 1280)
cap.set(cv2.CAP_PROP_FRAME_HEIGHT, 720)
cap.set(cv2.CAP_PROP_FPS, 120)
####################################################################################
# Unscented Kalman Filter
# State transition function (identity - no control input)
def fx(x, dt):
""" State transition function (no external control) """
return x # No change in state without an input
# Measurement function (identity)
def hx(x):
""" Measurement function (direct observation) """
return x # We measure the state directly
points = MerweScaledSigmaPoints(n=1, alpha=0.1, beta=2, kappa=0)# Define sigma points
ukf = UKF(dim_x=1, dim_z=1, fx=fx, hx=hx, points=points, dt=samplePeriod) # Initial State Estimate
ukf.x = np.array([refThroughput]) # Initial state estimate
ukf.Q = np.array([[0.02]]) # Process noise covariance (Q) - controls how much the state changes naturally
ukf.R = np.array([[0.5]]) # Measurement noise covariance (R) - how noisy the measurements are
ukf.P = np.eye(1) * 0.1 # Initial state covariance (P) - initial uncertainty
####################################################################################
# PI Controller
class PIController:
def __init__(self, Kp, Ki, Ts):
self.Kp = Kp
self.Ki = Ki
self.Ts = Ts
self.prevError = 0
self.prevOutput = 55
self.error = 0
def compute(self, setpoint, measurement):
"""Compute PI control output."""
self.error = setpoint - measurement
output = self.prevOutput + self.Kp * self.error + (self.Ki * self.Ts - self.Kp) * self.prevError # Z domain
self.prevError = self.error
# Apply saturation limits (0 to 90)
if output > 90:
output = 90
elif output < 0:
output = 0
self.prevOutput = output
return output
# PI Initialization
controller = PIController(0.063, 0.5, samplePeriod) # Kp, Ki, Ts
####################################################################################
# MQTT
# Mqtt Configuration
MQTT_BROKER = "192.168.1.110"
MQTT_PORT = 1883
MQTT_REF_TOPIC = "/jc/feedrate/"
MQTT_COUNT_TOPIC = "/jc/feedrate/count/"
MQTT_CONTROL_TOPIC = "jc/status/light:0"
MQTT_CONTROL_VISUAL_TOPIC = "/pi_controller/output"
# MQTT Handling
def on_connect(client, userdata, flags, rc, properties=None):
print("Connected with result code " + str(rc))
client.subscribe(MQTT_REF_TOPIC)
def on_message(client, userdata, message):
global refThroughput, switchState, prevSwitchState, controller
with refThroughput_lock:
refThroughput = float(message.payload.decode())
with controller_lock:
controller.prevError = 0
controller.prevOutput = 60
with ukf_lock:
ukf.x = np.array([refThroughput])
# Initialize MQTT client
mqtt_client = mqtt.Client()
mqtt_client.on_connect = on_connect
mqtt_client.on_message = on_message
mqtt_client.connect(MQTT_BROKER, MQTT_PORT, 60)
mqtt_client.loop_start() # Starts the loop in the background
####################################################################################
# Thread Initialization
# Queue to hold frames captured by the capture thread
frame_queue = queue.Queue(maxsize=1) # Limit to 1 frames in the queue
# Locks for thread synchronization
refThroughput_lock = threading.Lock()
ukf_lock = threading.Lock()
switchState_lock = threading.Lock()
controller_lock = threading.Lock()
####################################################################################
# Camera Thread
def capture_thread():
while True:
ret, frame = cap.read()
if not ret:
break
# Define the black box position (adjust as needed)
top_left = (0, 600)
bottom_right = (1280, 720)
# Draw a black rectangle (filled)
cv2.rectangle(frame, top_left, bottom_right, (0, 0, 0), thickness=-1)
# Flip Frame
frame = cv2.flip(frame, 0)
# Put the frame into the queue
if not frame_queue.full():
frame_queue.put(frame)
####################################################################################
# Processing Thread
def processing_thread():
global pecanCount, ids
sampleStart = time.time()
while True:
# Check if there are any frames in the queue
if not frame_queue.empty():
frame = frame_queue.get()
results = model.track(frame, persist=True, classes=0, device=device, stream=True, tracker='bytetrack_custom.yaml', iou = 0.6)
for result in results:
# Check if there are any boxes in the result
if result.boxes is not None and result.boxes.id is not None:
# Get the boxes (x, y, w, h), class IDs, track IDs, and confidences
boxes = result.boxes.xyxy.int().tolist() # Bounding boxes
track_ids = result.boxes.id.int().tolist() # Track IDs
# Iterate over each detected object
for box, track_id in zip(boxes, track_ids):
x1, y1, x2, y2 = box
cy = int((y1 + y2) // 2) # Center Y-coordinate
if cy < (cy1 + offset) and cy > (cy1 - offset) and track_id not in ids:
pecanCount += 1
ids.add(track_id)
sampleEnd = time.time()
if (sampleEnd - sampleStart) > samplePeriod:
measuredCount = pecanCount / samplePeriod
with ukf_lock:
ukf.predict()
ukf.update(np.array([measuredCount]))
filteredCount = ukf.x[0]
if refThroughput != 0:
with controller_lock:
controllerOutput = (controller.compute(refThroughput, filteredCount))
mqtt_client.publish(MQTT_CONTROL_TOPIC, str(int((controllerOutput) / 90 * 129)))
mqtt_client.publish(MQTT_CONTROL_VISUAL_TOPIC, str(controllerOutput))
mqtt_client.publish(MQTT_COUNT_TOPIC, str(filteredCount))
pecanCount = 0 # Reset count for next sample period
sampleStart = time.time() # Reset start time for next sample period
####################################################################################
# Threading
# Start capture and processing threads
capture_thread = threading.Thread(target=capture_thread)
capture_thread.daemon = True # Ensures the thread exits when the main program exits
capture_thread.start()
processing_thread = threading.Thread(target=processing_thread)
processing_thread.daemon = True # Ensures the thread exits when the main program exits
processing_thread.start()
####################################################################################
# Clean Up
try:
while True:
# Keep the main loop alive
if cv2.waitKey(1) & 0xFF == ord('q'): # Press 'q' to quit
break
except KeyboardInterrupt:
print("Process interrupted")
# Release resources when exiting
cap.release()
cv2.destroyAllWindows()
mqtt_client.loop_stop()
mqtt_client.disconnect()
print("Capture Released")
####################################################################################

View File

@@ -1,10 +0,0 @@
[project]
name = "usda-throughput-control"
version = "0.1.0"
description = "Add your description here"
readme = "README.md"
requires-python = ">=3.12"
dependencies = [
"ipykernel>=6.29.5",
"paho-mqtt>=2.1.0",
]

View File

@@ -1,107 +0,0 @@
task: detect
mode: train
model: yolo11s.pt
data: ./yolov11-pecan/data.yaml
epochs: 25
time: null
patience: 100
batch: 20
imgsz: 1280
save: true
save_period: -1
cache: false
device: cuda
workers: 16
project: null
name: train10
exist_ok: false
pretrained: true
optimizer: auto
verbose: true
seed: 0
deterministic: true
single_cls: false
rect: false
cos_lr: false
close_mosaic: 10
resume: false
amp: true
fraction: 1.0
profile: false
freeze: null
multi_scale: false
overlap_mask: true
mask_ratio: 4
dropout: 0.0
val: true
split: val
save_json: false
save_hybrid: false
conf: null
iou: 0.7
max_det: 300
half: false
dnn: false
plots: true
source: null
vid_stride: 1
stream_buffer: false
visualize: false
augment: false
agnostic_nms: false
classes: null
retina_masks: false
embed: null
show: false
save_frames: false
save_txt: false
save_conf: false
save_crop: false
show_labels: true
show_conf: true
show_boxes: true
line_width: null
format: torchscript
keras: false
optimize: false
int8: false
dynamic: false
simplify: true
opset: null
workspace: 4
nms: false
lr0: 0.01
lrf: 0.01
momentum: 0.937
weight_decay: 0.0005
warmup_epochs: 3.0
warmup_momentum: 0.8
warmup_bias_lr: 0.1
box: 7.5
cls: 0.5
dfl: 1.5
pose: 12.0
kobj: 1.0
label_smoothing: 0.0
nbs: 64
hsv_h: 0.015
hsv_s: 0.7
hsv_v: 0.4
degrees: 0.0
translate: 0.1
scale: 0.5
shear: 0.0
perspective: 0.0
flipud: 0.0
fliplr: 0.5
bgr: 0.0
mosaic: 1.0
mixup: 0.0
copy_paste: 0.0
copy_paste_mode: flip
auto_augment: randaugment
erasing: 0.4
crop_fraction: 1.0
cfg: null
tracker: botsort.yaml
save_dir: /home/engr-ugaif/USDA-throughput-control/runs/detect/train10

Binary file not shown.

Before

Width:  |  Height:  |  Size: 142 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 273 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 88 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 78 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 81 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 91 KiB

View File

@@ -1,107 +0,0 @@
task: detect
mode: train
model: yolo11s.pt
data: ./yolov11-pecan/data.yaml
epochs: 25
time: null
patience: 100
batch: 20
imgsz: 1280
save: true
save_period: -1
cache: false
device: cuda
workers: 16
project: null
name: train12
exist_ok: false
pretrained: true
optimizer: auto
verbose: true
seed: 0
deterministic: true
single_cls: false
rect: false
cos_lr: false
close_mosaic: 10
resume: false
amp: true
fraction: 1.0
profile: false
freeze: null
multi_scale: false
overlap_mask: true
mask_ratio: 4
dropout: 0.0
val: true
split: val
save_json: false
save_hybrid: false
conf: null
iou: 0.7
max_det: 300
half: false
dnn: false
plots: true
source: null
vid_stride: 1
stream_buffer: false
visualize: false
augment: false
agnostic_nms: false
classes: null
retina_masks: false
embed: null
show: false
save_frames: false
save_txt: false
save_conf: false
save_crop: false
show_labels: true
show_conf: true
show_boxes: true
line_width: null
format: torchscript
keras: false
optimize: false
int8: false
dynamic: false
simplify: true
opset: null
workspace: 4
nms: false
lr0: 0.01
lrf: 0.01
momentum: 0.937
weight_decay: 0.0005
warmup_epochs: 3.0
warmup_momentum: 0.8
warmup_bias_lr: 0.1
box: 7.5
cls: 0.5
dfl: 1.5
pose: 12.0
kobj: 1.0
label_smoothing: 0.0
nbs: 64
hsv_h: 0.015
hsv_s: 0.7
hsv_v: 0.4
degrees: 0.0
translate: 0.1
scale: 0.5
shear: 0.0
perspective: 0.0
flipud: 0.0
fliplr: 0.5
bgr: 0.0
mosaic: 1.0
mixup: 0.0
copy_paste: 0.0
copy_paste_mode: flip
auto_augment: randaugment
erasing: 0.4
crop_fraction: 1.0
cfg: null
tracker: botsort.yaml
save_dir: /home/engr-ugaif/USDA-throughput-control/runs/detect/train12

Binary file not shown.

Before

Width:  |  Height:  |  Size: 94 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 85 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 142 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 273 KiB

View File

@@ -1,26 +0,0 @@
epoch,time,train/box_loss,train/cls_loss,train/dfl_loss,metrics/precision(B),metrics/recall(B),metrics/mAP50(B),metrics/mAP50-95(B),val/box_loss,val/cls_loss,val/dfl_loss,lr/pg0,lr/pg1,lr/pg2
1,506.754,0.69773,0.6443,0.98677,0.85746,0.90067,0.95602,0.81969,0.57211,0.44531,0.84271,0.000665995,0.000665995,0.000665995
2,775.31,0.67191,0.46142,0.96903,0.89594,0.91124,0.96492,0.83347,0.56171,0.43418,0.84033,0.00127989,0.00127989,0.00127989
3,1042.43,0.64879,0.43295,0.95724,0.89927,0.92376,0.97455,0.84793,0.53096,0.3909,0.82332,0.00184098,0.00184098,0.00184098
4,1309.29,0.63499,0.41484,0.94974,0.8901,0.90711,0.96519,0.83708,0.53559,0.41364,0.82635,0.0017624,0.0017624,0.0017624
5,1576.24,0.6194,0.39346,0.94417,0.92455,0.92984,0.97784,0.85866,0.51774,0.35537,0.81741,0.0016832,0.0016832,0.0016832
6,1843.45,0.60151,0.37385,0.93784,0.89506,0.93742,0.96631,0.83846,0.55381,0.38597,0.82555,0.001604,0.001604,0.001604
7,2110.63,0.58751,0.35579,0.93003,0.90571,0.9501,0.97622,0.86446,0.51076,0.3642,0.8146,0.0015248,0.0015248,0.0015248
8,2377.57,0.57208,0.34024,0.92507,0.90235,0.93492,0.9714,0.86352,0.50438,0.35819,0.81116,0.0014456,0.0014456,0.0014456
9,2644.65,0.55947,0.32402,0.91929,0.91572,0.94436,0.97664,0.87084,0.49431,0.34051,0.80756,0.0013664,0.0013664,0.0013664
10,2911.65,0.54281,0.31078,0.91366,0.91424,0.93562,0.9652,0.86171,0.4887,0.38716,0.80484,0.0012872,0.0012872,0.0012872
11,3178.42,0.52475,0.29805,0.90675,0.90982,0.9442,0.96658,0.86221,0.49884,0.37786,0.80951,0.001208,0.001208,0.001208
12,3445.37,0.50654,0.28378,0.90022,0.91695,0.94206,0.96273,0.85841,0.50642,0.37648,0.81476,0.0011288,0.0011288,0.0011288
13,3712.44,0.48918,0.27473,0.89372,0.91413,0.9375,0.961,0.85692,0.51257,0.38685,0.81386,0.0010496,0.0010496,0.0010496
14,3979.6,0.47069,0.26422,0.88725,0.91369,0.94444,0.96014,0.85136,0.51508,0.37853,0.81735,0.0009704,0.0009704,0.0009704
15,4246.8,0.45515,0.25584,0.88293,0.89485,0.94321,0.94822,0.84115,0.51803,0.40433,0.81875,0.0008912,0.0008912,0.0008912
16,4509.67,0.40004,0.21119,0.8626,0.91392,0.93884,0.94297,0.83674,0.5208,0.42094,0.8231,0.000812,0.000812,0.000812
17,4771.34,0.37703,0.19988,0.85195,0.90937,0.94359,0.94351,0.83788,0.52937,0.41134,0.82689,0.0007328,0.0007328,0.0007328
18,5032.84,0.35892,0.19194,0.84558,0.90822,0.93263,0.93177,0.82919,0.52888,0.46293,0.8317,0.0006536,0.0006536,0.0006536
19,5294.47,0.34436,0.18312,0.84155,0.91178,0.93976,0.9361,0.83365,0.52819,0.43623,0.83142,0.0005744,0.0005744,0.0005744
20,5556.06,0.3276,0.17687,0.83577,0.9108,0.9393,0.9371,0.83403,0.52633,0.4396,0.83187,0.0004952,0.0004952,0.0004952
21,5817.69,0.31108,0.16883,0.83093,0.91184,0.93631,0.93389,0.83055,0.52741,0.45089,0.83429,0.000416,0.000416,0.000416
22,6079.32,0.29764,0.1618,0.8259,0.91338,0.93828,0.93298,0.83033,0.52668,0.4425,0.83452,0.0003368,0.0003368,0.0003368
23,6340.95,0.28511,0.15486,0.82229,0.91827,0.93003,0.9306,0.82773,0.52781,0.47135,0.8384,0.0002576,0.0002576,0.0002576
24,6602.43,0.27296,0.14872,0.81929,0.91692,0.92886,0.93197,0.82858,0.52829,0.48239,0.83885,0.0001784,0.0001784,0.0001784
25,6864.01,0.26224,0.14304,0.81588,0.91716,0.93172,0.93469,0.83199,0.52728,0.48326,0.84022,9.92e-05,9.92e-05,9.92e-05
1 epoch time train/box_loss train/cls_loss train/dfl_loss metrics/precision(B) metrics/recall(B) metrics/mAP50(B) metrics/mAP50-95(B) val/box_loss val/cls_loss val/dfl_loss lr/pg0 lr/pg1 lr/pg2
2 1 506.754 0.69773 0.6443 0.98677 0.85746 0.90067 0.95602 0.81969 0.57211 0.44531 0.84271 0.000665995 0.000665995 0.000665995
3 2 775.31 0.67191 0.46142 0.96903 0.89594 0.91124 0.96492 0.83347 0.56171 0.43418 0.84033 0.00127989 0.00127989 0.00127989
4 3 1042.43 0.64879 0.43295 0.95724 0.89927 0.92376 0.97455 0.84793 0.53096 0.3909 0.82332 0.00184098 0.00184098 0.00184098
5 4 1309.29 0.63499 0.41484 0.94974 0.8901 0.90711 0.96519 0.83708 0.53559 0.41364 0.82635 0.0017624 0.0017624 0.0017624
6 5 1576.24 0.6194 0.39346 0.94417 0.92455 0.92984 0.97784 0.85866 0.51774 0.35537 0.81741 0.0016832 0.0016832 0.0016832
7 6 1843.45 0.60151 0.37385 0.93784 0.89506 0.93742 0.96631 0.83846 0.55381 0.38597 0.82555 0.001604 0.001604 0.001604
8 7 2110.63 0.58751 0.35579 0.93003 0.90571 0.9501 0.97622 0.86446 0.51076 0.3642 0.8146 0.0015248 0.0015248 0.0015248
9 8 2377.57 0.57208 0.34024 0.92507 0.90235 0.93492 0.9714 0.86352 0.50438 0.35819 0.81116 0.0014456 0.0014456 0.0014456
10 9 2644.65 0.55947 0.32402 0.91929 0.91572 0.94436 0.97664 0.87084 0.49431 0.34051 0.80756 0.0013664 0.0013664 0.0013664
11 10 2911.65 0.54281 0.31078 0.91366 0.91424 0.93562 0.9652 0.86171 0.4887 0.38716 0.80484 0.0012872 0.0012872 0.0012872
12 11 3178.42 0.52475 0.29805 0.90675 0.90982 0.9442 0.96658 0.86221 0.49884 0.37786 0.80951 0.001208 0.001208 0.001208
13 12 3445.37 0.50654 0.28378 0.90022 0.91695 0.94206 0.96273 0.85841 0.50642 0.37648 0.81476 0.0011288 0.0011288 0.0011288
14 13 3712.44 0.48918 0.27473 0.89372 0.91413 0.9375 0.961 0.85692 0.51257 0.38685 0.81386 0.0010496 0.0010496 0.0010496
15 14 3979.6 0.47069 0.26422 0.88725 0.91369 0.94444 0.96014 0.85136 0.51508 0.37853 0.81735 0.0009704 0.0009704 0.0009704
16 15 4246.8 0.45515 0.25584 0.88293 0.89485 0.94321 0.94822 0.84115 0.51803 0.40433 0.81875 0.0008912 0.0008912 0.0008912
17 16 4509.67 0.40004 0.21119 0.8626 0.91392 0.93884 0.94297 0.83674 0.5208 0.42094 0.8231 0.000812 0.000812 0.000812
18 17 4771.34 0.37703 0.19988 0.85195 0.90937 0.94359 0.94351 0.83788 0.52937 0.41134 0.82689 0.0007328 0.0007328 0.0007328
19 18 5032.84 0.35892 0.19194 0.84558 0.90822 0.93263 0.93177 0.82919 0.52888 0.46293 0.8317 0.0006536 0.0006536 0.0006536
20 19 5294.47 0.34436 0.18312 0.84155 0.91178 0.93976 0.9361 0.83365 0.52819 0.43623 0.83142 0.0005744 0.0005744 0.0005744
21 20 5556.06 0.3276 0.17687 0.83577 0.9108 0.9393 0.9371 0.83403 0.52633 0.4396 0.83187 0.0004952 0.0004952 0.0004952
22 21 5817.69 0.31108 0.16883 0.83093 0.91184 0.93631 0.93389 0.83055 0.52741 0.45089 0.83429 0.000416 0.000416 0.000416
23 22 6079.32 0.29764 0.1618 0.8259 0.91338 0.93828 0.93298 0.83033 0.52668 0.4425 0.83452 0.0003368 0.0003368 0.0003368
24 23 6340.95 0.28511 0.15486 0.82229 0.91827 0.93003 0.9306 0.82773 0.52781 0.47135 0.8384 0.0002576 0.0002576 0.0002576
25 24 6602.43 0.27296 0.14872 0.81929 0.91692 0.92886 0.93197 0.82858 0.52829 0.48239 0.83885 0.0001784 0.0001784 0.0001784
26 25 6864.01 0.26224 0.14304 0.81588 0.91716 0.93172 0.93469 0.83199 0.52728 0.48326 0.84022 9.92e-05 9.92e-05 9.92e-05

Binary file not shown.

Before

Width:  |  Height:  |  Size: 328 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 634 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 600 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 485 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 562 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 525 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 648 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 635 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 810 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 510 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 592 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 504 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 599 KiB

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

View File

@@ -1,107 +0,0 @@
task: detect
mode: train
model: yolo11x.pt
data: dataset_pecan.yaml
epochs: 300
time: null
patience: 100
batch: 8
imgsz: 640
save: true
save_period: -1
cache: false
device: mps
workers: 0
project: null
name: train8
exist_ok: false
pretrained: true
optimizer: auto
verbose: true
seed: 0
deterministic: true
single_cls: false
rect: false
cos_lr: false
close_mosaic: 10
resume: false
amp: true
fraction: 1.0
profile: false
freeze: null
multi_scale: false
overlap_mask: true
mask_ratio: 4
dropout: 0.0
val: true
split: val
save_json: false
save_hybrid: false
conf: null
iou: 0.7
max_det: 300
half: false
dnn: false
plots: true
source: null
vid_stride: 1
stream_buffer: false
visualize: false
augment: false
agnostic_nms: false
classes: null
retina_masks: false
embed: null
show: false
save_frames: false
save_txt: false
save_conf: false
save_crop: false
show_labels: true
show_conf: true
show_boxes: true
line_width: null
format: torchscript
keras: false
optimize: false
int8: false
dynamic: false
simplify: true
opset: null
workspace: 4
nms: false
lr0: 0.01
lrf: 0.01
momentum: 0.937
weight_decay: 0.0005
warmup_epochs: 3.0
warmup_momentum: 0.8
warmup_bias_lr: 0.1
box: 7.5
cls: 0.5
dfl: 1.5
pose: 12.0
kobj: 1.0
label_smoothing: 0.0
nbs: 64
hsv_h: 0.015
hsv_s: 0.7
hsv_v: 0.4
degrees: 0.0
translate: 0.1
scale: 0.5
shear: 0.0
perspective: 0.0
flipud: 0.0
fliplr: 0.5
bgr: 0.0
mosaic: 1.0
mixup: 0.0
copy_paste: 0.0
copy_paste_mode: flip
auto_augment: randaugment
erasing: 0.4
crop_fraction: 1.0
cfg: null
tracker: botsort.yaml
save_dir: runs/detect/train8

Binary file not shown.

Before

Width:  |  Height:  |  Size: 142 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 228 KiB

View File

@@ -1,8 +0,0 @@
epoch,time,train/box_loss,train/cls_loss,train/dfl_loss,metrics/precision(B),metrics/recall(B),metrics/mAP50(B),metrics/mAP50-95(B),val/box_loss,val/cls_loss,val/dfl_loss,lr/pg0,lr/pg1,lr/pg2
1,1025.83,0.66603,0.70931,1.00467,0.79126,0.62088,0.63578,0.55598,0.53711,1.12546,0.61646,0.0033218,0.0033218,0.0033218
2,2234.46,0.67875,0.56064,0.97946,0.73778,0.22965,0.24951,0.20692,0.70498,1.24004,0.63871,0.00663317,0.00663317,0.00663317
3,3567.29,0.74777,0.60717,1.01042,0.78896,0.28977,0.31317,0.25897,0.68661,1.33028,0.66244,0.00992254,0.00992254,0.00992254
4,4924.91,0.75061,0.5652,1.02254,0.81885,0.49061,0.52847,0.44662,0.60725,1.0302,0.63908,0.009901,0.009901,0.009901
5,6311.84,0.71113,0.53651,1.01557,0.797,0.85082,0.87202,0.72871,0.61414,1.01847,0.63901,0.009868,0.009868,0.009868
6,7752.74,0.69393,0.50972,1.00952,0.83906,0.84134,0.89616,0.7712,0.55075,0.96689,0.61902,0.009835,0.009835,0.009835
7,10111.6,0.67585,0.49999,1.00538,0.85073,0.31173,0.35275,0.30764,0.5542,1.94607,0.62021,0.009802,0.009802,0.009802
1 epoch time train/box_loss train/cls_loss train/dfl_loss metrics/precision(B) metrics/recall(B) metrics/mAP50(B) metrics/mAP50-95(B) val/box_loss val/cls_loss val/dfl_loss lr/pg0 lr/pg1 lr/pg2
2 1 1025.83 0.66603 0.70931 1.00467 0.79126 0.62088 0.63578 0.55598 0.53711 1.12546 0.61646 0.0033218 0.0033218 0.0033218
3 2 2234.46 0.67875 0.56064 0.97946 0.73778 0.22965 0.24951 0.20692 0.70498 1.24004 0.63871 0.00663317 0.00663317 0.00663317
4 3 3567.29 0.74777 0.60717 1.01042 0.78896 0.28977 0.31317 0.25897 0.68661 1.33028 0.66244 0.00992254 0.00992254 0.00992254
5 4 4924.91 0.75061 0.5652 1.02254 0.81885 0.49061 0.52847 0.44662 0.60725 1.0302 0.63908 0.009901 0.009901 0.009901
6 5 6311.84 0.71113 0.53651 1.01557 0.797 0.85082 0.87202 0.72871 0.61414 1.01847 0.63901 0.009868 0.009868 0.009868
7 6 7752.74 0.69393 0.50972 1.00952 0.83906 0.84134 0.89616 0.7712 0.55075 0.96689 0.61902 0.009835 0.009835 0.009835
8 7 10111.6 0.67585 0.49999 1.00538 0.85073 0.31173 0.35275 0.30764 0.5542 1.94607 0.62021 0.009802 0.009802 0.009802

Binary file not shown.

Before

Width:  |  Height:  |  Size: 431 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 402 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 436 KiB

View File

@@ -1,8 +0,0 @@
from ultralytics import YOLO
import torch
device = torch.device('cuda')
# device = 'cpu'
model = YOLO('yolo11s.pt')
model.train(data='./yolov11-pecan/data.yaml',device=device,batch=20,epochs=25,workers=16, imgsz = 1280)