上述为网络调试助手界面 优先连接好本地主机地址
k230通过网络通讯可控舵机左右转动并且可实时观察图像
代码示例如下
import time, os, sys
import network, socket
from machine import Pin, PWM, FPIOA
from media.sensor import * # 导入sensor模块,使用摄像头相关接口
from media.display import * # 导入display模块,使用display相关接口
from media.media import * # 导入media模块,使用meida相关接口=== 配置舵机引脚 ===
fpioa = FPIOA()
fpioa.set_function(42, FPIOA.PWM0) # 配置引脚42为PWM0功能
fpioa.set_function(43, FPIOA.PWM1) # 配置引脚43为PWM1功能构建舵机PWM对象,频率为50Hz(对于标准舵机)
S1 = PWM(0, 50, duty=0, enable=True) # 舵机S1
S2 = PWM(1, 50, duty=0, enable=True) # 舵机S2=== 设置舵机角度的函数 ===
def set_servo_angle(servo, angle):
“”“设置指定舵机的角度。”“”
angle = max(-90, min(90, angle)) # 限制角度在-90到90度之间
duty = ((angle + 90) / 180 * 10 + 2.5) # 计算占空比
servo.duty(duty)WIFI连接函数
def WIFI_Connect():
WIFI_LED = Pin(52, Pin.OUT) # 初始化WIFI指示灯
wlan = network.WLAN(network.STA_IF) # STA模式
wlan.active(True) # 激活接口if not wlan.isconnected(): print('connecting to network...') wlan.connect('mate40', '12345678') # 输入WIFI账号密码 if wlan.isconnected(): # 连接成功 WIFI_LED.value(1) # LED蓝灯点亮 print('network information:', wlan.ifconfig()) return True else: for i in range(3): # LED闪烁3次提示 WIFI_LED.value(1) time.sleep_ms(300) WIFI_LED.value(0) time.sleep_ms(300) wlan.active(False) return False
=== 摄像头初始化 ===
def init_camera_display():
sensor = Sensor() # 构建摄像头对象
sensor.reset() # 复位和初始化摄像头
sensor.set_framesize(Sensor.VGA) # 设置帧大小
sensor.set_pixformat(Sensor.RGB565) # 设置输出图像格式Display.init(Display.VIRT, sensor.width(), sensor.height()) # 初始化显示 MediaManager.init() # 初始化media资源管理器 sensor.run() # 启动sensor return sensor
主程序
if name == “main”:
try:
# 初始化摄像头和显示
sensor = init_camera_display()# 尝试连接WIFI if WIFI_Connect(): # 连接WIFI成功 s = socket.socket() addr = socket.getaddrinfo('192.168.43.111', 10000)[0][-1] # 服务器IP和端口 s.connect(addr) s.setblocking(False) # 设置为非阻塞模式,防止网络等待时阻塞 clock = time.clock() while True: os.exitpoint() # 检测IDE中断 # ===== 摄像头图像采集与显示 ===== clock.tick() img = sensor.snapshot() # 拍摄一张图 Display.show_image(img) # 显示图片 print(clock.fps()) # 打印FPS # ===== 网络通讯处理 ===== try: text = s.recv(128) # 接收服务器信息 if text: try: # 假设服务器发送的是两个舵机的角度,格式为"angle1,angle2" angles = text.decode('utf-8').split('.') angle1 = int(angles[0]) angle2 = int(angles[1]) # 设置舵机角度 set_servo_angle(S1, angle1) set_servo_angle(S2, angle2) # 回复服务器 s.send(f"Servo angles set to: {angle1}, {angle2}") except Exception as e: print("Error:", e) s.send("Error in processing angles") except OSError: pass # 如果没有接收到数据,不进行处理 time.sleep(0.05) # 稍微减缓循环速度,降低CPU负载 except KeyboardInterrupt as e: print("User stopped the program:", e) finally: # 释放资源 if isinstance(sensor, Sensor): sensor.stop() Display.deinit() MediaManager.deinit() os.exitpoint(os.EXITPOINT_ENABLE_SLEEP) time.sleep_ms(100)
上述代码要注意的点
wlan.connect(‘mate40’, ‘12345678’) # 输入WIFI账号密码
这一处要连上2.4ghz的网络
addr = socket.getaddrinfo(‘192.168.43.111’, 10000)[0][-1] # 服务器IP和端口
找到连上网络对应的地址
s.setblocking(False) # 设置为非阻塞模式,防止网络等待时阻塞
加上这一段才能实现网络跟图像传输俩不误
# 假设服务器发送的是两个舵机的角度,格式为"angle1,angle2" angles = text.decode('utf-8').split('.') angle1 = int(angles[0]) angle2 = int(angles[1])
这里在网络通讯收发输入的数据格式为(x.x)例如(0.45)(25.-15)控制舵机1和舵机2
舵机引脚在代码内均有标识