Gitee
https://gitee.com/WangXi_Chn/RttOs_ModuleLib
开发环境
CubeMX
MDK5 IDE
STM32F407IGH6TR 芯片
HC06蓝牙通信模块
Android SPP蓝牙串口助手(下载见文末)
大疆开发板 C型
RT-Thread操作系统
面向对象模块接口设计
大疆M3508直流无刷电机(遥控对象)
大疆C620无刷电机调速器(遥控对象)
硬件条件

-
Kconfig
menuconfig BSP_USING_UARTbool "Enable UART"default yselect RT_USING_SERIALif BSP_USING_UARTconfig BSP_USING_UART1bool "Enable UART1"default yconfig BSP_USING_UART6bool "Enable UART6"default yconfig BSP_UART6_RX_USING_DMAbool "Enable UART6 RX DMA"depends on BSP_USING_UART6 && RT_SERIAL_USING_DMAdefault yendif
UART1为RTT操作系统命令行串口
- 这里添加了UART6,并且使能DMA
Env




-
接口函数
见官方使用手册
https://www.rt-thread.org/document/site/programming-manual/device/uart/uart/官方例程
不定长帧接收,直到收到指定的结束码 ```c /*
- 程序清单:这是一个串口设备接收不定长数据的示例代码
- 例程导出了 uart_dma_sample 命令到控制终端
- 命令调用格式:uart_dma_sample uart2
- 命令解释:命令第二个参数是要使用的串口设备名称,为空则使用默认的串口设备
- 程序功能:通过串口 uart2 输出字符串”hello RT-Thread!”,并通过串口 uart2 输入一串字符(不定长),再通过数据解析后,使用控制台显示有效数据。 */
include
define SAMPLE_UART_NAME “uart2”
define DATA_CMD_END ‘\r’ / 结束位设置为 \r,即回车符 /
define ONE_DATA_MAXLEN 20 / 不定长数据的最大长度 /
/ 用于接收消息的信号量 / static struct rt_semaphore rx_sem; static rt_device_t serial;
/ 接收数据回调函数 / static rt_err_t uart_rx_ind(rt_device_t dev, rt_size_t size) { / 串口接收到数据后产生中断,调用此回调函数,然后发送接收信号量 / if (size > 0) { rt_sem_release(&rx_sem); } return RT_EOK; }
static char uart_sample_get_char(void) { char ch;
while (rt_device_read(serial, 0, &ch, 1) == 0){rt_sem_control(&rx_sem, RT_IPC_CMD_RESET, RT_NULL);rt_sem_take(&rx_sem, RT_WAITING_FOREVER);}return ch;
}
/ 数据解析线程 / static void data_parsing(void) { char ch; char data[ONE_DATA_MAXLEN]; static char i = 0;
while (1){ch = uart_sample_get_char();rt_device_write(serial, 0, &ch, 1);if(ch == DATA_CMD_END){data[i++] = '\0';rt_kprintf("data=%s\r\n",data);i = 0;continue;}i = (i >= ONE_DATA_MAXLEN-1) ? ONE_DATA_MAXLEN-1 : i;data[i++] = ch;}
}
static int uart_data_sample(int argc, char *argv[]) { rt_err_t ret = RT_EOK; char uart_name[RT_NAME_MAX]; char str[] = “hello RT-Thread!\r\n”;
if (argc == 2){rt_strncpy(uart_name, argv[1], RT_NAME_MAX);}else{rt_strncpy(uart_name, SAMPLE_UART_NAME, RT_NAME_MAX);}/* 查找系统中的串口设备 */serial = rt_device_find(uart_name);if (!serial){rt_kprintf("find %s failed!\n", uart_name);return RT_ERROR;}/* 初始化信号量 */rt_sem_init(&rx_sem, "rx_sem", 0, RT_IPC_FLAG_FIFO);/* 以中断接收及轮询发送模式打开串口设备 */rt_device_open(serial, RT_DEVICE_FLAG_INT_RX);/* 设置接收回调函数 */rt_device_set_rx_indicate(serial, uart_rx_ind);/* 发送字符串 */rt_device_write(serial, 0, str, (sizeof(str) - 1));/* 创建 serial 线程 */rt_thread_t thread = rt_thread_create("serial", (void (*)(void *parameter))data_parsing, RT_NULL, 1024, 25, 10);/* 创建成功则启动线程 */if (thread != RT_NULL){rt_thread_startup(thread);}else{ret = RT_ERROR;}return ret;
}
/ 导出到 msh 命令列表中 / MSH_CMD_EXPORT(uart_data_sample, uart device sample);
<a name="E8ys4"></a># 适配模块接口<a name="vMj9O"></a>## Module_BlueToothHC06.h```c/** Copyright (c) 2020 - ~, HIT_HERO Team** BLUETOOTH HC06 MODULE HEAD FILE* Used in RT-Thread Operate System** Change Logs:* Date Author Notes Mail* 2020-08-09 WangXi first version WangXi_chn@foxmail.com*/#include <rtthread.h>#include <rtdevice.h>#include <board.h>#ifndef _MODULE_BLUETOOTHHC06_H_#define _MODULE_BLUETOOTHHC06_H_typedef enum funcFlag{LED_BlUE_1 = 0xE1,LED_GREEN_1,LED_RED_1,LED_YELLOW_1,LED_BlUE_2,LED_GREEN_2,LED_RED_2,LED_YELLOW_2,PARAM_SHOW_1 = 0xC1,PARAM_SHOW_2,PARAM_SHOW_3,PARAM_SHOW_4,PARAM_SHOW_5,PARAM_SHOW_6,WAVE_SHOW = 0x01,}FuncFlag;enum ConnectStatusFlag{DISCONNECTED = PIN_LOW,CONNECTED = PIN_HIGH,};struct _MODULE_BLUETOOTHHC06{/* Property */char * Property_UartDevName;rt_base_t ConnectStatusPin;rt_uint8_t ConnectCheckSwitch;/* Value */rt_device_t Value_uart_dev;rt_uint8_t Value_sendData[8];rt_uint8_t Value_feedData[8];rt_uint32_t ConnectStatus;rt_uint16_t Value_keyMask;/* Method */void (*Method_Init)(struct _MODULE_BLUETOOTHHC06 *module);void (*Method_Send)(struct _MODULE_BLUETOOTHHC06 *module,FuncFlag funcflag,rt_int16_t param);void (*Method_Feed)(struct _MODULE_BLUETOOTHHC06 *module);void (*Method_Code)(struct _MODULE_BLUETOOTHHC06 *module,FuncFlag funcflag,rt_int16_t param);void (*Method_Encode)(struct _MODULE_BLUETOOTHHC06 *module);rt_err_t (*Method_Handle)(rt_device_t dev, rt_size_t size);};typedef struct _MODULE_BLUETOOTHHC06 MODULE_BLUETOOTHHC06;rt_err_t Module_BlueToothHC06_Config(MODULE_BLUETOOTHHC06 *module);#endif/************************ (C) COPYRIGHT 2020 WANGXI **************END OF FILE****/
Module_BlueToothHC06.c
/** Copyright (c) 2020 - ~, HIT_HERO Team** BLUETOOTH HC06 MODULE SOUCE FILE* Used in RT-Thread Operate System** Change Logs:* Date Author Notes Mail* 2020-08-09 WangXi first version WangXi_chn@foxmail.com*/#include "Module_BlueToothHC06.h"static void Module_BlueToothHC06Init(MODULE_BLUETOOTHHC06 *module);static void Module_BlueToothHC06Send(MODULE_BLUETOOTHHC06 *module,FuncFlag funcflag,rt_int16_t param);static void Module_BlueToothHC06Feed(MODULE_BLUETOOTHHC06 *module);static void Module_BlueToothHC06Code(MODULE_BLUETOOTHHC06 *module,FuncFlag funcflag,rt_int16_t param);static void Module_BlueToothHC06Encode(MODULE_BLUETOOTHHC06 *module);static rt_err_t Module_BlueToothHC06Handle(rt_device_t dev, rt_size_t size);static struct rt_semaphore uartBluetoothHC06_sem;/* Global Method */rt_err_t Module_BlueToothHC06_Config(MODULE_BLUETOOTHHC06 *module){if( module->Method_Init ==NULL &&module->Method_Handle ==NULL &&module->Method_Send ==NULL &&module->Method_Feed ==NULL &&module->Method_Code ==NULL &&module->Method_Encode ==NULL){/* Link the Method */module->Method_Init = Module_BlueToothHC06Init;module->Method_Handle = Module_BlueToothHC06Handle;module->Method_Send = Module_BlueToothHC06Send;module->Method_Feed = Module_BlueToothHC06Feed;module->Method_Code = Module_BlueToothHC06Code;module->Method_Encode = Module_BlueToothHC06Encode;}else{rt_kprintf("Warning: Module BlueTooth HC06 is Configed twice\n");return RT_ERROR;}/* Device Init */module->Method_Init(module);return RT_EOK;}static void Module_BlueToothHC06Init(MODULE_BLUETOOTHHC06 *module){module->Value_uart_dev = rt_device_find(module->Property_UartDevName);if (!module->Value_uart_dev){rt_kprintf("find %s failed!\n", module->Value_uart_dev);return;}rt_sem_init(&uartBluetoothHC06_sem, "uartBluetoothHC06_sem", 0, RT_IPC_FLAG_FIFO);struct serial_configure config = RT_SERIAL_CONFIG_DEFAULT; /* 初始化配置参数 *//* step2:修改串口配置参数 */config.baud_rate = BAUD_RATE_9600; //修改波特率为 9600config.data_bits = DATA_BITS_8; //数据位 8config.stop_bits = STOP_BITS_1; //停止位 1config.bufsz = 128; //修改缓冲区 buff size 为 128config.parity = PARITY_NONE; //无奇偶校验位/* step3:控制串口设备。通过控制接口传入命令控制字,与控制参数 */rt_device_control(module->Value_uart_dev, RT_DEVICE_CTRL_CONFIG, &config);rt_device_open(module->Value_uart_dev, RT_DEVICE_FLAG_DMA_RX);rt_device_set_rx_indicate(module->Value_uart_dev, module->Method_Handle);/* Enable Connect Status GPIO */rt_pin_mode(module->ConnectStatusPin, PIN_MODE_INPUT_PULLDOWN);}static void Module_BlueToothHC06Send(MODULE_BLUETOOTHHC06 *module,FuncFlag funcflag,rt_int16_t param){module->ConnectStatus = rt_pin_read(module->ConnectStatusPin);module->Method_Code(module,funcflag,param);rt_device_write( module->Value_uart_dev, 0,&(module->Value_sendData),sizeof(module->Value_sendData));}static void Module_BlueToothHC06Feed(MODULE_BLUETOOTHHC06 *module){char ch;static char i = 0;while (1){while (rt_device_read(module->Value_uart_dev, 0, &ch, 1) == 0){rt_sem_control(&uartBluetoothHC06_sem, RT_IPC_CMD_RESET, RT_NULL);rt_sem_take(&uartBluetoothHC06_sem, RT_WAITING_FOREVER);}if((rt_uint8_t)ch == 0xAA){/* get the frame end flag and start encode the frame */module->Method_Encode(module);i = 0;continue;}i = (i >= 8-1) ? 8-1 : i;module->Value_feedData[i++] = ch;}}static rt_err_t Module_BlueToothHC06Handle(rt_device_t dev, rt_size_t size){rt_sem_release(&uartBluetoothHC06_sem);return RT_EOK;}static void Module_BlueToothHC06Code(MODULE_BLUETOOTHHC06 *module,FuncFlag funcflag,rt_int16_t param){module->Value_sendData[0] = 0xA5;module->Value_sendData[1] = 0x5A;switch (funcflag>>4){case 0x0E: //LED Showmodule->Value_sendData[2] = 0x05;module->Value_sendData[3] = funcflag;module->Value_sendData[4] = param;module->Value_sendData[5] = (0x05 + funcflag + param)&0xFF;module->Value_sendData[6] = 0xAA;break;case 0x0C: //Param Showmodule->Value_sendData[2] = 0x06;module->Value_sendData[3] = funcflag;module->Value_sendData[4] = param >> 8;module->Value_sendData[5] = param & 0xFF;module->Value_sendData[6] = (0x06 + funcflag + (param>>8) + (param&0xFF))&0xFF;module->Value_sendData[7] = 0xAA;break;case 0x00: //Wave Showmodule->Value_sendData[2] = 0x06;module->Value_sendData[3] = funcflag;module->Value_sendData[4] = param >> 8;module->Value_sendData[5] = param & 0xFF;module->Value_sendData[6] = (0x06 + funcflag + (param>>8) + (param&0xFF))&0xFF;module->Value_sendData[7] = 0xAA;break;}}static void Module_BlueToothHC06Encode(MODULE_BLUETOOTHHC06 *module){if((rt_uint8_t)(module->Value_feedData[0])==0xA5 && (rt_uint8_t)(module->Value_feedData[1])==0x5A){rt_uint8_t funcFlag = (rt_uint8_t)(module->Value_feedData[3])>>4;rt_uint8_t numFlag = (rt_uint8_t)(module->Value_feedData[3])&0x0F;switch(funcFlag){case 0x0B:module->Value_keyMask |= (0x01 << (numFlag-1));break;}}else{return;}}/************************ (C) COPYRIGHT 2020 WANGXI **************END OF FILE****/
使用
/** Copyright (c) 2020 - ~, HIT_HERO Team** MAIN SOUCE FILE* Used in RT-Thread Operate System** Change Logs:* Date Author Notes Mail* 2020-08-08 WangXi first version WangXi_chn@foxmail.com*/#include <rtthread.h>#include <rtdevice.h>#include <board.h>#include "Module_3508MotorGroup.h"#include "Module_BlueToothHC06.h"/* Module param list ---------------------------------------------------------------------------------------- */MODULE_BLUETOOTHHC06 dev_communicate ={.Property_UartDevName = "uart6",};MODULE_MOTOR3508GROUP dev_motor3508group ={.Property_CanDevName = "can1",.Value_module_motor3508[MOTOR3508ID_1] ={.Enable = 1,.Mode = MOTOR3508MODE_SPEED,.PID_Speed ={.Property_Kp = 6,.Property_Ki = 2,.Property_Kd = 0,.Property_dt = 0.005,.Property_integralMax = 500,.Property_AimMax = 9000,.Property_OutputMax =16300}},.Value_module_motor3508[MOTOR3508ID_2] ={.Enable = 1,.Mode = MOTOR3508MODE_SPEED,.PID_Speed ={.Property_Kp = 6,.Property_Ki = 2,.Property_Kd = 0,.Property_dt = 0.005,.Property_integralMax = 500,.Property_AimMax = 9000,.Property_OutputMax =16300}},.Value_module_motor3508[MOTOR3508ID_3] ={.Enable = 1,.Mode = MOTOR3508MODE_ANGLE,.PID_Speed ={.Property_Kp = 6,.Property_Ki = 2,.Property_Kd = 0,.Property_dt = 0.005,.Property_integralMax = 500,.Property_AimMax = 9000,.Property_OutputMax =10000},.PID_Angle ={.Property_Kp = 4,.Property_Ki = 2,.Property_Kd = 0,.Property_dt = 0.005,.Property_integralMax = 500,.Property_AimMax = 7200,.Property_OutputMax =300},},};/* thread entry list ---------------------------------------------------------------------------------------- */static void motor_entry(void *parameter){while (1){/* Communicate with motor group */dev_motor3508group.Method_Feed(&dev_motor3508group);rt_thread_mdelay(1);dev_motor3508group.Method_Send(&dev_motor3508group);}}static void bluetupdata_entry(void *parameter){dev_communicate.Method_Feed(&dev_communicate);}static void bluetcontrol_entry(void *parameter){static rt_uint32_t time_1000m = 0;while(1){rt_thread_mdelay(1);time_1000m++;switch(dev_communicate.Value_keyMask){case (0x0001<<0): //speed up the friction wheeldev_motor3508group.Value_module_motor3508[MOTOR3508ID_1].Value_motor_AimRPM -= 200;dev_motor3508group.Value_module_motor3508[MOTOR3508ID_2].Value_motor_AimRPM += 200;break;case (0x0001<<1): //start up the friction wheeldev_motor3508group.Value_module_motor3508[MOTOR3508ID_1].Value_motor_AimRPM = -1400;dev_motor3508group.Value_module_motor3508[MOTOR3508ID_2].Value_motor_AimRPM = 1400;break;case (0x0001<<2): //slow down the friction wheelif(dev_motor3508group.Value_module_motor3508[MOTOR3508ID_2].Value_motor_AimRPM >= 200){dev_motor3508group.Value_module_motor3508[MOTOR3508ID_1].Value_motor_AimRPM += 200;dev_motor3508group.Value_module_motor3508[MOTOR3508ID_2].Value_motor_AimRPM -= 200;}break;case (0x0001<<3): //raise up the pawdev_motor3508group.Value_module_motor3508[MOTOR3508ID_3].PID_Angle.Property_Kp = 4;dev_motor3508group.Value_module_motor3508[MOTOR3508ID_3].PID_Angle.Property_Ki = 2;dev_motor3508group.Value_module_motor3508[MOTOR3508ID_3].PID_Angle.Property_Kd = 0;dev_motor3508group.Value_module_motor3508[MOTOR3508ID_3].PID_Angle.Property_dt = 0.005;dev_motor3508group.Value_module_motor3508[MOTOR3508ID_3].PID_Angle.Property_integralMax = 500;dev_motor3508group.Value_module_motor3508[MOTOR3508ID_3].PID_Angle.Property_AimMax = 7200;dev_motor3508group.Value_module_motor3508[MOTOR3508ID_3].PID_Angle.Property_OutputMax = 300;dev_motor3508group.Value_module_motor3508[MOTOR3508ID_3].PID_Speed.Property_OutputMax = 10000;dev_motor3508group.Value_module_motor3508[MOTOR3508ID_3].Value_motor_AimAngle = -720;break;case (0x0001<<4): //stop the friction wheeldev_motor3508group.Value_module_motor3508[MOTOR3508ID_1].Value_motor_AimRPM = 0;dev_motor3508group.Value_module_motor3508[MOTOR3508ID_2].Value_motor_AimRPM = 0;break;case (0x0001<<5): //put down the pawdev_motor3508group.Value_module_motor3508[MOTOR3508ID_3].PID_Angle.Property_Kp = 0.05;dev_motor3508group.Value_module_motor3508[MOTOR3508ID_3].PID_Angle.Property_Ki = 0.0001;dev_motor3508group.Value_module_motor3508[MOTOR3508ID_3].PID_Angle.Property_Kd = 0;dev_motor3508group.Value_module_motor3508[MOTOR3508ID_3].PID_Angle.Property_dt = 0.005;dev_motor3508group.Value_module_motor3508[MOTOR3508ID_3].PID_Angle.Property_integralMax = 500;dev_motor3508group.Value_module_motor3508[MOTOR3508ID_3].PID_Angle.Property_AimMax = 7200;dev_motor3508group.Value_module_motor3508[MOTOR3508ID_3].PID_Angle.Property_OutputMax = 100;dev_motor3508group.Value_module_motor3508[MOTOR3508ID_3].PID_Speed.Property_OutputMax = 100;dev_motor3508group.Value_module_motor3508[MOTOR3508ID_3].Value_motor_AimAngle = 0;break;case (0x0001<<6):break;case (0x0001<<7):break;case (0x0001<<8):break;case (0x0001<<9):break;case (0x0001<<10):break;case (0x0001<<11):break;}dev_communicate.Value_keyMask = 0x0000;if(time_1000m >= 1000){time_1000m = 0;dev_communicate.Method_Send(&dev_communicate,PARAM_SHOW_1,dev_motor3508group.Value_module_motor3508[MOTOR3508ID_2].Value_motor_AimRPM/200);}}}int main(void){/* Config module ---------------------------------------------------------------------------------------- */Module_Motor3508Group_Config(&dev_motor3508group);Module_BlueToothHC06_Config(&dev_communicate);/* Enable task thread ---------------------------------------------------------------------------------------- *//* motor control thread */rt_thread_t motor_thread = rt_thread_create("motor", motor_entry, RT_NULL,1024, RT_THREAD_PRIORITY_MAX - 2, 20);if (motor_thread != RT_NULL){rt_thread_startup(motor_thread);}/* blue tooth updata thread */rt_thread_t bluetupdata_thread = rt_thread_create("bluetupdata", bluetupdata_entry, RT_NULL,512, RT_THREAD_PRIORITY_MAX - 5, 20);if (bluetupdata_thread != RT_NULL){rt_thread_startup(bluetupdata_thread);}/* blue tooth updata thread */rt_thread_t bluetcontrol_thread = rt_thread_create("bluetcontrol", bluetcontrol_entry, RT_NULL,512, RT_THREAD_PRIORITY_MAX - 5, 20);if (bluetcontrol_thread != RT_NULL){rt_thread_startup(bluetcontrol_thread);}}/************************ (C) COPYRIGHT 2020 WANGXI **************END OF FILE****/
说明
- 配合Android手机蓝牙串口助手SPP使用
- 模块内部已集成遵循软件协议的编码和解码
- 使用示例中,已实现通过按键调节电机转速,并每一秒一次返回电机转速
- 按键的使能中也参考了掩码的思想,通过读取一个16位数据的每一位,判断哪个按键被按下
- 最终留出的函数接口是三个
- 初始化模块config(全局函数)
- 发送指令Send(成员函数,即方法)
- 读取指令Feed(成员函数)
- 发送指令的参数有三个
- 模块自身指针
- 发送指令的功能(用枚举限定,对应手机端的LED、参数、示波)
- 发送参数(LED仅1和0,其他功能填写想呈现的数据)
- 现已可实现波形显示功能 2020-8-12
-
手机SPP下载
尽可能不要修改手机端默认协议以保持一致
