SmartRobot扫地机器人
1 项目需求分析
1.1 项目背景介绍
随着科技的快速发展和人们生活水平的不断提高,智能家居设备正逐渐成为现代家庭的重要组成部分。在快节奏的生活中,人们对于家务自动化的需求日益增长,尤其是日常清洁工作,既耗时又费力。传统的清洁方式(如手动扫地、拖地)已无法满足现代家庭对高效、便捷生活的追求。扫地机器人作为智能清洁领域的代表性产品,凭借其自主导航、智能避障、自动回充等先进功能,能够有效减轻用户的清洁负担,提升生活品质。近年来,随着人工智能(AI)、传感器技术、路径规划算法以及物联网(IoT)技术的进步,扫地机器人的性能与智能化水平显著提升,市场需求持续扩大。
本项目基于市场上成熟的海尔扫地机器人硬件方案,通过复刻和优化现有设计,重点研究其核心功能模块,包括运动控制、传感器数据处理、路径规划算法等。在复刻过程中,我们将深入分析现有扫地机器人的优缺点,并结合实际应用场景进行针对性改进,例如优化清洁路径、提升避障精度、降低功耗等。该项目的实施不仅有助于深入理解扫地机器人的关键技术,还能为后续的二次开发和功能拓展奠定基础。通过复刻与优化,我们期望在降低研发成本的同时,提升产品的稳定性和用户体验,为智能家居设备的本地化应用提供参考方案。
1.2 设计需求与相关指标确定
基于以上项目背景,结合硬件实机情况与初步调研结果,总结出了以下几条功能设计需求,并本着定量化的思想,在每一条功能需求上都提出了对应的指标:
良好的避障功能:扫地机器人应集成有效传感器,以实现对障碍物的检测和避让,确保在复杂环境中的自主导航。除此之外,为保证最大程度的清洁,不放过任何一个清洁死角,我们希望机器人在触碰到墙体后,能够尽可能地以低速(不超过0.1m/s)贴近墙体行进。
具体而言,在碰撞传感器触发时,机器人需要在50ms内作出反应,先后退离开墙体区域,在原地进行小角度旋转后继续向前行进,再次碰到墙体时继续做出这样的反应。
防坠落能力:设备应具备悬崖检测传感器(本项目中硬件设备为红外传感器),以识别楼梯边缘或高度差,防止从高处坠落。
具体而言,我们希望在悬崖传感器检测到机器人位于高度垂直落差大于5cm的界面时,能够在50ms内作出反应,先紧急制动,接着低速后退离开悬崖区域,在原地旋转改变运动方向后继续行进,以最大限度地保护机器人地工作安全,避免损坏。
运动功能:扫地机器人应能根据家庭环境尺寸,实现高精度的运动控制。
具体而言,我们希望基于编码器利用PID控制器实现高精度的电机调控与运动控制,在直线行驶1m距离的测试中总偏角应不超过5°、距离误差不超过2cm.
用户通讯控制:设备应配备直观的用户界面,包括按键和指示灯,以便用户轻松启动、暂停和控制扫地机器人。应支持通过蓝牙连接,实现电脑端应用程序的远程控制,包括启动/停止自动清扫、遥控机器人(基于实时遥控信号调整运动状态)、监控电池状态等。
具体而言,希望在中低速运动条件下(0.05~0.15m/s)实现频率至少10Hz的实时位置坐标与姿态(偏转角度)的数据解算(位置坐标各方向误差<5cm、偏转角度误差<5°),并将数据传至用户界面,根据已有的行进位姿数据进行实时路径可视化,基于已有建图结果实现全覆盖路径规划。
1.3 项目分工
PCB设计及硬件维护:余虹鋈 | 学号:20222957 |
---|---|
嵌入式程序:王冲 | 学号:20224841 |
上位机及嵌入式程序:肖范熠 | 学号:20223984 |
算法及嵌入式程序:许晶华 | 学号:20224546 |
1.4 本章小结
本章对于扫地机器人项目的应用背景进行了介绍,并基于实机测试与调研结果确定了产品的功能需求指标,这为后续的项目开发起到了良好的引领和指导作用,后续的项目功能研发也将紧密围绕这些功能需求点与性能指标进行展开。
2 PCB电路设计
2.1 设计目标
本次PCB设计面向智能扫地机器人控制系统,目标是实现电源管理、电机驱动、传感器输入处理、MCU外围支持、IMU通信等功能模块的稳定集成,并兼顾成本控制、布局合理性与后期调试便利性。
2.2 PCB总体布局与功能划分
PCB采用双面布局,充分利用板面空间,模块化划分如下:
电源管理区:提供从锂电池到各类电压等级(如5V/3.3V)的转换;
单片机核心区:部署STM32及其基本外围电路;
电机驱动区:负责控制左右驱动电机及各个毛刷电机和吸尘电机;
传感器接口区:用于悬崖、碰撞等传感器信号接入与处理;
辅助保护与调试区:如状态指示灯、串口接口等。
2.3 电源管理电路设计
2.3.1 充电电路设计
电源模块采用多级稳压设计,满足不同子系统电压需求。在芯片选型方面,我们选择使用SLM6900降压模块,其特性如下:
输出固定16.8V,无需外围分压,适合三到四节锂电池充电;
高效率(5A负载),封装易焊,适配性好;
可通过ADC分压获得充电状态,便于MCU监控;
NCHRG(充电中低电平)和NSTDBY(充满低电平)引脚可直接驱动LED简化状态监控,红绿LED指示灯直观反馈。
相较于另一常见的充电芯片BQ24610RGER而言,拥有更易焊接的封装方式和更便宜的价格。
2.3.2 降压电路设计
在降压电路设计中,我们选择采用TPS54531作为降压芯片,该芯片具有以下优点:
支持从低至锂电池单节电压到24V工业电源的广泛输入,适配多种电源场景(如车载系统、分布式电源);
轻载时自动切换至脉冲跳跃模式,静态电流低至1μA(关断状态),显著提升电池供电设备的待机时长;
逐周期电流限制、频率折返、热关断(165℃触发)三重保护。过压瞬态保护抑制启动电压过冲;
封装焊接简易;
成本低,三元一个,单个可售。
在选型时,我们还考虑了其他型号的降压芯片,其中TPS56637适用于4.5V至28V,价格五元一个,与选用的TPS54531价格相近,但是其封装在焊接过程中出问题的概率更大,综合考虑不予选用;而LM2679S性能强悍,但是价格高昂,五十元一个,不予选用。
线性稳压器方面,由于在这一步仅需5v降到3.3v压差小,因此选用合适、最廉价的芯片即可,不必追求过高性能。这里我们选用AMS1117-3.3线性稳压器,其主要特性如下:
为MCU提供3.3V电压;
精度±1%,外围电路极简,仅需输入/输出电容。
2.4 电机驱动与控制逻辑设计
2.4.1 运动电机驱动芯片选型对比
由于驱动直流电机需要的电流很大,单片机I/O的驱动能力是远远达不到的。因此需要使用专用的电机驱动芯片。芯片驱动能力及使用复杂度简单对比如下:
A4950:8~40V,高压大电流,外围适中;
DRV8833:2.7~10.8V,体积小,适合低压,使用简单;
TB6612FNG:2.5~13.5V,性能稳定,体积小;
L298N:3~48V,体积大,驱动强,但外围复杂。
DRV8833电机驱动芯片是基于H桥电路的,芯片中共有两个全H桥,因此最多可以同时驱动两个直流电机或一个步进电机。电源供电电压2.7~10.8V,每个H桥输出的均方根(RMS)电流为1.5A,峰值可达2A。内置过热保护和用户可调的限流保护电路。
框图中也包含了DRV8833芯片外部所需要的元件,主要是三个电容以及两个电流检测电阻(电阻可不接)。当温度过高,温度检测保护模块会使nFAULT所接的FET导通拉到低电平,同时H桥转成衰减模式,不再给电机供电。
TB6612FNC是东芝半导体公司的一款电机驱动芯片,也是集成了两个全H桥。在应用上基本与DRV8833相似,但性能更好,价格也相对较高。电源供电电压2.5~13.5V,H桥输出的平均电流1.2A,最大可到3.2A。(可见驱动能力比DRV8833略强)内置过热保护和低压检测关断电路,PWM控制的频率可达100kHZ。
上面框图中画出了使用该芯片需要外接的元件(4个滤波电容)。从中可发现,其与DRV8833最大不同即在输入控制上,除了输入1和输入2,还有一个PWM输入脚。
A4950是美国埃戈罗公司生产的一款单H桥电机驱动芯片。因此网上卖的模块多是使用两块芯片以达到可以控制两个直流电机的能力。电机驱动电压:8~40V,输出最大电流可达3.5A;内置过温保护,短路保护和可选择的过流保护。
通过引脚说明和功能框图可看出,此芯片不同之处有:只有单H桥,因此引脚较少;限流比较的参考电压由外部给出(VREF脚);因此限流值Isense=Vref/10/Rsense。如上面的模块中,Vref接5V,Rsense为R250精密检测电阻(0.25Ω),因此限流值为2A。当IN1和IN2均保持低电平1ms,芯片进入待机模式。而不是通过引脚直接控制。经过对比发现,此芯片的驱动逻辑与上述的DRV8833PWP芯片完全一致。
L298N是ST公司的一款电机驱动芯片,也是集成了双H桥,但与上面两个略有不同。该芯片适配的电机驱动电压为3~48V;可持续工作的输出电流为2A,峰值可达3A。如上图,L298N模块明显比前两个芯片模块外接的元件多,这与L298N的内部结构有关。如上图,由于该芯片在H桥上的损耗严重发热较明显(饱和压降大),需要加装散热片,因此在使用上比前两个芯片复杂,体积也相对较大。
如上图所示:L298N的内部功能很多都类似,比如电流检测,H桥驱动,外接电容等。主要区别在于L298N的H桥采用了BJT而不是MOSFET。这就直接导致没有寄生二极管,无法像前两个芯片一样实现续流。因此需要外接8个续流二极管。因为频率不高,选用普通的整流二极管即可(如1N4007)。如下图所示:
此芯片的电流检测脚Sense-X并不像前面的芯片,其没有在内部进行电压比较从而限流,从数据手册上看,需要一个L297芯片配合进行限流。因此一般直接接地,不进行限流。
综上所述,对比四款常用的电机驱动芯片,可以得到如下结论:
三款芯片的内部原理和控制方式大同小异;
可通过两个H桥输出的并联控制一个直流电机,这样最大驱动电流可翻倍,这在芯片的数据手册中均有说明;
以上三种芯片驱动能力排序:DRV8833<BT6612<A4950≈L298N;
DRV8833、TB6612和A4950的体积小,外接元件少,使用简单;L298N体积大,外接元件多,使用相对复杂;
在选择这种集成H桥芯片时,需要考虑的参数有:可承受的工作电流要大于电机的堵转电流,防止堵转时驱动芯片烧毁;导通电阻尽可能小,减少芯片的发热损耗。综合这些因素考虑,本项目最终选用A4950作为主驱动芯片,其适配性与功率支持表现均较为优异。
2.4.2 其余电机驱动控制逻辑设计
在刷子电机和风机驱动方面,选择使用74HC14D来对单片机信号进行增强,从而达到控制的目的,因为这些电机不需要特别精细的控制,这样的选择可以最低限度实现功能的同时,减少PCB版面空间的消耗。
这一部分的驱动电路设计主要有以下要点:
74HC14D 施密特反相器用于整形PWM信号,防抖处理;
NCE6020AK MOSFET 用作电机功率开关管;
二极管续流保护,防止感性反冲。
在上述电路中,MCU输出的PWM信号经R178/R188限流后输入74HC14D,整形后的反相信号驱动NCE6020AK栅极。同时,74HC14D输出端应通过栅极电阻(典型值10-100Ω)连接MOSFET栅极,连接形式为:VCC15V→ MOSFET漏极 → 源极 → 100mΩ采样电阻 → 电机 →GND。当电机停转时,电感能量经B340A续流二极管释放。该电路还包含过流保护与电压尖峰抑制的功能,将采样电阻压差送ADC6,MCU触发关断,B340A续流二极管吸收反向电动势。
2.5 单片机外围电路
本项目的MCU采用STM32系列芯片,外围电路主要包括以下几个部分:
晶振电路(8MHz或16MHz);
上拉/下拉电阻;
下载接口(SWD);
启动配置引脚;
调试指示LED、UART通讯接口等。
2.6 PCB布局设计说明
2.6.1 正面布局
以MCU为核心,周边辐射式布局传感器与电源模块,整体走线遵循横平竖直的原则,下半区集中走线,保证PCB美观。
2.6.2 反面布局
主电源走线、地平面铺铜,布线优化短路径,增强抗干扰能力,布局1206封装的电阻,充分保证正面的布局空间。
2.6.3 实物图展示
实际焊接效果良好;各模块标识清晰,便于调试。
2.7 本章小结
本次PCB设计实现了功能完备、结构合理的控制系统硬件支持。后续根据产品实际需要,若需要进一步改进,可以从如下方面入手:
1、优化板面尺寸,提升布局紧凑性;
2、考虑EMC设计与测试,提升抗干扰性能;
3、引入模块化可插拔接口,便于维护升级。
3 硬件外设程序设计
3.1 设计目标
本章节内容主要介绍PCB上的硬件外设的程序设计以及功能接口的使用方法,包含LED、按键、IMU、电机驱动、编码器、悬崖传感器、电压读取以及碰撞传感器的相关内容。
3.2 LED
项目中共有四颗可供使用的空闲LED(LED0~1),为方便使用、扩展进行了统一的封装。目前四颗均为上拉连接低电平触发。
3.2.1 硬件描述
为了程序的规范性和可拓展性,我们需要在main文件中使用上述函数对LED进行硬件描述:
1 | typedef struct { |
其中工作模式如下:
1 | typedef enum { |
示例:LED0连接在PD端口0号引脚,低电平触发,则如下:
1 | LED_HandleTypeDef LED0 = { |
3.2.2 初始化
效果为根据描述的硬件连接匹配对应的电平输出。对应函数代码如下:
1 | /* LED 初始化函数 */ |
示例:初始化LED0,则可直接调用该函数:
1 | LED_Init (&LED0); |
3.2.3 点亮LED
效果为点亮LED。对应函数代码如下:
1 | /* 点亮LED */ |
示例:点亮LED0,则可直接调用该函数:
1 | LED_On (&LED0); |
3.2.4 熄灭LED
效果为熄灭LED。对应函数代码如下:
1 | /* 熄灭LED */ |
示例:初始化LED0,则可直接调用该函数:
1 | LED_Off (&LED0); |
3.2.5 翻转LED
效果为转换当前LED的亮灭状态。对应函数代码如下:
1 | /* 切换LED状态(开/关) */ |
示例:初始化LED0,则可直接调用该函数:
1 | LED_Toggle (&LED0); |
3.3 按键
如下图所示,项目有两个可供使用的微动按键(KEY0、KEY1),均为上拉连接低电平触发,配置为GPIO的Input模式。
3.3.1 硬件描述
硬件描述结构体如下:
1 | typedef struct { |
其中,按键状态又有如下枚举:
1 | typedef enum { |
示例:直接描述两个按钮如下,均为低电平触发:
1 | Key_HandleTypeDef key[] = { |
3.3.2 按键初始化
效果为重置按键状态,并且更新时间戳。对应函数代码如下:
1 | /* 按键初始化 */ |
示例:初始化key0:
1 | Key_Init (&key[0]); |
3.3.3 按键更新
效果为检测并更新按键的按下状态。对应函数代码如下:
1 | /* 按键更新(需要定期调用) */ |
示例:检测并更新key0:
1 | Key_Update (key[0]); |
3.3.4 获取按键状态
效果为配合按键状态更新函数,会返回Key_State中的状态,进行逻辑编写。
1 | /* 获取当前按键状态 */ |
示例:读取key1:
1 | Key_State state = Key_GetState(&key[1]); |
3.4 IMU
本次项目采用JY901S九轴姿态传感器,连接到USART2与单片机通信,使用中断的方式来接收数据,配置如下,根据与算法同学沟通,共需用到加速度、角速度、欧拉角每组三个共九个数据。
3.4.1 IMU初始化
功能为配置缓冲区并开启首次接收中断。对应函数代码如下:
1 | void JY901S_Init(UART_HandleTypeDef *huart){ |
示例:初始化IMU:
1 | JY901S_Init(&huart2); |
3.4.2 IMU数据解析
功能为根据官方文档解算IMU回传的数据。对应函数代码如下:
1 | void JY901S_UART_RxHandler(uint8_t *data){ |
示例:定义中断回调
1 | void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart){ |
3.4.3 获取IMU数据
1 | IMU_Data_t* JY901S_GetData(void){ |
示例:在主循环中获取数据:
1 | imu = JY901S_GetData(); |
此处imu作全局变量定义(IMU_Data_t *imu;),便于debug监视。
3.5 电机驱动
左右电机分别由一个A4950电机驱动来进行驱动,该芯片需要两路PWM来差值控制,左右驱动分别接至TIM1和TIM9的两路通道,设置如图所示。
3.5.1 电机初始化
基于以上配置的两路PWM通道,编写如下函数进行左右电机驱动的初始化:
1 | void A4950_Init(void){ |
3.5.2 左(右)轮驱动
根据CubeMX的设置,PWM调速绝对值上限为99。分别编写左轮与右轮的PWM驱动函数如下:
1 | // 左轮 |
3.5.3 制动
1 | void A4950_Brake(void){ |
3.6 编码器
3.6.1 结构体关联句柄
1 | typedef struct { |
示例:在主程序中定义如下结构体,分别代表左编码器与右编码器:
1 | Encoder_HandleTypeDef encL, encR; |
3.6.2 编码器初始化
效果为关联定时器的编码器接口。对应函数代码如下:
1 | void Encoder_Init(Encoder_HandleTypeDef *enc, TIM_HandleTypeDef *htim){ |
示例:绑定左右编码器并启动对应的接口,可按照如下方式调用该函数,需输入对应的编码器结构体与相关联的定时器句柄:
1 | Encoder_Init(&encL, &htim2); |
3.6.3 获取计数
1 | int32_t Encoder_GetCount(Encoder_HandleTypeDef *enc){ |
示例:
1 | leftCountGlobal = Encoder_GetCount(&encL); |
3.6.4 编码器清零
1 | void Encoder_Reset(Encoder_HandleTypeDef *enc){ |
示例:
1 | Encoder_Reset(&encL); |
3.7 悬崖传感器
共有四个悬崖传感器(0~3),使用ADC和DMA进行读取并由TIM3定时触发,ADC的配置,TIM3配置如下图所示:
3.7.1 初始化
编写以下函数,以启动定时器3的定时触发以及DMA:
1 | void CliffSensor_Init(void){ |
3.7.2 读取四个传感器值
1 | void CliffSensor_GetValues(uint16_t *out){ |
示例:
1 | CliffSensor_GetValues(sensor_vals); |
3.7.3 判断单个传感器的状态
1 | bool CliffSensor_IsCliff(uint8_t idx){ |
使用时传入对应传感器编号(0~3)即可。
3.7.4 用掩码返回所有传感器状态编码器清零
1 | uint8_t CliffSensor_GetMask(void){ |
示例:
1 | if (mask == 0) { |
3.8 碰撞传感器
机器人左前方右前方各有一个碰撞传感器,为数字器件,采用与按钮类似的逻辑编写即可,此处和悬崖一样使用了掩码方式来进行统一的封装:
1 | bool CrashSensor_Left(void){ |
3.9 电压读取
如下图所示,R124和R128阻值分别为18kΩ和1kΩ,根据分压原理,电池电压为连接ADC处的19倍,据此我们只需要用ADC读取该处模拟值还原为电压值再乘19就可以得到电池电压。此处ADC也为ADC1,与悬崖传感器一同读取。用于读取电压值的回调函数如下:
1 | float BT15V_GetVoltage(void){ |
3.10 本章小结
至此完成了单片机所需调用的所有外设的基础配置工作,并已经过基本的功能验证测试,确认各外设配置与调用均正常。负责嵌入式开发的成员将上述内容整合成使用文档,提供给负责算法的成员进行控制算法等的二次开发工作。此外,为方便版本管理,将嵌入式程序推至远程Github仓库以便于远程协同工作,仓库地址:PyConqueror-16/Sweeping。
4 上位机监控系统开发
4.1 系统架构
4.1.1 模块化设计思路
本系统采用”核心-功能-接口”三级模块化架构(如图1所示),各模块通过标准化接口进行通信。
具体设计原则如下:
- 功能解耦设计
ControlProtocol:模块独立处理指令编码,不依赖具体通信方式;
KeyboardController:将输入事件转换为标准速度指令;
BluetoothProtocol:输出结构化数据,界面模块负责可视化;
- 接口标准化
控制协议接口
1
2class ContrilProtocol:
def create_command(mode: int, speed_left: int, speed_right: int) -\> bytes:键盘控制接口
1
2class KeyboardController(QObject):
def eventFilter(self, obj: QObject, event, QEvent) -\> bool:数据解析接口
1
2class BluetoothProtocol:
def parse_data(self, raw_data: bytes) -\> List[Dict]:串口通信接口
1
2class SerialThread(QThread):
def send_command(self, command: bytes):
- 状态管理机制
采用”发布-订阅”模式处理模块间状态同步;
关键状态变更通过PyQt信号通知相关模块;
共享数据通过队列实现线程安全访问。
- 异常隔离设计
通信异常限制在SerialThread模块内处理;
界面卡顿不影响后台数据处理;
协议解析错误自动触发数据重传机制。
4.1.2 主要功能组件划分
系统功能组件及其相互关系:
表4.1 系统功能组件及其相互关系
组件类型 | 核心组件 | 功能描述 | 依赖关系 |
---|---|---|---|
控制核心 | ControlCenter | 协调各模块运行,维护系统状态机 | 依赖所有功能组件 |
通信链 | SerialThread | 管理串口连接,实现数据收发多线程处理 | →BluetoothProtocol |
BluetoothProtocol | 解析原始数据帧,校验数据完整性 | ← SerialThread | |
人机交互 | KeyboardController | 将键盘事件转换为标准控制指令 | → ControlProtocol |
GUIComponents | 提供速度调节、模式切换等交互控件 | → ControlCenter | |
数据处理 | DataProcessor | 提供速度调节、模式切换等交互控件 | ←BluetoothProtocol |
可视化 | TrajectoryVisualizer | 实时绘制机器人轨迹和姿态 | ← DataProcessor |
StatusDashboard | 显示速度、电量等实时参数 | ← DataProcessor | |
高级功能 | PathPlanner | 实现牛耕式覆盖路径规划算法 | → ControlProtocol |
DataRecorder | 支持轨迹记录与回放功能 | ← DataProcessor |
4.1.3 数据流与控制流分析
表4.2 通信数据流一览表
数据类型 | 方向 | 频率 | 数据量 | 处理方式 |
---|---|---|---|---|
控制指令 | 上位→下位 | 5-10Hz | 6Byte | 立即发送 |
状态数据 | 下位→上位 | 10Hz | 14Byte | 队列缓冲+定时处理 |
轨迹坐标 | 内部传输 | 5Hz | 12Byte | 环形缓冲区存储 |
配置参数 | 双向 | 事件触发 | ≤1KB | JSON序列化 |
实时控制流(周期≤100ms)为:
键盘输入 → KeyboardController生成标准化速度值(-100~100)
ControlProtocol将速度值编码为机器指令(0xAA 0x01…)
SerialThread通过串口发送指令
下位机响应指令并返回状态数据
BluetoothProtocol校验解析数据帧
DataProcessor进行数据平滑处理
GUI线程定时获取处理后的数据更新界面
此外,我们还针对多线程任务进行了线程安全设计,采用”生产者-消费者”模式处理串口数据,并使用QTimer实现跨线程定时触发。其中的共享资源通过QMutex进行保护。
4.2 技术选型
4.2.1 开发框架:Python+PyQt5
本系统选用Python 3.8 + PyQt5作为基础技术栈,主要基于以下考量:
Python原型能够快速开发,具有很强的开发效率优势;
Python动态特性支持实时调试,界面修改可热更新;
Python具有丰富的标准库,os/sys/json等模块简化文件操作和数据处理;
PyQt5有特有完善的GUI组件,提供超过620个可直接使用的类,对比Tkinter仅约150个;
PyQt5的信号槽机制能实现低耦合的模块通信;
PyQt5样式定制能力支持CSS语法美化界面。
4.2.2 Matplotlib用于数据可视化
采用FigureCanvasQTAgg后端实现与PyQt5无缝集成。优化后的轨迹绘制可处理10000+数据点无卡顿。
表4.3 Matplotlib功能实现方案与性能需求对应一览表
需求 | Matplotlib实现方案 | 性能指标 |
---|---|---|
机器人位姿显示 | Arrow+Circle补丁组合 | 渲染耗时<15ms |
历史轨迹覆盖 | fill_between+透明度控制 | 支持5000点实时绘制 |
动态坐标轴 | **set_xlim()**智能缩放 | 自适应刷新率 |
4.2.3 PySerial串口通信库
选用PySerial作为串口通信解决方案,主要基于其简洁高效的API设计以及稳定的通信性能。通过非阻塞读取和双缓冲机制优化,有效避免了数据堆积问题,配合定时发送控制策略(100ms间隔),在Windows平台上保持稳定表现。相较于Qt原生QSerialPort,PySerial虽然与Qt集成度稍逊,但其更简洁的异常处理机制和无需额外依赖的特性,使其成为本项目中平衡性能与开发效率的最佳选择,最终实现了与STM32下位机10Hz稳定通信、500ms内快速校正的优异表现。
4.3 用户界面设计
4.3.1 主界面布局
在主界面布局上,采用经典的”三明治”布局设计,如下图所示:
可以看到,界面中主要包含以下三块主要的功能区域:
顶部控制区(设备连接组、控制设置组)
中部数据显示区(左侧实时数据面板、右侧轨迹图)
底部功能区(辅助控制按钮组、帮助信息栏)
4.3.2 交互设计
本项目用户GUI界面的交互设计主要体现在以下几个板块:
- 控制面板交互:主要包含速度调节交互(滑块与数值标签联动)与设备连接(流程图如下图所示)
- 数据可视化:
- 状态反馈机制:
在评价交互的响应性能时,我们设定了以下指标,保证用户在界面交互过程中能够得到即时且准确的反馈:
表4.4 交互性能响应指标
操作类型 | 响应延迟 | 视觉反馈方式 |
---|---|---|
按钮点击 | <50ms | 按钮下沉动画 |
滑块拖动 | 即时 | 数值标签实时更新 |
键盘控制 | <30ms | 轨迹即时更新 |
数据加载 | <200ms | 进度条+旋转等待图标 |
4.4 核心功能模块
4.4.1 通讯协议模块(ControlProtocol)
实现上下位机通讯时,我们采用帧通讯的方式实现即时通讯。其中,协议帧具有双极性速度编码(正/负方向独立处理),校验和简化算法(求和取低8位),固定6字节帧长保证传输效率等特点。
4.4.2 键盘控制模块(KeyboardController)
在该模块中定义并实现了基本的按键与遥操作功能,并引入了防抖机制。
4.4.3 蓝牙协议解析(BluetoothProtocol)
4.4.4 串口通信线程(SerialThread)
4.5 高级功能实现
4.5.1 轨迹记录与回放
数据中包含:记录动作创建时间,传送指令总量,总持续时间,控制模式;时间,指令间时间差,指令,模式。
4.5.2 地图数据管理
JSON文件具有加载速度快、压缩率高、可读性强的特点,所以地图存储同样使用JSON文件的不同格式来保存地图信息。
4.5.3 路径规划功能
此处仅展示路径规划算法可视化效果,具体算法细节在第五章详细阐述。
4.6 本章小结
本章详细介绍了上位机监测与控制系统的设计流程,从整体架构到功能实现效果,有效实现了上下位机间的相互通信,并能成功进行遥控功能与数据可视化。界面交互设计上充分考虑人因学因素,布局合理,简单易用,能够方便用户实现对机器人即时而准确的移动控制与状态监测。
5 控制逻辑与算法设计
5.1 下位机整体底盘控制逻辑
根据需求分析部分提出的设计需求与性能指标,在下位机的底盘控制上主要分为如下几个控制功能逻辑模块:
模式指令读取/基于按键切换
基于编码器获取实时电机转速并利用PID控制器调节电机转速
机器人实时位姿解算与惯导定位
针对碰撞/悬崖等传感器感知数据做出实时响应
这些模块间的交互关系如下面的逻辑框图所示。接下来将依次介绍各模块的实现细节。
接下来将依次介绍各模块的实现细节。
5.1.1 开/关机按键与模式指令接受逻辑设计
在开关机按键与模式切换逻辑设计上,我们采用了如下图所示的框图逻辑,充分利用电路板上预留的两个按键,实现机器人的开关机:
扫地机器人一共具有三种状态模式,模式代码及其对应功能如下:
0 ROBOT_OFF:关机状态,位姿和里程均重置为0
1 REMOTE_CONTROL:遥控模式,左右轮速度通过上位机指令获取
2 AUTO_MAPPING:自主建图模式,按设定速度(左轮15cm/s,右轮3cm/s)结合碰撞传感器实现贴墙行进
其中,模式1和模式2由接收到的上位机数据包经函数解析后得到的模式码决定,上位机GUI中可自由切换。同时,为便于用户日常使用,我们将PCB电路板上预留的两个按钮KEY0与KEY1使能,通过上述逻辑使得:按下KEY0后为关机状态,此时置为模式0且不会接收上位机发送的模式信息;按下KEY1后为开机状态,此时开始接收上位机发送的模式信息,并按照上位机指令进行后续运动。
该模块实现的主要代码如下:
1 | // 更新按键状态 |
其中调用了用于重置机器人状态的函数ResetRobotState,在关机时会运行该函数,重置当前存储的偏角、里程等数据:
1 | // 重置机器人状态 |
5.1.2 基于编码器的电机转速PID控制算法设计
针对电机转速的精准控制,我们选择采用PID控制器,基于经编码器解析而来的实时转速信息实现反馈调节,使得电机转速能够在较短的时间响应达到设定的速度。
在电机转速的获取上,我们基于编码器的读取数据进行解算,换算关系如下:
查阅电机的产品手册,可以获得该电机与编码器对应的相关参数:
减速比𝑀𝑂𝑇𝑂𝑅_𝑅𝐸𝐷𝑈𝐶𝑇𝐼𝑂𝑁_𝑅𝐴𝑇𝐼𝑂 = 1 : 63
每转过一圈的脉冲数𝑃𝑈𝐿𝑆𝐸_𝑃𝐸𝑅_𝑅𝑂𝑈𝑁𝐷 = 20
单位时间𝑡𝑖𝑚𝑒 = 50ms
轮子周长CIRCLES_OF_TIRE = 34 * 2 * 3.14 mm
基于上述公式,编写以下函数代码,用于计算电机实时转速:
1 | float getLeftSpeed(Encoder_HandleTypeDef *enc){ |
1 | float getRightSpeed(Encoder_HandleTypeDef *enc){ |
在电机转速控制器上,我们选择最为经典的PID控制器用于实现电机转速的实时反馈调节,PID控制器主要具有以下几个特点:
为系统指定一个目标值;
PID将目标值与被控对象当前的反馈量作差得到误差;
PID将误差值分别经过三个环节计算得到输出分量,再将三个分量加起来得到PID的输出;
将PID的输出施加到被控对象上,使反馈量向目标值靠拢。
基于上述PID算法原理,我们将其封装成了如下的函数,实现对指定转速的快速动态响应:
1 | void PID_Control_Left(float target_speed_left){ |
1 | void PID_Control_Right(float target_speed_right){ |
在main函数中,我们可以根据接收到的上位机速度指令,直接调用上述函数读取实时转速并利用PID控制器进行速度调节:
1 | // 运动控制 |
其中,经过实机测试与调整,我们最终采用的PID控制器参数为:KP=0.1,KI=0.1,KD=0.001。经测试,该组参数在目标电机转速为5至15cm/s时具有高灵敏度与高精度的动态响应特性。
5.1.3 机器人实时位姿解算与惯导定位
在机器人的位姿解算上,我们采用了综合电机实时转速与IMU惯导模块的方式,通过电机转速计算单个时间步内的分段里程(根据时间步长可以累加得到总里程),同时结合IMU直接读取到当前机器人的面朝偏角(启动时标志为0,范围为-180°~180°),可以得到单个时间步内机器人的近似位移,进而计算出机器人的实时位置坐标(相对于摁下开机键后的起始点而言,起始点坐标(0,0),面朝方向为y轴正方向)。
在实际计算与调试时,为降低调速过程中的距离计算误差,对达到指定速度前后的距离计算进行不同倍率的调整,以尽可能保证距离计算的精准度。
基于以上思想,编写如下代码实现机器人的实时位姿解算与惯导定位:
1 | // 位姿计算(融合IMU+编码器) |
后续可将实时总里程、位置坐标与偏角等数据发送至上位机,进行进一步的建图可视化处理。
5.1.4 碰撞/悬崖传感器感知数据处理逻辑设计
在碰撞与悬崖传感器反馈的感知数据的处理上,我们设计了如下图所示的框图逻辑(以碰撞为例,逻辑上设置碰撞传感器的处理优先级高于悬崖,事实上两者往往互斥),让机器人实现贴墙/悬崖行进,以尽可能地清扫到所有的清洁死角:
在遥控模式下,为避免机器人进入视野盲区(如床底等区域)而产生误操作,设定该模式下机器人遇到障碍物时(即碰撞传感器触发)先后退再原地掉头。
在自主运动(建图)模式下,为使得机器人尽可能稳定地贴墙行进,针对两侧碰撞传感器共三种不同的触发状态,分别设置了不同的转角提供给turning_left函数执行左转,并在达到指定转角后重置碰撞状态。
显然,处于保护机器人自身安全的原则,其对于传感器的感知数据做出的任何反应的优先级均应高于上位机的控制命令。
为对于不同的碰撞情形进行区分,我们对碰撞状态码进行了区分,并设定了机器人在不同碰撞状态下应该做出的反应,以尽可能完成贴墙行走的任务:
crash_status = 1 :左侧碰撞 —— 左转60°
crash_status = 3 :两侧均碰撞 —— 左转40°
crash_status = 2 :右侧碰撞 —— 持续左转直至不再碰撞(直行)
crash_status = 0 :无碰撞,按照上位机发送速度或设定速度继续行进
针对悬崖传感器,其感知数据的处理逻辑与碰撞类似,均为先后退再原地掉头(偏转一定角度后继续行进)。不同的是,由于悬崖传感器本质上是红外传感器,因此我们需要事先测定其阈值(由于不同传感器的性能差异,其阈值也有所不同)为{245,145,190,130}。本项目使用的扫地机器人硬件设备上共有四个悬崖传感器,其中任一触发时(大于阈值)其对应的二进制掩码cliff_mask均不为0,此时可认为机器人已到达悬崖边缘,需要做出对应的响应。
针对遥控模式,处理碰撞与悬崖传感器感知数据的代码如下:
1 | // 优先处理碰撞 |
针对自主运动(建图)模式,处理碰撞与悬崖传感器感知数据的代码如下:
1 | // 优先处理碰撞 |
5.2 全覆盖路径规划算法设计:牛耕式扫描Boustrophedon
针对扫地这一具体应用场景,希望尽可能不放过区域内的每一个清洁死角,这实际是一个全覆盖路径规划(Complete Coverage Path Planning, CCPP)任务,需要确定一条路径,在避开障碍物的情况下通过该区域范围内的所有点。
我们选择采用离线式的牛耕式扫描法,基于静态环境信息,通过不断地覆盖分割后的子区域实现整个区域的全覆盖。牛耕式扫描(Boustrophedon Coverage)是一种高效的全覆盖路径规划算法,其核心思想是模拟农耕时的犁地模式,通过往复式运动实现无遗漏覆盖。算法首先将工作区域划分为若干条带,条带宽度w由机器人清扫半径(经测量机器人机身直径为32cm)决定,相邻条带间距通常取d≤w以确保覆盖连续性。机器人沿初始方向(y轴)移动,到达边界后垂直偏移d并反向移动,形成如下的路径模式:
$$
\begin{cases}x_{k+1}=x_k+(-1)^k\cdot L\y_{k+1}=y_k+d&\end{cases}
$$
其中L为条带长度,k为往返计数。当遇到障碍物时,算法会将区域分解为若干子多边形,在每个子区域内独立执行牛耕式扫描。该方法的覆盖率理论上可达100%,其路径总长度可表示为:
$$
D\approx\frac{A}{w}\cdot(L+2t)
$$
式中A为区域面积,t为转向损耗距离。
实际应用中,该算法常结合SLAM技术动态调整w,并通过匈牙利算法优化子区域访问顺序以提升效率。这种平衡了覆盖率和能耗的特性,使其成为扫地机器人等清洁设备的首选方案。
在建图过程中,由于没有采用激光雷达(电路板上未预留对应接口),我们通过机器人自主巡航模式下的贴墙碰撞,实现对封闭区域边界的建图。
基于以上算法原理,编写如下Python函数,根据建图过程中采集到的边界点云数据,调用牛耕式扫描算法规划全覆盖路径与关键节点:
1 | def generate_coverage_path(x_coords, y_coords, robot_width): |
基于这些关键节点,可以进一步生成各时间步的左右轮速度:
1 | def calculate_wheel_velocities(x_path, y_path, robot_diameter, dt): |
以上所有的计算均在上位机完成,将这些速度信息按照时间步顺序依次发送至下位机,从而可以实现规划路径的运动控制。由于建图时仅扫描边界,下位机实际控制时仍然需要结合传感器反馈做出响应。
5.3 本章小结
本章主要介绍了机器人下位机整体底盘控制的基本逻辑框架,并对其中主要的功能模块实现细节进行介绍。该部分为基于已配置好各种外设的单片机工程的二次开发,由负责运动控制算法开发的成员从负责嵌入式的成员建立的Github仓库中Fork出来并在Algorithm分支中进行后续算法部分的开发更新,仓库地址:微电路设计课程项目。
除此之外,本章还介绍了我们采用的全覆盖路径规划算法——牛耕式扫描算法的基本原理与部分实现细节,这也与扫地机器人这一实际应用场景相契合。
6 项目实现效果与总结
演示视频链接:https://www.bilibili.com/video/BV1HkKNzDEjV
6.1 项目实现效果
项目最终圆满完成了第一章需求分析中给出的所有功能设计需求,并基本达到了设定的需求指标。下面将给出部分主要功能的测试结果。
6.1.1 直线行驶精度测试
结合高精度的位姿解算与电机转速调节,我们可以对扫地机器人的运动实现高精度的控制。下图为扫地机器人直线行驶固定距离100cm的精度测试情况:
可以看到,在该测试中无论是距离精度还是行驶偏角均满足设定的性能需求(偏角<5°,距离偏差<2cm),这一方面说明PID控制器对于电机转速的控制具有良好的动态响应特性,另一方面也说明了位姿解算补偿算法的高精度。
6.1.2 指定转角精度测试
为便于应对碰撞/悬崖等突发情况,编写了固定转角旋转函数以根据不同情形做出灵活反应:
void turning_left(float CONTROL_DEG){
1 | void turning_left(float CONTROL_DEG){ |
其中,基于当前角度制,根据几何关系指定如下规则,判定机器人是否转过指定角度(需记录开始旋转时偏角turn_start_deg)【满足以下任一条即可】:
当前偏角 > 起始偏角 + 指定转角
起始偏角 > 180° - 指定转角 且 当前偏角 > 起始偏角 + 指定转角 – 360° 且 当前偏角 < 指定转角 – 180°
为提高旋转角度精度,考虑响应滞后性与运动惯性等问题,还在角度判标中加入转动加速度gy。
调用该函数进行测试,结果如上图所示。可以看到,在设定旋转角度为90°的情况下,机器人转过了91.7°,与实际设定角度相差小于2°,说明在基于IMU的偏角位姿结算上也具有较高的精度。当然,若增大原地旋转时的左右轮速度,该偏差值会由于惯性而有所增大,因此后续优化时可以考虑进一步采用高阶的转动加速度函数对转角控制进行修正。
6.1.3 贴墙行进与建图效果测试
可以看到,在自制的约150cm*100cm的封闭多边形区域内,机器人能够很好地完成贴墙行进的任务,同时在上位机客户端的建图精度也较高,基本还原了整个封闭区域的地形轮廓。
6.1.4 全覆盖路径规划效果测试
基于上述贴墙建图的测试结果,将路径点云数据以JSON文件形式导出存储。在路径规划测试时,将点云数据再次导入至客户端,并点击“路径规划”,效果如上图所示。可以看到,生成的路径与算法原理相一致。在实机部署实现的过程中,结合路径规划的关键点与实时的碰撞感知数据,机器人能够良好地扫过地图内的所有区域并避开障碍物,这进一步说明了路径规划与运动控制算法的有效性。
6.2 总结与收获
在本次微电路设计课程项目中,我们组的四位成员合理分工、通力合作,成功完成了SmartRobot扫地机器人的设计与开发工作。从项目需求分析、PCB电路设计、硬件外设程序设计,到上位机监控系统开发、控制逻辑与算法设计,再到最终的测试与优化,每一个环节都凝聚了团队成员的心血与智慧。通过复刻和优化现有扫地机器人的硬件方案,我们深入研究了其核心功能模块,包括运动控制、传感器数据处理、路径规划算法等,并结合实际应用场景进行了针对性改进。
在项目过程中,我们不仅掌握了PCB设计、嵌入式编程、传感器集成、电机控制等核心技术,还深刻体会到团队协作的重要性。通过分工合作,每位成员充分发挥了自己的专长,共同攻克了技术难题。例如,PCB设计中的电源管理优化、电机驱动选型,嵌入式程序中的PID控制算法实现,上位机系统的模块化设计与交互优化,以及全覆盖路径规划算法的开发与部署,都是团队智慧的结晶。
此外,项目还锻炼了我们的工程实践能力和问题解决能力。从理论到实践,我们学会了如何将课堂知识应用于实际项目,如何通过调试与测试不断优化系统性能。最终,扫地机器人实现了良好的避障功能、防坠落能力、高精度运动控制以及用户远程监控等设计目标,圆满完成了各项性能指标。
通过这次项目,我们不仅提升了专业技能,还增强了团队协作与沟通能力,为未来的工程实践与科研工作积累了宝贵经验。我们深刻认识到,技术创新需要扎实的理论基础、严谨的工程态度和高效的团队合作。这段经历将成为我们成长道路上难忘的一课,激励我们在未来的学习和工作中继续追求卓越。
6.3 本章小结
本章对于机器人功能与性能指标的测试结果进行了展示与分析,并对于项目成果与收获进行了总结。
SmartRobot扫地机器人