BetaFlight飞控启动&运行过程简介

1. 源由

BetaFlight经过工程结构、代码框架、传感模块框架、统一硬件配置文件这一路的研读,让我们对BetaFlight飞控系统更多的了解。

逐步领悟到结构化设计的优势的同时,为了更好的理解整体系统如何融合在一起,我们将会进入本章BetaFlight飞控启动和运行过程,这也是SOC系统初始化的主轴。

2. 启动过程

作为C语言级别启动过程的入口,相信大家都很容易就想到了Linux应用程序之Helloworld入门

因此,我们这里就是从main入口开始分析的,详见下面代码走读。

2.1 main(主程序)

不错,C的入口就是main程序,而BetaFlight是用C语言开发的一款飞控项目,其入口当然亦是如此,详见:betaflight\src\main\main.c

整体上分为两部分:初始化和运行。

main
 ├──> init
 └──> run

注:飞控基本上电池拔掉就好了,没有复杂的去初始化过程。这也体现了航模的专属特性 _

2.2 init (初始化)

整个初始化流程是比较长的,所以看这个初始化流程真的比较辛苦,但是从流程的角度来说,注意以下几点:

  1. 初始化步骤逐一自上而下执行;
  2. 初始化可能存在硬件初始化和应用初始化;
  3. 应用对应的硬件初始化应早于应用执行初始化;
  4. 应用之前有耦合的需要根据依赖关系初始化;

笔者阅读代码时,整个函数长度 1000 - 258 = 742 (代码行,含空行),非常可怕的一个函数。

注:如果能够进行归纳,整理,进行应用功能块区分就好了,可惜目前代码尚没有做到这点。

init
 ├──> <SERIAL_PORT_COUNT> printfSerialInit
 ├──> systemInit
 ├──> tasksInitData
 ├──> IOInitGlobal
 ├──> <USE_HARDWARE_REVISION_DETECTION> detectHardwareRevision
 ├──> <USE_TARGET_CONFIG> targetConfiguration
 ├──> pgResetAll
 ├──> <USE_SDCARD_SPI> configureSPIBusses();  initFlags |= SPI_BUSSES_INIT_ATTEMPTED;
 ├──> sdCardAndFSInit; initFlags |= SD_INIT_ATTEMPTED;
 ├──> <!sdcard_isInserted()> failureMode(FAILURE_SDCARD_REQUIRED)
 ├──> [SD Card FS check] //while (afatfs_getFilesystemState() != AFATFS_FILESYSTEM_STATE_READY)
 │   ├──> afatfs_poll()
 │   └──> <afatfs_getFilesystemState() == AFATFS_FILESYSTEM_STATE_FATAL> failureMode(FAILURE_SDCARD_INITIALISATION_FAILED)
 ├──> <CONFIG_IN_EXTERNAL_FLASH> || <CONFIG_IN_MEMORY_MAPPED_FLASH)>
 │   ├──> pgResetAll()
 │   ├──> <CONFIG_IN_EXTERNAL_FLASH> configureSPIBusses(); initFlags |= SPI_BUSSES_INIT_ATTEMPTED;
 │   ├──> configureQuadSPIBusses();configureOctoSPIBusses();initFlags |= QUAD_OCTO_SPI_BUSSES_INIT_ATTEMPTED;
 │   ├──> bool haveFlash = flashInit(flashConfig());
 │   ├──> <!haveFlash>failureMode(FAILURE_EXTERNAL_FLASH_INIT_FAILED)
 │   └──> initFlags |= FLASH_INIT_ATTEMPTED
 ├──> initEEPROM
 ├──> ensureEEPROMStructureIsValid
 ├──> bool readSuccess = readEEPROM()
 ├──> <USE_BOARD_INFO> initBoardInformation
 ├──> <!readSuccess || !isEEPROMVersionValid() || strncasecmp(systemConfig()->boardIdentifier, TARGET_BOARD_IDENTIFIER, sizeof(TARGET_BOARD_IDENTIFIER))> resetEEPROM()
 ├──> systemState |= SYSTEM_STATE_CONFIG_LOADED
 ├──> <USE_DEBUG_PIN> dbgPinInit
 ├──> debugMode = systemConfig()->debug_mode
 ├──> <TARGET_PREINIT> targetPreInit
 ├──> <!defined(USE_VIRTUAL_LED)> ledInit(statusLedConfig())
 ├──> <!defined(SIMULATOR_BUILD)> EXTIInit
 ├──> <USE_BUTTONS>
 │   ├──> buttonsInit
 │   └──> <EEPROM_RESET_PRECONDITION && defined(BUTTON_A_PIN) && defined(BUTTON_B_PIN)>  //#define EEPROM_RESET_PRECONDITION (!isMPUSoftReset())
 │       └──> resetEEPROM/systemReset
 ├──> <defined(STM32F4) || defined(STM32G4)> // F4 has non-8MHz boards, G4 for Betaflight allow 24 or 27MHz oscillator
 │   └──> systemClockSetHSEValue(systemConfig()->hseMhz * 1000000U)
 ├──> <USE_OVERCLOCK> OverclockRebootIfNecessary(systemConfig()->cpu_overclock)
 ├──> <USE_MCO>
 │   ├──> <defined(STM32F4) || defined(STM32F7)>
 │   │   └──> mcoConfigure(MCODEV_2, mcoConfig(MCODEV_2));
 │   └──> <defined(STM32G4)>
 │       └──> mcoConfigure(MCODEV_1, mcoConfig(MCODEV_1));
 ├──> <USE_TIMER> timerInit
 ├──> <BUS_SWITCH_PIN> busSwitchInit
 ├──> <defined(USE_UART) && !defined(SIMULATOR_BUILD)> uartPinConfigure(serialPinConfig())
 ├──> [serialInit]
 │   ├──> <AVOID_UART1_FOR_PWM_PPM> serialInit(featureIsEnabled(FEATURE_SOFTSERIAL), featureIsEnabled(FEATURE_RX_PPM) || featureIsEnabled(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART1 : SERIAL_PORT_NONE);
 │   ├──> <AVOID_UART2_FOR_PWM_PPM> serialInit(featureIsEnabled(FEATURE_SOFTSERIAL), featureIsEnabled(FEATURE_RX_PPM) || featureIsEnabled(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART2 : SERIAL_PORT_NONE);
 │   ├──> <AVOID_UART3_FOR_PWM_PPM> serialInit(featureIsEnabled(FEATURE_SOFTSERIAL), featureIsEnabled(FEATURE_RX_PPM) || featureIsEnabled(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART3 : SERIAL_PORT_NONE);
 │   └──> <else> serialInit(featureIsEnabled(FEATURE_SOFTSERIAL), SERIAL_PORT_NONE)
 ├──> mixerInit(mixerConfig()->mixerMode)
 ├──> uint16_t idlePulse = motorConfig()->mincommand
 ├──> <featureIsEnabled(FEATURE_3D)> idlePulse = flight3DConfig()->neutral3d
 ├──> <motorConfig()->dev.motorPwmProtocol == PWM_TYPE_BRUSHED> idlePulse = 0; // brushed motors
 ├──> <USE_MOTOR> motorDevInit(&motorConfig()->dev, idlePulse, getMotorCount()); systemState |= SYSTEM_STATE_MOTORS_READY
 ├──> <USE_RX_PPM> <featureIsEnabled(FEATURE_RX_PARALLEL_PWM)> pwmRxInit(pwmConfig())
 ├──> <USE_BEEPER> beeperInit(beeperDevConfig())
 ├──> <defined(USE_INVERTER) && !defined(SIMULATOR_BUILD)> initInverters(serialPinConfig())
 ├──> [Hardware Bus Initialization]
 │   ├──> <TARGET_BUS_INIT> targetBusInit()
 │   └──> <else> 
 │       ├──> <!(initFlags & SPI_BUSSES_INIT_ATTEMPTED)> configureSPIBusses();initFlags |= SPI_BUSSES_INIT_ATTEMPTED;
 │       ├──> <!(initFlags & QUAD_OCTO_SPI_BUSSES_INIT_ATTEMPTED)> configureQuadSPIBusses();configureOctoSPIBusses();initFlags |= QUAD_OCTO_SPI_BUSSES_INIT_ATTEMPTED;
 │       ├──> <defined(USE_SDCARD_SDIO) && !defined(CONFIG_IN_SDCARD) && defined(STM32H7)> sdioPinConfigure(); SDIO_GPIO_Init();
 │       ├──> <USE_USB_MSC>
 │       │   ├──> mscInit()
 │       │   └──> <USE_SDCARD> <blackboxConfig()->device == BLACKBOX_DEVICE_SDCARD> <sdcardConfig()->mode> <!(initFlags & SD_INIT_ATTEMPTED)> sdCardAndFSInit();initFlags |= SD_INIT_ATTEMPTED;
 │       ├──> <USE_FLASHFS> <blackboxConfig()->device == BLACKBOX_DEVICE_FLASH> emfat_init_files
 │       ├──> <USE_SPI> spiInitBusDMA
 │       ├──> <mscStart() == 0> mscWaitForButton();
 │       ├──> <mscStart() != 0> systemResetFromMsc()
 │       ├──> <USE_PERSISTENT_MSC_RTC>
 │       │   ├──> persistentObjectWrite(PERSISTENT_OBJECT_RTC_HIGH, 0);
 │       │   └──> persistentObjectWrite(PERSISTENT_OBJECT_RTC_LOW, 0);
 │       └──> <USE_I2C>
 │           ├──> i2cHardwareConfigure(i2cConfig(0));
 │           ├──> <USE_I2C_DEVICE_1> i2cInit(I2CDEV_1);
 │           ├──> <USE_I2C_DEVICE_2> i2cInit(I2CDEV_2);
 │           ├──> <USE_I2C_DEVICE_3> i2cInit(I2CDEV_3);
 │           └──> <USE_I2C_DEVICE_4> i2cInit(I2CDEV_4);
 ├──> <USE_HARDWARE_REVISION_DETECTION> updateHardwareRevision     
 ├──> <USE_VTX_RTC6705> bool useRTC6705 = rtc6705IOInit(vtxIOConfig());
 ├──> <USE_CAMERA_CONTROL> cameraControlInit();
 ├──> <USE_ADC> adcInit(adcConfig());
 ├──> initBoardAlignment(boardAlignment());
 ├──> <!sensorsAutodetect()>
 │   ├──> <isSystemConfigured()>
 │   │   └──> indicateFailure(FAILURE_MISSING_ACC, 2);
 │   └──> setArmingDisabled(ARMING_DISABLED_NO_GYRO);
 ├──> systemState |= SYSTEM_STATE_SENSORS_READY;
 ├──> gyroSetTargetLooptime(pidConfig()->pid_process_denom); // Set the targetLooptime based on the detected gyro sampleRateHz and pid_process_denom
 ├──> validateAndFixGyroConfig();
 ├──> gyroSetTargetLooptime(pidConfig()->pid_process_denom); // Now reset the targetLooptime as it's possible for the validation to change the pid_process_denom
 ├──> gyroInitFilters();
 ├──> pidInit(currentPidProfile);
 ├──> mixerInitProfile();
 ├──> <USE_PID_AUDIO> pidAudioInit();
 ├──> <USE_SERVOS>
 │   ├──> servosInit();
 │   ├──> <isMixerUsingServos()> servoDevInit(&servoConfig()->dev) //pwm_params.useChannelForwarding = featureIsEnabled(FEATURE_CHANNEL_FORWARDING);
 │   └──> servosFilterInit();
 ├──> <USE_PINIO> pinioInit(pinioConfig());
 ├──> <USE_PIN_PULL_UP_DOWN> pinPullupPulldownInit();
 ├──> <USE_PINIOBOX> pinioBoxInit(pinioBoxConfig());
 ├──> [LED Oprations]
 ├──> imuInit();
 ├──> failsafeInit();
 ├──> rxInit();
 ├──> <USE_GPS> <featureIsEnabled(FEATURE_GPS)>
 │   ├──> gpsInit();
 │   └──> <USE_GPS_RESCUE> gpsRescueInit();
 ├──> <USE_LED_STRIP>
 │   ├──> ledStripInit();
 │   └──> <featureIsEnabled(FEATURE_LED_STRIP)> ledStripEnable();
 ├──> <USE_ESC_SENSOR> <featureIsEnabled(FEATURE_ESC_SENSOR)> escSensorInit();
 ├──> <USE_USB_DETECT> usbCableDetectInit();
 ├──> <USE_TRANSPONDER> <featureIsEnabled(FEATURE_TRANSPONDER)>
 │   ├──> transponderInit();
 │   ├──> transponderStartRepeating();
 │   └──> systemState |= SYSTEM_STATE_TRANSPONDER_ENABLED;
 ├──> <USE_FLASH_CHIP> <!(initFlags & FLASH_INIT_ATTEMPTED)>
 │   └──> flashInit(flashConfig());initFlags |= FLASH_INIT_ATTEMPTED;
 ├──> <USE_FLASHFS> flashfsInit();
 ├──> <USE_SDCARD> <dcardConfig()->mode> <!(initFlags & SD_INIT_ATTEMPTED)>
 │   └──> sdCardAndFSInit();initFlags |= SD_INIT_ATTEMPTED;
 ├──> <USE_BLACKBOX> blackboxInit();
 ├──> <USE_ACC> <mixerConfig()->mixerMode == MIXER_GIMBAL> accStartCalibration();
 ├──> gyroStartCalibration(false);
 ├──> <USE_BARO> baroStartCalibration();
 ├──> positionInit();
 ├──> <defined(USE_VTX_COMMON) || defined(USE_VTX_CONTROL)> vtxTableInit();
 ├──> <USE_VTX_CONTROL> 
 │   ├──> vtxControlInit();
 │   ├──> <USE_VTX_COMMON> vtxCommonInit();
 │   ├──> <USE_VTX_MSP> vtxMspInit();
 │   ├──> <USE_VTX_SMARTAUDIO> vtxSmartAudioInit();
 │   ├──> <USE_VTX_TRAMP> vtxTrampInit();
 │   └──> <USE_VTX_RTC6705> <!vtxCommonDevice() && useRTC6705> vtxRTC6705Init();
 ├──> <USE_TIMER> timerStart();
 ├──> batteryInit(); // always needs doing, regardless of features.
 ├──> <USE_RCDEVICE> rcdeviceInit();
 ├──> <USE_PERSISTENT_STATS> statsInit();
 ├──> [Initialize MSP]
 │   ├──> mspInit();
 │   └──> mspSerialInit();
 ├──> <USE_CMS> cmsInit();
 ├──> <defined(USE_OSD) || (defined(USE_MSP_DISPLAYPORT) && defined(USE_CMS))> displayPort_t *osdDisplayPort = NULL;
 ├──> <USE_OSD>
 │   ├──> osdDisplayPortDevice_e osdDisplayPortDevice = OSD_DISPLAYPORT_DEVICE_NONE;
 │   └──> <featureIsEnabled(FEATURE_OSD)>
 │       ├──> osdDisplayPortDevice_e device = osdConfig()->displayPortDevice;
 │       ├──> <case OSD_DISPLAYPORT_DEVICE_AUTO:> FALLTHROUGH;
 │       ├──> <case OSD_DISPLAYPORT_DEVICE_FRSKYOSD:>
 │       │   ├──> osdDisplayPort = frskyOsdDisplayPortInit(vcdProfile()->video_system);
 │       │   └──> <osdDisplayPort || device == OSD_DISPLAYPORT_DEVICE_FRSKYOSD>  osdDisplayPortDevice = OSD_DISPLAYPORT_DEVICE_FRSKYOSD; break;
 │       ├──> <case OSD_DISPLAYPORT_DEVICE_MAX7456:>
 │       │   └──> <max7456DisplayPortInit(vcdProfile(), &osdDisplayPort) || device == OSD_DISPLAYPORT_DEVICE_MAX7456> osdDisplayPortDevice = OSD_DISPLAYPORT_DEVICE_MAX7456;break;
 │       ├──> <case OSD_DISPLAYPORT_DEVICE_MSP:>
 │       │   ├──> osdDisplayPort = displayPortMspInit();
 │       │   └──> <osdDisplayPort || device == OSD_DISPLAYPORT_DEVICE_MSP> osdDisplayPortDevice = OSD_DISPLAYPORT_DEVICE_MSP; break;
 │       ├──> <case OSD_DISPLAYPORT_DEVICE_NONE:) default:
 │       ├──> osdInit(osdDisplayPort, osdDisplayPortDevice);
 │       └──> <osdDisplayPortDevice == OSD_DISPLAYPORT_DEVICE_NONE> featureDisableImmediate(FEATURE_OSD);
 ├──> <defined(USE_CMS) && defined(USE_MSP_DISPLAYPORT)> <!osdDisplayPort> cmsDisplayPortRegister(displayPortMspInit());
 ├──> <USE_DASHBOARD> <featureIsEnabled(FEATURE_DASHBOARD)>
 │   ├──> dashboardInit();
 │   ├──> <USE_OLED_GPS_DEBUG_PAGE_ONLY> dashboardShowFixedPage(PAGE_GPS);
 │   └──> <!USE_OLED_GPS_DEBUG_PAGE_ONLY> dashboardResetPageCycling();dashboardEnablePageCycling();
 ├──> <USE_TELEMETRY> <featureIsEnabled(FEATURE_TELEMETRY)> telemetryInit();
 ├──> setArmingDisabled(ARMING_DISABLED_BOOT_GRACE_TIME);
 ├──> <defined(USE_SPI) && defined(USE_SPI_DMA_ENABLE_EARLY)> spiInitBusDMA();
 ├──> <USE_MOTOR> 
 │   ├──> motorPostInit();
 │   └──> motorEnable();
 ├──> <defined(USE_SPI) && defined(USE_SPI_DMA_ENABLE_LATE) && !defined(USE_SPI_DMA_ENABLE_EARLY)>
 │   └──> spiInitBusDMA();
 ├──> debugInit();
 ├──> unusedPinsInit();
 ├──> tasksInit();
 └──> systemState |= SYSTEM_STATE_READY;

2.3 run

初始化完成以后,我们来理解run运行的过程,它主要是一个BetaFlight自研的一个任务调度。

注:这个任务调度不会再任务运行过程中途被打断,与通常OS系统所描述的任务是不一样的。

run
 └──> loop: scheduler()

通俗点的理解:

可以认为BetaFlight是在一个bare-metal loop的基础上增加了对业务过程耗时统计+基于过程时间优先级调度的一个算法逻辑scheduler。

注:后面我们会重点针对BetaFlight自研的调度器进行研读和介绍。

3. 任务调度

系统启动后,接下来最为核心的就是任务调度。作为飞控自研的调度器,其BetaFlight设计有以下特点:

  1. 历史遗留问题:从性价比,开发历程等方面来思考,也许不难想象,为什么现在是一个基于bare-metal的一个自研任务调度器。
  2. 业务强耦合:鉴于IMU和PID业务对于飞行器飞行来说至关重要,因此该调度器在Gyro/Acc/PID的任务调用采用了精准时刻调度(+/-0.1us)。
  3. 任务优先级:MCU性能和业务逻辑复杂度,在至关重要任务调度之后剩余的时间片可能存在资源不够导致任务“饿死”得不到调度的情况。
  4. 边缘弹性任务时间优化:有限资源 + 非充分测试 + 资源可体感设计(OSD/CPU占用率等)

3.1 任务定义

这个结构体是一个优先级和任务配置的相关结构。当然因为BetaFlight自研调度器与飞控应用高度耦合(强耦合),这只是调度的一部分内容。

typedef struct {
    // Task static data
    task_attribute_t *attribute;

    // Scheduling
    uint16_t dynamicPriority;           // measurement of how old task was last executed, used to avoid task starvation
    uint16_t taskAgePeriods;
    timeDelta_t taskLatestDeltaTimeUs;
    timeUs_t lastExecutedAtUs;          // last time of invocation
    timeUs_t lastSignaledAtUs;          // time of invocation event for event-driven tasks
    timeUs_t lastDesiredAt;             // time of last desired execution

    // Statistics
    float    movingAverageCycleTimeUs;
    timeUs_t anticipatedExecutionTime;  // Fixed point expectation of next execution time
    timeUs_t movingSumDeltaTime10thUs;  // moving sum over 64 samples
    timeUs_t movingSumExecutionTime10thUs;
    timeUs_t maxExecutionTimeUs;
    timeUs_t totalExecutionTimeUs;      // total time consumed by task since boot
    timeUs_t lastStatsAtUs;             // time of last stats gathering for rate calculation
#if defined(USE_LATE_TASK_STATISTICS)
    uint32_t runCount;
    uint32_t lateCount;
    timeUs_t execTime;
#endif
} task_t;

3.2 scheduler (调度器)

这就是大名鼎鼎的BetaFlight任务调度器。这里对调度算法进行了认真的研读。

scheduler
 ├──> <gyroEnabled>
 │   ├──> [Realtime gyro/filtering/PID tasks get complete priority]
 │   │   ├──> task_t *gyroTask = getTask(TASK_GYRO)
 │   │   ├──> nowCycles = getCycleCounter()
 │   │   ├──> nextTargetCycles = lastTargetCycles + desiredPeriodCycles
 │   │   └──> schedLoopRemainingCycles = cmpTimeCycles(nextTargetCycles, nowCycles)

 │   │ ################################################################################
 │   │ # Rootcause: USB VCP Data Transfer
 │   │ ################################################################################
 │   ├──> <schedLoopRemainingCycles < -desiredPeriodCycles>  //错过了一个desiredPeriodCycles周期,导致剩余时间负值(且大于一个运行周期)
 │   │   ├──> nextTargetCycles += desiredPeriodCycles * (1 + (schedLoopRemainingCycles / -desiredPeriodCycles))  //常见USB配置工具连接的时候,尽力挽救scheduler算法
 │   │   └──> schedLoopRemainingCycles = cmpTimeCycles(nextTargetCycles, nowCycles)

 │   │ ################################################################################
 │   │ # schedLoopStartMinCycles range rebound
 │   │ ################################################################################
 │   ├──> <(schedLoopRemainingCycles < schedLoopStartMinCycles) && (schedLoopStartCycles < schedLoopStartMaxCycles)>
 │   │   └──> schedLoopStartCycles += schedLoopStartDeltaUpCycles
 │   └──> <schedLoopRemainingCycles < schedLoopStartCycles>
 │       ├──> <schedLoopStartCycles > schedLoopStartMinCycles>
 │       │   └──> schedLoopStartCycles -= schedLoopStartDeltaDownCycles
 
 │       │ ################################################################################
 │       │ # Polling for gyro data
 │       │ ################################################################################
 │       ├──> <while (schedLoopRemainingCycles > 0)> 
 │       │   ├──> nowCycles = getCycleCounter();
 │       │   └──> schedLoopRemainingCycles = cmpTimeCycles(nextTargetCycles, nowCycles);

 │       │ ################################################################################
 │       │ # Execute gyro/filter/pid tasks and check data avalibility in rc link
 │       │ ################################################################################
 │       ├──> currentTimeUs = micros()
 │       ├──> taskExecutionTimeUs += schedulerExecuteTask(gyroTask, currentTimeUs)
 │       ├──> <gyroFilterReady()> taskExecutionTimeUs += schedulerExecuteTask(getTask(TASK_FILTER), currentTimeUs)
 │       ├──> <pidLoopReady()> taskExecutionTimeUs += schedulerExecuteTask(getTask(TASK_PID), currentTimeUs)
 │       ├──> rxFrameCheck(currentTimeUs, cmpTimeUs(currentTimeUs, getTask(TASK_RX)->lastExecutedAtUs))  //检查是否有新的RC控制链路数据包收到
 │       ├──> <cmp32(millis(), lastFailsafeCheckMs) > PERIOD_RXDATA_FAILURE> //核查、更新failsafe状态
 │       ├──> lastTargetCycles = nextTargetCycles
 │       ├──> gyroDev_t *gyro = gyroActiveDev() //获取活跃的gyro设备
 
 │       │ ################################################################################
 │       │ # Exact gyro time sync, using GYRO_RATE_COUNT/GYRO_LOCK_COUNT
 │       │ ################################################################################
 │       └──> [Sync scheduler into lock with gyro] // gyro->gyroModeSPI != GYRO_EXTI_NO_INT, 这里指数级收敛,只要desiredPeriodCycles越精准,理论精度会越高
 │           ├──> [Calculate desiredPeriodCycles = sampleCycles / GYRO_RATE_COUNT and reset terminalGyroRateCount += GYRO_RATE_COUNT]
 │           └──> [Sync lastTargetCycles using exponential normalization by GYRO_RATE_COUNT/GYRO_LOCK_COUNT times iteration]
 ├──> nowCycles = getCycleCounter();schedLoopRemainingCycles = cmpTimeCycles(nextTargetCycles, nowCycles);
 ├──> <!gyroEnabled || (schedLoopRemainingCycles > (int32_t)clockMicrosToCycles(CHECK_GUARD_MARGIN_US))>
 │   │ ################################################################################
 │   │ # Find task need to be execute when there is time.
 │   │ ################################################################################
 │   ├──> currentTimeUs = micros()
 │   ├──> for (task_t *task = queueFirst(); task != NULL; task = queueNext()) <task->attribute->staticPriority != TASK_PRIORITY_REALTIME> //Update task dynamic priorities
 │   │   ├──> <task->attribute->checkFunc> //有属性检查函数
 │   │   │   ├──> <task->dynamicPriority > 0>
 │   │   │   │   ├──> task->taskAgePeriods = 1 + (cmpTimeUs(currentTimeUs, task->lastSignaledAtUs) / task->attribute->desiredPeriodUs);
 │   │   │   │   └──> task->dynamicPriority = 1 + task->attribute->staticPriority * task->taskAgePeriods;
 │   │   │   ├──> <task->attribute->checkFunc(currentTimeUs, cmpTimeUs(currentTimeUs, task->lastExecutedAtUs))>
 │   │   │   │   ├──> const uint32_t checkFuncExecutionTimeUs = cmpTimeUs(micros(), currentTimeUs);
 │   │   │   │   ├──> checkFuncMovingSumExecutionTimeUs += checkFuncExecutionTimeUs - checkFuncMovingSumExecutionTimeUs / TASK_STATS_MOVING_SUM_COUNT;
 │   │   │   │   ├──> checkFuncMovingSumDeltaTimeUs += task->taskLatestDeltaTimeUs - checkFuncMovingSumDeltaTimeUs / TASK_STATS_MOVING_SUM_COUNT;
 │   │   │   │   ├──> checkFuncTotalExecutionTimeUs += checkFuncExecutionTimeUs;   // time consumed by scheduler + task
 │   │   │   │   ├──> checkFuncMaxExecutionTimeUs = MAX(checkFuncMaxExecutionTimeUs, checkFuncExecutionTimeUs)
 │   │   │   │   ├──> task->lastSignaledAtUs = currentTimeUs
 │   │   │   │   ├──> task->taskAgePeriods = 1
 │   │   │   │   └──> task->dynamicPriority = 1 + task->attribute->staticPriority
 │   │   │   └──> <else>
 │   │   │       └──> task->taskAgePeriods = 0
 │   │   ├──> <!task->attribute->checkFunc> //无属性检查函数
 │   │   │   ├──> task->taskAgePeriods = (cmpTimeUs(currentTimeUs, task->lastExecutedAtUs) / task->attribute->desiredPeriodUs)
 │   │   │   └──> <task->taskAgePeriods > 0>
 │   │   │       └──> task->dynamicPriority = 1 + task->attribute->staticPriority * task->taskAgePeriods
 │   │   └──> <task->dynamicPriority > selectedTaskDynamicPriority>
 │   │       ├──> timeDelta_t taskRequiredTimeUs = task->anticipatedExecutionTime >> TASK_EXEC_TIME_SHIFT
 │   │       ├──> int32_t taskRequiredTimeCycles = (int32_t)clockMicrosToCycles((uint32_t)taskRequiredTimeUs)
 │   │       ├──> taskRequiredTimeCycles += checkCycles + taskGuardCycles //增加守护时间(预留一些)
 │   │       └──> <taskRequiredTimeCycles < schedLoopRemainingCycles> ||  //剩余时间足够执行任务
 │   │            <(scheduleCount & SCHED_TASK_DEFER_MASK) == 0> ||  //???? 这里还不太清楚什么情况?
 │   │            <(task - tasks) == TASK_SERIAL)>  //串行任务不阻塞
 │   │           ├──> selectedTaskDynamicPriority = task->dynamicPriority;
 │   │           └──> selectedTask = task;  //选中任务
 
 │   │ ################################################################################
 │   │ # Select task execution
 │   │ ################################################################################
 │   ├──> checkCycles = cmpTimeCycles(getCycleCounter(), nowCycles) //优先级调整,以及checkFunc运行需要计算耗时时间
 │   └──> <selectedTask>
 │       ├──> timeDelta_t taskRequiredTimeUs = selectedTask->anticipatedExecutionTime >> TASK_EXEC_TIME_SHIFT  // Recheck the available time as checkCycles is only approximate
 │       ├──> int32_t taskRequiredTimeCycles = (int32_t)clockMicrosToCycles((uint32_t)taskRequiredTimeUs)
 │       ├──> nowCycles = getCycleCounter()
 │       ├──> schedLoopRemainingCycles = cmpTimeCycles(nextTargetCycles, nowCycles)
 │       ├──> <!gyroEnabled || (taskRequiredTimeCycles < schedLoopRemainingCycles)>
 │       │   ├──> uint32_t antipatedEndCycles = nowCycles + taskRequiredTimeCycles;
 │       │   ├──> taskExecutionTimeUs += schedulerExecuteTask(selectedTask, currentTimeUs);
 │       │   ├──> nowCycles = getCycleCounter();
 │       │   ├──> int32_t cyclesOverdue = cmpTimeCycles(nowCycles, antipatedEndCycles);
 │       │   ├──> <(currentTask - tasks) == TASK_RX>
 │       │   │   └──> skippedRxAttempts = 0
 │       │   ├──> <(currentTask - tasks) == TASK_OSD>
 │       │   │   └──> skippedOSDAttempts = 0
 │       │   ├──> <(cyclesOverdue > 0) || (-cyclesOverdue < taskGuardMinCycles)> //超时,但可控在taskGuardMinCycles范围之内
 │       │   │   └──> <taskGuardCycles < taskGuardMaxCycles>
 │       │   │       └──> taskGuardCycles += taskGuardDeltaUpCycles //增加守护时间(预留更多一些)
 │       │   └──> <else if (taskGuardCycles > taskGuardMinCycles> //未超时
 │       │           └──> taskGuardCycles -= taskGuardDeltaDownCycles; //减少守护时间

 │       │ ################################################################################
 │       │ # Special task handling
 │       │ ################################################################################
 │       └──> <else <selectedTask->taskAgePeriods > TASK_AGE_EXPEDITE_COUNT>) ||
 │            <((selectedTask - tasks) == TASK_OSD) && (TASK_AGE_EXPEDITE_OSD != 0) && (++skippedOSDAttempts > TASK_AGE_EXPEDITE_OSD)> ||
 │            <((selectedTask - tasks) == TASK_RX) && (TASK_AGE_EXPEDITE_RX != 0) && (++skippedRxAttempts > TASK_AGE_EXPEDITE_RX)>
 │               └──> selectedTask->anticipatedExecutionTime *= TASK_AGE_EXPEDITE_SCALE
 └──> scheduleCount++;

注:这里讨论的是不包含UNIT_TEST和USE_LATE_TASK_STATISTICS的代码。

4. 总结

从当前最新4.4.x版本代码上看:

  1. BetaFlight整体代码可以分为两部分:初始化(init)和运行时(run)
  2. 应用功能代码已经通过宏定义,支持可剪裁编译;
  3. 整个调度器要了解存在一些背景知识需要澄清和讨论(已经在附录中整理,并正在与开发团队讨论中。。。。);

5. 参考资料

【1】BetaFlight开源工程结构简明介绍
【2】BetaFlight开源代码框架简介
【3】BetaFlight深入传感设计:传感模块设计框架
【4】BetaFlight统一硬件配置文件研读

6. 附录 – 问题汇总

预知问题后续细节,详见:BetaFlight飞控启动&运行过程简介疑问跟踪

6.1 Why desiredPeriodCycles is so important to Betaflight task?

Let’s say default desiredPeriodCycles is about 8K, which 125us. And the code still check desiredPeriodCycles by GYRO_RATE_COUNT interrupts, what’s the story here?

If sample rate is NOT sync with gyro task, there might be dirty/invalid data, is there any bad thing happens if just missed 1 or 2 valid samples?

Or this code only tends to logically eliminate this effective data sampling bias?

6.2 What root cause has made gyro task to been overrun, so scheduler has to skip a gyro cycle?

As scheduler comments "A task has so grossly overrun that at entire gyro cycle has been skipped, especially via USB as the serial.

Is there too much serial communication through bf configurator and FC or just USB-VCP code on FC side take a lot of resources?

It’ll be the same issue when switching to TTL comunication with FC (suggest test bf-configurator <> usb_serial convertor <> FC(UART1 for example)?

6.3 What if serial task is running quite long, which corrupt gyro cycle, is it a problem?

As previous discussion on “Why desiredPeriodCycles is so important during Betaflight task?”

e.g. use MSP protocol as communication channel with companion computer
==> there are lots of packets, result in long time processing.
==> if this happens, it seems mess up with the gyro cycle, am i right? is there any solution or way to overcome this issue?

Code

6.4 What does the condition of “scheduleCount & SCHED_TASK_DEFER_MASK == 0” stand for in scheduler?

Code

There are three scenarios for normal(except gyro/acc/pid) tasks to execute:

  1. taskRequiredTimeCycles < schedLoopRemainingCycles // there is time for task to execute.
  2. scheduleCount & SCHED_TASK_DEFER_MASK == 0 //???
  3. (task - tasks) == TASK_SERIAL // ok, special case for serial

So what’s for case #2 “scheduleCount & SCHED_TASK_DEFER_MASK == 0”

  • 2
    点赞
  • 9
    收藏
    觉得还不错? 一键收藏
  • 1
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 1
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值