K210 面部追踪小尝试

前言

最近偶然得知一个名为 K210 的 MCU,带有 RISC-V 架构的处理器,而且芯片中自带了一个自研的神经网络加速器,称为 KPU,允许进行高效卷积神经网络计算(据嘉楠官方数据,可以达到 0.8 TOPS)。于是萌生了一个用 K210 控制 SG90 伺服电机(舵机),上面放个摄像头,检测人脸然后伺服电机进行跟踪,拍照存储到 microSD 卡的奇怪想法;然后不知不觉间就下手了 Sipeed MaixBit,OV2460 摄像头,SG90 伺服电机以及一大堆乱七八糟的线缆面包板等配件(剁手ing)。用基于 MicroPython 的 MaixPy 进行开发(Python 真香,才不是因为懒以及我在 MaixBit 上运行了好几个勘智的官方 C 例程都失败了)。

PS: 本文不会讲述如何给 MaixBit 刷入 MaixPy 固件以及 MaixPyIDE 的使用方法等,请参考官方文档

硬件参数

MaixBit

  • 双核 64 bit RISC-V RV64IMAFDC CPU / 400MHz (集成双精度 FPU, AES, SHA256 加速)
  • 8MiB 64bit 片上 SRAM
  • 16 MiB Flash,板载 micro SDXC 接口 (最大支持 128 GiB)
  • 板载 DVP 摄像头接口和 LCD 接口,都是 24 Pin FPC 底座(0.5mm 间距)
    更多信息可以参阅 Sipeed MaixBit Datasheet

OV2640

  • 320 × 240 分辨率
  • 200W 像素
  • DVP 接口(FPC 24 Pin 0.5mm)
  • 支持 YUV422 颜色模式
  • 手动变焦
    PS: 其实官方对 OV5640 的支持要更完善一点点,支持自动变焦和 RGB565 颜色模式(甚至可以配广角镜头),而且价格也没有比 OV2640 高到哪里去,打算以后弄个来玩玩(再次剁手预备)。
    摄像头选型可以参考 这个文档

SG90 伺服电机

  • 无负载速度: 0.002s/度 (4.8V)
  • 堵转扭矩: 1.2-1.4 kg/cm(4.8V)
  • 死区设定: 7us (7 MHz)
  • 工作电压: 4.8 - 6V (我之前脑抽插到了 3.3V 供电上,死活不动。。所以使用前仔细阅读说明书是个好习惯)
  • 位置等级: 1024
  • 脉冲精度: 2us
    该伺服电机需要 MCU 产生持续 20ms 的脉冲信号,以持续 0.5ms ~ 2.5ms 的高电平来控制角度,大概可以用下表来表示
高电平时间(ms) 角度 占空比(%)
0.5 0 2.5
1.0 45 5.0
1.5 90 7.5
2.0 135 10.0
2.5 180 12.5

PS: 有关 PWM 的知识可以在网上搜索得到。我使用的驱动器是两个 SG90 组成的,可以实现水平 180 度和垂直 90 度的运动。

标题不存在

先上两张图吧,这是我搭好的(不要在意为什么这么丑)。

?!
?!!

0x00

具体的 IO 定义可以参考上面的 MaixBit 规格文档,这里以 IO 编号说明。
水平伺服电机 PWM 连接 23 管脚,垂直伺服电机连接 22 管脚,两个电机均接入 MaixBit 的 5V 供电管脚(推荐使用额外的电源,如果是在电脑 USB 接口上调试且电机运动激烈,容易导致 MaixBit 欠压重启)。

0x01

因为个人的习惯(懒得用配置文件),开始先定义一些常量,初始化一些对象,方便后面的代码复用这些东西。

1
2
3
4
5
6
7
8
9
10
11
CAMERA_VFLIP = 1
CAMERA_HMIRROR = 1
CAMERA_WIDTH = 320
CAMERA_HEIGHT = 240
CENTER_POINT_X = CAMERA_WIDTH / 2
CENTER_POINT_Y = CAMERA_HEIGHT / 2
CENTER_CIRCLE_RADIUS = 10
TRACE_DELTA_RADIUS = 20

# Save photo to specific folder if detected a face, set empty to disable this function
PHOTO_SAVE_PATH = "/sd/images"

VFLIPHMIRROR 用来控制摄像头的水平及垂直翻转,具体定义可参考 MaixPy 文档的 sensor
CENTER_POINT_xxx 指的是图像中心点的 X, Y 坐标,跟踪是以这个点为基准,要求目标的中心点在这个点的一定范围内。
TRACE_DELTA_RADIUS 是目标中心点与图像中心点的允许位置偏差,当目标的中心点与图像中心点的距离超过这个值时,将控制伺服电机跟踪目标。
PHOTO_SAVE_PATH 表示拍照时的存储路径,设为空可以关闭拍照的功能。

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
# Initialize Servo Motor
# Horizontal
SRVMOT_HORI_PIN = GPIO.GPIOHS23
SRVMOT_HORI_MAX = 13
SRVMOT_HORI_MIN = 3
SRVMOT_HORI_DUTY_DEFAULT = (SRVMOT_HORI_MAX + SRVMOT_HORI_MIN) / 2
SRVMOT_HORI = PWM(
Timer(Timer.TIMER2, Timer.CHANNEL0, mode=Timer.MODE_PWM),
freq=50,
duty=SRVMOT_HORI_DUTY_DEFAULT,
pin=SRVMOT_HORI_PIN)

# Vertical
SRVMOT_VECT_PIN = GPIO.GPIOHS22
SRVMOT_VECT_MAX = 12
SRVMOT_VECT_MIN = 4
SRVMOT_VECT_DUTY_DEFAULT = (SRVMOT_VECT_MAX + SRVMOT_VECT_MIN) / 2
SRVMOT_VECT = PWM(
Timer(Timer.TIMER2, Timer.CHANNEL1, mode=Timer.MODE_PWM),
freq=50,
duty=SRVMOT_VECT_DUTY_DEFAULT,
pin=SRVMOT_VECT_PIN)

定义伺服电机管脚和默认位置,设置电机的运行范围,最后用 PWM 类实现对特定管脚的 PWM 输出,控制对应的电机(由于我的垂直伺服电机比较特殊,最大角度只有 90 度但是 PWM 占空比还是 2.5 ~ 12.5,这部分需要根据自己的电机来实际确定)。
后续的初始化面部检测模型,摄像头,LCD 以及在 KPU 中加载模型,均为 MaixPy 中的官方例程,我就懒得打了,反正最后会放上完整代码。

0x02

我比较喜欢在用类,可以避免写出一大堆 nonlocal 啊,global 之类的东西。

1
2
3
4
5
6
7
8
9
10
11
12
class FaceTrack:
def __init__(self):
# When we get current value of PWM object, it returns a integer,
# so we need to use the variables ourselves to accurately control the servo motor.
self.h_duty = SRVMOT_HORI.duty()
self.v_duty = SRVMOT_VECT.duty()

# Last saved time of camera auto shot
self.last_save_time = 0

# Last time when lost detected face
self.lost_face_time = 0
  • 为什么要自定义 *_duty 来存储 PWM 的占空比?直接用 duty() 读取占空比然后再计算不香吗?我之前也是这么想的,然后踩了坑,因为从 PWM 对象的 duty() 函数直接读取当前占空比时,返回的是一个整数,无法精确控制占空比(伺服电机跟疯了一样要么不动要么直接瞬移),此时需要自己定义变量来存储当前的精确占空比,方便精确控制伺服电机。
  • last_save_time 是最后一次拍照存储的时间戳,用来控制拍照间隔。
  • lost_face_time 是最后一次检测不到面部的时间戳,用以在丢失目标时让伺服电机复位。
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
def reset_servo_motor(self):
self.h_duty = SRVMOT_HORI.duty()
self.v_duty = SRVMOT_VECT.duty()
SRVMOT_HORI.duty(SRVMOT_HORI_DUTY_DEFAULT)
SRVMOT_VECT.duty(SRVMOT_VECT_DUTY_DEFAULT)

def move_hori_servo_motor(self, delta: float):
if math.fabs(delta) > TRACE_DELTA_RADIUS:
h_duty_delta = delta / CAMERA_WIDTH * \
(SRVMOT_HORI_MAX - SRVMOT_HORI_MIN) * 0.2

if CAMERA_HMIRROR == 1:
h_duty_delta = -h_duty_delta
print("Hduty delta: {}".format(h_duty_delta))

new_h_duty = self.h_duty + h_duty_delta

if new_h_duty <= SRVMOT_HORI_MAX and new_h_duty >= SRVMOT_HORI_MIN:
self.h_duty = new_h_duty
SRVMOT_HORI.duty(self.h_duty)
  • reset_servo_motor 用于复位电机位置,在丢失目标后调用
  • move_hori_servo_motor 控制水平电机,检测目标的水平位移并进行跟踪,其中 h_duty_delta 是经过计算转换后的 PWM 占空比改变量,其算法为计算水平改变量在图像大小中的比值,然后乘以水平电机的最大可用占空比与最小可用占空比的差值,最后乘以一个比例,经过我的多次测试这个值在我这里应设为 0.2 比较合适,既能保证平稳跟踪目标又不会使电机运动幅度过大;同理有一个 move_vect_servo_motor 控制垂直电机的运动。
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
def loop(self):
while True:
try:
gc.collect()

img = sensor.snapshot() # Read image from camera
codes = kpu.run_yolo2(FACE_DECT_TASK, img) # Run detection
if codes: # Detected
# Take photo and save if needed
if PHOTO_SAVE_PATH and utime.ticks_ms() - self.last_save_time > 2000:
fn = "{}/{}.jpg".format(PHOTO_SAVE_PATH,
utime.ticks_ms())
img.save(fn, quality=100)
print("Photo saved as {}".format(fn))
self.last_save_time = utime.ticks_ms()

# Draw center circle and delta range circle
img.draw_circle(CENTER_POINT_X, CENTER_POINT_Y,
CENTER_CIRCLE_RADIUS)
img.draw_circle(CENTER_POINT_X, CENTER_POINT_Y,
TRACE_DELTA_RADIUS)

for code in codes:
x = code.x()
y = code.y()
w = code.w()
h = code.h()
img.draw_rectangle(x, y, w, h)

x_center = int(x + w / 2)
y_center = int(y + h / 2)
img.draw_line(x_center, y, x_center, y + h)
img.draw_line(x, y_center, x + w, y_center)

self.move_hori_servo_motor(x_center - CENTER_POINT_X)
self.move_vect_servo_motor(y_center - CENTER_POINT_Y)

break # Only one face tracking at same time for now

self.lost_face_time = utime.ticks_ms()
else:
# Reset servo motor if lost detected face
if utime.ticks_ms() - self.lost_face_time > 3000:
self.reset_servo_motor()

lcd.display(img)
except KeyboardInterrupt:
break
except Exception as e:
if str(e) == "IDE interrupt":
break
print(e)

程序主循环,在每次循环开始或结束时,千万一定必须要执行 gc.collect() 来回收垃圾,否则有极大可能导致内存溢出程序崩溃。这部分代码在每次循环时从摄像头获取图像,执行识别,拍照存储,控制伺服电机等,具体可阅读代码(没错就是我又懒得敲详细内容了)。

小结

这次也是尝鲜,用 Python 写了一下 K210 的程序,发现 K210 确实很强大,便宜(单块 K210 BGA 封装只要 20 块不到)低功耗且性能强大,但是由于 Python 的性能问题导致无法跑高精度模型,下一步打算学习勘智的 C SDK 并尝试把这篇文章中写的东西复刻一下,提高一下自己 C 的水平。

完整代码

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
# -*- encoding: utf-8 -*-
# pylint: disable=import-error, no-member

import math
import gc
import sensor # MaixBit camera sensor
import KPU as kpu
import lcd
from machine import PWM, Timer
from Maix import GPIO
import utime
import uos

CAMERA_VFLIP = 1
CAMERA_HMIRROR = 1
CAMERA_WIDTH = 320
CAMERA_HEIGHT = 240
CENTER_POINT_X = CAMERA_WIDTH / 2
CENTER_POINT_Y = CAMERA_HEIGHT / 2
CENTER_CIRCLE_RADIUS = 10
TRACE_DELTA_RADIUS = 20

# Save photo to specific folder if detected a face, set empty to disable this function
PHOTO_SAVE_PATH = "/sd/images"

# Initialize Servo Motor
# Horizontal
SRVMOT_HORI_PIN = GPIO.GPIOHS23
SRVMOT_HORI_MAX = 13
SRVMOT_HORI_MIN = 3
SRVMOT_HORI_DUTY_DEFAULT = (SRVMOT_HORI_MAX + SRVMOT_HORI_MIN) / 2
SRVMOT_HORI = PWM(
Timer(Timer.TIMER2, Timer.CHANNEL0, mode=Timer.MODE_PWM),
freq=50,
duty=SRVMOT_HORI_DUTY_DEFAULT,
pin=SRVMOT_HORI_PIN)

# Vertical
SRVMOT_VECT_PIN = GPIO.GPIOHS22
SRVMOT_VECT_MAX = 12
SRVMOT_VECT_MIN = 4
SRVMOT_VECT_DUTY_DEFAULT = (SRVMOT_VECT_MAX + SRVMOT_VECT_MIN) / 2
SRVMOT_VECT = PWM(
Timer(Timer.TIMER2, Timer.CHANNEL1, mode=Timer.MODE_PWM),
freq=50,
duty=SRVMOT_VECT_DUTY_DEFAULT,
pin=SRVMOT_VECT_PIN)

# Face detection model config
# From MaixPy offcial document
FACE_DETECT_ANCHOR = (1.889, 2.5245, 2.9465, 3.94056, 3.99987, 5.3658, 5.155437,
6.92275, 6.718375, 9.01025)
FACE_DETECT_MODEL = 0x200000
FACE_DETECT_THRESHOLD = 0.5
FACE_DETECT_NMS = 0.3
FACE_DETECT_ANCHOR_NUM = 5

# Initialize camera
sensor.reset()
sensor.set_framesize(sensor.QVGA)
sensor.set_pixformat(sensor.RGB565) # Set Frame Size
sensor.set_vflip(CAMERA_VFLIP)
sensor.set_hmirror(CAMERA_HMIRROR)
sensor.run(1)

# Initialize kpu
FACE_DECT_TASK = kpu.load(FACE_DETECT_MODEL)
kpu.init_yolo2(FACE_DECT_TASK, FACE_DETECT_THRESHOLD,
FACE_DETECT_NMS, FACE_DETECT_ANCHOR_NUM, FACE_DETECT_ANCHOR)

# Initialize LCD screen
lcd.init()


class FaceTrack:
def __init__(self):
# When we get current value of PWM object, it returns a integer,
# so we need to use the variables ourselves to accurately control the servo motor.
self.h_duty = SRVMOT_HORI.duty()
self.v_duty = SRVMOT_VECT.duty()

# Last saved time of camera auto shot
self.last_save_time = 0

# Last time when lost detected face
self.lost_face_time = 0

def reset_servo_motor(self):
self.h_duty = SRVMOT_HORI.duty()
self.v_duty = SRVMOT_VECT.duty()
SRVMOT_HORI.duty(SRVMOT_HORI_DUTY_DEFAULT)
SRVMOT_VECT.duty(SRVMOT_VECT_DUTY_DEFAULT)

def move_hori_servo_motor(self, delta: float):
if math.fabs(delta) > TRACE_DELTA_RADIUS:
h_duty_delta = delta / CAMERA_WIDTH * \
(SRVMOT_HORI_MAX - SRVMOT_HORI_MIN) * 0.2

if CAMERA_HMIRROR == 1:
h_duty_delta = -h_duty_delta
print("Hduty delta: {}".format(h_duty_delta))

new_h_duty = self.h_duty + h_duty_delta

if new_h_duty <= SRVMOT_HORI_MAX and new_h_duty >= SRVMOT_HORI_MIN:
self.h_duty = new_h_duty
SRVMOT_HORI.duty(self.h_duty)

def move_vect_servo_motor(self, delta: float):
if math.fabs(delta) > TRACE_DELTA_RADIUS:
v_duty_delta = delta / CAMERA_HEIGHT * \
(SRVMOT_VECT_MAX - SRVMOT_VECT_MIN) * 0.2

if CAMERA_VFLIP == 0:
v_duty_delta = -v_duty_delta
print("Vduty delta: {}".format(v_duty_delta))

new_v_duty = self.v_duty + v_duty_delta

if new_v_duty <= SRVMOT_VECT_MAX and new_v_duty >= SRVMOT_VECT_MIN:
self.v_duty = new_v_duty
SRVMOT_VECT.duty(self.v_duty)

def start(self):
self.loop()

def loop(self):
while True:
try:
gc.collect()

img = sensor.snapshot() # Read image from camera
codes = kpu.run_yolo2(FACE_DECT_TASK, img) # Run detection
if codes: # Detected
# Take photo and save if needed
if PHOTO_SAVE_PATH and utime.ticks_ms() - self.last_save_time > 2000:
fn = "{}/{}.jpg".format(PHOTO_SAVE_PATH,
utime.ticks_ms())
img.save(fn, quality=100)
print("Photo saved as {}".format(fn))
self.last_save_time = utime.ticks_ms()

# Draw center circle and delta range circle
img.draw_circle(CENTER_POINT_X, CENTER_POINT_Y,
CENTER_CIRCLE_RADIUS)
img.draw_circle(CENTER_POINT_X, CENTER_POINT_Y,
TRACE_DELTA_RADIUS)

for code in codes:
x = code.x()
y = code.y()
w = code.w()
h = code.h()
img.draw_rectangle(x, y, w, h)

x_center = int(x + w / 2)
y_center = int(y + h / 2)
img.draw_line(x_center, y, x_center, y + h)
img.draw_line(x, y_center, x + w, y_center)

self.move_hori_servo_motor(x_center - CENTER_POINT_X)
self.move_vect_servo_motor(y_center - CENTER_POINT_Y)

break # Only one face tracking at same time for now

self.lost_face_time = utime.ticks_ms()
else:
# Reset servo motor if lost detected face
if utime.ticks_ms() - self.lost_face_time > 3000:
self.reset_servo_motor()

lcd.display(img)
except KeyboardInterrupt:
break
except Exception as e:
if str(e) == "IDE interrupt":
break
print(e)


if __name__ == "__main__":
try:
if PHOTO_SAVE_PATH:
uos.stat(PHOTO_SAVE_PATH)
except OSError:
uos.mkdir(PHOTO_SAVE_PATH)

ft = FaceTrack()
ft.start()