【ART-Pi作品秀】瞎转悠
作者: 樊晓杰
概述
简单介绍项目应用产生的背景 ,所产生的软硬件方案 及主要实现的功能。
应用产生背景
在和娃玩老鹰转小鸡时候,突然就想做个小车,可以和孩子互动,就想到人挡在小车前面,然后转向,就一直这么循环下去,一个很简单的功能。就是漫无目的 瞎转悠,这就是名字的由来。也是一个提醒,尤其到冬天了还是在疫情期间,没事别瞎转悠,老实在家呆着没事 就玩玩rt-thread,多参加参加电路城的活动。
所采用的硬件方案
硬件方案采用 : 主控板 ART-Pi + SR04 超声波 测距仪 + 小车套件。
1.ART-Pi 简介
ART-Pi是 RT-Thread 团队经过半年的精心准备,专门为嵌入式软件工程师、开源创客设计的一款极具扩展功能的 DIY 开源硬件。
板载资源:
-
- STM32H750XBH6 - On-board ST-LINK/V2.1 - USB OTG with Type-C connector
-
- SDIO TF Card slot - SDIO WIFI:AP6212 - HDC UART BuleTooth:AP6212
-
- RGB888 FPC connector - 32-Mbytes SDRAM - 16-Mbytes SPI FLASH
-
- 8-Mbytes QSPI FLASH - D1(blue) for 3.3 v power-on - Two user LEDs:D2 (blue),D2 (red)
-
- Two ST-LINK LEDs: D4(blue),D4 (red) - Two push-buttons (user and reset)
扩展接口:
-
- 4路UART(LPUART) - 3路SPI - 2路hardware iic
-
- 1路USB-FS - 1路ETH - 1路SAI
-
- 1路DCMI - 2路CANFD - 超过5路ADC (支持查分输入ADC)
驱动支持:
-
- UART - SPI - SDMMC - CAN - QSPI
-
- ADC - PWM - DCMI - SAI - LTDC
-
- USB - ETH - SDRAM - HRTIM - I2C
2.SR04 超声波测距传感器
超声波测距 我们这里采用很常见的一个模块 SR04 。HC-SR04超声波模块常用于机器人避障、物体测距、液位检测、公共安防、停车场检测等场所。HC-SR04超声波模块主要是由两个通用的压电陶瓷超声传感器,并加外围信号处理电路构成的。
3. 小车套件
小车基础平台采购慧净电子四驱智能小车底盘 及驱动板。
4.电机驱动模块:
每一路需要3个信号控制,一路pwm ,一路正传一路反转。
所采用软件方案
软件方案 基于 RT-Thread IoT RTOS 此方案中使用SR04 超声波测距软件包,RT-Robot 软件包。
开发环境:
使用的是rt-thread 4.0.3 版本软件,使用mdk 结合env 工具 开发。
分别简介如下:
RT-Thread 的架构简介:
近年来,物联网(Internet Of Things,IoT)概念广为普及,物联网市场发展迅猛,嵌入式设备的联网已是大势所趋。终端联网使得软件复杂性大幅增加,传统的 RTOS 内核已经越来越难满足市场的需求,在这种情况下,物联网操作系统(IoT OS)的概念应运而生。物联网操作系统是指以操作系统内核(可以是 RTOS、Linux 等)为基础,包括如文件系统、图形库等较为完整的中间件组件,具备低功耗、安全、通信协议支持和云端连接能力的软件平台,RT-Thread 就是一个 IoT OS。
RT-Robot 是 RT-Thread 的机器人框架,希望能够支持智能小车、机械臂、无人机等各种不同类型的机器人。
当前以智能车为主要目标,希望支持两轮差分驱动、四轮差分驱动、麦克纳姆轮驱动、经典 Ackerman (两轮差分,一方向连杆) 的小车底盘。
当前功能特点:
SR04 软件包工作流程 ultrasonic sensor v2.0 a.单片机引脚触发Trig测距,给至少 10us 的高电平信号; b.模块自动发送 8 个 40khz 的方波,自动检测是否有信号返回; c.有信号返回,通过 IO 输出一高电平,并单片机定时器计算高电平持续的时间; d.超声波从发射到返回的时间. 计算公式:测试距离=(高电平时间*声速(340M/S))/2;
目前 程序使用如下线程:
线程 | 功能 | 优先级 |
---|---|---|
按键处理线程 | 处理按键响应 | 20 |
小车控制线程 | 控制小车四轮驱动 | 23 |
测距线程 | 处理距离数据处理 | 16 |
led 线程 | 程序正常运行指示 | 10 |
FinSH线程 | 命令行组件,方便调试 | 20 |
实现功能
-
按键按下,小车功能启动;
-
小车一直测量前方距离,当距离小于30cm 时,左拐,然后前进
-
然后一直循环上述判断过程
-
按键再次按下,小车停止。
RT-Thread 使用情况概述
应用中RT-Thread 使用情况:
内核部分:
1.使用到四个线程:按键处理线程,超声波测距线程,小车控制线程,led 状态显示线程。
2.线程间通信使用:邮箱在超声波测距线程中将距离数据发送给小车控制线程,
3.线程间同步使用:信号量作为按键 处理线程 和 电机控制线程之间 启动停止的信号 同步。
设备驱动部分:
1.PWM 设备及驱动-------电机驱动部分用到
2.定时器设备及驱动-------超声波测距 部分用到
组件部分:
1.FinSH控制台 ----------------调试用到
软件包部分:
-
SR04 超声波测距 软件包 ,一贯的好用,方便集成;地址如下:
-
robot RT-Thread 的机器人框架软件包 ,数据结构优美的一个软件包 .地址如下:
硬件框架说明
主控芯片 | STM32H750XBH6 | Cortex-M系列高性能处理器,M7内核,主频400MHz |
---|---|---|
超声波测距模块 | SR04 | 可提供 2cm - 400cm 的非接触式距离感测功能 |
电机驱动板 | L298P直流电机驱动模块 | 4路直流电机驱动模块 |
小车车架 | 4轮驱动 | 智能小车底盘套件 |
供电模块 | 2节 18650 | 3.7V 大容量锂电池 |
硬件方案 直接使用 ART-Pi开发板,使用的外设说明如下:
-
按键用来启动小车,停止小车;
-
测距模块使用定期器来换算 距离;
-
直流电机驱动模块使用PWM 驱动;
-
led 显示系统正常运行;
接线说明:这个系统使用到的引脚如下
超声波 TRIG PB1 ECHO PB2 定时器13. PWM: 有网友说用到 time2 --- 2,3 tim5 两个引脚 。 PH10 CH1 TIME5 正转 PB12 反转 PG10 PH11 CH2 TIME5 正转 PA15 反转 PH15 PH12 CH3 TIME5 正传PH13 反转 反转 PI3 PI0 CH4 TIME5 正转 PH7 反转 PH9 led: RED: PC15 BLUE: PI8 按键: PH4 低电平有效。
软件框架说明
【主要介绍应用所采用的软件方案框图、流程图等】
最终的使用的线程情况如下:
msh />ps thread pri status sp stack size max used left tick error -------- --- ------- ---------- ---------- ------ ---------- --- sr04 16 suspend 0x00000118 0x00000400 27% 0x00000002 000 tshell 20 running 0x00000108 0x00001000 12% 0x00000004 000 keythrea 20 suspend 0x00000080 0x00000200 25% 0x00000005 000 motor_ru 23 suspend 0x00000150 0x00000400 32% 0x00000004 000 tidle0 31 ready 0x00000044 0x00000100 32% 0x0000000a 000 timer 4 suspend 0x00000060 0x00000200 18% 0x00000009 000 main 10 suspend 0x0000008c 0x00000800 16% 0x00000004 000
软件流程:
-
上电开机 led 显示系统正常运行;
-
电机控制线程 接收按键信号 启动信号量 ,启动电机 直行,;
-
sr04 超声波测距模块线程 接收到启动信号后 ,开始测距,并将测量数据发给 通过邮箱 发给 电机控制线程;
-
电机控制线程通过邮箱 接收到距离数据判断有障碍物,就左转,直行;
-
电机控制线程接收到按键 停止信号 停止信号量 ,然后停车。
软件模块说明
(介绍应用软件关键部分的逻辑、采用的实现方式等)
1.电机控制模块处理
电机控制模块,主要控制电机的直行 转向 ,停止 及对接收到的距离数据的处理,关键代码具体如下:
static void motor_entry(void *parameter) { rt_uint32_t count = 0; motor_t letf_moto = RT_NULL; motor_t right_moto = RT_NULL; //chassis_t chas; struct velocity target_vel; // 1. Initialize two wheels - left and right wheel_t* c_wheels = (wheel_t*) rt_malloc(sizeof(wheel_t) * 4); if (c_wheels == RT_NULL) { LOG_D("Failed to malloc memory for wheels"); } // 1.1 Create two motors //motor_t left_motor = motor_create(left_motor_init, left_motor_enable, left_motor_disable, left_motor_set_speed, DC_MOTOR); //motor_t right_motor = motor_create(right_motor_init, right_motor_enable, right_motor_disable, right_motor_set_speed, DC_MOTOR); single_pwm_motor_t left_forward_motor = single_pwm_motor_create(LEFT_FORWARD_PWM,LEFT_FORWARD_PWM_CHANNEL, LEFT_FORWARD_STRAIGHT_PIN, LEFT_FORWARD_BACK_PIN); single_pwm_motor_t left_backward_motor = single_pwm_motor_create(LEFT_BACKWARD_PWM,LEFT_BACKWARD_PWM_CHANNEL, LEFT_BACKWARD_STRAIGHT_PIN, LEFT_BACKWARD_BACK_PIN); single_pwm_motor_t right_forward_motor = single_pwm_motor_create(RIGHT_FORWARD_PWM,RIGHT_FORWARD_PWM_CHANNEL, RIGHT_FORWARD_STRAIGHT_PIN, RIGHT_FORWARD_BACK_PIN); single_pwm_motor_t right_backward_motor = single_pwm_motor_create(RIGHT_BACKWARD_PWM,RIGHT_BACKWARD_PWM_CHANNEL, RIGHT_BACKWARD_STRAIGHT_PIN, RIGHT_BACKWARD_BACK_PIN); // 1.2 Create two encoders //encoder_t left_encoder = encoder_create(LEFT_ENCODER_PIN, PULSE_PER_REVOL); //encoder_t right_encoder = encoder_create(RIGHT_ENCODER_PIN, PULSE_PER_REVOL); single_phase_encoder_t left_forward_encoder = single_phase_encoder_create(LEFT_ENCODER_PIN,PULSE_PER_REVOL,SAMPLE_TIME ); single_phase_encoder_t right_forward_encoder = single_phase_encoder_create(RIGHT_ENCODER_PIN,PULSE_PER_REVOL,SAMPLE_TIME); // 1.3 Create two pid contollers //pid_control_t left_pid = pid_create(); //pid_control_t right_pid = pid_create(); inc_pid_controller_t left_pid = inc_pid_controller_create(kp,ki,kd,SAMPLE_TIME); inc_pid_controller_t right_pid = inc_pid_controller_create(kp, ki,kd,SAMPLE_TIME); // 1.4 Add two wheels //wheel_t wheel_create(motor_t w_motor, encoder_t w_encoder, controller_t w_controller, float radius, rt_uint16_t gear_ratio) c_wheels[0] = wheel_create((motor_t)left_forward_motor, (encoder_t)left_forward_encoder,(controller_t)left_pid, WHEEL_RADIUS, GEAR_RATIO);//left_pid c_wheels[2] = wheel_create((motor_t)left_backward_motor, (encoder_t)left_forward_encoder,(controller_t)left_pid, WHEEL_RADIUS, GEAR_RATIO);//left_pid c_wheels[1] = wheel_create((motor_t)right_forward_motor, (encoder_t)right_forward_encoder,(controller_t)right_pid, WHEEL_RADIUS, GEAR_RATIO);//left_pid c_wheels[3] = wheel_create((motor_t)right_backward_motor, (encoder_t)right_forward_encoder,(controller_t)right_pid, WHEEL_RADIUS, GEAR_RATIO);//left_pid // 2. Iinialize Kinematics - Two Wheel Differential Drive kinematics_t c_kinematics = kinematics_create(FOUR_WD, WHEEL_DIST_X, WHEEL_DIST_Y, WHEEL_RADIUS); // 3. Initialize Chassis chas = chassis_create(c_wheels, c_kinematics); // 4. Enable Chassis //chassis_enable(chas); // Set Sample time encoder_set_sample_time(chas->c_wheels[0]->w_encoder, SAMPLE_TIME); encoder_set_sample_time(chas->c_wheels[1]->w_encoder, SAMPLE_TIME); encoder_set_sample_time(chas->c_wheels[2]->w_encoder, SAMPLE_TIME); encoder_set_sample_time(chas->c_wheels[3]->w_encoder, SAMPLE_TIME); //pid_set_sample_time(chas->c_wheels[0]->w_pid, PID_SAMPLE_TIME); //pid_set_sample_time(chas->c_wheels[1]->w_pid, PID_SAMPLE_TIME); // 4. Enable Chassis chassis_enable(chas); // Turn left **struct rt_sensor_data *sensor_data;//关键地方** while(1) { //chassis_update(chas); /* 永久方式等待信号量,获取到信号量,则执行number自加的操作 */ result = rt_sem_take(start_sem, RT_WAITING_FOREVER); if (result != RT_EOK) { rt_kprintf("thread2 take a start semaphore, failed.n"); rt_sem_delete(start_sem); return; } else { number++; rt_kprintf("thread2 take a start semaphore. number = %dn", number); while(1) { run();//直行 /* 从邮箱中收取邮件 */ if (rt_mb_recv(&mb, (rt_uint32_t *)&sensor_data, RT_WAITING_FOREVER) == RT_EOK) { // rt_kprintf("thread1: get a mail from mailbox, the content:%sn", ); if (sensor_data.data.proximity/10 < 30) { rt_kprintf("distance:%3d.%dcm, timestamp:%5d turn left n", sensor_data.data.proximity / 10, sensor_data.data.proximity % 10, sensor_data.timestamp); left(); } /* 延时100ms */ rt_thread_mdelay(100); } result = rt_sem_take(stop_sem, RT_WAITING_NO); if (result == RT_EOK) { //rt_kprintf("thread2 take a start semaphore, failed.n"); //rt_sem_delete(stop_sem); stop(); break; } } } rt_thread_mdelay(1500); } }
调试说明:
①主要看pwm 是否可以正常输出波形。
可以通过命令:来测试。遇到过 有下面波形,但和电机程序结合起来的话,没有输出波形。
msh />pwm_set pwm5 2 1000 500
msh />pwm_e
pwm_enable
msh />pwm_enable pwm5 2
msh />pwm_disable pwm5 2
② 有个电机控制引脚,PA15,初始就是高电平,导致一上电就转,换一个其他引脚。
③先把几个引脚都先调通,对应起来,可以通过直接将引脚接高电平的方式,来测试,因为线不一定接的对。可以先根据引脚的分布,初步先列出来控制引脚序号。然后再通过调试,进行调整。
④ 通过第一步调试,证明pwm 驱动没有问题,但任然出现过 robot 程序 没有输出pwm 波形,原因分析如下:
通过单步调试,发现最终只是设置了速度,并没有最后的运行。也就是这句 chassis_update(chas);
⑤ 有波形 但占空比很低的话,电机也跑不起来,可以在
rt_pwm_set(mot_sub->pwm_dev, mot_sub->channel, MOTOR_PWM_PERIOD, pluse + 28000 );//50 000 在一半的 基础上增加。
⑥ 调试其他几个方向,比如不动的话,可以实时调整参数。比如下面几个:
void stop(void)
{
struct velocity target_vel;
target_vel.linear_x = 0.0; // m/s
target_vel.linear_y = 0; // m/s
target_vel.angular_z = 0; // rad/s
chassis_set_velocity(chas, target_vel);
chassis_update(chas);
rt_thread_mdelay(500);
}
MSH_CMD_EXPORT(stop, moto stop);
void left(void)
{
struct velocity target_vel;
// Turn left
target_vel.linear_x = 0.8;//0.06; // m/s
target_vel.linear_y = 0; // m/s
target_vel.angular_z = PI / 4; // rad/s
chassis_set_velocity(chas, target_vel);
chassis_update(chas);
rt_thread_mdelay(800);
stop();
}
MSH_CMD_EXPORT(left, moto left);
void right(void)
{
struct velocity target_vel;
// Turn right
target_vel.linear_x = 0.8;//0.06; // m/s
target_vel.linear_y = 0; // m/s
target_vel.angular_z = - PI / 4; // rad/s
chassis_set_velocity(chas, target_vel);
chassis_update(chas);
rt_thread_mdelay(400);
stop();
}
MSH_CMD_EXPORT(right, moto right);
void run(void)
{
rt_kprintf("runrn");
struct velocity target_vel;
// Go straight
target_vel.linear_x = 1.0;//0.08; // m/s
target_vel.linear_y = 0; // m/s
target_vel.angular_z = 0;
chassis_set_velocity(chas, target_vel);
chassis_update(chas);
rt_thread_mdelay(500);
}
MSH_CMD_EXPORT(run, moto straight);
void back(void)
{
struct velocity target_vel;
// Go straight
target_vel.linear_x = -1.0;//-0.08; // m/s
target_vel.linear_y = 0; // m/s
target_vel.angular_z = 0;
chassis_set_velocity(chas, target_vel);
chassis_update(chas);
rt_thread_mdelay(500);
}
MSH_CMD_EXPORT(back, moto back);
2.按键处理模块
按键处理模块,主要 是 发送开始 和停止信号。
关键代码:
#define USER_KEY_1 GET_PIN(H,4) static rt_uint8_t flag_start = 0; /* 指向信号量的指针 */ rt_sem_t start_sem = RT_NULL; rt_sem_t stop_sem = RT_NULL; void process_key(void *args) { rt_thread_mdelay(50); if (rt_pin_read(USER_KEY_1) == 0) { if (flag_start == 0) { flag_start = 1; rt_sem_release(start_sem); } else { flag_start = 0; rt_sem_release(stop_sem); } } } static void key_entry(void *parameter) { rt_pin_mode(USER_KEY_1, PIN_MODE_INPUT_PULLUP); rt_pin_attach_irq(USER_KEY_1, PIN_IRQ_MODE_FALLING, process_key, RT_NULL); while(1) { rt_thread_mdelay(1000); } }
3. SR04 超声波测距模块
超声波测距模块,完成距离测量,并将数据通过邮箱发给电机控制模块。关键代码分析:
为什么这里选择邮箱作为两个线程间通信的方式?
(1)邮箱的开销比较低,效率高;
(2)非阻塞方式的邮件发送过程能够安全地应用于中断服务中,是线程,中断服务,定期器想线程发送消息的有效手段。
如何用邮箱来发送一个传感器接收的数据?
(1)
为什么这里选择邮箱作为两个线程间通信的方式?
(1)邮箱的开销比较低,效率高;
(2)非阻塞方式的邮件发送过程能够安全地应用于中断服务中,是线程,中断服务,定期器想线程发送消息的有效手段。
如何用邮箱来发送一个传感器接收的数据?
(1) 就是如何发送这个数据结构的地址,然后接收线程可以解析这个数据接收,也就是通过邮箱发送指定数据结构的数据。直接取这个数据结构的地址,接收线程,定义一个 对应数据结构的指针,然后取 & 这个地址,取出数据,就可以。这是取到正确数据最关键的地方。
struct rt_sensor_data { rt_uint32_t timestamp; /* The timestamp when the data was received */ rt_uint8_t type; /* The sensor type of the data */ union { struct sensor_3_axis acce; /* Accelerometer. unit: mG */ struct sensor_3_axis gyro; /* Gyroscope. unit: mdps */ struct sensor_3_axis mag; /* Magnetometer. unit: mGauss */ rt_int32_t temp; /* Temperature. unit: dCelsius */ rt_int32_t humi; /* Relative humidity. unit: permillage */ rt_int32_t baro; /* Pressure. unit: pascal (Pa) */ rt_int32_t light; /* Light. unit: lux */ rt_int32_t proximity; /* Distance. unit: centimeters */ rt_int32_t hr; /* Heart rate. unit: bpm */ rt_int32_t tvoc; /* TVOC. unit: permillage */ rt_int32_t noise; /* Noise Loudness. unit: HZ */ rt_uint32_t step; /* Step sensor. unit: 1 */ rt_int32_t force; /* Force sensor. unit: mN */ rt_uint32_t dust; /* Dust sensor. unit: ug/m3 */ rt_uint32_t eco2; /* eCO2 sensor. unit: ppm */ } data; };
struct rt_sensor_data sensor_data; static void sr04_read_distance_entry(void *parameter) { rt_device_t dev = RT_NULL; rt_size_t res; dev = rt_device_find(parameter); if (dev == RT_NULL) { rt_kprintf("Can't find device:%sn", parameter); return; } if (rt_device_open(dev, RT_DEVICE_FLAG_RDWR) != RT_EOK) { rt_kprintf("open device failed!n"); return; } rt_device_control(dev, RT_SENSOR_CTRL_SET_ODR, (void *)100); while (1) { res = rt_device_read(dev, 0, &sensor_data, 1); if (res != 1) { rt_kprintf("read data failed!size is %dn", res); rt_device_close(dev); return; } else { rt_mb_send(&mb, (rt_uint32_t)&sensor_data);//发送 数据 rt_kprintf("distance:%3d.%dcm, timestamp:%5dn", sensor_data.data.proximity / 10, sensor_data.data.proximity % 10, sensor_data.timestamp); } rt_thread_mdelay(2000); } }
4. LED显示模块
主要就是系统正常运行指示。
关键代码如下:
#define LED_PIN GET_PIN(I, 8) int main(void) { rt_uint32_t count = 1; rt_pin_mode(LED_PIN, PIN_MODE_OUTPUT); while(count++) { rt_thread_mdelay(500); rt_pin_write(LED_PIN, PIN_HIGH); rt_thread_mdelay(500); rt_pin_write(LED_PIN, PIN_LOW); } return RT_EOK; }
演示效果
视频播放地址:目前只有超声波测距部分视频,后续会在这个地址添加完整版。
(1)小车
(2) 超声波测距
电机控制演示
完整视频
第一次下地视频
比赛感悟
虽然实现的功能很简单,但是完全利用时间搞要搞成功,还是挺不容易的,还是整体的时间安排不好。主要收获是对rt-thread 的线程间的同步和通信增强了认识和体验,实践出真知,多多参与这样的活动。给主办方点个赞。
主要克服的难点:
(1)是之前pwm 驱动一直卡着,没有进展,最后在网友的支援下顺利解决,主要是初始化时候,没有使能相应的时钟,陷在完全按照之前添加bsp 的方式搞,没明白这其中的细节,感谢网友支持;
(2)还有就是邮箱发送 结构体数据的正确的接收和发送处理。
主要收获:
(1)第一次使用H7 高性能MCU, 很多处理方式跟之前不一样,比如烧录方式,也折腾了好几天,这个过程中,收获不少
(2) 这个art pi 开发板 很不错的学习平台,也开源了挺多好的扩展板项目,后续希望可以搞一个专门的小车方面的扩展板,应该挺不错的,很好玩。