本篇介绍匿名源码(ti版)整体的逻辑顺序,主要解读飞控板的初始化与整体的任务调度,大部分为Ano_Scheduler.c/.h里面的代码,看完此篇,你会初步了解这款开源飞控的整体逻辑
main.c
首先打开main.c
int main(void)//主函数,飞控开机后循环执行while(1)里面的程序
{
Drv_BspInit();//飞控板初始化
flag.start_ok = 1;//初始化成功标志
while(1)//主循环,采用了实时系统常见的时钟驱动调度算法,用于周期任务。说白了就是给每一个循环执行的任务一个相应的频率
{
Main_Task();//轮询任务调度器
}
}
再打开Drv_Bsp.c,看Drv_BspInit()函数,可以看到,里面全都是各个小部分的初始化函数。初始化函数其实就是变量赋为 默认值/储存值,把控件设为默认状态,把硬件准备好
如读取数据(如上位机设置的一些参数)、参数赋值、器件初始化、波特率设置等等,这部分注释给的很清楚,所以就不贴代码了。
Ano_Scheduler.c/.h
再打开Ano_Scheduler.c/.h,查看轮询任务调度是如何实现的。
先看每个任务的定义,看的时候你就想,这个Loop_Task_是多少ms执行一次,执行的什么。具体怎样控制周期的在Main_Task()里面,文末会讲到。
这部分看完有利于你对飞控有一个总体上的认识,而每个Loop_Task_里面的每个任务是如何进行的,我们以后再说。
废话不多说,看代码
void INT_1ms_Task()//该函数借助了icm的1ms中断来进行,即函数本身就是每1ms运行一次
{
//1ms任务Loop_Task_0()的判断位,Main_Task()函数里面判断是否执行Loop_Task_0()
lt0_run_flag ++;
//灯光驱动
LED_1ms_DRV();
//循环计数,这个逻辑很简单,但好像并没有调用什么。if(!circle_cnt[0])里面的东西被注释掉了,原来应该是每20ms执行某个任务一次。
circle_cnt[0] ++;
//20次循环
circle_cnt[0] %= CIRCLE_NUM;
if(!circle_cnt[0])
{
//
}
}
static void Loop_Task_0()//该任务1ms执行一次
{
/*传感器数据读取,包括陀螺仪,磁力计,气压计*/
Fc_Sensor_Get();
/*惯性传感器数据准备,其实是陀螺仪的数据初步处理*/
Sensor_Data_Prepare(1);
/*姿态解算更新,飞控里面最重要的东西,根据前一步读取的数据(陀螺仪、磁力计),解算出飞行器的状态*/
IMU_Update_Task(1);
/*获取WC_Z加速度,实际是一个简易的滤波,其计算部分在IMU_Update_Task()里*/
WCZ_Acc_Get_Task();
WCXY_Acc_Get_Task();
/*飞行状态任务,1.飞行状态设置。2.飞行控制,根据遥控(CH_N)、程控(program_ctrl)、和上位机控制(pc_user)整合设置期望速度,后期经过各种环控制,最终给到电机。注:CH_N(遥控摇杆的量)、program_ctrl(飞控板里的速度设置数据)、pc_user(上位机设置的速度数据),后期详细讲*/
Flight_State_Task(1,CH_N);
/*开关状态任务,判断各个传感器是否工作正常,若正常,标志位置位,若不正常,则复位*/
Swtich_State_Task(1);
/*光流融合数据准备任务,比赛时这部分看的不是很清楚,但后期我也会尽量解读*/
ANO_OF_Data_Prepare_Task(0.001f);
/*数传数据交换,其实是数传和u***数据发送,上位机上显示的各种数据就是在这发送过去的*/
ANO_DT_Data_Exchange();
}
static void Loop_Task_1(u32 dT_us) //2ms执行一次
{
/*姿态角速度环控制,用的pid控制,包括后面的角度环、高度环、z向速度环,原理都是根据Flight_State_Task()算出的期望速度,pid算出距离期望的偏差,然后整合到电机输出*/
Att_1level_Ctrl(2*1e-3f);
/*电机输出控制,这里是根据各种环控制的结果直接给到电调电机输出*/
Motor_Ctrl_Task(2);
}
static void Loop_Task_2(u32 dT_us) //6ms执行一次
{
float t2_dT_s;
t2_dT_s = (float)dT_us *1e-6f;
/*获取姿态角(ROLL PITCH YAW)*/
calculate_RPY();
/*姿态角度环控制,跟角速度环配合使用,双环控制,后期会讲*/
Att_2level_Ctrl(6e-3f,CH_N);
}
static void Loop_Task_5(u32 dT_us) //11ms执行一次
{
/*遥控器数据处理,里面有失控保护*/
RC_duty_task(11);
/*飞行模式设置任务,根据RC_duty_task()里面读到的数据,设置不同的飞行模式*/
Flight_Mode_Set(11);
/*高度数据融合任务,匿名里面的高度传感器为气压计加(激光/超声波)测距传感器,这个函数是将高度数据融合起来 */
WCZ_Fus_Task(11);
/*GPS电赛没用到,但是后期我会读代码的,可能稍微晚一点*/
GPS_Data_Processing_Task(11);
/*高度速度环控制,pid调节,类似角速度环*/
Alt_1level_Ctrl(11e-3f);
/*高度环控制,pid调节,类似于角度环*/
Alt_2level_Ctrl(11e-3f);
/*-光流数据有关,后期有时间会尽量讲……*/
AnoOF_DataAnl_Task(11)
/*灯光控制,有些重要参数你要随时知道他是什么状态的,所以用灯光来表示*/
LED_Task2(11);
}
static void Loop_Task_8(u32 dT_us) //20ms执行一次
{
/*罗盘数据处理任务*/
Mag_Update_Task(20);
/*程序指令控制,上位机发送的指令,飞控解析这些指令,然后*/
FlyCtrl_Task(20);
/*光流数据处理有关的任务*/
ANO_OFDF_Task(20);
/*-这个应该是UWB的处理函数,后期看看能不能读一下这部分代码*/
Ano_UWB_Data_Calcu_Task(20);
/*位置速度环控制,这个环控制相比程序上代码量更大,其实是因为不同的定位组合,xy方向的速度环控制也会不一样*/
Loc_1level_Ctrl(20,CH_N);
/*OPMV检测是否掉线,openmv是前几年电赛比过了,很多开源飞控会直接给出例题来,下面几个函数都是处理openmv的函数*/
OpenMV_Offline_Check(20);
/*OPMV色块追踪数据处理任务*/
ANO_CBTracking_Task(20);
/*OPMV寻线数据处理任务*/
ANO_LTracking_Task(20);
/*OPMV控制任务*/
ANO_OPMV_Ctrl_Task(20);
}
static void Loop_Task_9(u32 dT_us) //50ms执行一次
{
/*电压相关任务,读取电压,报警等*/
Power_UpdateTask(50);
//恒温控制(不能直接注释掉,否则开机过不了校准)
Thermostatic_Ctrl_Task(50);
/*延时存储任务*/
Ano_Parame_Write_task(50);
}
首先,在.h文件里面,定义了一个结构体,代表着每个循环任务的基本参数
typedef struct
{
void(*task_func)(u32 dT_us);//函数指针,有一个u32的输入参数
u32 interval_ticks;//每个任务运行的时间间隔,单位为微秒
u32 last_run;//最后一次运行的时间
}sched_task_t;
c文件里,定义了一个sched_task_t结构体的数组,每个数组的周期也有定义
//系统任务配置,创建不同执行频率的“线程”
static sched_task_t sched_tasks[] =
{
//任务n, 周期us, 上次时间us
{Loop_Task_1 , 2000, 0 },
//loop task为函数指针,指向对应的函数
{Loop_Task_2 , 6000, 0 },
{Loop_Task_5 , 11000, 0 },
{Loop_Task_8 , 20000, 0 },
{Loop_Task_9 , 50000, 0 },
};
TASK_NUM (sizeof(sched_tasks)/sizeof(sched_task_t))//线程的数量
最后,看一下主函数中提到的 Main_Task() 函数的定义
Main_Task()在主函数中循环执行
u8 Main_Task(void)
{
uint8_t index = 0;//Main_Task函数内循环次数标记,每次进都清零
//查询1ms任务是否需要执行,前面讲过,INT_1ms_Task()中每1ms就会加一置为,这就会运行Loop_Task_0(),然后复位
if(lt0_run_flag!=0)
{
lt0_run_flag--;
Loop_Task_0();
}
//循环判断其他所有线程任务,是否应该执行
uint32_t time_now,delta_time_us;
for(index=0;index < TASK_NUM;index++)
{
//获取系统当前时间,单位US
time_now = GetSysRunTimeUs();//SysTick_GetTick();
//注意,这里的循环判断用的函数指针(sched_task_t 结构体中定义的就是函数指针)
//进行判断,如果当前时间减去上一次执行的时间,大于等于该线程的执行周期,则执行线程
if(time_now - sched_tasks[index].last_run >= sched_tasks[index].interval_ticks)
{
delta_time_us = (u32)(time_now - sched_tasks[index].last_run);
//更新线程的执行时间,用于下一次判断
sched_tasks[index].last_run = time_now;
//执行线程函数,使用的是函数指针
sched_tasks[index].task_func(delta_time_us);
}
}
return 0;
}
看完Main_Task(),你应该理解,飞控是如何控制各个线程的频率的,也就是每一个任务,可以认为就是按照固定频率运行的
下面介绍一下匿名的记时是如何实现的,很多人看代码的时候常会看不懂记时操作。
我们再拿上面的一个线程举例,task1,我们查看sched_task_t sched_tasks[],可知它是2ms执行一次,我们把注意力放到Motor_Ctrl_Task(2)上
static void Loop_Task_1(u32 dT_us) //2ms执行一次
{
//Att_1level_Ctrl(2*1e-3f);
Motor_Ctrl_Task(2); //因为这个程序就是2ms执行一次,上次执行和这次执行中间就是隔2ms,所以给他输入参数2
//这个参数2其实代表着2ms,在这个函数内部,只要定义一个变量,每次执行时都加上这个2,这个变量其实就等于计时器
}
如果有错误,请指出
32版本和ti版本会有差距,但是差距不大。比如32线程命名用的频率,这个用的task几,大体都一样。今天看了一下32版本的,好像32更‘成熟’一点,但笔者电赛期间看的ti版本的,所以就不换了。
本篇介绍匿名源码(ti版)整体的逻辑顺序,主要解读飞控板的初始化与整体的任务调度,大部分为Ano_Scheduler.c/.h里面的代码,看完此篇,你会初步了解这款开源飞控的整体逻辑
main.c
首先打开main.c
int main(void)//主函数,飞控开机后循环执行while(1)里面的程序
{
Drv_BspInit();//飞控板初始化
flag.start_ok = 1;//初始化成功标志
while(1)//主循环,采用了实时系统常见的时钟驱动调度算法,用于周期任务。说白了就是给每一个循环执行的任务一个相应的频率
{
Main_Task();//轮询任务调度器
}
}
再打开Drv_Bsp.c,看Drv_BspInit()函数,可以看到,里面全都是各个小部分的初始化函数。初始化函数其实就是变量赋为 默认值/储存值,把控件设为默认状态,把硬件准备好
如读取数据(如上位机设置的一些参数)、参数赋值、器件初始化、波特率设置等等,这部分注释给的很清楚,所以就不贴代码了。
Ano_Scheduler.c/.h
再打开Ano_Scheduler.c/.h,查看轮询任务调度是如何实现的。
先看每个任务的定义,看的时候你就想,这个Loop_Task_是多少ms执行一次,执行的什么。具体怎样控制周期的在Main_Task()里面,文末会讲到。
这部分看完有利于你对飞控有一个总体上的认识,而每个Loop_Task_里面的每个任务是如何进行的,我们以后再说。
废话不多说,看代码
void INT_1ms_Task()//该函数借助了icm的1ms中断来进行,即函数本身就是每1ms运行一次
{
//1ms任务Loop_Task_0()的判断位,Main_Task()函数里面判断是否执行Loop_Task_0()
lt0_run_flag ++;
//灯光驱动
LED_1ms_DRV();
//循环计数,这个逻辑很简单,但好像并没有调用什么。if(!circle_cnt[0])里面的东西被注释掉了,原来应该是每20ms执行某个任务一次。
circle_cnt[0] ++;
//20次循环
circle_cnt[0] %= CIRCLE_NUM;
if(!circle_cnt[0])
{
//
}
}
static void Loop_Task_0()//该任务1ms执行一次
{
/*传感器数据读取,包括陀螺仪,磁力计,气压计*/
Fc_Sensor_Get();
/*惯性传感器数据准备,其实是陀螺仪的数据初步处理*/
Sensor_Data_Prepare(1);
/*姿态解算更新,飞控里面最重要的东西,根据前一步读取的数据(陀螺仪、磁力计),解算出飞行器的状态*/
IMU_Update_Task(1);
/*获取WC_Z加速度,实际是一个简易的滤波,其计算部分在IMU_Update_Task()里*/
WCZ_Acc_Get_Task();
WCXY_Acc_Get_Task();
/*飞行状态任务,1.飞行状态设置。2.飞行控制,根据遥控(CH_N)、程控(program_ctrl)、和上位机控制(pc_user)整合设置期望速度,后期经过各种环控制,最终给到电机。注:CH_N(遥控摇杆的量)、program_ctrl(飞控板里的速度设置数据)、pc_user(上位机设置的速度数据),后期详细讲*/
Flight_State_Task(1,CH_N);
/*开关状态任务,判断各个传感器是否工作正常,若正常,标志位置位,若不正常,则复位*/
Swtich_State_Task(1);
/*光流融合数据准备任务,比赛时这部分看的不是很清楚,但后期我也会尽量解读*/
ANO_OF_Data_Prepare_Task(0.001f);
/*数传数据交换,其实是数传和u***数据发送,上位机上显示的各种数据就是在这发送过去的*/
ANO_DT_Data_Exchange();
}
static void Loop_Task_1(u32 dT_us) //2ms执行一次
{
/*姿态角速度环控制,用的pid控制,包括后面的角度环、高度环、z向速度环,原理都是根据Flight_State_Task()算出的期望速度,pid算出距离期望的偏差,然后整合到电机输出*/
Att_1level_Ctrl(2*1e-3f);
/*电机输出控制,这里是根据各种环控制的结果直接给到电调电机输出*/
Motor_Ctrl_Task(2);
}
static void Loop_Task_2(u32 dT_us) //6ms执行一次
{
float t2_dT_s;
t2_dT_s = (float)dT_us *1e-6f;
/*获取姿态角(ROLL PITCH YAW)*/
calculate_RPY();
/*姿态角度环控制,跟角速度环配合使用,双环控制,后期会讲*/
Att_2level_Ctrl(6e-3f,CH_N);
}
static void Loop_Task_5(u32 dT_us) //11ms执行一次
{
/*遥控器数据处理,里面有失控保护*/
RC_duty_task(11);
/*飞行模式设置任务,根据RC_duty_task()里面读到的数据,设置不同的飞行模式*/
Flight_Mode_Set(11);
/*高度数据融合任务,匿名里面的高度传感器为气压计加(激光/超声波)测距传感器,这个函数是将高度数据融合起来 */
WCZ_Fus_Task(11);
/*GPS电赛没用到,但是后期我会读代码的,可能稍微晚一点*/
GPS_Data_Processing_Task(11);
/*高度速度环控制,pid调节,类似角速度环*/
Alt_1level_Ctrl(11e-3f);
/*高度环控制,pid调节,类似于角度环*/
Alt_2level_Ctrl(11e-3f);
/*-光流数据有关,后期有时间会尽量讲……*/
AnoOF_DataAnl_Task(11)
/*灯光控制,有些重要参数你要随时知道他是什么状态的,所以用灯光来表示*/
LED_Task2(11);
}
static void Loop_Task_8(u32 dT_us) //20ms执行一次
{
/*罗盘数据处理任务*/
Mag_Update_Task(20);
/*程序指令控制,上位机发送的指令,飞控解析这些指令,然后*/
FlyCtrl_Task(20);
/*光流数据处理有关的任务*/
ANO_OFDF_Task(20);
/*-这个应该是UWB的处理函数,后期看看能不能读一下这部分代码*/
Ano_UWB_Data_Calcu_Task(20);
/*位置速度环控制,这个环控制相比程序上代码量更大,其实是因为不同的定位组合,xy方向的速度环控制也会不一样*/
Loc_1level_Ctrl(20,CH_N);
/*OPMV检测是否掉线,openmv是前几年电赛比过了,很多开源飞控会直接给出例题来,下面几个函数都是处理openmv的函数*/
OpenMV_Offline_Check(20);
/*OPMV色块追踪数据处理任务*/
ANO_CBTracking_Task(20);
/*OPMV寻线数据处理任务*/
ANO_LTracking_Task(20);
/*OPMV控制任务*/
ANO_OPMV_Ctrl_Task(20);
}
static void Loop_Task_9(u32 dT_us) //50ms执行一次
{
/*电压相关任务,读取电压,报警等*/
Power_UpdateTask(50);
//恒温控制(不能直接注释掉,否则开机过不了校准)
Thermostatic_Ctrl_Task(50);
/*延时存储任务*/
Ano_Parame_Write_task(50);
}
首先,在.h文件里面,定义了一个结构体,代表着每个循环任务的基本参数
typedef struct
{
void(*task_func)(u32 dT_us);//函数指针,有一个u32的输入参数
u32 interval_ticks;//每个任务运行的时间间隔,单位为微秒
u32 last_run;//最后一次运行的时间
}sched_task_t;
c文件里,定义了一个sched_task_t结构体的数组,每个数组的周期也有定义
//系统任务配置,创建不同执行频率的“线程”
static sched_task_t sched_tasks[] =
{
//任务n, 周期us, 上次时间us
{Loop_Task_1 , 2000, 0 },
//loop task为函数指针,指向对应的函数
{Loop_Task_2 , 6000, 0 },
{Loop_Task_5 , 11000, 0 },
{Loop_Task_8 , 20000, 0 },
{Loop_Task_9 , 50000, 0 },
};
TASK_NUM (sizeof(sched_tasks)/sizeof(sched_task_t))//线程的数量
最后,看一下主函数中提到的 Main_Task() 函数的定义
Main_Task()在主函数中循环执行
u8 Main_Task(void)
{
uint8_t index = 0;//Main_Task函数内循环次数标记,每次进都清零
//查询1ms任务是否需要执行,前面讲过,INT_1ms_Task()中每1ms就会加一置为,这就会运行Loop_Task_0(),然后复位
if(lt0_run_flag!=0)
{
lt0_run_flag--;
Loop_Task_0();
}
//循环判断其他所有线程任务,是否应该执行
uint32_t time_now,delta_time_us;
for(index=0;index < TASK_NUM;index++)
{
//获取系统当前时间,单位US
time_now = GetSysRunTimeUs();//SysTick_GetTick();
//注意,这里的循环判断用的函数指针(sched_task_t 结构体中定义的就是函数指针)
//进行判断,如果当前时间减去上一次执行的时间,大于等于该线程的执行周期,则执行线程
if(time_now - sched_tasks[index].last_run >= sched_tasks[index].interval_ticks)
{
delta_time_us = (u32)(time_now - sched_tasks[index].last_run);
//更新线程的执行时间,用于下一次判断
sched_tasks[index].last_run = time_now;
//执行线程函数,使用的是函数指针
sched_tasks[index].task_func(delta_time_us);
}
}
return 0;
}
看完Main_Task(),你应该理解,飞控是如何控制各个线程的频率的,也就是每一个任务,可以认为就是按照固定频率运行的
下面介绍一下匿名的记时是如何实现的,很多人看代码的时候常会看不懂记时操作。
我们再拿上面的一个线程举例,task1,我们查看sched_task_t sched_tasks[],可知它是2ms执行一次,我们把注意力放到Motor_Ctrl_Task(2)上
static void Loop_Task_1(u32 dT_us) //2ms执行一次
{
//Att_1level_Ctrl(2*1e-3f);
Motor_Ctrl_Task(2); //因为这个程序就是2ms执行一次,上次执行和这次执行中间就是隔2ms,所以给他输入参数2
//这个参数2其实代表着2ms,在这个函数内部,只要定义一个变量,每次执行时都加上这个2,这个变量其实就等于计时器
}
如果有错误,请指出
32版本和ti版本会有差距,但是差距不大。比如32线程命名用的频率,这个用的task几,大体都一样。今天看了一下32版本的,好像32更‘成熟’一点,但笔者电赛期间看的ti版本的,所以就不换了。
举报