运行该项目需要准备树莓派5和嘉立创K230,K230通过USB和树莓派5连接,树莓派5的系统下载官方原版。机器上电前,需要把三个轴都移动到初始位置。
需要协助,请带鄂应院身份证明到b站找'天月风沙'
一、嘉立创K230主程序如下所示
保存为main.py(应该不用我来教),运行的是yolo11,嘉立创K230要加钱买那个可以变焦的摄像头和配套屏幕
from libs.PipeLine import PipeLine
from libs.YOLO import YOLO11
from libs.Utils import *
import os,sys,gc
import ulab.numpy as np
import image
if __name__=="__main__":
# 这里仅为示例,自定义场景请修改为您自己的模型路径、标签名称、模型输入大小
kmodel_path="/sdcard/best.kmodel"
labels = ["relay","openmv","dcdc","motor","stm32","oled","ultrasound","servo","battery","stc51"]
model_input_size=[320,320]
# 添加显示模式,默认hdmi,可选hdmi/lcd/lt9611/st7701/hx8399/nt35516,其中hdmi默认置为lt9611,分辨率1920*1080;lcd默认置为st7701,分辨率800*480
display_mode="lcd"
rgb888p_size=[640,360]
confidence_threshold = 0.35
nms_threshold=0.45
# 初始化PipeLine
pl=PipeLine(rgb888p_size=rgb888p_size,display_mode=display_mode)
pl.create()
display_size=pl.get_display_size()
# 初始化YOLO11实例
yolo=YOLO11(task_type="detect",mode="video",kmodel_path=kmodel_path,labels=labels,rgb888p_size=rgb888p_size,model_input_size=model_input_size,display_size=display_size,conf_thresh=confidence_threshold,nms_thresh=nms_threshold,max_boxes_num=50,debug_mode=0)
yolo.config_preprocess()
while True:
with ScopedTiming("total",1):
# 逐帧推理
img=pl.get_frame()
res=yolo.run(img)
# 提取并打印标签名称(简单文本格式)
if res and len(res) >= 2:
class_indices = res[1] # 获取类别索引
detected_labels = [labels[idx] for idx in class_indices] # 转换为标签名称
# 将列表转换为逗号分隔的字符串
if detected_labels:
output_str = ", ".join(detected_labels)
print(output_str)
else:
print("No detection")
yolo.draw_result(res,pl.osd_img)
pl.show_image()
gc.collect()
yolo.deinit()
pl.destroy()
"""
# 立创·庐山派-K230-CanMV开发板资料与相关扩展板软硬件资料官网全部开源
# 开发板官网:www.lckfb.com
# 技术支持常驻论坛,任何技术问题欢迎随时交流学习
# 立创论坛:www.jlc-bbs.com/lckfb
# 关注bilibili账号:【立创开发板】,掌握我们的最新动态!
# 不靠卖板赚钱,以培养中国工程师为己任
import time, os, sys
#使用默认摄像头,可选参数:0,1,2.
sensor_id = 2
# ========== 多媒体/图像相关模块 ==========
from media.sensor import Sensor, CAM_CHN_ID_0
from media.display import Display
from media.media import MediaManager
import image
# ========== GPIO/按键/LED相关模块 ==========
from machine import Pin
from machine import FPIOA
# ========== 创建FPIOA对象并为引脚功能分配 ==========
fpioa = FPIOA()
fpioa.set_function(62, FPIOA.GPIO62) # 红灯
fpioa.set_function(20, FPIOA.GPIO20) # 绿灯
fpioa.set_function(63, FPIOA.GPIO63) # 蓝灯
fpioa.set_function(53, FPIOA.GPIO53) # 按键
# ========== 初始化LED (共阳:高电平熄灭,低电平亮) ==========
LED_R = Pin(62, Pin.OUT, pull=Pin.PULL_NONE, drive=7) # 红灯
LED_G = Pin(20, Pin.OUT, pull=Pin.PULL_NONE, drive=7) # 绿灯
LED_B = Pin(63, Pin.OUT, pull=Pin.PULL_NONE, drive=7) # 蓝灯
# 默认熄灭所有LED
LED_R.high()
LED_G.high()
LED_B.high()
# 选一个LED用来拍照提示
PHOTO_LED = LED_G
# ========== 初始化按键:按下时高电平 ==========
button = Pin(53, Pin.IN, Pin.PULL_DOWN)
debounce_delay = 200 # 按键消抖时长(ms)
last_press_time = 0
button_last_state = 0
# ========== 显示配置 ==========
DISPLAY_MODE = "LCD" # 可选:"VIRT","LCD","HDMI"
if DISPLAY_MODE == "VIRT":
DISPLAY_WIDTH = 1920
DISPLAY_HEIGHT = 1080
FPS = 30
elif DISPLAY_MODE == "LCD":
DISPLAY_WIDTH = 800
DISPLAY_HEIGHT = 480
FPS = 60
elif DISPLAY_MODE == "HDMI":
DISPLAY_WIDTH = 1920
DISPLAY_HEIGHT = 1080
FPS = 30
else:
raise ValueError("未知的 DISPLAY_MODE,请选择 'VIRT', 'LCD' 或 'HDMI'")
def lckfb_save_jpg(img, filename, quality=95):
compressed_data = img.compress(quality=quality)
with open(filename, "wb") as f:
f.write(compressed_data)
print(f"[INFO] 使用 lckfb_save_jpg() 保存完毕: {filename}")
# ========== 自动创建图片保存文件夹 & 计算已有图片数量 ==========
image_folder = "/sdcard/images"
# 若不存在该目录则创建
try:
os.stat(image_folder) # 尝试获取目录信息
except OSError:
os.mkdir(image_folder) # 若失败则创建该目录
# 统计当前目录下以 "lckfb_XX.jpg" 命名的文件数量,自动从最大编号继续
image_count = 0
existing_images = [fname for fname in os.listdir(image_folder)
if fname.startswith("lckfb_") and fname.endswith(".jpg")]
if existing_images:
# 提取编号并找出最大值
numbers = []
for fname in existing_images:
# 假设文件名格式为 "lckfb_XX.jpg"
# 取中间 XX 部分转为数字
try:
num_part = fname[6:11] # "lckfb_" 长度为6,取到 ".jpg" 前还要注意下标
numbers.append(int(num_part))
except:
pass
if numbers:
image_count = max(numbers)
try:
print("[INFO] 初始化摄像头 ...")
sensor = Sensor(id=sensor_id)
sensor.reset()
# 在本示例中使用 VGA (640x480) 做演示
sensor.set_framesize(width=DISPLAY_WIDTH, height=DISPLAY_HEIGHT, chn=CAM_CHN_ID_0)
sensor.set_pixformat(Sensor.RGB565, chn=CAM_CHN_ID_0)
# ========== 初始化显示 ==========
if DISPLAY_MODE == "VIRT":
Display.init(Display.VIRT, width=DISPLAY_WIDTH, height=DISPLAY_HEIGHT, fps=FPS)
elif DISPLAY_MODE == "LCD":
Display.init(Display.ST7701, width=DISPLAY_WIDTH, height=DISPLAY_HEIGHT, to_ide=True)
elif DISPLAY_MODE == "HDMI":
Display.init(Display.LT9611, width=DISPLAY_WIDTH, height=DISPLAY_HEIGHT, to_ide=True)
# ========== 初始化媒体管理器 ==========
MediaManager.init()
# ========== 启动摄像头 ==========
sensor.run()
print("[INFO] 摄像头已启动,进入主循环 ...")
fps = time.clock()
while True:
fps.tick()
os.exitpoint()
#抓取通道0的图像
img = sensor.snapshot(chn=CAM_CHN_ID_0)
#按键处理(检测上升沿)
current_time = time.ticks_ms()
button_state = button.value()
if button_state == 1 and button_last_state == 0: # 上升沿
if current_time - last_press_time > debounce_delay:
# LED闪烁提示
PHOTO_LED.low() # 点亮LED
time.sleep_ms(20)
PHOTO_LED.high() # 熄灭LED
# 拍照并保存
image_count += 1
filename = f"{image_folder}/lckfb_{image_count:05d}_{img.width()}x{img.height()}.jpg"
print(f"[INFO] 拍照保存 -> {filename}")
# 直接调用自定义的 lckfb_save_jpg() 函数
lckfb_save_jpg(img, filename, quality=95)
last_press_time = current_time
button_last_state = button_state
img.draw_string_advanced(0, 0, 32, str(image_count), color=(255, 0, 0))
img.draw_string_advanced(0, DISPLAY_HEIGHT-32, 32, str(fps.fps()), color=(255, 0, 0))
Display.show_image(img)
except KeyboardInterrupt:
print("[INFO] 用户停止")
except BaseException as e:
print(f"[ERROR] 出现异常: {e}")
finally:
if 'sensor' in locals() and isinstance(sensor, Sensor):
sensor.stop()
Display.deinit()
os.exitpoint(os.EXITPOINT_ENABLE_SLEEP)
time.sleep_ms(100)
MediaManager.deinit()
"""
二、树莓派5显示本地数据
新建终端,需要先执行这个程序。这个程序和下一个程序需要在同一个文件夹里面,这很重要
import json
import time
import tkinter as tk
from tkinter import ttk
import os
from pathlib import Path
class JSONMonitor:
def __init__(self, root, json_path):
self.root = root
self.json_path = Path(json_path)
self.root.title("JSON数据实时监控")
self.root.geometry("750x600") # 调整窗口大小
# 设置窗口样式
self.root.configure(bg='#f0f0f0')
# 创建标题(固定高度)
title_frame = tk.Frame(self.root, bg='#f0f0f0', height=50)
title_frame.pack(fill=tk.X, pady=(10, 0))
title_frame.pack_propagate(False) # 固定高度
title_label = tk.Label(
title_frame,
text="数据实时监控",
font=("微软雅黑", 16, "bold"),
bg='#f0f0f0',
fg='#333333'
)
title_label.pack(expand=True)
# 创建主框架(可扩展)
main_frame = tk.Frame(self.root, bg='#f0f0f0')
main_frame.pack(fill=tk.BOTH, expand=True, padx=20, pady=10)
# 创建Treeview表格
columns = ('field', 'cn_name', 'value')
self.tree = ttk.Treeview(
main_frame,
columns=columns,
show='headings',
selectmode='none'
)
# 设置列标题
self.tree.heading('field', text='字段名')
self.tree.heading('cn_name', text='中文描述')
self.tree.heading('value', text='数值')
# 设置列宽(等宽分布)
total_width = 700 # 总宽度减去滚动条宽度
col_width = total_width // 3
self.tree.column('field', width=col_width, anchor='center', minwidth=150)
self.tree.column('cn_name', width=col_width, anchor='center', minwidth=150)
self.tree.column('value', width=col_width, anchor='center', minwidth=150)
# 添加滚动条
vsb = ttk.Scrollbar(main_frame, orient=tk.VERTICAL, command=self.tree.yview)
hsb = ttk.Scrollbar(main_frame, orient=tk.HORIZONTAL, command=self.tree.xview)
self.tree.configure(yscrollcommand=vsb.set, xscrollcommand=hsb.set)
# 布局 - 使用grid并设置权重
main_frame.grid_rowconfigure(0, weight=1)
main_frame.grid_columnconfigure(0, weight=1)
self.tree.grid(row=0, column=0, sticky='nsew')
vsb.grid(row=0, column=1, sticky='ns')
hsb.grid(row=1, column=0, sticky='ew')
# 设置表格样式
style = ttk.Style()
style.theme_use('default')
style.configure("Treeview",
background="#ffffff",
foreground="#000000",
rowheight=30,
fieldbackground="#ffffff",
borderwidth=1,
relief='solid',
font=('微软雅黑', 10))
style.configure("Treeview.Heading",
background="#4a7a9c",
foreground="white",
relief="raised",
font=('微软雅黑', 10, 'bold'),
borderwidth=2)
style.map("Treeview.Heading",
background=[('active', '#5a8aac')])
style.map("Treeview",
background=[('selected', '#ffffff')],
foreground=[('selected', '#000000')])
# 配置标签颜色
self.tree.tag_configure('normal', foreground='#27ae60', font=('微软雅黑', 10, 'bold'))
self.tree.tag_configure('abnormal', foreground='#e74c3c', font=('微软雅黑', 10, 'bold'))
self.tree.tag_configure('voltage', foreground='#2980b9', font=('微软雅黑', 10, 'bold'))
self.tree.tag_configure('default', foreground='#34495e', font=('微软雅黑', 10))
# 交替行颜色
self.tree.tag_configure('oddrow', background='#f8f9fa')
self.tree.tag_configure('evenrow', background='#ffffff')
# 创建状态栏(固定高度)
status_frame = tk.Frame(self.root, bg='#333333', height=40)
status_frame.pack(fill=tk.X, side=tk.BOTTOM)
status_frame.pack_propagate(False) # 固定高度
# 状态栏内部布局
status_inner = tk.Frame(status_frame, bg='#333333')
status_inner.pack(fill=tk.BOTH, expand=True, padx=10)
# 文件路径显示(左)
self.file_label = tk.Label(
status_inner,
text=f"📁 {os.path.basename(str(self.json_path))}",
font=("微软雅黑", 9),
bg='#333333',
fg='#cccccc'
)
self.file_label.pack(side=tk.LEFT)
# 状态显示(左)
self.status_label = tk.Label(
status_inner,
text="⏳ 等待读取...",
font=("微软雅黑", 9, "bold"),
bg='#333333',
fg='white'
)
self.status_label.pack(side=tk.LEFT, padx=20)
# 数据统计(右)
self.stats_label = tk.Label(
status_inner,
text="数据行数: 0",
font=("微软雅黑", 9),
bg='#333333',
fg='#cccccc'
)
self.stats_label.pack(side=tk.RIGHT, padx=10)
# 最后更新时间(右)
self.last_update_label = tk.Label(
status_inner,
text="更新: --",
font=("微软雅黑", 9),
bg='#333333',
fg='#cccccc'
)
self.last_update_label.pack(side=tk.RIGHT, padx=10)
# 中文字段映射
self.field_names_cn = {
'one': 'openmv数量',
'two': '继电器',
'three': '电压转换',
'four': '电机',
'five': 'stm32开发板',
'six': 'oled屏幕',
'seven': '超声波模块',
'eight': 'pwm舵机',
'nine': '电池' ,
'ten': 'stc51',
'state': '状态',
'CurrentVoltage': '当前电压'
}
# 定义字段显示顺序
self.field_order = [
'one', 'two', 'three', 'four', 'five',
'six', 'seven', 'eight', 'nine', 'ten',
'state', 'CurrentVoltage'
]
# 启动监控
self.update_data()
def update_data(self):
"""更新数据"""
try:
# 读取JSON文件
if self.json_path.exists():
with open(self.json_path, 'r', encoding='utf-8') as f:
data = json.load(f)
# 清空现有数据
for item in self.tree.get_children():
self.tree.delete(item)
# 按顺序添加数据
row_count = 0
for i, key in enumerate(self.field_order):
if key in data:
value = data[key]
cn_name = self.field_names_cn.get(key, key)
# 格式化数值
if key == 'CurrentVoltage' and isinstance(value, (int, float)):
display_value = f"{value:.2f} V"
else:
display_value = str(value)
# 确定标签
tags = []
# 添加行颜色
if i % 2 == 0:
tags.append('evenrow')
else:
tags.append('oddrow')
# 根据值设置标签颜色
if key == 'state':
if value == '正常':
tags.append('normal')
else:
tags.append('abnormal')
elif key == 'CurrentVoltage':
tags.append('voltage')
else:
tags.append('default')
# 插入数据
self.tree.insert('', tk.END, values=(key, cn_name, display_value), tags=tags)
row_count += 1
# 如果没有数据,显示提示
if row_count == 0:
self.tree.insert('', tk.END, values=('无数据', '无数据', '无数据'), tags=('default',))
row_count = 1
# 更新状态
current_time = time.strftime("%H:%M:%S")
self.last_update_label.config(text=f"更新: {current_time}")
self.status_label.config(text="✅ 监控中", fg='#2ecc71')
self.stats_label.config(text=f"数据行数: {row_count}")
else:
# 文件不存在,显示提示
for item in self.tree.get_children():
self.tree.delete(item)
self.tree.insert('', tk.END, values=('错误', '文件不存在', str(self.json_path)), tags=('abnormal',))
self.status_label.config(text=f"❌ 文件不存在", fg='#e74c3c')
self.stats_label.config(text="数据行数: 0")
except json.JSONDecodeError as e:
# JSON解析错误
for item in self.tree.get_children():
self.tree.delete(item)
self.tree.insert('', tk.END, values=('错误', 'JSON解析错误', str(e)), tags=('abnormal',))
self.status_label.config(text=f"❌ JSON解析错误", fg='#e74c3c')
except Exception as e:
# 其他错误
for item in self.tree.get_children():
self.tree.delete(item)
self.tree.insert('', tk.END, values=('错误', '未知错误', str(e)), tags=('abnormal',))
self.status_label.config(text=f"❌ 错误", fg='#e74c3c')
# 设置下一次更新(每1000ms = 1秒)
self.root.after(1000, self.update_data)
def main():
# JSON文件路径 - 请修改为你的文件路径
json_file_path = "device_data.json"
# 确保使用绝对路径
json_file_path = os.path.abspath(json_file_path)
print(f"监控文件路径: {json_file_path}")
# 创建测试JSON文件(如果不存在)
if not os.path.exists(json_file_path):
test_data = {
"one": "0",
"two": "0",
"three": "0",
"four": "0",
"five": "0",
"six": "0",
"seven": "0",
"eight": "0",
"nine": "0",
"ten": "0",
"state": "正常",
"CurrentVoltage": 12.29
}
try:
with open(json_file_path, 'w', encoding='utf-8') as f:
json.dump(test_data, f, ensure_ascii=False, indent=2)
print(f"已创建测试文件: {json_file_path}")
except Exception as e:
print(f"创建测试文件失败: {e}")
# 创建主窗口
root = tk.Tk()
app = JSONMonitor(root, json_file_path)
# 设置最小窗口大小
root.minsize(600, 400)
# 运行主循环
root.mainloop()
if __name__ == "__main__":
main()
三、树莓派5主程序
新建一个终端后执行,里面的PRODUCT_KEY为了避免浪费我的钱。需要的请来B站找我
import serial
import time
import threading
from queue import Queue
import os
import json
import hmac
import hashlib
import paho.mqtt.client as mqtt
import random
# ================= 舵机控制相关定义 =================
# 字节操作宏函数
def GET_LOW_BYTE(A): return (A) & 0xFF
def GET_HIGH_BYTE(A): return ((A) >> 8) & 0xFF
def BYTE_TO_HW(A, B): return ((A << 8) | B)
# 舵机ID
ID_ALL = 254
LOBOT_SERVO_FRAME_HEADER = 0x55
# 指令类型
LOBOT_SERVO_MOVE_TIME_WRITE = 1
LOBOT_SERVO_POS_READ = 28
LOBOT_SERVO_VIN_READ = 27
LOBOT_SERVO_TEMP_READ = 26
LOBOT_SERVO_LOAD_OR_UNLOAD_WRITE = 31
# ================= 设备配置 =================
PRODUCT_KEY = "请带身份证明到b站找'天月风沙'"
DEVICE_NAME = "device_one"
DEVICE_SECRET = "9e9d06c631e7068770d3e5b06f707002"
REGION_ID = "cn-shanghai"
HOST = f"{PRODUCT_KEY}.iot-as-mqtt.{REGION_ID}.aliyuncs.com"
PUB_TOPIC = f"/{PRODUCT_KEY}/{DEVICE_NAME}/user/data"
PUB_TOPIC2 = f"/sys/{PRODUCT_KEY}/{DEVICE_NAME}/thing/event/property/post"
# 全局串口对象
receive_ser = None
send_ser = None
servo_ser = None # 舵机专用串口
# 接收队列
receive_queue = Queue()
# 控制标志
is_ready_for_new_command = True
current_command = None
last_command_time = 0
cooldown_period = 5
# ================= 数据文件配置 =================
DATA_FILE = "device_data.json"
# ================= 数据管理器类 =================
class DataManager:
def __init__(self, data_file=DATA_FILE):
self.data_file = data_file
self.default_data = {
"one": "0", "two": "0", "three": "0", "four": "0", "five": "0",
"six": "0", "seven": "0", "eight": "0", "nine": "0", "ten": "0",
"state": "正常", "CurrentVoltage": 0.0
}
self.current_data = self.load_data()
def load_data(self):
try:
if os.path.exists(self.data_file):
with open(self.data_file, 'r', encoding='utf-8') as f:
data = json.load(f)
for key in self.default_data:
if key not in data:
data[key] = self.default_data[key]
return data
else:
return self.default_data.copy()
except Exception as e:
print(f"❌ 加载数据文件失败: {e}")
return self.default_data.copy()
def save_data(self):
try:
with open(self.data_file, 'w', encoding='utf-8') as f:
json.dump(self.current_data, f, ensure_ascii=False, indent=2)
return True
except Exception as e:
print(f"❌ 保存数据失败: {e}")
return False
def set_value(self, field_name, value):
if field_name in self.current_data:
self.current_data[field_name] = value
self.save_data()
return self.current_data
return None
def get_current_data(self):
return self.current_data.copy()
def print_current_data(self):
print("📊 当前数据状态:")
for key, value in self.current_data.items():
print(f" {key}: {value}")
data_manager = DataManager()
# ================= MQTT 相关函数 =================
def generate_mqtt_params():
timestamp = str(int(time.time() * 1000))
client_id = f"{DEVICE_NAME}|securemode=3,signmethod=hmacsha256,timestamp={timestamp}|"
username = f"{DEVICE_NAME}&{PRODUCT_KEY}"
content = (
"clientId" + DEVICE_NAME +
"deviceName" + DEVICE_NAME +
"productKey" + PRODUCT_KEY +
"timestamp" + timestamp
)
password = hmac.new(
DEVICE_SECRET.encode(),
content.encode(),
hashlib.sha256
).hexdigest()
return client_id, username, password
def on_connect(client, userdata, flags, rc):
if rc == 0:
print("✅ MQTT 连接成功")
else:
print(f"❌ MQTT 连接失败,代码: {rc}")
def send_data(client, data):
client.publish(PUB_TOPIC, json.dumps(data), qos=1)
# 物模型格式
payload_wumoxin = {
"id": int(time.time()),
"version": "1.0",
"params": data,
"method": "thing.event.property.post"
}
client.publish(PUB_TOPIC2, json.dumps(payload_wumoxin), qos=1)
cid, user, pwd = generate_mqtt_params()
client = mqtt.Client(client_id=cid)
client.username_pw_set(user, pwd)
client.on_connect = on_connect
try:
client.connect(HOST, 1883, 60)
client.loop_start()
time.sleep(2)
print("🚀 MQTT 客户端已启动")
except Exception as e:
print(f"⚠️ MQTT 启动失败 (可能是网络问题): {e}")
# ================= 舵机控制类 =================
class LobotSerialServo:
def __init__(self, port='/dev/ttyAMA0', baudrate=115200, timeout=0.1):
self.ser = None
self.port = port
self.baudrate = baudrate
self.timeout = timeout
def connect(self):
try:
self.ser = serial.Serial(
port=self.port,
baudrate=self.baudrate,
timeout=self.timeout
)
print(f"✅ 舵机串口已连接到 {self.port}")
return True
except Exception as e:
print(f"❌ 舵机串口连接失败: {e}")
return False
def disconnect(self):
if self.ser and self.ser.is_open:
self.ser.close()
def _check_sum(self, buf):
temp = sum(buf[2:buf[3] + 2])
return (~temp) & 0xFF
def _send_command(self, buf):
if self.ser and self.ser.is_open:
self.ser.write(bytearray(buf))
def _receive_handle(self, length=32, timeout=0.1):
if not self.ser or not self.ser.is_open:
return None
frame_started = False
frame_count = 0
data_count = 0
data_length = 2
recv_buf = [0] * length
start_time = time.time()
while time.time() - start_time < timeout:
if self.ser.in_waiting == 0:
time.sleep(0.001)
continue
rx_byte = ord(self.ser.read(1))
if not frame_started:
if rx_byte == LOBOT_SERVO_FRAME_HEADER:
frame_count += 1
if frame_count == 2:
frame_count = 0
frame_started = True
data_count = 1
else:
frame_started = False
data_count = 0
frame_count = 0
if frame_started:
if data_count < length:
recv_buf[data_count] = rx_byte
if data_count == 3:
data_length = recv_buf[data_count]
if data_length < 3 or data_length > 7:
data_length = 2
frame_started = False
data_count += 1
if data_count == data_length + 3:
if data_count <= length and self._check_sum(recv_buf[:data_count]) == recv_buf[data_count - 1]:
return recv_buf[4:data_count - 1]
return None
return None
def _send_and_receive(self, buf, timeout=0.1):
if self.ser and self.ser.in_waiting > 0:
self.ser.read(self.ser.in_waiting)
self._send_command(buf)
time.sleep(0.01)
return self._receive_handle(timeout=timeout)
def read_voltage(self, servo_id=1):
"""读取舵机电压"""
buf = [0] * 6
buf[0] = buf[1] = LOBOT_SERVO_FRAME_HEADER
buf[2] = servo_id
buf[3] = 3
buf[4] = LOBOT_SERVO_VIN_READ
buf[5] = self._check_sum(buf)
response = self._send_and_receive(buf, timeout=0.2)
if response and len(response) >= 3:
voltage_mv = BYTE_TO_HW(response[2], response[1])
return voltage_mv / 1000.0 # 转换为伏特
return None
def read_position(self, servo_id=1):
buf = [0] * 6
buf[0] = buf[1] = LOBOT_SERVO_FRAME_HEADER
buf[2] = servo_id
buf[3] = 3
buf[4] = LOBOT_SERVO_POS_READ
buf[5] = self._check_sum(buf)
response = self._send_and_receive(buf, timeout=0.2)
return BYTE_TO_HW(response[2], response[1]) if response and len(response) >= 3 else None
def move(self, servo_id, position, move_time=1000):
position = max(0, min(1000, position))
buf = [0] * 10
buf[0] = buf[1] = LOBOT_SERVO_FRAME_HEADER
buf[2] = servo_id
buf[3] = 7
buf[4] = LOBOT_SERVO_MOVE_TIME_WRITE
buf[5] = GET_LOW_BYTE(position)
buf[6] = GET_HIGH_BYTE(position)
buf[7] = GET_LOW_BYTE(move_time)
buf[8] = GET_HIGH_BYTE(move_time)
buf[9] = self._check_sum(buf)
self._send_command(buf)
# ================= 串口初始化 =================
def init_receive_serial():
global receive_ser
try:
receive_ser = serial.Serial(
port='/dev/ttyACM0', baudrate=115200,
bytesize=serial.EIGHTBITS, parity=serial.PARITY_NONE,
stopbits=serial.STOPBITS_ONE, timeout=0.1
)
print("📥 接收串口 (/dev/ttyACM0) 初始化成功")
return True
except Exception as e:
print(f"❌ 接收串口初始化失败: {e}")
return False
def init_send_serial():
global send_ser
try:
send_ser = serial.Serial(
port='/dev/ttyAMA0', baudrate=115200,
bytesize=serial.EIGHTBITS, parity=serial.PARITY_NONE,
stopbits=serial.STOPBITS_ONE, timeout=1
)
print("发送串口 (/dev/ttyAMA0) 初始化成功")
return True
except Exception as e:
print(f"❌ 发送串口初始化失败: {e}")
return False
def init_servo_serial():
"""初始化舵机串口"""
global servo_ser
servo_ser = LobotSerialServo(port='/dev/ttyAMA0', baudrate=115200)
return servo_ser.connect()
def send_serial_command(command):
global send_ser
command_data = {
"START": bytes([0x01, 0xf6, 0x01, 0x05, 0x01, 0x0a, 0x00, 0x6b]),
"STOP": bytes([0x01, 0xfe, 0x98, 0x00, 0x6b]),
"2Y_GO_ONE": bytes([0x02, 0xfd, 0x01, 0x00, 0x64, 0x00, 0x00, 0x00, 0x0c, 0x80, 0x00, 0x00, 0x6b]),
"2Y_BLACK_ONE": bytes([0x02, 0xfd, 0x00, 0x00, 0x64, 0x00, 0x00, 0x00, 0x0c, 0x80, 0x00, 0x00, 0x6b]),
"2Y_GO_0_5": bytes([0x02, 0xfd, 0x01, 0x00, 0x64, 0x00, 0x00, 0x00, 0x06, 0x40, 0x00, 0x00, 0x6b]),
"2Y_BLACK_0_5": bytes([0x02, 0xfd, 0x00, 0x00, 0x64, 0x00, 0x00, 0x00, 0x06, 0x40, 0x00, 0x00, 0x6b]),
"2Y_GO_5": bytes([0x02, 0xfd, 0x01, 0x00, 0x64, 0x00, 0x00, 0x00, 0x40, 0xD8, 0x00, 0x00, 0x6b]),
"2Y_BLACK_5": bytes([0x02, 0xfd, 0x00, 0x00, 0x64, 0x00, 0x00, 0x00, 0x40, 0xD8, 0x00, 0x00, 0x6b]),
"3X_LEFT_ONE": bytes([0x03, 0xfd, 0x01, 0x00, 0x64, 0x00, 0x00, 0x00, 0x0c, 0x80, 0x00, 0x00, 0x6b]),
"3X_RIGHT_ONE": bytes([0x03, 0xfd, 0x00, 0x00, 0x64, 0x00, 0x00, 0x00, 0x0c, 0x80, 0x00, 0x00, 0x6b]),
"3X_LEFT_0_5": bytes([0x03, 0xfd, 0x01, 0x00, 0x64, 0x00, 0x00, 0x00, 0x06, 0x40, 0x00, 0x00, 0x6b]),
"3X_RIGHT_0_5": bytes([0x03, 0xfd, 0x00, 0x00, 0x64, 0x00, 0x00, 0x00, 0x06, 0x40, 0x00, 0x00, 0x6b]),
"3X_LEFT_3": bytes([0x03, 0xfd, 0x01, 0x00, 0x64, 0x00, 0x00, 0x00, 0x25, 0x80, 0x00, 0x00, 0x6b]),
"3X_RIGHT_3": bytes([0x03, 0xfd, 0x00, 0x00, 0x64, 0x00, 0x00, 0x00, 0x25, 0x80, 0x00, 0x00, 0x6b]),
"3X_LEFT_3_5": bytes([0x03, 0xfd, 0x01, 0x00, 0x64, 0x00, 0x00, 0x00, 0x2A, 0xF8, 0x00, 0x00, 0x6b]),
"3X_RIGHT_3_5": bytes([0x03, 0xfd, 0x00, 0x00, 0x64, 0x00, 0x00, 0x00, 0x2A, 0xF8, 0x00, 0x00, 0x6b]),
"3X_LEFT_5_5": bytes([0x03, 0xfd, 0x01, 0x00, 0x64, 0x00, 0x00, 0x00, 0x44, 0x5C, 0x00, 0x00, 0x6b]),
"3X_RIGHT_5_5": bytes([0x03, 0xfd, 0x00, 0x00, 0x64, 0x00, 0x00, 0x00, 0x44, 0x5C, 0x00, 0x00, 0x6b]),
"4Z_UP_ONE": bytes([0x04, 0xfd, 0x00, 0x00, 0x64, 0x00, 0x00, 0x00, 0x0c, 0x80, 0x00, 0x00, 0x6b]),
"4Z_DOWN_ONE": bytes([0x04, 0xfd, 0x01, 0x00, 0x64, 0x00, 0x00, 0x00, 0x0c, 0x80, 0x00, 0x00, 0x6b]),
"4Z_UP_0_5": bytes([0x04, 0xfd, 0x00, 0x00, 0x64, 0x00, 0x00, 0x00, 0x06, 0x40, 0x00, 0x00, 0x6b]),
"4Z_DOWN_0_5": bytes([0x04, 0xfd, 0x01, 0x00, 0x64, 0x00, 0x00, 0x00, 0x06, 0x40, 0x00, 0x00, 0x6b]),
"4Z_UP_START": bytes([0x04, 0xfd, 0x00, 0x00, 0x64, 0x00, 0x00, 0x00, 0x01, 0x90, 0x00, 0x00, 0x6b]),
"4Z_UP_START_BLACK": bytes([0x04, 0xfd, 0x01, 0x00, 0x64, 0x00, 0x00, 0x00, 0x01, 0x90, 0x00, 0x00, 0x6b]),
"4Z_UP_5": bytes([0x04, 0xfd, 0x00, 0x00, 0x64, 0x00, 0x00, 0x00, 0x3E, 0x80, 0x00, 0x00, 0x6b]),
"4Z_DOWN_5": bytes([0x04, 0xfd, 0x01, 0x00, 0x64, 0x00, 0x00, 0x00, 0x3E, 0x80, 0x00, 0x00, 0x6b]),
"duoji0": bytes([0x55, 0x55, 0x01, 0x07, 0x01, 0x00, 0x00, 0xE8, 0x03, 0x0B]),
"duoji200": bytes([0x55, 0x55, 0x01, 0x07, 0x01, 0xC8, 0x00, 0xE8, 0x03, 0x43]),
"duoji250": bytes([0x55, 0x55, 0x01, 0x07, 0x01, 0xFA, 0x00, 0xE8, 0x03, 0x11]),
"duoji300": bytes([0x55, 0x55, 0x01, 0x07, 0x01, 0x2C, 0x01, 0xE8, 0x03, 0xDE]),
"duoji350": bytes([0x55, 0x55, 0x01, 0x07, 0x01, 0x5E, 0x01, 0xE8, 0x03, 0xAC]),
"duoji400": bytes([0x55, 0x55, 0x01, 0x07, 0x01, 0x90, 0x01, 0xE8, 0x03, 0x7A]),
"duoji450": bytes([0x55, 0x55, 0x01, 0x07, 0x01, 0xC6, 0x01, 0xE8, 0x03, 0x44]),
"duoji500": bytes([0x55, 0x55, 0x01, 0x07, 0x01, 0xF4, 0x01, 0xE8, 0x03, 0x16]),
}
if command not in command_data:
print(f"❌ 错误: 无效命令 '{command}'")
return False
hex_data = command_data[command]
try:
if not send_ser or not send_ser.is_open:
if not init_send_serial():
return False
print(f"🔧 发送硬件指令: {command}")
send_ser.write(hex_data)
return True
except Exception as e:
print(f"❌ 发送命令时出错: {e}")
return False
# ================= 线程函数 =================
def serial_receive_thread():
"""串口接收线程"""
global receive_ser, is_ready_for_new_command, current_command
print("🧵 [接收线程] 启动")
receive_buffer = ""
while True:
try:
if receive_ser and receive_ser.is_open:
if receive_ser.in_waiting > 0:
data = receive_ser.read(receive_ser.in_waiting)
try:
received_str = data.decode('utf-8', errors='ignore')
receive_buffer += received_str
lines = receive_buffer.split('\n')
if len(lines) > 1:
receive_buffer = lines[-1]
for line in lines[:-1]:
line = line.strip()
if line:
valid_commands = ["relay", "openmv", "dcdc", "motor", "stm32", "oled", "ultrasound", "servo","battery"]
if is_ready_for_new_command and line in valid_commands:
print(f"✅ 接收到新任务: [{line}]")
receive_queue.put(line)
is_ready_for_new_command = False
elif not is_ready_for_new_command:
task_name = current_command if current_command else "未知任务"
print(f"🚫 忙碌中,正在执行:[{task_name}] 命令,忽略新命令: {line}")
else:
print(f"⚠️ 接收到无效命令格式: {line}")
except Exception as decode_error:
print(f"❌ 数据解码错误: {decode_error}")
receive_buffer = ""
else:
time.sleep(0.02)
else:
time.sleep(0.1)
except Exception as e:
print(f"❌ 串口接收异常: {e}")
time.sleep(0.1)
def process_received_data():
"""数据处理线程"""
global is_ready_for_new_command, current_command, last_command_time, cooldown_period
print("🧵 [处理线程] 启动")
while True:
try:
received_str = receive_queue.get()
current_command = received_str
print(f"▶️ 开始执行命令: [{current_command}]")
execute_command(current_command)
last_command_time = time.time()
print(f"⏳ 命令 [{current_command}] 执行完成,进入 {cooldown_period} 秒冷却期...")
for i in range(cooldown_period, 0, -1):
print(f"⏳ 冷却中... (剩余 {i} 秒) | 当前占用任务: [{current_command}]")
time.sleep(1)
while not receive_queue.empty():
try:
receive_queue.get_nowait()
except:
break
is_ready_for_new_command = True
finished_task = current_command
current_command = None
print(f"✅ 冷却结束,任务 [{finished_task}] 彻底完成,准备接收新命令。\n")
except Exception as e:
print(f"❌ 处理数据时出错: {e}")
is_ready_for_new_command = True
current_command = None
def increment_counter(field_name, display_name=None):#计数器增加函数
"""通用的计数器增加函数"""
if display_name is None:
display_name = field_name
# 使用 .get() 方法安全地获取当前值
# 如果字段不存在,默认返回 "0"
# 这样即使 JSON 文件中没有该字段,程序也能正常运行
current_value = data_manager.current_data.get(field_name, "0")
try:
new_value = int(current_value) + 1
except (ValueError, TypeError):
new_value = 1
data_manager.set_value(field_name, str(new_value))
print(f"📊 {display_name} 执行次数: {new_value}")
return new_value
def execute_command(command):#根据命令执行具体动作
if command == "openmv":
print("📷 执行 OpenMV 动作序列...")
ONE() # 移动到位置1并返回
increment_counter("one", "openmv") # 增加计数
read_and_report_voltage()
elif command == "relay":
print("🔌 执行 Relay 动作序列...")
TWO() # 移动到位置2并返回
increment_counter("two", "relay") # 增加计数
read_and_report_voltage()
elif command == "dcdc":
print("⚡ 执行 DCDC 动作序列...")
THREE() # 移动到位置3并返回
increment_counter("three", "dcdc") # 增加计数
read_and_report_voltage()
elif command == "motor":
print("🌀 执行 Motor 动作序列...")
FOUR() # 移动到位置4并返回
increment_counter("four", "motor") # 增加计数
read_and_report_voltage()
elif command == "stm32":
print("📟 执行 STM32 动作序列...")
FIVE() # 移动到位置5并返回
increment_counter("five", "stm32") # 增加计数
read_and_report_voltage()
elif command == "oled":
print("📺 执行 OLED 动作序列...")
SIX() # 移动到位置6并返回
increment_counter("six", "oled") # 增加计数
read_and_report_voltage()
elif command == "ultrasound":
print("📏 执行 Ultrasound 动作序列...")
SEVEN() # 移动到位置7并返回
increment_counter("seven", "ultrasound") # 增加计数
read_and_report_voltage()
elif command == "servo":
print("🦾 执行 Servo 动作序列...")
EIGHT() # 移动到位置8并返回
increment_counter("eight", "servo") # 增加计数
read_and_report_voltage()
elif command == "battery":
print("🔋 执行 Battery 动作序列...")
NINE() # 移动到位置9并返回
increment_counter("nine", "battery") # 增加计数
read_and_report_voltage()
elif command == "stc51":
print("🔋 执行 Battery 动作序列...")
TEN() # 移动到位置9并返回
increment_counter("ten", "stc51") # 增加计数
read_and_report_voltage()
# ================= 机械臂运动函数 =================
def start(): send_serial_command("duoji200"); time.sleep(2);send_serial_command("4Z_UP_START"); time.sleep(1); send_serial_command("2Y_GO_ONE"); time.sleep(3)
def black(): send_serial_command("2Y_BLACK_ONE"); time.sleep(1); send_serial_command("4Z_UP_START_BLACK"); time.sleep(1);send_serial_command("duoji500");time.sleep(3)
def GO_TO_ONE(): send_serial_command("duoji450"); time.sleep(2);send_serial_command("4Z_UP_0_5"); time.sleep(1); send_serial_command("3X_RIGHT_0_5"); time.sleep(1); send_serial_command("2Y_GO_5"); time.sleep(3)
def ONE_TO_HOME(): send_serial_command("2Y_BLACK_5"); time.sleep(1); send_serial_command("3X_LEFT_0_5"); time.sleep(2.5); send_serial_command("4Z_DOWN_0_5"); time.sleep(4)
def GO_TO_TWO(): send_serial_command("duoji350"); time.sleep(2);send_serial_command("4Z_UP_0_5"); time.sleep(1); send_serial_command("2Y_GO_5"); time.sleep(3); send_serial_command("3X_RIGHT_3"); time.sleep(3)
def TWO_TO_HOME(): send_serial_command("3X_LEFT_3"); time.sleep(1); send_serial_command("2Y_BLACK_5"); time.sleep(3); send_serial_command("4Z_DOWN_0_5"); time.sleep(4)
def GO_TO_THREE(): send_serial_command("duoji350"); time.sleep(2); send_serial_command("4Z_UP_0_5"); time.sleep(1); send_serial_command("2Y_GO_5"); time.sleep(3); send_serial_command("3X_RIGHT_5_5"); time.sleep(3)
def THREE_TO_HOME(): send_serial_command("3X_LEFT_5_5"); time.sleep(4); send_serial_command("2Y_BLACK_5"); time.sleep(3); send_serial_command("4Z_DOWN_0_5"); time.sleep(4)
def GO_TO_FOUR(): send_serial_command("duoji500"); time.sleep(2);send_serial_command("4Z_UP_5"); time.sleep(1); send_serial_command("3X_RIGHT_0_5"); time.sleep(3); send_serial_command("2Y_GO_5"); time.sleep(3)
def FOUR_TO_HOME(): send_serial_command("2Y_BLACK_5"); time.sleep(3); send_serial_command("3X_LEFT_0_5"); time.sleep(3); send_serial_command("4Z_DOWN_5"); time.sleep(4)
def GO_TO_FIVE(): send_serial_command("duoji450"); time.sleep(2); send_serial_command("4Z_UP_5"); time.sleep(4); send_serial_command("3X_RIGHT_3"); time.sleep(2); send_serial_command("2Y_GO_5"); time.sleep(4)
def FIVE_TO_HOME(): send_serial_command("2Y_BLACK_5"); time.sleep(4); send_serial_command("3X_LEFT_3"); time.sleep(2); send_serial_command("4Z_DOWN_5"); time.sleep(4)
def GO_TO_SIX(): send_serial_command("duoji400"); time.sleep(2); send_serial_command("4Z_UP_5"); time.sleep(5); send_serial_command("3X_RIGHT_5_5"); time.sleep(3); send_serial_command("2Y_GO_5"); time.sleep(4)
def SIX_TO_HOME(): send_serial_command("2Y_BLACK_5"); time.sleep(4); send_serial_command("3X_LEFT_5_5"); time.sleep(3); send_serial_command("4Z_DOWN_5"); time.sleep(4)
def GO_TO_SEVEN(): send_serial_command("duoji450"); time.sleep(2); send_serial_command("4Z_UP_0_5"); time.sleep(1); send_serial_command("2Y_BLACK_0_5"); time.sleep(1); send_serial_command("3X_RIGHT_3_5"); time.sleep(3)
def SEVEN_TO_HOME(): send_serial_command("3X_LEFT_3_5"); time.sleep(3); send_serial_command("2Y_GO_0_5"); time.sleep(1); send_serial_command("4Z_DOWN_0_5"); time.sleep(2)
def GO_TO_EIGHT(): send_serial_command("duoji350"); time.sleep(2); send_serial_command("4Z_UP_0_5"); time.sleep(1.5); send_serial_command("2Y_BLACK_0_5"); time.sleep(1); send_serial_command("3X_RIGHT_5_5"); time.sleep(4)
def EIGHT_TO_HOME(): send_serial_command("3X_LEFT_5_5"); time.sleep(4); send_serial_command("2Y_GO_0_5"); time.sleep(1); send_serial_command("4Z_DOWN_0_5"); time.sleep(2)
def GO_TO_NINE(): send_serial_command("duoji500"); time.sleep(2); send_serial_command("2Y_BLACK_0_5"); time.sleep(1); send_serial_command("4Z_UP_5"); time.sleep(4); send_serial_command("3X_RIGHT_3"); time.sleep(3)
def NINE_TO_HOME(): send_serial_command("2Y_GO_0_5"); time.sleep(3); send_serial_command("3X_LEFT_3"); time.sleep(3); send_serial_command("4Z_DOWN_5"); time.sleep(4)
def GO_TO_TEN(): send_serial_command("duoji450"); time.sleep(2); send_serial_command("2Y_BLACK_0_5"); time.sleep(1); send_serial_command("4Z_UP_5"); time.sleep(3); send_serial_command("3X_RIGHT_5_5"); time.sleep(3)
def TEN_TO_HOME(): send_serial_command("2Y_GO_0_5"); time.sleep(3); send_serial_command("3X_LEFT_5_5"); time.sleep(3); send_serial_command("4Z_DOWN_5"); time.sleep(3)
def ONE(): GO_TO_ONE(); send_serial_command("duoji200");time.sleep(3); ONE_TO_HOME()
def TWO(): GO_TO_TWO(); send_serial_command("duoji200");time.sleep(3); TWO_TO_HOME()
def THREE(): GO_TO_THREE(); send_serial_command("duoji200");time.sleep(3); THREE_TO_HOME()
def FOUR(): GO_TO_FOUR(); send_serial_command("duoji200");time.sleep(3); FOUR_TO_HOME()
def FIVE(): GO_TO_FIVE(); send_serial_command("duoji200");time.sleep(3); FIVE_TO_HOME()
def SIX(): GO_TO_SIX(); send_serial_command("duoji200");time.sleep(3); SIX_TO_HOME()
def SEVEN(): GO_TO_SEVEN(); send_serial_command("duoji200");time.sleep(3); SEVEN_TO_HOME()
def EIGHT(): GO_TO_EIGHT(); send_serial_command("duoji200");time.sleep(3); EIGHT_TO_HOME()
def NINE(): GO_TO_NINE(); send_serial_command("duoji200");time.sleep(3); NINE_TO_HOME()
def TEN(): GO_TO_TEN(); send_serial_command("duoji200");time.sleep(3); TEN_TO_HOME()
def read_and_report_voltage():#"""读取舵机电压并上报"""
global servo_ser
print("\n🔋 正在读取舵机电压...")
voltage = servo_ser.read_voltage(1)
if voltage is not None:
# 修改1:使用 format 确保显示两位小数
print(f"✅ 舵机电压读取成功: {voltage:.2f}V") # 这里已经自动显示两位小数
# 修改2:保存时也确保是两位小数的浮点数
data_manager.set_value("CurrentVoltage", round(voltage, 2))
send_data(client, data_manager.get_current_data())
print("电压数据已上报到云端")
return True
else:
print("❌ 舵机电压读取失败")
return False
def main():
global is_ready_for_new_command, servo_ser
# 初始化所有串口
if not init_receive_serial():
print("❌ 接收串口初始化失败,程序退出")
return
if not init_send_serial():
print("❌ 发送串口初始化失败,程序退出")
return
if not init_servo_serial():
print("❌ 舵机串口初始化失败,程序退出")
return
# 读取并上报电压(仅一次)
time.sleep(1) # 给串口一点稳定时间
read_and_report_voltage()
time.sleep(1)
start()
time.sleep(1)
read_and_report_voltage()
# 启动线程
threading.Thread(target=serial_receive_thread, daemon=True).start()
threading.Thread(target=process_received_data, daemon=True).start()
print("\n" + "="*40)
print("🤖 系统已启动,等待视觉模块指令...")
print("支持命令: relay, openmv, dcdc, motor, stm32, oled, ultrasound, servo","battery")
print("="*40 + "\n")
try:
while True:
time.sleep(1)
except KeyboardInterrupt:
print("\n⛔ 用户中断,正在关闭...")
finally:
if receive_ser and receive_ser.is_open: receive_ser.close()
if send_ser and send_ser.is_open: send_ser.close()
if servo_ser: servo_ser.disconnect()
client.disconnect()
print("👋 程序已安全退出")
if __name__ == "__main__":
main()