STM32实现四驱小车(二)通信任务——遥控器SBUS通信

目录

  • 一. 遥控器通信原理简介
  • 二. SBUS信号解析
    • 1. SBUS信号简介
    • 2. STM32F7解析SBUS信号
  • 三. 通信任务实现

一. 遥控器通信原理简介

要实现一个遥控小车当然要有一个遥控器了,目前市面上常用的航模遥控器基本都是2.4G无线信号,从遥控器到小车子的链路是这样子的。
STM32实现四驱小车(二)通信任务——遥控器SBUS通信_第1张图片
接收机出来的信号一般有SBUS信号、PPM信号、PWM信号,SBUS信号就是一路串行信号,连接到控制板的串口按协议解析就行了。PWM信号就不说了,多路PWM接口表示多个信号,PPM信号也是一路信号,只不过它是一串波,它把多路PWM值混合到一帧信号里了,一帧数据的高电平时间按顺序解析出来就是各路PWM的值。这里不讲后两种,解析起来麻烦还浪费控制板资源,后面所有机器人系列都用SBUS信号,也推荐大家用SBUS信号。

二. SBUS信号解析

关于STM32解析SBUS信号我之前写过一篇文章,有源码,大家可以直接去读那一篇,传送门:STM32解析SBUS信号例程详解. 在这里我简单再介绍一下。

1. SBUS信号简介

SBUS全称serial-bus,是一种串口通信协议,广泛应用于航模遥控器(接收机)中。只用一根信号线就能传输多达16通道的数据,比多路PWM捕获高效且省资源。

  1. 串口配置:
    100k波特率,8位数据位,2位停止位,偶校验(EVEN),无控流,25个字节。
  2. 协议格式:(每帧数据25字节)
    [startbyte] [data1][data2]…[data22][flags][endbyte]
    startbyte=0x0f;
    endbyte=0x00;
    data1…data22: LSB(低位在前),对应16个通道(ch1-ch16),每个通道11bit(22 × 8=16 × 11);
    flag位标志遥控器的通讯状态,我使用的乐迪AT9S在遥控器通上的时候是0x00,断开的时候是0xC0,可以通过查询flag位来采取失控保护。
  3. 数据范围
    航模遥控器输出的PWM值是1000~2000,中值为1500,sbus输出的会不一样,例如乐迪AT9S的范围为300 ~ 1700,中值1000,我使用的另一套数传设备的范围是341-1707,中值1024。大家注意用串口调试助手把数据读出来看看范围是多少。不然后面会出问题。
  4. sbus的负逻辑
    这个地方一定要万分注意,接收机接板子必须加硬件反相器,因为SBUS的信号是采用的负逻辑,也就是电平相反,不要试图在软件里面取反,因为软件里面只能操作数据位(记得串口配置里面的数据位8么),你是操作不了停止位、校验位啥的!!
    如果是自己画板子也很简单,如图所示
    STM32实现四驱小车(二)通信任务——遥控器SBUS通信_第2张图片

2. STM32F7解析SBUS信号

在上一章STM32实现四驱小车(一)硬件与软件准备的工程模板基础上,创建sbus.h,sbus.c两个文件用于SBUS解析,再创建uart.h, uart.c两个文件写串口驱动。

sbus.h的内容如下

#ifndef __SBUS_H
#define __SBUS_H
#include "sys.h"

#define SBUS_FRAME_SIZE		25
#define SBUS_INPUT_CHANNELS	16

//定义subs信号的最小值 最大值 中值 死区 以及希望转换成PWM值的范围(1000-2000)
#define SBUS_RANGE_MIN 300.0f
#define SBUS_RANGE_MAX 1700.0f
#define SBUS_TARGET_MIN 1000.0f
#define SBUS_TARGET_MAX 2000.0f
#define DEAD_RANGE_MIN 960          //死区
#define DEAD_RANGE_MAX 1040
#define SBUS_RANGE_MIDDLE 1000.0f
#define SBUS_CONNECT_FLAG 0x00

//低速与高速模式,这里用一个二段开关控制速度档位
#define LOW_SPEED 0
#define HIGH_SPEED 1

// 定义四个摇杆与拨动开关的功能
#define YAW 1
#define THROTTLE 2
#define PITCH 3
#define ROLL 4
#define SPEED_MODE 6

extern int command[20];			   //遥控器数据

typedef struct
{
    uint16_t signal[25];
	uint16_t CH1;//通道1数值
	uint16_t CH2;//通道2数值
	uint16_t CH3;//通道3数值
	uint16_t CH4;//通道4数值
	uint16_t CH5;//通道5数值
	uint16_t CH6;//通道6数值
    uint16_t CH7;//通道7数值
    uint16_t CH8;//通道8数值
    uint16_t CH9;//通道9数值
    uint16_t CH10;//通道10数值
	uint16_t CH11;//通道11数值
	uint16_t CH12;//通道12数值
	uint16_t CH13;//通道13数值
	uint16_t CH14;//通道14数值
	uint16_t CH15;//通道15数值
	uint16_t CH16;//通道16数值
	uint8_t ConnectState;//遥控器与接收器连接状态 0=未连接,1=正常连接
}SBUS_CH_Struct;

extern SBUS_CH_Struct SBUS_CH;
//SBUS信号解析相关函数
u8 update_sbus(u8 *buf);
u16 sbus_to_pwm(u16 sbus_value);
float sbus_to_Range(u16 sbus_value, float p_min, float p_max);
#endif

这里稍作解释,SBUS信号读出来是300-1700的数据,我们需要把它转换成1000-2000的PWM值(不转其实也没关系,只是为了方便)。遥控器上两个摇杆对应的是1-4四路通道,范围是连续变化的,其他的拨码开关是离散值,二段开关对应通道值为300和1700,三段开关对应的通道值为300,1000,1700.根据数值就可以判断拨码开关是在什么状态,就可以进行换挡。本文只使用了一个二段开关,用于低速与高速模式。在比较复杂的系统里面所有的拨码开关可能都会用到甚至复合作用。比如PX4飞控里面有定高/手动模式,有头/无头模式,一键起飞/降落模式,定点、特技模式等,都需要用拨码开关来进行切换和换挡。在这里定义了一个全局变量command[20],用来存储遥控器各个通道的值,用PWM值表示,范围1000-2000. 知道了各个通道的值就可以去映射到不同的功能。

sbus.c的内容如下

#include "sbus.h"

SBUS_CH_Struct SBUS_CH;
int command[20];			   //遥控器数据

//将sbus信号转化为通道值
u8 update_sbus(u8 *buf)
{
    int i;
    for (i=0;i<25;i++)
        SBUS_CH.signal[i] = buf[i];
    if (buf[23] == SBUS_CONNECT_FLAG)
    {
        SBUS_CH.ConnectState = 1;
        SBUS_CH.CH1 = ((int16_t)buf[ 1] >> 0 | ((int16_t)buf[ 2] << 8 )) & 0x07FF;
        SBUS_CH.CH2 = ((int16_t)buf[ 2] >> 3 | ((int16_t)buf[ 3] << 5 )) & 0x07FF;
        SBUS_CH.CH3 = ((int16_t)buf[ 3] >> 6 | ((int16_t)buf[ 4] << 2 ) | (int16_t)buf[ 5] << 10 ) & 0x07FF;
        SBUS_CH.CH4 = ((int16_t)buf[ 5] >> 1 | ((int16_t)buf[ 6] << 7 )) & 0x07FF;
        SBUS_CH.CH5 = ((int16_t)buf[ 6] >> 4 | ((int16_t)buf[ 7] << 4 )) & 0x07FF;
        SBUS_CH.CH6 = ((int16_t)buf[ 7] >> 7 | ((int16_t)buf[ 8] << 1 ) | (int16_t)buf[9] << 9 ) & 0x07FF;
        SBUS_CH.CH7 = ((int16_t)buf[ 9] >> 2 | ((int16_t)buf[10] << 6 )) & 0x07FF;
        SBUS_CH.CH8 = ((int16_t)buf[10] >> 5 | ((int16_t)buf[11] << 3 )) & 0x07FF;
        SBUS_CH.CH9 = ((int16_t)buf[12] << 0 | ((int16_t)buf[13] << 8 )) & 0x07FF;
        SBUS_CH.CH10 = ((int16_t)buf[13] >> 3 | ((int16_t)buf[14] << 5 )) & 0x07FF;
		SBUS_CH.CH11 = ((int16_t)buf[14] >> 6 | ((int16_t)buf[15] << 2 ) | (int16_t)buf[16] << 10 ) & 0x07FF;
		SBUS_CH.CH12 = ((int16_t)buf[16] >> 1 | ((int16_t)buf[17] << 7 )) & 0x07FF;
		SBUS_CH.CH13 = ((int16_t)buf[17] >> 4 | ((int16_t)buf[18] << 4 )) & 0x07FF;
		SBUS_CH.CH14 = ((int16_t)buf[18] >> 7 | ((int16_t)buf[19] << 1 ) | (int16_t)buf[20] << 9 ) & 0x07FF;
		SBUS_CH.CH15 = ((int16_t)buf[20] >> 2 | ((int16_t)buf[21] << 6 )) & 0x07FF;
		SBUS_CH.CH16 = ((int16_t)buf[21] >> 5 | ((int16_t)buf[22] << 3 )) & 0x07FF;
        return 1;
    }
    else 
    {
        SBUS_CH.ConnectState = 0;
        return 0;
    }
	
  
}
//将sbus信号通道值转化为PWM的数值  [1000,2000] 
u16 sbus_to_pwm(u16 sbus_value)
{
    float pwm;
    pwm = (float)SBUS_TARGET_MIN + (float)(sbus_value - SBUS_RANGE_MIN) * SBUS_SCALE_FACTOR;
    //                1000                                   300              1000/1400
    if (pwm > 2000) pwm = 2000;
    if (pwm < 1000) pwm = 1000;
    return (u16)pwm;
}
//将sbus信号通道值转化为特定区间的数值  [p_min,p_max] 
float sbus_to_Range(u16 sbus_value, float p_min, float p_max)
{
    float p;
    p = p_min + (float)(sbus_value - SBUS_RANGE_MIN) * (p_max-p_min)/(float)(SBUS_RANGE_MAX - SBUS_RANGE_MIN);  
    if (p > p_max) p = p_max;
    if (p < p_min) p = p_min;
    return p;
}

这个文件的核心是实现update_sbus()函数,在串口中断函数里面会调用这个函数,用于更新SBUS信号值,后面的sbus_to_pwm()函数在main.c中的通信任务里会调用,用于将SBUS信号转换为PWM值。

uart.h的内容如下

#ifndef _USART_H
#define _USART_H
#include "sys.h"
#include "stdio.h"	
#include "pid.h"

#define USART_REC_LEN  			100  	//定义最大接收字节数 200
#define RXBUFFERSIZE   1 //缓存大小

//串口1
#define EN_USART1_RX 			1		//使能(1)/禁止(0)串口1接收  	
extern u8  USART1_RX_BUF[USART_REC_LEN]; //接收缓冲,最大USART_REC_LEN个字节.末字节为换行符 
extern u16 USART1_RX_STA;         		//接收状态标记	
extern UART_HandleTypeDef UART1_Handler; //UART句柄
extern u8 aRxBuffer1[RXBUFFERSIZE];//HAL库USART接收Buffer


//串口2
#define EN_USART2_RX 			1		//使能(1)/禁止(0)串口1接收
extern u8  USART2_RX_BUF[USART_REC_LEN]; //接收缓冲,最大USART_REC_LEN个字节.末字节为换行符 
extern u16 USART2_RX_STA;         		//接收状态标记	
extern UART_HandleTypeDef UART2_Handler; //UART句柄
extern u8 aRxBuffer2[RXBUFFERSIZE];//HAL库USART接收Buffer

//串口3
#define EN_USART3_RX 			1		//使能(1)/禁止(0)串口1接收
extern u8  USART3_RX_BUF[USART_REC_LEN]; //接收缓冲,最大USART_REC_LEN个字节.末字节为换行符 
extern u16 USART3_RX_STA;         		//接收状态标记	
extern UART_HandleTypeDef UART3_Handler; //UART句柄
extern u8 aRxBuffer3[RXBUFFERSIZE];//HAL库USART接收Buffer

//如果想串口中断接收,请不要注释以下宏定义
void uart1_init(u32 bound);
//如果想串口中断接收,请不要注释以下宏定义
void uart2_init(u32 bound);
void uart3_init(u32 bound);

#endif

这里我们将会使用到三个串口,串口1用于解析SBUS信号,串口2用于读取姿态传感器数据,串口3在不久的将来用于地面站通信(小车系列不涉及)。

uart.c的内容如下

#include "usart.h"
#include "sys.h"
#include <iwdg.h>
#include "pid.h"
#include "HT905.h"
#include "string.h"
#include "sbus.h"
//
//如果使用os,则包括下面的头文件即可.
#if SYSTEM_SUPPORT_OS
#include "includes.h" //os 使用
#endif

//加入以下代码,支持printf函数,而不需要选择use MicroLIB
//#define PUTCHAR_PROTOTYPE int fputc(int ch, FILE *f)
#if 1
#pragma import(__use_no_semihosting)
//标准库需要的支持函数
struct __FILE
{
	int handle;
};

FILE __stdout;
//定义_sys_exit()以避免使用半主机模式
void _sys_exit(int x)
{
	x = x;
}
//重定义fputc函数
int fputc(int ch, FILE *f)
{
	while ((USART1->ISR & 0X40) == 0)
		; //循环发送,直到发送完毕
	USART1->TDR = (u8)ch;
	return ch;
}
#endif

//串口1中断服务程序
//注意,读取USARTx->SR能避免莫名其妙的错误
u8 USART1_RX_BUF[USART_REC_LEN]; //接收缓冲,最大USART_REC_LEN个字节.
//接收状态
//bit15,	接收完成标志
//bit14,	接收到0x0d
//bit13~0,	接收到的有效字节数目
u16 USART1_RX_STA = 0; //接收状态标记
u8 aRxBuffer1[RXBUFFERSIZE];		  //HAL库使用的串口接收缓冲
UART_HandleTypeDef UART1_Handler; //UART句柄

//串口2中断服务程序
u8 USART2_RX_BUF[USART_REC_LEN];     //接收缓冲,最大USART_REC_LEN个字节.
u16 USART2_RX_STA=0;       //接收状态标记	
u8 aRxBuffer2[RXBUFFERSIZE];//HAL库使用的串口接收缓冲
UART_HandleTypeDef UART2_Handler; //UART句柄

//串口3
u8  USART3_RX_BUF[USART_REC_LEN]; //接收缓冲,最大USART_REC_LEN个字节.末字节为换行符 
u16 USART3_RX_STA;         		//接收状态标记	
UART_HandleTypeDef UART3_Handler; //UART句柄
u8 aRxBuffer3[RXBUFFERSIZE];//HAL库USART接收Buffer


//初始化IO 串口1
//bound:波特率
void uart1_init(u32 bound)
{
	//UART 初始化设置
	UART1_Handler.Instance = USART1;					//USART1
	UART1_Handler.Init.BaudRate = bound;				//波特率
	UART1_Handler.Init.WordLength = UART_WORDLENGTH_9B; //字长为9位数据格式
	UART1_Handler.Init.StopBits = UART_STOPBITS_1;		//一个停止位
	UART1_Handler.Init.Parity = UART_PARITY_EVEN;		//偶校验位
	UART1_Handler.Init.HwFlowCtl = UART_HWCONTROL_NONE; //无硬件流控
	UART1_Handler.Init.Mode = UART_MODE_TX_RX;			//收发模式
	HAL_UART_Init(&UART1_Handler);						//HAL_UART_Init()会使能UART1

	HAL_UART_Receive_IT(&UART1_Handler, (u8 *)aRxBuffer1, RXBUFFERSIZE); //该函数会开启接收中断:标志位UART_IT_RXNE,并且设置接收缓冲以及接收缓冲接收最大数据量
}


void uart2_init(u32 bound)
{
	//UART3 初始化设置
	UART2_Handler.Instance=USART2;					    //USART1
	UART2_Handler.Init.BaudRate=bound;				    //波特率
	UART2_Handler.Init.WordLength=UART_WORDLENGTH_8B;   //字长为8位数据格式
	UART2_Handler.Init.StopBits=UART_STOPBITS_1;	    //一个停止位
	UART2_Handler.Init.Parity=UART_PARITY_NONE;		    //无奇偶校验位
	UART2_Handler.Init.HwFlowCtl=UART_HWCONTROL_NONE;   //无硬件流控
	UART2_Handler.Init.Mode=UART_MODE_TX_RX;		    //收发模式
	HAL_UART_Init(&UART2_Handler);					    //HAL_UART_Init()会使能UART2
	
	HAL_UART_Receive_IT(&UART2_Handler, (u8 *)aRxBuffer2, RXBUFFERSIZE);//该函数会开启接收中断:标志位UART_IT_RXNE,并且设置接收缓冲以及接收缓冲接收最大数据量
}

//串口3解析SBUS信号,100k波特率,2个停止位,偶校验
void uart3_init(u32 bound)
{
	//UART3 初始化设置
	UART3_Handler.Instance=USART3;					    //USART1
	UART3_Handler.Init.BaudRate=bound;				    //波特率
	UART3_Handler.Init.WordLength=UART_WORDLENGTH_8B;   //字长为8位数据格式
	UART3_Handler.Init.StopBits=UART_STOPBITS_1;	    //2个停止位
	UART3_Handler.Init.Parity=UART_PARITY_NONE;		    //偶校验位
	UART3_Handler.Init.HwFlowCtl=UART_HWCONTROL_NONE;   //无硬件流控
	UART3_Handler.Init.Mode=UART_MODE_TX_RX;		    //收发模式
	HAL_UART_Init(&UART3_Handler);					    //HAL_UART_Init()会使能UART1
	
	HAL_UART_Receive_IT(&UART3_Handler, (u8 *)aRxBuffer3, RXBUFFERSIZE);//该函数会开启接收中断:标志位UART_IT_RXNE,并且设置接收缓冲以及接收缓冲接收最大数据量
}

//UART底层初始化,时钟使能,引脚配置,中断配置
//此函数会被HAL_UART_Init()调用
//huart:串口句柄

void HAL_UART_MspInit(UART_HandleTypeDef *huart)
{
	//GPIO端口设置
	GPIO_InitTypeDef GPIO_Initure;

	if (huart->Instance == USART1) //如果是串口1,进行串口1 MSP初始化
	{
		__HAL_RCC_GPIOA_CLK_ENABLE();  //使能GPIOA时钟
		__HAL_RCC_USART1_CLK_ENABLE(); //使能USART1时钟

		GPIO_Initure.Pin = GPIO_PIN_9;			  //PA9
		GPIO_Initure.Mode = GPIO_MODE_AF_PP;	  //复用推挽输出
		GPIO_Initure.Pull = GPIO_PULLUP;		  //上拉
		GPIO_Initure.Speed = GPIO_SPEED_FAST;	  //高速
		GPIO_Initure.Alternate = GPIO_AF7_USART1; //复用为USART1
		HAL_GPIO_Init(GPIOA, &GPIO_Initure);	  //初始化PA9

		GPIO_Initure.Pin = GPIO_PIN_10;		 //PA10
		HAL_GPIO_Init(GPIOA, &GPIO_Initure); //初始化PA10

#if EN_USART1_RX
		HAL_NVIC_EnableIRQ(USART1_IRQn);		 //使能USART1中断通道
		HAL_NVIC_SetPriority(USART1_IRQn, 3, 2); //抢占优先级3,子优先级3
#endif
	}

	if(huart->Instance==USART2)//如果是串口3,进行串口3 MSP初始化
	{
		__HAL_RCC_GPIOA_CLK_ENABLE();			//使能GPIOB时钟
		__HAL_RCC_USART2_CLK_ENABLE();			//使能USART1时钟
	
		GPIO_Initure.Pin=GPIO_PIN_2;			//PA2 TX
		GPIO_Initure.Mode=GPIO_MODE_AF_PP;		//复用推挽输出
		GPIO_Initure.Pull=GPIO_PULLUP;			//上拉
		GPIO_Initure.Speed=GPIO_SPEED_FAST;		//高速
		GPIO_Initure.Alternate=GPIO_AF7_USART2;	//复用为USART3
		HAL_GPIO_Init(GPIOA,&GPIO_Initure);	   	//初始化PA9

		GPIO_Initure.Pin=GPIO_PIN_3;			//PA3 RX
		HAL_GPIO_Init(GPIOA,&GPIO_Initure);	   	//初始化PA10
		
#if EN_USART2_RX
		HAL_NVIC_EnableIRQ(USART2_IRQn);				//使能USART1中断通道
		HAL_NVIC_SetPriority(USART2_IRQn,3,3);			//抢占优先级3,子优先级3
#endif	
	}
	if(huart->Instance==USART3)//如果是串口3,进行串口3 MSP初始化
	{
		__HAL_RCC_GPIOB_CLK_ENABLE();			//使能GPIOB时钟
		__HAL_RCC_USART3_CLK_ENABLE();			//使能USART1时钟
	
		GPIO_Initure.Pin=GPIO_PIN_10;			//PB10 TX
		GPIO_Initure.Mode=GPIO_MODE_AF_PP;		//复用推挽输出
		GPIO_Initure.Pull=GPIO_PULLUP;			//上拉
		GPIO_Initure.Speed=GPIO_SPEED_FAST;		//高速
		GPIO_Initure.Alternate=GPIO_AF7_USART3;	//复用为USART3
		HAL_GPIO_Init(GPIOB,&GPIO_Initure);	   	//初始化PA9

		GPIO_Initure.Pin=GPIO_PIN_11;			//PB11 RX
		HAL_GPIO_Init(GPIOB,&GPIO_Initure);	   	//初始化PA10
		
#if EN_USART3_RX
		HAL_NVIC_EnableIRQ(USART3_IRQn);				//使能USART1中断通道
		HAL_NVIC_SetPriority(USART3_IRQn,2,1);			//抢占优先级3,子优先级3
#endif	
	}
}


void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart)
{
	int i;
	while (huart->Instance == USART1) //如果是串口1
	{
		USART1_RX_BUF[USART1_RX_STA] = aRxBuffer1[0];
		if (USART1_RX_STA == 0 && USART1_RX_BUF[USART1_RX_STA] != 0x0F) break; //帧头不对,丢掉
		USART1_RX_STA++;
		if (USART1_RX_STA > USART_REC_LEN) USART1_RX_STA = 0;  ///接收数据错误,重新开始接收

//		if (USART1_RX_BUF[0] == 0x0F && USART1_RX_BUF[24] == 0x00 && USART1_RX_STA == 25)	//接受完一帧数据
		if (USART1_RX_BUF[0] == 0x0F && USART1_RX_STA == 25)	//接受完一帧数据
		{
			update_sbus(USART1_RX_BUF);
			for (i = 0; i<25; i++)
			{
				USART1_RX_BUF[i] = 0;
			}
			USART1_RX_STA = 0;
		#ifdef ENABLE_IWDG
			IWDG_Feed();    			//喂狗		//超过时间没有收到遥控器的数据会复位
		#endif
		}
		break;
	}

	if (huart->Instance==USART2)//如果是串口2
	{
	}

	if (huart->Instance==USART3)//如果是串口3
	{
	}
}

//串口1中断服务程序
void USART1_IRQHandler(void)
{
	u32 timeout = 0;
	u32 maxDelay = 0x1FFFF;
#if SYSTEM_SUPPORT_OS //使用OS
	OSIntEnter();
#endif

	HAL_UART_IRQHandler(&UART1_Handler); //调用HAL库中断处理公用函数

	timeout = 0;
	while (HAL_UART_GetState(&UART1_Handler) != HAL_UART_STATE_READY) //等待就绪
	{
		timeout++; 超时处理
		if (timeout > maxDelay)
			break;
	}

	timeout = 0;
	while (HAL_UART_Receive_IT(&UART1_Handler, (u8 *)aRxBuffer1, RXBUFFERSIZE) != HAL_OK) //一次处理完成之后,重新开启中断并设置RxXferCount为1
	{
		timeout++; //超时处理
		if (timeout > maxDelay)
			break;
	}
#if SYSTEM_SUPPORT_OS //使用OS
	OSIntExit();
#endif
}

//串口2中断服务程序
void USART2_IRQHandler(void)                	
{ 
	u32 timeout=0;
    u32 maxDelay=0x1FFFF;
#if SYSTEM_SUPPORT_OS	 	//使用OS
	OSIntEnter();    
#endif
	
	HAL_UART_IRQHandler(&UART2_Handler);	//调用HAL库中断处理公用函数
	
	timeout=0;
    while (HAL_UART_GetState(&UART2_Handler)!=HAL_UART_STATE_READY)//等待就绪
	{
        timeout++;超时处理
        if(timeout>maxDelay) break;		
	}
     
	timeout=0;
	while(HAL_UART_Receive_IT(&UART2_Handler,(u8 *)aRxBuffer2, RXBUFFERSIZE)!=HAL_OK)//一次处理完成之后,重新开启中断并设置RxXferCount为1
	{
        timeout++; //超时处理
        if(timeout>maxDelay) break;	
	}
#if SYSTEM_SUPPORT_OS	 	//使用OS
	OSIntExit();  											 
#endif
} 

//串口3中断服务程序
void USART3_IRQHandler(void)                	
{ 
	u32 timeout=0;
    u32 maxDelay=0x1FFFF;
#if SYSTEM_SUPPORT_OS	 	//使用OS
	OSIntEnter();    
#endif
	
	HAL_UART_IRQHandler(&UART3_Handler);	//调用HAL库中断处理公用函数
	
	timeout=0;
    while (HAL_UART_GetState(&UART3_Handler)!=HAL_UART_STATE_READY)//等待就绪
	{
        timeout++;超时处理
        if(timeout>maxDelay) break;		
	}
     
	timeout=0;
	while(HAL_UART_Receive_IT(&UART3_Handler,(u8 *)aRxBuffer3, RXBUFFERSIZE)!=HAL_OK)//一次处理完成之后,重新开启中断并设置RxXferCount为1
	{
        timeout++; //超时处理
        if(timeout>maxDelay) break;	
	}
#if SYSTEM_SUPPORT_OS	 	//使用OS
	OSIntExit();  											 
#endif
} 

uart.c里面就是实现串口的驱动和串口中断函数的编写。这里串口2和串口3中断函数都是空的,后续章节会补上,咱们一步步来。看串口一的中断函数,这段不多讲了,先进行数据校验,再进行数据接收和解析,核心如前所述,调用update_sbus()函数更新信号值,这个值在主函数里面会周期性调用。

while (huart->Instance == USART1) //如果是串口1
	{
		USART1_RX_BUF[USART1_RX_STA] = aRxBuffer1[0];
		if (USART1_RX_STA == 0 && USART1_RX_BUF[USART1_RX_STA] != 0x0F) break; //帧头不对,丢掉
		USART1_RX_STA++;
		if (USART1_RX_STA > USART_REC_LEN) USART1_RX_STA = 0;  ///接收数据错误,重新开始接收

//		if (USART1_RX_BUF[0] == 0x0F && USART1_RX_BUF[24] == 0x00 && USART1_RX_STA == 25)	//接受完一帧数据
		if (USART1_RX_BUF[0] == 0x0F && USART1_RX_STA == 25)	//接受完一帧数据
		{
			update_sbus(USART1_RX_BUF);
			for (i = 0; i<25; i++)
			{
				USART1_RX_BUF[i] = 0;
			}
			USART1_RX_STA = 0;
		#ifdef ENABLE_IWDG
			IWDG_Feed();    			//喂狗		//超过时间没有收到遥控器的数据会复位
		#endif
		}
		break;
	}

还要记得在main函数里面调用串口初始化函数,这里串口1用于解析SBUS,波特率是100k。

    uart1_init(100000);				 //串口1初始化
	uart2_init(115200);				 //串口2初始化
	uart3_init(115200);				 //串口3初始化

三. 通信任务实现

在上一章实现了SBUS的驱动部分,下面我们写应用部分。还记得上一篇文章里的communicate_task函数吗,现在我们来补充它。

void communicate_task(void *p_arg)
{
	OS_ERR err;
	CPU_SR_ALLOC();
	char remotor_ready = 0; //遥控器通讯是否准备好
	char motor_ready = 0;	//电机通讯是否正常
	u8 sbus_count = 0;
	u8 can_count = 0;
	SBUS_CH.ConnectState = 0;

	//等待遥控器通讯正常,否则一直等待。遥控器校正,初值初始化
	while (sbus_count < 10)
	{
		if (SBUS_CH.ConnectState == 1)
		{
			sbus_count++;
			SBUS_CH.ConnectState = 0;
		}
		LED0_Toggle;
		LED1_Toggle;
		delay_ms(100);
	}

	remotor_ready = 1;									  //遥控器通讯成功
	HAL_GPIO_WritePin(GPIOB, GPIO_PIN_0, GPIO_PIN_RESET); //遥控器就绪LED1常亮

	 //等待CAN通讯正常,否则一直等待
	 while (can_count < 10)
	 {
		if (get_moto_measure(&moto_info, &CAN1_Handler))
			can_count++;
		delay_ms(100);
	 }

	motor_ready = 1;
	HAL_GPIO_WritePin(GPIOB, GPIO_PIN_1, GPIO_PIN_RESET); //电机就绪LED0常亮

	//读遥控器数据
	while (1)
	{
		if (SBUS_CH.CH6 < 400) //速度档位
			command[SPEED_MODE] = LOW_SPEED;
		else
			command[SPEED_MODE] = HIGH_SPEED;

		// 左手油门
		command[THROTTLE] = sbus_to_pwm(SBUS_CH.CH3);
		command[YAW] = sbus_to_pwm(SBUS_CH.CH4);			
		command[ROLL] = sbus_to_pwm(SBUS_CH.CH1);
		command[PITCH] = sbus_to_pwm(SBUS_CH.CH2);

		delay_ms(10);
	}
}
	

这段代码很简单,开始时等待遥控器状态正常,然后等待CAN总线通信正常(也就是电机通信正常,因为用的总线电机)。在等待的时候用指示灯指示状态,当然这里可以用多个指示灯,设计酷炫的效果用于显示各种运行状态。等所有的连接都是正常的之后,进入while死循环,每隔10ms读一次遥控器的数据,并转换为PWM值和档位值。这些数据在StabilizationTask姿态控制中会用到,具体如何应用,请听下回分解。

这里做下说明,本系列文章笔者重在分享思想、算法,在讲解上会弱化一些基本知识(比如单片机各个外设的原理、单片机编程的基本知识、操作系统的具体原理等),在代码的粘贴上会忽视一些底层的驱动代码和无关紧要的部分,事实上上面的代码我都经过删减了,只留下了干货。所以可以说面向的是中高级选手,拿来主义者可以打道回府了,本系列文章不开源,不提供源码,请见谅。

你可能感兴趣的:(嵌入式,STM32,stm32,嵌入式,人工智能)