整体架构
思路总结(飞控板):
灯控和一些基础配置
1.测试PWM
开启四路PWM的通道,测试一下是否可以控制四个电机旋转和旋转速度。
2.开启无人机上面的四个LED灯,并且设置一个枚举控制LED灯的四种状态,比如快闪,慢闪,常亮,流水的,对角亮,这个自定义就行。后续无人机处于什么位置的时候就可以同步让LED也亮起来
3.开启一下ADC,测量下无人机的电池电压是否准确,这里是用的DMA,开启DMA的时候强制开启了中断,用数组进行保存数据的时候,需要注意的是即使我们只有一个Uint16的数据,但是需要讲数组的长度设置长一点不然会卡死。然后这里有电阻进行了分压,所以实际的电压需要乘一个2。
出现这种情况的可能原因是DMA太快覆盖变量导致缓冲区溢出
或者是中断触发得太快,然后一直抢占cpu的资源,表现出卡死的现象
合理设置缓冲区长度 建议数组长度至少为2的幂次(如4、8),避免循环模式下的边界问题。
运动传感器模块MPU6050(读取和写入)
1.通过I2C读取mpu6050的六轴数据,
2.需要配置MPU6050这个驱动,硬件接口层。一般对于I2C读取驱动,主要是单读,单写,连续读取,连续写入,mpu6050的 配置这几个函数
/**
* @description: 读取指定寄存器一个字节数据
* @param {uint8_t} reg_addr
* @param {uint8_t} *receive_byte
* @return {*}
*/
uint8_t Int_MPU6050_ReadByte(uint8_t reg_addr, uint8_t *receive_byte)
{
return HAL_I2C_Mem_Read(&hi2c1, MPU_IIC_ADDR << 1, reg_addr, I2C_MEMADD_SIZE_8BIT, receive_byte, 1, 2000);
}
/**
这里需要说明的是
1.在i2c通讯的时候,设别地址码一般是七位的,最后一位来决定是读还是写,所以要将地址码放在高位,最后一位在hal库中不用管,因为在hal库函数的底层已经做了相应的处理,自动给你写1或者写0了
最后一位 = 0 → 写(主机发送数据)
最后一位 = 1 → 读(主机接收数据)
2.注意寄存器的大小,如果设备的寄存器的大小为8,那在参数中就选择I2C_MEMADD_SIZE_8BIT就行了,如果为16就选择16.
*/
读写多个
uint8_t Int_MPU6050_ReadBytes(uint8_t reg_addr, uint8_t *receive_buff, uint8_t size)
{
return HAL_I2C_Mem_Read(&hi2c1, MPU_IIC_ADDR << 1, reg_addr, I2C_MEMADD_SIZE_8BIT, receive_buff, size, 2000);
}
写入和这个类似
3.MPU6050的初始化(重点)
void Int_MPU6050_Init(void)
{
uint8_t dev_id = 0;
/* 2 复位 -》延迟一会 -》 唤醒 */
Int_MPU6050_WriteByte(MPU_PWR_MGMT1_REG, 0x80);
HAL_Delay(300);
Int_MPU6050_WriteByte(MPU_PWR_MGMT1_REG, 0x00);
/* 3 陀螺仪量程 +-2000°/s, fsr=3 */
//置满量程决定了陀螺仪能检测的角速度范围,量程越大,灵敏度越低(精度下降),量程越小,灵敏度越高(精度提升)。
Int_MPU6050_WriteByte(MPU_GYRO_CFG_REG, 3 << 3);
/* 4 加速度量程 */
Int_MPU6050_WriteByte(MPU_ACCEL_CFG_REG, 0 << 3);
/* 5 其他功能设置(可选):FIFO、第二IIC、中断 */
Int_MPU6050_WriteByte(MPU_INT_EN_REG, 0x00); // 关闭所有中断
Int_MPU6050_WriteByte(MPU_USER_CTRL_REG, 0x00); // 关闭第二IIC
Int_MPU6050_WriteByte(MPU_FIFO_EN_REG, 0x00); // 关闭FIFO
/* 6 系统时钟源、陀螺仪采样率、低通滤波的设置 */
/* 配置时钟源之前,确认正常工作,读一下id */
Int_MPU6050_ReadByte(MPU_DEVICE_ID_REG, &dev_id);
if (dev_id == MPU_IIC_ADDR)
{
/* 6.1 设置时钟源:陀螺仪X轴的时钟,精度更高 */
Int_MPU6050_WriteByte(MPU_PWR_MGMT1_REG, 0x01);
/* 6.2 设置陀螺仪采样率、低通滤波 */
Int_MPU6050_SetGyroRate(100);
/* 6.3 让两个传感器退出待机模式,进入正常工作状态*/
Int_MPU6050_WriteByte(MPU_PWR_MGMT2_REG, 0x00);
}
}
时钟源原本有默认的8MHZ但是不推荐,手册有说建议选其他的。
读取六轴数据
void Int_MPU6050_Get_Gyro(int16_t *gx, int16_t *gy, int16_t *gz)
{
uint8_t buff[6];
Int_MPU6050_ReadBytes(MPU_GYRO_XOUTH_REG, buff, 6);
/*
buff[0]:角速度X轴高8位
buff[1]:角速度X轴低8位
buff[2]:角速度Y轴高8位
buff[3]:角速度Y轴低8位
buff[4]:角速度Z轴高8位
buff[5]:角速度Z轴低8位
*/
*gx = ((short)buff[0] << 8) | buff[1];
*gy = ((short)buff[2] << 8) | buff[3];
*gz = ((short)buff[4] << 8) | buff[5];
}
void Int_MPU6050_Get_Accel(int16_t *ax, int16_t *ay, int16_t *az)
{
uint8_t buff[6];
Int_MPU6050_ReadBytes(MPU_ACCEL_XOUTH_REG, buff, 6);
/*
buff[0]:加速度X轴高8位
buff[1]:加速度X轴低8位
buff[2]:加速度Y轴高8位
buff[3]:加速度Y轴低8位
buff[4]:加速度Z轴高8位
buff[5]:加速度Z轴低8位
*/
*ax = ((short)buff[0] << 8) | buff[1];
*ay = ((short)buff[2] << 8) | buff[3];
*az = ((short)buff[4] << 8) | buff[5];
}
读取的时候需要拼接一下,因为每一轴的数据都是16位的,但是一次只能读8位。
对数据零点偏移处理
首先需要判断无人机是否处于静止,然后再校准数据。当然这里有个前提一定是要提前把无人机放在平面上,不然就没有意义。
具体用代码实先思路是:设置30次外层循环,内层循环判断是否稳定,每一次判断一下角速度的三轴的数据和上一次差值不能大于设置的阈值-5和5,如果有超过说明不稳定,继续执行内层循环,如果稳定下来了,就执行外层循环,30次,最后确定最后的偏差值。最后再做356次的mpu取六轴数据,前100次不做处理,后256次累加再相除,减去之前得到的偏差值,就可以基本上校准
具体函数如下:
// 偏移量计算
void App_mpu_offsets(void)
{
// 循环计数器,控制等待传感器静止的次数,共30次
uint8_t gyro_i = 30;
// 用于累加陀螺仪和加速度计数据的缓冲区,依次存储gyro_x、gyro_y、gyro_z、accel_x、accel_y、accel_z的累加值
uint32_t buff[6] = {0};
// 判断传感器是否处于静止状态的阈值,取陀螺仪角速度两次测量值的差值
// 若差值在 [MIN_GYRO, MAX_GYRO] 范围内,则认为传感器静止
const int8_t MAX_GYRO = 5;
const int8_t MIN_GYRO = -5;
// 存储上一次读取的陀螺仪角速度数据,依次对应x、y、z轴
uint16_t lastgyro[3] = {0};
// 存储当前和上一次陀螺仪角速度数据的差值,依次对应x、y、z轴
int16_t offsetgyro[3] = {0};
// 等待传感器静止,循环30次确保传感器稳定
while (gyro_i--)
{
do
{
// 延时10毫秒,给传感器足够时间稳定
HAL_Delay(10);
// 计算当前和上一次陀螺仪角速度数据的差值
offsetgyro[0] = mpu_data.gyro_x - lastgyro[0];
offsetgyro[1] = mpu_data.gyro_y - lastgyro[1];
offsetgyro[2] = mpu_data.gyro_z - lastgyro[2];
// 更新上一次的陀螺仪角速度数据
lastgyro[0] = mpu_data.gyro_x;
lastgyro[1] = mpu_data.gyro_y;
lastgyro[2] = mpu_data.gyro_z;
} while (
// 只要有一个轴的差值超出 [MIN_GYRO, MAX_GYRO] 范围,就继续等待
offsetgyro[0] > MAX_GYRO || offsetgyro[0] < MIN_GYRO ||
offsetgyro[1] > MAX_GYRO || offsetgyro[1] < MIN_GYRO ||
offsetgyro[2] > MAX_GYRO || offsetgyro[2] < MIN_GYRO);
}
// 采集传感器数据,共采集356次
for (uint16_t i = 0; i < 356; i++)
{
// 调用函数读取并处理传感器数据
App_mpu_data();
// 从第100次开始累加数据,前100次数据用于预热
if (i >= 100)
{
// 累加陀螺仪数据
buff[0] += mpu_data.gyro_x;
buff[1] += mpu_data.gyro_y;
buff[2] += mpu_data.gyro_z;
// 累加加速度计数据,z轴减去重力加速度对应的数值(16384)
buff[3] += mpu_data.accel_x;
buff[4] += mpu_data.accel_y;
buff[5] += mpu_data.accel_z - 16384;
}
}
// 计算零偏值,将累加值除以256(即取平均值)
MPU_offset[0] = buff[0] / 256;
MPU_offset[1] = buff[1] / 256;
MPU_offset[2] = buff[2] / 256;
MPU_offset[3] = buff[3] / 256;
MPU_offset[4] = buff[4] / 256;
MPU_offset[5] = buff[5] / 256;
}
对六轴速度滤波处理
使用一阶低通滤波对角速度数据进行滤波(因为角速度的变化比较大,用卡尔曼滤波不太好,就用的低通滤波)
低通滤波公式:
这次的值= 0.85 * 上次的值 + 0.15 *这次的值;
void App_mpu_data(void)
{
// 先读取原始数据
Int_MPU6050_Get_Gyro(&mpu_data.gyro_x, &mpu_data.gyro_y, &mpu_data.gyro_z);
Int_MPU6050_Get_Accel(&mpu_data.accel_x, &mpu_data.accel_y, &mpu_data.accel_z);
printf("=========滤波前:\n");
printf("%d %d %d\r\n", mpu_data.gyro_x, mpu_data.gyro_y, mpu_data.gyro_z);
printf("%d %d %d\r\n", mpu_data.accel_x, mpu_data.accel_y, mpu_data.accel_z);
// 零偏校准
mpu_data.gyro_x -= MPU_offset[0];
mpu_data.gyro_y -= MPU_offset[1];
mpu_data.gyro_z -= MPU_offset[2];
mpu_data.accel_x -= MPU_offset[3];
mpu_data.accel_y -= MPU_offset[4];
mpu_data.accel_z -= MPU_offset[5];
// 对加速度卡尔曼滤波
Common_Filter_KalmanFilter(&kfs[0], mpu_data.accel_x);
mpu_data.accel_x = (int16_t)kfs[0].out;
Common_Filter_KalmanFilter(&kfs[1], mpu_data.accel_y);
mpu_data.accel_y = (int16_t)kfs[1].out;
Common_Filter_KalmanFilter(&kfs[2], mpu_data.accel_z);
mpu_data.accel_z = (int16_t)kfs[2].out;
// 对角速度低通滤波应用低通滤波
static int16_t last_gyro[3];
mpu_data.gyro_x = 0.85 * last_gyro[0] + 0.15 * mpu_data.gyro_x;
last_gyro[0] = mpu_data.gyro_x;
mpu_data.gyro_y = 0.85 * last_gyro[1] + 0.15 * mpu_data.gyro_y;
last_gyro[1] = mpu_data.gyro_y;
mpu_data.gyro_z = 0.85 * last_gyro[2] + 0.15 * mpu_data.gyro_z;
last_gyro[2] = mpu_data.gyro_z;
printf("=========滤波后:\n");
printf("%d %d %d\r\n", mpu_data.gyro_x, mpu_data.gyro_y, mpu_data.gyro_z);
printf("%d%d %d\r\n", mpu_data.accel_x, mpu_data.accel_y, mpu_data.accel_z);
// 计算角度(四元数)
}
使用卡尔曼滤波对加速度进行滤波
卡尔曼滤波具体实现过程比较复杂,这里移植的现成的。(不详细介绍了)
四元数姿态解算(计算角度),这里也不详细说了,移植的,这种算法自己写会花很多时间。
到这里已经可以得到稳定的六轴数据了
SI24RI(2.4G通讯模块)
这个芯片需要说明一下,这是国产的完全盗版挪威的NRF24L01,里面的寄存器和实现方式都一模一样,直接拿NRF24L01的例程来做SI24RI也是可以的。
简要介绍
遥控器是通过2.4G通讯实现的远程控制无人机的飞行.
我们使用的是国产2.4G无线通讯芯片Si24R1.
Si24R1 是由中国公司设计和制造的射频芯片,其设计灵感和功能类似于 Nordic Semiconductor 的 nRF24L01+ 芯片。Si24R1 具有高度集成、低功耗和高数据传输速率的特点。
工作频率:2.4GHz ISM 频段. 数据传输速率:最高可达 2Mbps. 支持自动重传和自动确认. 多达 126**数据信道. 低成本、高性能:适用于大规模应用. 传输距离**:视环境和天线设计,通常在几十米到数百米范围内.
Si24R1 通过 SPI接口与微控制器通信。
Si24R1 是一款高性能、低成本的 2.4GHz 射频收发芯片,适用于多种无线通信应用。它的低功耗、高数据速率和多通道支持,使其成为无线传感器网络、智能家居、遥控玩具和计算机外设等领域的理想选择。通过 SPI 接口,可以方便地与各种微控制器进行通信,实现无线数据传输。
接口层配置
主要还是那几个经典的读取写入函数,初始化等。
uint8_t Inf_Si24R1_WriteReg(uint8_t reg, uint8_t data)
{
uint8_t status = 0;
/* 1、片选选中 */
SI24R1_CS_L;
/* 2、写寄存器地址 */
status = SPI_SwapByte(reg);
/* 3、写入数据 */
SPI_SwapByte(data);
/* 4、片选取消 */
SI24R1_CS_H;
return status;
}
/**
* @description: 读寄存器
* @param {uint8_t} reg 要读取的寄存器
* @return {*} 读取到的值
*/
uint8_t Inf_Si24R1_ReadReg(uint8_t reg)
{
uint8_t res = 0;
/* 1、片选选中 */
SI24R1_CS_L;
/* 2、写寄存器地址(读指令) */
SPI_SwapByte(reg);
/* 3、读取数据(写什么无所谓) */
res = SPI_SwapByte(0);
/* 4、片选取消 */
SI24R1_CS_H;
return res;
}
/**
* @description: 向指定寄存器写多个字节
* @param {uint8_t} reg 写入的寄存器地址
* @param {uint8_t*} pBuf 写入的多个字节数据指针
* @param {uint8_t} len 数据字节数
* @return {*}
*/
uint8_t Inf_Si24R1_WriteBuf(uint8_t reg, uint8_t *pBuf, uint8_t len)
{
uint8_t status = 0;
/* 1、片选选中 */
SI24R1_CS_L;
/* 2、写寄存器地址 */
status = SPI_SwapByte(reg);
/* 3、循环写入多个字节数据 */
for (uint8_t i = 0; i < len; i++)
{
SPI_SwapByte(*pBuf++);
}
/* 4、片选取消 */
SI24R1_CS_H;
return status;
}
/**
* @description: 读多个字节
* @param {uint8_t} reg 要读取的寄存器地址
* @param {uint8_t *} pBuf 用来接收的数据缓冲的指针
* @param {uint8_t} len 接收的字节数
* @return {*}
*/
uint8_t Inf_Si24R1_ReadBuf(uint8_t reg, uint8_t *pBuf, uint8_t len)
{
/* 1、片选选中 */
SI24R1_CS_L;
/* 2、写寄存器地址(读指令) */
SPI_SwapByte(reg);
/* 3、循环读取多个字节数据(写什么无所谓) */
for (uint8_t i = 0; i < len; i++)
{
*pBuf++ = SPI_SwapByte(0);
// printf("pBuf[%d]=%2x\r\n",i,pBuf[i]);
}
/* 4、片选取消 */
SI24R1_CS_H;
return 0;
}
通讯模式
在配置SI24RI的时候,是用命令进行配置,具体命令表如下:
void Inf_Si24R1_TXMode(void)
{
/* 1、进入待机模式,CE=0 */
SI24R1_EN_L;
/* 2、相关的配置:发送地址、接收管道0地址(一样)、ACK使能、使能管道0、功率、Config为发送模式 */
Inf_Si24R1_WriteBuf(SPI_WRITE_REG + TX_ADDR, TX_ADDRESS, TX_ADR_WIDTH); // 写入发送地址
Inf_Si24R1_WriteBuf(SPI_WRITE_REG + RX_ADDR_P0, RX_ADDRESS, RX_ADR_WIDTH); // 为了应答接收设备,接收通道0地址和发送地址相
Inf_Si24R1_WriteReg(SPI_WRITE_REG + EN_AA, 0x01); // 使能接收通道0自动应答
Inf_Si24R1_WriteReg(SPI_WRITE_REG + EN_RXADDR, 0x01); // 使能接收通道0
Inf_Si24R1_WriteReg(SPI_WRITE_REG + SETUP_RETR, 0x0a); // 自动重发延时等待250us+86us,自动重发10次
Inf_Si24R1_WriteReg(SPI_WRITE_REG + RF_CH, CH); // 选择射频通道0x40
Inf_Si24R1_WriteReg(SPI_WRITE_REG + RF_SETUP, 0x0f); // 数据传输率2Mbps,发射功率7dBm
Inf_Si24R1_WriteReg(SPI_WRITE_REG + CONFIG, 0x0e); // CRC使能,16位CRC校验,上电
/* 3、使能CE */
SI24R1_EN_H;
}
/**
* @description: 接收模式
* @return {*}
*/
void Inf_Si24R1_RXMode(void)
{
SI24R1_EN_L;
/*
与发送的区别:
1、不需要设置发送地址
2、需要设置接收通道0的负载长度
3、config配置的,bit0=1 为接收模式
*/
Inf_Si24R1_WriteBuf(SPI_WRITE_REG + RX_ADDR_P0, RX_ADDRESS, RX_ADR_WIDTH); // 接收设备接收通道0使用和发送设备相同的发送地址
Inf_Si24R1_WriteReg(SPI_WRITE_REG + EN_AA, 0x01); // 使能接收通道0自动应答
Inf_Si24R1_WriteReg(SPI_WRITE_REG + EN_RXADDR, 0x01); // 使能接收通道0
Inf_Si24R1_WriteReg(SPI_WRITE_REG + RF_CH, CH); // 选择射频通道0x40
Inf_Si24R1_WriteReg(SPI_WRITE_REG + RX_PW_P0, TX_PLOAD_WIDTH); // 接收通道0选择和发送通道相同有效数据宽度
Inf_Si24R1_WriteReg(SPI_WRITE_REG + RF_SETUP, 0x0f); // 数据传输率2Mbps,发射功率7dBm
Inf_Si24R1_WriteReg(SPI_WRITE_REG + CONFIG, 0x0f); // CRC使能,16位CRC校验,上电,接收模式
SI24R1_EN_H; // 拉高CE启动接收设备
}
接收数据包,和发送数据包逻辑:
uint8_t Inf_Si24R1_TxPacket(uint8_t *txBuf)
{
uint8_t state = 0;
/* 1、使用写Tx FIFO指令,将数据发送 */
SI24R1_EN_L;
Inf_Si24R1_WriteBuf(WR_TX_PLOAD, txBuf, TX_PLOAD_WIDTH);
SI24R1_EN_H; // 确保进入发射模式
/* 2、判断发送完成(或达到最大重发次数):循环读取状态寄存器,并判断bit4、bit5 */
while (!(state & (TX_OK | MAX_TX)))
{
state = Inf_Si24R1_ReadReg(SPI_READ_REG + STATUS);
}
/* 3、 清空 接收或最大重发次数 中断标志位 */
Inf_Si24R1_WriteReg(SPI_WRITE_REG + STATUS, state);
/* 4、达到最大重发次数,就要主动清除Tx FIFO,否则无法继续发送 */
if (state & MAX_TX)
{
if (state & 0x01) // bit0: 如果TX FIFO满了,=1,没满=0
{
Inf_Si24R1_WriteReg(FLUSH_TX, 0xff);
}
}
/* 5、如果是发送成功 */
if (state & TX_OK)
{
return 0;
}
return 1; // 其他原因未成功
}
/**
* @description: 接收一个数据包
* @param {uint8_t} *txBuf 存读取的数据
* @return {*} 0:成功读到数据;1:未读到数据
*/
uint8_t Inf_Si24R1_RxPacket(uint8_t *rxBuf)
{
/* 1、读状态寄存器,判断是否收到数据了 */
uint8_t state = 0;
state = Inf_Si24R1_ReadReg(SPI_READ_REG + STATUS);
/* 2、 清除 接收中断 标志 */
Inf_Si24R1_WriteReg(SPI_WRITE_REG + STATUS, state);
/* 3、如果收到数据了,就开始读 RX FIFO */
if (state & RX_OK)
{
/* 2.1 从 RX FIFO读取数据到 buff 里 */
Inf_Si24R1_ReadBuf(RD_RX_PLOAD, rxBuf, RX_PLOAD_WIDTH);
/* 2.2 清空 RX FIFO */
Inf_Si24R1_WriteReg(FLUSH_RX, 0xff);
connect_flag = 0;
// 测试打印的数据
// for (uint8_t i = 0; i < RX_PLOAD_WIDTH; i++)
// {
// printf("receice data:[%d] = %02x\r\n", i, rxBuf[i]);
// }
/* 2.3 接收到数据后,对标志位置0 */
connect_flag = 0;
/* =============测试:打印接收的数据================= */
// for (uint8_t i = 0; i < RX_PLOAD_WIDTH; i++)
// {
// printf("receive[%d]=%02x\r\n", i, txBuf[i]);
// }
/* ================================================ */
return 0; // 成功接收数据
}
return 1; // 未接收到数据
}
这里官方有给例程,直接移植就行。
要使用的话只需要在主函数里,自检一下,并且设置为接收模式即可,接收数据的函数暂时写在while循环里,后面添加freeRTOS可以单独写在任务里面。
printf("2.4g开始自检\r\n");
while (Inf_Si24R1_Check())
{
/* code */
}
printf("2.4g自检成功\r\n");
Inf_Si24R1_RXMode();
while(1){
Inf_Si24R1_RxPacket(rxBuf);
}
解析2.4G的数据包协议
在遥控板那边会传输很多数据,而且是按照一定的数据格式,这里采取的数据格式如下,在2.4G数据包里最多传输的数据为32个字节。
分为
帧头 :16字节 0xAAAF
功能字 :8字节 0x03
长度 : 长度 总共28个字节
数据 :10个数据 20个字节
校验和 :1个32位 4个字节
然后只需要对遥控板传过来的数据进行解析即可。
具体解析,那肯定是先判断帧头是不是相同,如果相同再一个一个将数据解析出来,存入结构体。然后再总体把接收到的数据进行累加,看看与校验和是否相等,如果不相等就舍弃。
/**
* @brief 检查并处理接收到的遥控数据,同时更新连接标志。
*
* 该函数首先更新连接标志,接着对接收的数据进行帧头校验和校验和校验。
* 若校验通过且数据类型为 0x03,则提取遥控数据和辅助通道数据。
* 最后对连接标志进行范围限制。
*
* @param data 指向接收到的遥控数据缓冲区的指针。
* @param len 接收到的数据长度。
*/
void App_Flight_Remote_check(uint8_t *data, uint8_t len)
{
// 连接标志加1,用于记录与遥控器的连接状态
connect_flag++;
// 当连接标志首次变为1时,可在此添加初始化代码
if (connect_flag == 1)
{
/* code */
}
// 初始化变量,用于存储接收到的校验和和计算得到的校验和
uint32_t init_sum = 0;
uint32_t flight_sum = 0;
// 帧头校验,判断数据的前两个字节是否为 0XAA 和 0XAF
if (!((*data == 0XAA) && (*(data + 1) == 0XAF)))
{
// 帧头不正确,说明数据可能损坏或非预期,直接返回
return;
}
// 提取数据末尾的4字节校验和
init_sum = *(data + len - 4) << 24 | *(data + len - 3) << 16 | *(data + len - 2) << 8 | *(data + len - 1);
// 计算数据(除校验和部分)的累加和
for (uint8_t i = 0; i < len - 4; i++)
{
flight_sum += data[i];
}
// 比较计算得到的校验和与接收到的校验和
if (flight_sum != init_sum)
{
// 校验和不一致,说明数据可能在传输过程中损坏,丢弃该数据
return;
}
// 判断数据类型是否为 0x03
if (data[2] == 0x03)
{
// 从索引4开始提取遥控数据
checkdata.THR = data[4] << 8 | data[5]; // 油门数据
checkdata.YAW = data[6] << 8 | data[7]; // 偏航数据
checkdata.ROL = data[8] << 8 | data[9]; // 横滚数据
checkdata.PIT = data[10] << 8 | data[11]; // 俯仰数据
// 提取辅助通道的数据
checkdata.AUX1 = data[12] << 8 | data[13];
checkdata.AUX2 = data[14] << 8 | data[15];
checkdata.AUX3 = data[16] << 8 | data[17];
checkdata.AUX4 = data[18] << 8 | data[19];
checkdata.AUX5 = data[20] << 8 | data[21];
checkdata.AUX6 = data[22] << 8 | data[23];
// 以下注释的代码用于调试,可打印提取的数据
// printf("thr = %d\r\n", checkdata.THR);
// printf("pit = %d\r\n", checkdata.PIT);
// printf("rol = %d\r\n", checkdata.ROL);
// printf("yaw = %d\r\n", checkdata.YAW);
// printf("aux1 = %d\r\n", checkdata.AUX1);
// printf("aux2 = %d\r\n", checkdata.AUX2);
// printf("aux3 = %d\r\n", checkdata.AUX3);
// printf("aux4 = %d\r\n", checkdata.AUX4);
// printf("aux5 = %d\r\n", checkdata.AUX5);
// printf("aux6 = %d\r\n", checkdata.AUX6);
}
// 限制连接标志的范围,防止其值过大
if (connect_flag > 500)
{
connect_flag = 1;
}
设计解锁无人机动作
如果无人机这边一连接,直接能够油门开电机,会很危险,所以我们需要一个解锁动作,防止误触。
这里设计的解锁动作为:
1.油门最低-》
2.油门最高-》
3.油门最低-》
这里直接使用的状态机,设置几个状态
#define WAITING_1 1
#define WAITING_2 2
#define WAITING_3 3
#define WAITING_4 4
#define PROCESS 5
#define WARNING 6
#define EXIT 7
然后实现的思路是:
/**
* @brief 实现无人机解锁逻辑,通过特定的油门操作序列完成解锁和锁定。
*
* 解锁流程需要依次满足油门最低、油门最高保持一段时间、油门再次最低的条件。
* 解锁成功后,可通过将油门保持在最低一段时间来重新锁定。
*/
void App_Fly_Unlock(void)
{
// 解锁状态机,初始状态为 WAITING_1,等待油门最低
static uint8_t status = WAITING_1;
// 时间计数器,用于记录在特定状态下的持续时间
static uint16_t time_count = 0;
// 如果状态为 WARNING,将状态切换为 EXIT
if (status == WARNING)
{
status = EXIT;
}
// 根据当前状态执行不同的操作
switch (status)
{
case WAITING_1: // 阶段1:判断油门是否最低
if (checkdata.THR < 1030) // 油门值小于1030认为油门最低,不用卡太死
{
printf("==========进入阶段一\r\n");
status = WAITING_2; // 满足条件,准备进入阶段2
}
break;
case WAITING_2: // 阶段2:判断油门是否最高
if (checkdata.THR > 1960) // 油门值大于1960认为油门最高
{
printf("==========进入阶段二\r\n");
time_count++; // 计数器加1
if (time_count > 50)
{
status = WAITING_3; // 油门最高状态持续超过50个计数周期,进入阶段3
time_count = 0; // 计数器清零
}
}
break;
case WAITING_3: // 阶段3:判断油门是否再次最低
if (checkdata.THR < 1010) // 油门值小于1010认为油门最低
{
printf("==========进入阶段三\r\n");
status = WAITING_4; // 满足条件,进入阶段4
}
break;
case WAITING_4: // 阶段4:解锁完成
flag_unlock = 1; // 解锁标志置1,表示解锁完成
status = PROCESS;
printf("==========进入阶段四\r\n");
break;
case PROCESS: // 阶段5:解锁后的运行状态
printf("==========进入阶段五\r\n");
time_count++; // 计数器加1
if (checkdata.THR < 1010) // 油门值小于1010
{
if (time_count > 1000)
{
status = WAITING_1; // 油门最低状态持续超过1000个计数周期,重新进入等待解锁状态
flag_unlock = 0; // 解锁标志置0,表示锁定
time_count = 0; // 计数器清零
}
}
if (!flag_unlock)
{
status = EXIT; // 解锁标志为0,进入退出模式
}
break;
case EXIT: // 退出模式
printf("==========退出模式==========\r\n");
flag_unlock = 0; // 解锁标志置0,表示锁定
status = WAITING_1; // 状态重置为初始等待状态
time_count = 0; // 计数器清零
break;
default: // 默认情况,状态重置为初始等待状态
status = WAITING_1;
break;
}
}
通过一个switch选择判断语句实现,然后具体的逻辑,代码已经写得很明白了。
状态1:油门值<1030
状态2:油门值大于1960认为油门最高,并且要持续一定的时间,这里的持续时间没有使用延时函数,使用的是count++来实现,用一个static变量维持生命周期,然后在while循环里,如果设置延迟4ms,那么真实的时间就是 4*判断的标志位
状态3:判断油门是否再次最低
状态4:让解锁的一个标志位置1
状态5:(需要考虑假如,用户已经很久没操作了,这个时候的操作变化)在这个地方已经解锁了,但是如果长时间没操作了,会跳转到EXIT标志位,相当于已经退出了
EXIT:退出,重置标志位,跳转状态1(初始状态)
这个地方的逻辑判断可以灵活修改,根据自己的喜好,然后前面我们设计了灯控系统,这个时候就可以把不同类型闪烁方式放在不同的状态上。
处理无人机失联的问题
无人机如果在控制的过程中,突然被其他的信道冲突打断,或者飞太远了。2.4G连不上了,这个时候就需要处理失联问题。
我这里处理的思路是:给一个全局变量标志位connect_flag,然后如是是解锁状态的话就一直为1,如果一但接收不到数据,持续一段时间,就判断为失联,并将当前状态置为危险,并且缓慢减少电机转速,直到停止,电机转速都为0后,就将状态置为1(初始状态):
void App_Flight_Rc_Aalysis(void)
{
// 静态变量,用于记录油门减少的计数
static uint16_t thr_count = 0;
// 判断连接标志是否为 1
if (connect_flag == 1)
{
/* 执行解锁指令*/
App_Fly_Unlock();
}
else
{
// 连接标志加 1 并判断是否超过 300,超过则认为失联
if (connect_flag++ > 300)
{
/* code */
// 进入失联状态
// 将 24G 模块设置为接收模式
Inf_Si24R1_RXMode();
// 除了油门,将俯仰、偏航、横滚通道数据归中
checkdata.PIT = 1500;
checkdata.YAW = 1500;
checkdata.ROL = 1500;
// 进入紧急状态,尝试重连 2.4G 模块,直到连接成功
while (Inf_Si24R1_Check())
{
/* code */
}
// 若原先油门很低(小于 1200),直接将油门值设为 1000
if (checkdata.THR < 1200)
{
checkdata.THR = 1000;
}
else
{
// 若原先油门不算低,每 100 个计数周期减少 50 的油门值
if ((thr_count++ > 100))
{
checkdata.THR -= 50;
// 计数清零,准备下一次计时
thr_count = 0;
}
}
// 调用 Limit 函数将油门值限制在 1000 到 2000 之间
Limit(checkdata.THR, 1000, 2000);
}
}
}
无人机的电机旋转
用一个结构体去存储,将接收并解析到的遥感数据用来控制PWM
PID控制
设计PID算法,先判断P的极性,I的极性,D的极性,然后慢慢调参数就行了
思路总结(遥控板):
ADC读取遥感的数值(yaw,roll,pitch,throttle)(并校准)
用结构体存储4个数值,然后直接开DMA读取ADC的数值,打印测试,这里会发现极性不对,按照我们的想法,往上应该是增加,往下是减少,往左是减少,往右是增加,极性都是反的,这个时候就需要调整极性了,然后他的最大值是4095(12位),最小是0,因为我们要通过遥感的数值来控制电机的缘故,在电机里pwm的自动重装载数值是1000,所以将ADC的数值限制在1000,而且不想有负数产生,就将范围限制在1000-2000。
void App_Remote_Stick_Scan(void)
{
// printf("6(左边的左右) = %u\r\n",adc_buf[0]);
// printf("1(左边的上下) = %u\r\n",adc_buf[1]);
// printf("3(右边的左右) = %u\r\n",adc_buf[2]);
// printf("2(右边的上下) = %u\r\n",adc_buf[3]);
RemoteData.YAW = 2000 - (uint16_t)(0.25 * adc_buf[0]) - offsets.YAW_offset;
RemoteData.THR = 2000 - (uint16_t)(0.25 * adc_buf[1]) - offsets.THR_offset;
RemoteData.ROL = 2000 - (uint16_t)(0.25 * adc_buf[2]) - offsets.ROL_offset;
RemoteData.PIT = 2000 - (uint16_t)(0.25 * adc_buf[3]) - offsets.PIT_offset;
App_Window_Skip(&RemoteData);
// 中点校准:油门最低校准,其他中间校准
App_Remote_Mid_Offset(&RemoteData);
App_Remote_Mid_Limit(&RemoteData);
App_Remote_Limit(&RemoteData);
}
//上面这三个函数是后续要进行的处理,我马上说明
滑动串口滤波(adc值)
这里窗口大小取10,每次移动一次,取下一个的值,丢掉第一个的值,然后累加和,再求平均。
/**
* @brief 滑动窗口滤波函数,对遥控器数据进行滤波处理
*
* 该函数使用滑动窗口滤波算法,对遥控器的俯仰(PIT)、横滚(ROL)、油门(THR)和偏航(YAW)数据进行滤波。
* 它维护一个长度为 Filter_Num 的窗口,不断更新窗口内的数据并计算平均值,以减少数据的波动。
*
* @param pRemoteData 指向 Remote_Data_t 结构体的指针,包含遥控器的原始数据
*/
void App_Window_Skip(Remote_Data_t *pRemoteData)
{
// 1.丢掉旧数据
// 静态变量 count 用于记录当前要替换的旧数据的索引,初始值为 0
static uint16_t count = 0;
// 处理俯仰(PIT)数据
// 从滤波器的总和中减去旧数据
filter_pitch.sum -= filter_pitch.old[count];
// 将当前的俯仰数据存入旧数据数组
filter_pitch.old[count] = pRemoteData->PIT;
// 将新数据累加到滤波器的总和中
filter_pitch.sum += filter_pitch.old[count];
// 计算滤波后的俯仰数据,即窗口内数据的平均值
pRemoteData->PIT = filter_pitch.sum / Filter_Num;
// 处理横滚(ROL)数据
// 从滤波器的总和中减去旧数据
filter_roll.sum -= filter_roll.old[count];
// 将当前的横滚数据存入旧数据数组
filter_roll.old[count] = pRemoteData->ROL;
// 将新数据累加到滤波器的总和中
filter_roll.sum += filter_roll.old[count];
// 计算滤波后的横滚数据,即窗口内数据的平均值
pRemoteData->ROL = filter_roll.sum / Filter_Num;
// 处理油门(THR)数据
// 从滤波器的总和中减去旧数据
filter_throttle.sum -= filter_throttle.old[count];
// 将当前的油门数据存入旧数据数组
filter_throttle.old[count] = pRemoteData->THR;
// 将新数据累加到滤波器的总和中
filter_throttle.sum += filter_throttle.old[count];
// 计算滤波后的油门数据,即窗口内数据的平均值
pRemoteData->THR = filter_throttle.sum / Filter_Num;
// 处理偏航(YAW)数据
// 从滤波器的总和中减去旧数据
filter_yaw.sum -= filter_yaw.old[count];
// 将当前的偏航数据存入旧数据数组
filter_yaw.old[count] = pRemoteData->YAW;
// 将新数据累加到滤波器的总和中
filter_yaw.sum += filter_yaw.old[count];
// 计算滤波后的偏航数据,即窗口内数据的平均值
pRemoteData->YAW = filter_yaw.sum / Filter_Num;
// 索引递增
count++;
// 当索引达到窗口长度(10)时,重置索引为 0,实现循环更新
if (count >= 10)
{
count = 0;
}
}
在油门和偏航的控制手柄上,油门不能自动回正,其他三个都可以自动回正,为了让操作更加精确,需要做油门校准,中点限幅,最大小限制幅度(长按按键校准)
//校准,获得偏差值
void App_Remote_Mid_Offset(Remote_Data_t *RemoteData)
{
static uint16_t keycount = 0;
static uint32_t sum_thr = 0;
static uint32_t sum_pit = 0;
static uint32_t sum_rol = 0;
static uint32_t sum_yaw = 0;
static uint32_t count = 0;
if (!LEFT_TOP)
{
keycount++;
if (keycount >= 20)
{
if (count == 0)
{
offsets.PIT_offset = 0;
offsets.ROL_offset = 0;
offsets.YAW_offset = 0;
offsets.THR_offset = 0;
sum_thr = 0;
sum_pit = 0;
sum_rol = 0;
sum_yaw = 0;
count = 1;
}
else
{
count++;
sum_thr += RemoteData->THR;
sum_pit += RemoteData->PIT;
sum_rol += RemoteData->ROL;
sum_yaw += RemoteData->YAW;
}
if (count == 51)
{
count--;
offsets.THR_offset = sum_thr / count - 1000;
offsets.PIT_offset = sum_pit / count - 1500;
offsets.ROL_offset = sum_rol / count - 1500;
offsets.YAW_offset = sum_yaw / count - 1500;
count = 0;
keycount = 0;
}
}
}
}
// 遥感限制幅度
void App_Remote_Limit(Remote_Data_t *RemoteData)
{
if (RemoteData->THR > 2000)
{
RemoteData->THR = 2000;
}
else if (RemoteData->THR < 1000)
{
RemoteData->THR = 1000;
}
if (RemoteData->PIT > 2000)
{
RemoteData->PIT = 2000;
}
else if (RemoteData->PIT < 1000)
{
RemoteData->PIT = 1000;
}
if (RemoteData->YAW > 2000)
{
RemoteData->YAW = 2000;
}
else if (RemoteData->YAW < 1000)
{
RemoteData->YAW = 1000;
}
if (RemoteData->ROL > 2000)
{
RemoteData->ROL = 2000;
}
else if (RemoteData->ROL < 1000)
{
RemoteData->ROL = 1000;
}
}
void App_Remote_Mid_Limit(Remote_Data_t *RemoteData)
{
if (RemoteData->THR > 1450 && RemoteData->THR < 1550)
{
RemoteData->THR = 1500;
}
if (RemoteData->YAW > 1480 && RemoteData->YAW < 1520)
{
RemoteData->YAW = 1500;
}
if (RemoteData->PIT > 1480 && RemoteData->PIT < 1520)
{
RemoteData->PIT = 1500;
}
if (RemoteData->ROL > 1480 && RemoteData->ROL < 1520)
{
RemoteData->ROL = 1500;
}
}
通讯模块
//和飞控板上的SI24R1保持一致
//只需要在主函数里,改为发送模式,就行
这里就不详细说,注意通道什么的都要对应
发送数据(自定义协议)
这里就跟在飞控板解析的数据应该要保持一致
帧头 :16字节 0xAAAF
功能字 :8字节 0x03
长度 : 长度 总共28个字节
数据 :10个数据 20个字节
校验和 :1个32位 4个字节
void App_Remote_RemoteData(uint8_t *data)
{
uint8_t index = 0;
uint32_t checksum = 0;
// 枕头
data[index++] = 0xAA;
data[index++] = 0xAF;
// 功能字
data[index++] = 0x03;
// 长度
data[index++] = 0x0;
// 数据
data[index++] = (uint8_t)(RemoteData.THR >> 8);
data[index++] = (uint8_t)RemoteData.THR;
data[index++] = (uint8_t)(RemoteData.YAW >> 8);
data[index++] = (uint8_t)(RemoteData.YAW);
data[index++] = (uint8_t)(RemoteData.ROL >> 8);
data[index++] = (uint8_t)(RemoteData.ROL);
data[index++] = (uint8_t)(RemoteData.PIT >> 8);
data[index++] = (uint8_t)(RemoteData.PIT);
// AUX1-6辅助通道
data[index++] = 0x0;
data[index++] = 0x0;
data[index++] = 0x0;
data[index++] = 0x0;
data[index++] = 0x0;
data[index++] = 0x0;
data[index++] = 0x0;
data[index++] = 0x0;
data[index++] = 0x0;
data[index++] = 0x0;
data[index++] = 0x0;
data[index++] = 0x0;
// 重新计算长度
data[3] = index - 8;
// 校验和
for (uint8_t i = 0; i < index; i++)
{
checksum += data[i];
}
data[index++] = (uint8_t)(checksum >> 24);
data[index++] = (uint8_t)(checksum >> 16);
data[index++] = (uint8_t)(checksum >> 8);
data[index++] = (uint8_t)(checksum);
}
最后就只需要把这些函数放到任务中就可以了。
OLED
这个就不用写了吧,移植就行,看自己想要显示什么
任务架构(飞控,遥控)
最后——踩的坑
1.第一个就是我说的ADC使用DMA结果卡死了,解决办法就是把数组给增长了
2.在配置初始化MPU6050的时候,电源1寄存器配置后,进入睡眠了,需要唤醒需要时间,但是没有延迟,所以I2C一直读取不到数据
3.通讯配置完了后,进行测试,没有清除标志位,所以直接卡死了,这块芯片每次触发了中断都需要触发标志位。
/* 2.2 清空 RX FIFO */
Inf_Si24R1_WriteReg(FLUSH_RX, 0xff);
3.在两块板子配置好通讯模块的时候,准备进行测试,遥控按那边自建完毕一直发,飞控板这边接收到的信息会冲突,不是按照顺序了,原因是因为文档里面有说,这个接收fafo最多只能接收3个字节的数据,如果满了会触发中断,所以要让飞控板那边的数据传慢一点,当然不要太慢了,太慢了的话会影响手感。