系统架构优化部分主要实现设计API代替直接引用全局变量。
Sbus协议是遥控器常用协议,此文将实现读取并解析协议内容。
作为测试,使用遥控器油门控制PWM,调节电机转速。
整个工程Gitee链接为:https://gitee.com/gengstrong/UAV021/raw/master/UAV021_6-Sbus_ControlMotor.zip
之前实现的程序里定义了几个全局变量,例如全局的时间计时 tim,姿态角结构体 atti 等。全局变量会增强文件之间的关联性,定义、声明、赋值、应用可能在不同的文件,使得变量难以管理。对此,改用API接口的形式,一个简单的例子如下:
在 timer.c 里实现一个每 0.1ms 加1的变量 tim。之前的做法是把此变量作为全局变量使用,也即在 timer.c 里定义并赋值,在 timer.h 里使用 extern
关键词说明,其他文件只要包含 timer.h 即可使用此变量。下面分别是 timer.h, timer.c 和 attitude.c 里面定义和使用 tim 的情况:
// timer.h
extern uint32_t tim;
// timer.c
uint32_t tim;
void TIM6_DAC_IRQHandler(void)
{
if(__HAL_TIM_GET_IT_SOURCE(&TIM6_Handler, TIM_IT_UPDATE) !=RESET)
{
__HAL_TIM_CLEAR_IT(&TIM6_Handler, TIM_IT_UPDATE); // 清除中断标志位
}
tim ++; // 又是0.1ms,全局时间计数加1
}
// attitude.c
#include "timer.h"
Ts = (float)(tim - last_t) / 10.0 / 1000.0; // 0.1ms加1 = 1/10/1000s加1
last_t = tim; // 更新时间
这种方式有一定缺点,一是只读到 attitude.c 突然给 last_t 赋值 tim 容易让人迷惑,可能需要跳转到定义后才发现原来这是一个全局变量。对于其他一些变量,我们还想追踪在哪里赋值的,这将让问题更加复杂。二是在 attitude.c 里,我们仍然可以修改 tim 的值,这会让变量变得不安全。还有要避免命名重复,不然会让人脑阔疼的。
使用API函数后,可以有效解决上面的问题。
我们再在 timer.c 里定义一个函数 GetTimeApi(),当然,在头文件里声明:
// timer.h
uint32_t GetTimeApi(void);
// timer.c
uint32 tim_;
// 定时器6中断服务函数
void TIM6_DAC_IRQHandler(void)
{
if(__HAL_TIM_GET_IT_SOURCE(&TIM6_Handler, TIM_IT_UPDATE) !=RESET)
{
__HAL_TIM_CLEAR_IT(&TIM6_Handler, TIM_IT_UPDATE); // 清除中断标志位
}
tim_ ++; // 又是0.1ms,全局时间计数加1
}
/* 获取全局时间接口 */
uint32_t GetTimeApi(void)
{
return tim_;
}
// attitude.c
#include "timer.h"
Ts = (float)(GetTimeApi() - last_t) / 10.0 / 1000.0; // 0.1ms加1 = 1/10/1000s加1
last_t = GetTimeApi(); // 更新时间
做两个小小的约定,提供全局变量的函数以 Api 结束,全局变量以 下划线结束。
此时,使用函数的方式代替变量,程序可读性、安全性和独立性都增强,是一个不错的选择。
注意函数的定义问题,以姿态结构体的传递为例,比较以下两个函数:
struct ATTI_t atti_;
/* 获取姿态接口 */
void GetAttiApi(struct ATTI_t *atti)
{
atti->theta = atti_.theta;
atti->phi = atti_.phi;
atti->psi = atti_.psi;
}
struct ATTI_t atti_;
/* 获取姿态接口 */
void GetAttiApi(struct ATTI_t atti)
{
atti.theta = atti_.theta;
atti.phi = atti_.phi;
atti.psi = atti_.psi;
}
我们希望的是传入GetAttiApi() 函数的结构体变量 atti 能够获取真实姿态 atti_ 的数据。第一种定义,使用指针的方式是有效的;第二种定义无效,atti 作为形参,函数调用结束后即被释放,不能达到预期效果。
因此,一般我们都采用指针来传值。数组和指针有一样的效果,因为数组名就是指向该数组第一个数值得指针,以下两段程序是等价的:
/* 获取三轴加速度接口 */
void GetAccelDataApi(float acc[3])
{
acc[0] = acc_[0];
acc[1] = acc_[1];
acc[2] = acc_[2];
}
/* 获取三轴加速度接口 */
void GetAccelDataApi(float *acc)
{
acc[0] = acc_[0];
acc[1] = acc_[1];
acc[2] = acc_[2];
}
协议帧很简洁,一帧包括25字节数据:
首部(1字节)+ 数据(22字节)+ 标志位(1字节)+ 结束符(1字节)
这里容易有一个思维定势,就是里面的22个数据是从头到尾每11位作为一个通道的。认真看协议解析容易发现刚好是相反的(吐槽ing),是从尾到头每11位放一块。请看这张经典图片(全网几乎只此一张):
并不是第一个字节与第二个字节的高三位组合在一起,而是与低三位。其实,反过来看就对劲了:
第三个字节的12被拿走了,于是有345678,不够从第二个字节拿,又拿了12345;
第二个字节被拿走了黄色的,只剩 678了,没有了继续从第一个字节拿,拿到了12345678。
整个协议可用串口进行解析:
这个100kHz是非标准的,一般的串口助手不支持,只能解析出来之后再使用串口打印(吐槽ing)。
Sbus协议里,使用TTL电平,高电平(3.3V)代表逻辑 ‘0’,低电平代表逻辑 ‘1’,逻辑反了无所谓,取个反不就可以吗?还真不可以。虽然网上都说要硬件取反,还是抱着侥幸心理试一试,果然不行。非要硬件取反一下,一般的接收机也不带这功能,简直是个设计bug(吐槽ing)。
硬件取反电路如下,实际上就是一个很简单的三极管电路。Sbus的信号从基极输入,从集电极输出。基极输入 ‘0’,集电极上拉输出 ‘1’;基极输入 ‘1’,三极管导通,输出被拉低为 ‘0’,实现了反向。
不过为什么软件直接取反不行呢?还是没有想清楚,目前个人理解是接收机输出的驱动不足,或者和单片机引脚电阻不匹配?只能通过通过三极管放大来驱动引脚?暂不猜测,继续往下。总之吐槽了三次,觉得这个协议没有多少人性化的地方,它的成功或许是靠着强大的商业资本吧。
知道了规则,便可以使用串口进行解析了,请看程序。
先看头文件,可见此文件主要功能:
包括两个宏定义、两个结构体,SBUS_t 用于存储一帧数据,MC6C_t 专门针对 MC6C遥控器,仅六通道数据。
后面还有 SBUS硬件初始化,也即配置串口2的函数;Sbus协议解析任务;遥控器校准函数,也即将遥控数据映射到想要区间;测试遥控器控制电机任务。
最后是两个API函数,向外提供遥控器数据。
#ifndef SBUS_H
#define SBUS_H
#include "sys.h"
#define USART_BUF_SIZE 4 // HAL库USART接收Buffer大小
#define SBUS_DATA_SIZE 25 // 25字节
/* SBUS协议帧 */
struct SBUS_t
{
uint8_t head; // 1字节首部
uint16_t ch[16]; // 16个字节数据
uint8_t flag; // 1字节标志位
uint8_t end; // 1字节结束
};
/* MC6C遥控器只有六个通道,只使用了SBUS协议帧的部分数据 */
struct MC6C_t
{
float ail; // CH1, aileron, 副翼,调节滚转角
float ele; // CH2, elevator, 升降,调节俯仰角
float thr; // CH3, throttle, 油门
float rud; // CH4, rudder, 方向舵,调节偏航角
uint16_t ch5; // CH5, 最终只三档, 取值 1,2,3
uint16_t ch6; // CH6, 最终值两档, 取值 1,2
};
void SBUS_Init(void); // SBUS硬件初始化
void SbusParseTask(void *arg); // 解析遥控器接收的数据
void CaliMc6cData(struct MC6C_t *mc6c); // 遥控器校准,将遥控器接收数据映射到想要区间
void TestCtrlMotorTask(void *arg); // 测试遥控器控制电机任务
void GetSbusDataApi(struct SBUS_t *sbus); // Sbus数据调用接口
void GetMc6cDataApi(struct MC6C_t *mc6c); // 针对MC6C遥控器,MC6C遥控器数据接口
#endif
之前使用了 USART1,用于调试打印,此处使用 USART2。
串口配置流程如下:
// sbus.c USART2 配置、中断,Sbus协议捕获、解析
#include "sbus.h"
#include "delay.h"
#include "define.h"
#include "pwm.h"
struct SBUS_t sbus_; // SBUS接收数据全局变量
uint8_t usart_buf[USART_BUF_SIZE];
uint8_t sbus_rx_head = 0; // 发现起始字节 0x0F
uint8_t sbus_rx_sta = 0; // sbus_ 接收状态,0:未完成,1:已完成一帧接收
uint8_t sbus_rx_index = 0; // 接收字节计数
uint8_t sbus_rx_buf[SBUS_DATA_SIZE]; // 接收sbus_数据缓冲区
UART_HandleTypeDef UART2_Handler; // 串口2配置句柄
/* Sbus初始化,包括时钟、串口配置、引脚和中断配置*/
void SBUS_Init(void)
{
GPIO_InitTypeDef GPIO_Initure;
// 时钟使能
SBUS_ENCLK();
// 串口初始化配置
// 波特率100kbps,8位数据,偶校验(even),2位停止位,无流控。
UART2_Handler.Instance = USART2;
UART2_Handler.Init.BaudRate = 100000;
UART2_Handler.Init.WordLength = UART_WORDLENGTH_8B;
UART2_Handler.Init.StopBits = UART_STOPBITS_2;
UART2_Handler.Init.Parity = UART_PARITY_EVEN;
UART2_Handler.Init.HwFlowCtl = UART_HWCONTROL_NONE;
UART2_Handler.Init.Mode = UART_MODE_TX_RX;
// 引脚 配置
GPIO_Initure.Pin = SBUS_PIN; // PA2--TX, PA3--RX
GPIO_Initure.Mode = GPIO_MODE_AF_PP;
GPIO_Initure.Pull = GPIO_PULLUP;
GPIO_Initure.Speed = GPIO_SPEED_HIGH;
GPIO_Initure.Alternate = GPIO_AF7_USART2;
HAL_GPIO_Init(GPIOA, &GPIO_Initure);
// 中断配置
HAL_NVIC_EnableIRQ(USART2_IRQn);
HAL_NVIC_SetPriority(USART2_IRQn, 3, 2);
HAL_UART_Init(&UART2_Handler); //HAL_UART_Init()会使能UART2
HAL_UART_Receive_IT(&UART2_Handler, (uint8_t *)usart_buf, USART_BUF_SIZE); //该函数会开启接收中断:标志位UART_IT_RXNE,并且设置接收缓冲以及接收缓冲接收最大数据量
}
/* USART2 中断服务函数 */
/* 实现对S.BUS协议缓存,头部为 0x0F,结尾为 0x00, 中间22Bytes16通道数据,1Byte标志符 */
void USART2_IRQHandler(void) //中断函数
{
uint8_t chr;
if ((__HAL_UART_GET_FLAG(&UART2_Handler, UART_FLAG_RXNE) != RESET)) // 接收中断
{
HAL_UART_Receive(&UART2_Handler, &chr, 1, 1000); // 接收一个字符
if (sbus_rx_sta == 0) // 接收未完成
{
if ((chr == 0x0F) || sbus_rx_head) // 找到首字节或已经找到首字节
{
sbus_rx_head = 1; // 标明已经找到首字母
if (sbus_rx_index < SBUS_DATA_SIZE) // 未接收到25个字符
{
sbus_rx_buf[sbus_rx_index] = chr; // 不断接收
sbus_rx_index ++;
}
else // 接收到25个字符了
{
sbus_rx_sta = 1; // 接收完成
sbus_rx_head = 0; // 清零,准备下一次接收
sbus_rx_index = 0;
}
}
}
}
HAL_UART_IRQHandler(&UART2_Handler);
}
/* 对SBUS协议数据进行解析 */
/* 实现对S.BUS协议缓存,头部为 0x0F,结尾为 0x00, 中间22Bytes16通道数据,1Byte标志符 */
void SbusParseTask(void *arg)
{
while (1)
{
if(sbus_rx_sta==1) // 接收完一帧
{
NVIC_DisableIRQ(USART2_IRQn); // 要关闭中断,防止读写混乱
sbus_.head = sbus_rx_buf[0]; // 首部
sbus_.flag = sbus_rx_buf[23]; // 标志符
sbus_.end = sbus_rx_buf[24]; // 结尾
sbus_.ch[0] =((uint16_t)(sbus_rx_buf[2]<<8) | (uint16_t)(sbus_rx_buf[1])) & 0x07ff;
sbus_.ch[1] =((uint16_t)(sbus_rx_buf[3]<<5) | (uint16_t)(sbus_rx_buf[2]>>3)) & 0x07ff;
sbus_.ch[2] =((uint32_t)(sbus_rx_buf[5]<<10) | (uint32_t)(sbus_rx_buf[4]<<2) | (sbus_rx_buf[3]>>6)) & 0x07ff;
sbus_.ch[3] =((uint16_t)(sbus_rx_buf[6]<<7) | (uint16_t)(sbus_rx_buf[5]>>1)) & 0x07ff;
sbus_.ch[4] =((uint16_t)(sbus_rx_buf[7]<<4) | (sbus_rx_buf[6]>>4)) & 0x07ff;
sbus_.ch[5] =((uint16_t)(sbus_rx_buf[9]<<9) | (uint16_t)(sbus_rx_buf[8]<<1) | (sbus_rx_buf[7]>>7)) & 0x07ff;
sbus_.ch[6] =((uint16_t)(sbus_rx_buf[10]<<6) | (uint16_t)(sbus_rx_buf[9]>>2)) & 0x07ff;
sbus_.ch[7] =((uint16_t)(sbus_rx_buf[11]<<3) | (uint16_t)(sbus_rx_buf[10]>>5)) & 0x07ff;
sbus_.ch[8] =((uint16_t)(sbus_rx_buf[13]<<8) | (uint16_t)sbus_rx_buf[12]) & 0x07ff;
sbus_.ch[9] =((uint16_t)(sbus_rx_buf[14]<<5) | (uint16_t)(sbus_rx_buf[13]>>3)) & 0x07ff;
sbus_.ch[10]=((uint16_t)(sbus_rx_buf[16]<<10)| (uint16_t)(sbus_rx_buf[15]<<2) | (sbus_rx_buf[14]>>6)) & 0x07ff;
sbus_.ch[11]=((uint16_t)(sbus_rx_buf[17]<<7) | (uint16_t)(sbus_rx_buf[16]>>1)) & 0x07ff;
sbus_.ch[12]=((uint16_t)(sbus_rx_buf[18]<<4) | (uint16_t)(sbus_rx_buf[17]>>4)) & 0x07ff;
sbus_.ch[13]=((uint16_t)(sbus_rx_buf[20]<<9) | (uint16_t)(sbus_rx_buf[19]<<1) | (sbus_rx_buf[18]>>7)) & 0x07ff;
sbus_.ch[14]=((uint16_t)(sbus_rx_buf[21]<<6) | (uint16_t)(sbus_rx_buf[20]>>2)) & 0x07ff;
sbus_.ch[15]=((uint16_t)(sbus_rx_buf[22]<<3) | (uint16_t)(sbus_rx_buf[21]>>5)) & 0x07ff;
printf("======================================\r\n");
printf("正常: head=0x0F, flag=0x00, end=0x00\r\n\r\n");
printf("head: %d\r\n", sbus_.head);
printf(" %d, %d, %d, %d\r\n", sbus_.ch[0], sbus_.ch[1], sbus_.ch[2], sbus_.ch[3]);
printf(" %d, %d, %d, %d\r\n", sbus_.ch[4], sbus_.ch[5], sbus_.ch[6], sbus_.ch[7]);
printf(" %d, %d, %d, %d\r\n", sbus_.ch[8], sbus_.ch[9], sbus_.ch[10], sbus_.ch[11]);
printf(" %d, %d, %d, %d\r\n", sbus_.ch[12], sbus_.ch[13], sbus_.ch[14], sbus_.ch[15]);
printf("flag: %d\r\n", sbus_.flag);
printf("end: %d\r\n", sbus_.end);
printf("======================================\r\n\r\n");
delay_ms(100); // 先做完延时再开启中断与下一次捕获,否则延时期间中断到来,没有达到预期效果
NVIC_EnableIRQ(USART2_IRQn); // 打开串口中断
sbus_rx_sta = 0; // 准备下一次接收
}
else
{
delay_ms(100); // 免得异常时,到此处使得低优先级任务无法执行
}
}
}
注意到 SbusParseTask() 里面延时的位置。正常的思维是放在while(1) 的最后一行,也即 if else外,此处就不行了(为此冥思苦想了几个小时,排除各种可能,偶然解决问题后才想通)。
如果把延时放在最后 if else外,逻辑是这样的:解析完此帧后,使能中断,这个函数还在延时100ms的路途中,接收机的数据蜂拥而至,一直发一直发,不出bug就不正常了。
但是把这100ms放在 if else内的开启中断和接收下一帧前,不过这 100ms,打死也进不来中断的,实现了解析完一帧,休息一下,再解析下一帧的目的,这是我们预期的效果。
上面的内容以及成功获取遥控器指令,存储在 sbus_ 结构体之中。比如油门(第三通道)数据,取值可能在196 ~1289之间。这个数据不能直接使用,现在我们希望将这个数据转化在 400 ~ 800(程序里有解释)之间,用于直接调节电机占空比。因此我们需要做一个线性变化,将油门的数据变化到我们想要的区间。其他通道亦如此,暂且习惯性地叫做“校准”吧。
除此之外,我们设计遥控器控制电机的任务,也即读取遥控器油门数据,转化为PWM波控制电机转速。两个API接口函数也在此,不再赘述。
// sbus.c 遥控器校准与控制电机测试部分
/*
CH1 -- 俯仰角, 归中0°, 最大最小 ±30°
CH2 -- 滚转角, 归中0°, 最大最小 ±30°
CH3 -- 油门, 归中0°, 最大设置占空比 80%, 最小设置占空比 40%, 电调驱动频率为400Hz=2.5ms, 40%=1ms, 80%=2ms
CH4 -- 偏航角角速度, 归中0°/s, 最大最小 ±36°/s
CH5 -- 档位, 上中下分别为 1, 2, 3三档
CH6 -- 档位, 上下分别为 1, 2两档
*/
void CaliMc6cData(struct MC6C_t *mc6c)
{
static const float mc6c_min[6] = {64, 174, 196, 129, 193, 200}; // 转动摇杆,各通道最小值,本为 uint16_t,为方便计算直接为 float
static const float mc6c_max[6] = {1812, 1800, 1289, 1833, 1973, 1544}; // 转动摇杆,各通道最大值
static const float mc6c_mid[6] = {1030, 1001, 489, 948, 996, 200}; // CH6 只有两通道
float k;
float b;
// CH1 映射, [64, 894] --> [-30, 0]; [894, 1812] --> [0 30]
if (mc6c->ail < mc6c_mid[0])
{
k = (0 - (-30)) / (mc6c_mid[0] - mc6c_min[0]);
b = 0 - k * mc6c_mid[0];
mc6c->ail = k * mc6c->ail + b;
}
else
{
k = (30 - 0) / (mc6c_max[0] - mc6c_mid[0]);
b = 0 - k * mc6c_mid[0];
mc6c->ail = k * mc6c->ail + b;
}
// CH2 映射, [174, 1001] --> [-30, 0]; [1001, 1800] --> [0 30]
if (mc6c->ele < mc6c_mid[1])
{
k = (0 - (-30)) / (mc6c_mid[1] - mc6c_min[1]);
b = 0 - k * mc6c_mid[1];
mc6c->ele = k * mc6c->ele + b;
}
else
{
k = (30 - 0) / (mc6c_max[1] - mc6c_mid[1]);
b = 0 - k * mc6c_mid[1];
mc6c->ele = k * mc6c->ele + b;
}
// CH3 映射, [196, 1289] --> [400, 800]
if (mc6c->thr < mc6c_min[2])
mc6c->thr = mc6c_min[2];
else if (mc6c->thr > mc6c_max[2])
mc6c->thr = mc6c_max[2];
else
{
k = (800 - 400) / (mc6c_max[2] - mc6c_min[2]);
b = 400 - k * mc6c_min[2];
mc6c->thr = k * mc6c->thr + b;
}
// CH4 映射,[129, 948] --> [-36, 0]; [948, 1833] --> [0, 36]
if (mc6c->rud < mc6c_mid[3])
{
k = (0 - (-36)) / (mc6c_mid[3] - mc6c_min[3]);
b = 0 - k * mc6c_mid[3];
mc6c->rud = k * mc6c->rud + b;
}
else
{
k = (36 - 0) / (mc6c_max[3] - mc6c_mid[3]);
b = 0 - k * mc6c_mid[3];
mc6c->rud = k * mc6c->rud + b;
}
// CH5 映射,得到三档分别赋值 1,2,3
if (mc6c->ch5 < (mc6c_min[4] + mc6c_mid[4]) / 2)
mc6c->ch5 = 1;
else if (mc6c->ch5 < (mc6c_mid[4] + mc6c_max[4]) / 2)
mc6c->ch5 = 2;
else
mc6c->ch5 = 3;
// CH6 映射,得到两档分别赋值 1,2
if (mc6c->ch6 < (mc6c_min[5] + mc6c_max[5]) / 2)
mc6c->ch6 = 1;
else
mc6c->ch6 = 2;
}
/* MC6C遥控器数据接口 */
/* 依赖SbusParseTask()任务 */
void GetMc6cDataApi(struct MC6C_t *mc6c)
{
mc6c->ail = (float)sbus_.ch[0];
mc6c->ele = (float)sbus_.ch[1];
mc6c->thr = (float)sbus_.ch[2];
mc6c->rud = (float)sbus_.ch[3];
mc6c->ch5 = sbus_.ch[4];
mc6c->ch6 = sbus_.ch[5];
CaliMc6cData(mc6c);
}
/* 获取遥控器数据接口 */
/* 目前未使用此函数 */
void GetSbusDataApi(struct SBUS_t *sbus)
{
sbus->head = sbus_.head;
sbus->flag = sbus_.flag;
sbus->end = sbus_.end ;
sbus->ch[0] = sbus_.ch[0];
sbus->ch[1] = sbus_.ch[1];
sbus->ch[2] = sbus_.ch[2];
sbus->ch[3] = sbus_.ch[3];
sbus->ch[4] = sbus_.ch[4];
sbus->ch[5] = sbus_.ch[5];
sbus->ch[6] = sbus_.ch[6];
sbus->ch[7] = sbus_.ch[7];
sbus->ch[8] = sbus_.ch[8];
sbus->ch[9] = sbus_.ch[9];
sbus->ch[10] = sbus_.ch[10];
sbus->ch[11] = sbus_.ch[11];
sbus->ch[12] = sbus_.ch[12];
sbus->ch[13] = sbus_.ch[13];
sbus->ch[14] = sbus_.ch[14];
sbus->ch[15] = sbus_.ch[15];
}
/* 遥控器控制电机测试 */
/* 遥控器油门将调节电机占空比 */
void TestCtrlMotorTask(void *arg)
{
struct MC6C_t mc6c;
while (1)
{
GetMc6cDataApi(&mc6c);
SetMotorDutyApi(MOTOR1, (uint16_t)mc6c.thr); // MOTOR1, 引脚为TIM3 CH1, PB4
SetMotorDutyApi(MOTOR2, (uint16_t)mc6c.thr); // MOTOR2, 引脚为TIM3 CH2, PB5
SetMotorDutyApi(MOTOR3, (uint16_t)mc6c.thr); // MOTOR3, 引脚为TIM3 CH3, PB0
SetMotorDutyApi(MOTOR4, (uint16_t)mc6c.thr); // MOTOR4, 引脚为TIM3 CH4, PB1
delay_ms(200);
}
}
运行结果如下,正常时,head为0x0F,flag为0x00,end为0x00。
现在已经开启四路电机输出PWM波,随便测一路即可,输入捕获也开启,遥控器也接上,引脚如下:
注意:
有一个问题,依旧没有解决,遥控器油门通道总是有跳变,其他通道正常,一直没找到bug,如果遇到相同问题或解决办法,讨论区见。
此时接收Sbus协议帧没有使用DMA,后期将优化。
— 完 —