BetaFlight开源飞控源码分析

BetaFlight开源飞控源码分析

  • 1.整体框架
  • 2.主函数源码分析
    • 2.1.初始化
    • 2.2.运行
  • 3.如何使用这个程序
    • 3.1.目标文件源码分析
    • 3.2.添加目标文件
    • 3.3.编译程序
  • 4.参考文献

betaflight github开源地址:https://github.com/betaflight/betaflight.git
BetaFlight是穿越机领域比较成熟的开源飞控,需要注意的是BetaFlight官网只是提供开源软件工程,用户需要根据这套程序,结合自己的硬件,自行修改相关驱动代码。
本文主要是分析BetaFlight源码框架,然后基于这个框架做修改,生成自己硬件对应的程序固件。

1.整体框架

这里以4.4版本的程序为例。
程序克隆下来之后,使用VScode打开文件夹,下面是一级目录的介绍
在这里插入图片描述下面在linux终端上使用命令

sudo apt install tree
tree -a

tree命令可以以树状图列出文件目录结构:
在这里插入图片描述
可以看到整个程序目录分支众多,还是比较庞大的。

betaflight├──> src/main          //源代码&引用头文件目录│   ├──> main.c        //C代码入口main()│   ├──> ...           //省略很多模块,后续会深入分析,比如:blackbox,osd等│   ├──> drivers       //各类硬件芯片驱动│   ├──> target        //各类目标板(airframe):代码+配置│   │   └──> STM32F405  //举例:STM32F405│   │       ├──> target.c│   │       ├──> target.h│   │       └──> target.mk│   └──> startup│       └──> startup_stm32f745xx.s├──> obj               //编译目标文件目录│   ├──> main│   └──> betaflight_4.4.0_STM32F405.hex├──> lib/main          //库代码目录│   ├──> MAVLink│   ├──> CMSIS│   ├──> STM32_USB-FS-Device_Driver│   ├──> FatFS│   └──> STM32F7├──> src/link          //链接脚本目录│   ├──> stm32_flash_f7_split.ld│   └──> stm32_flash_f74x.ld├──> make              //通用makefile目录├──> tools             //本地工具安装,比如:gcc-arm-none-eabi-9-2020-q2-update└──> downloads         //下载目录,比如:下载的工具链压缩包gcc-arm-none-eabi-9-2020-q2-update-x86_64-linux.tar.bz2

2.主函数源码分析

src是整个代码的核心文件夹,打开betaflight\src\main\main.c,可以看到betaflight是用C语言开发的一款飞控项目,其入口也是从main()函数开始。

main├──> init()     //硬件初始化└──> run()	 //任务循环运行

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

2.1.初始化

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;

初始化可以分成两大部分:

初始化
驱动层初始化
USB UART 陀螺仪 电机 VTX OSD等
应用层初始化
初始默认参数 任务初始化等

应用层的初始化通常是在对应的驱动层初始化之后。

2.2.运行

始化完成以后就执行run函数,它是一个BetaFlight自研的一个时间片任务调度器。这种调度器的实时性是介于裸机和RTOS之间的,它比传统裸机的任务顺序执行效率高,但没有FreeRTOS的实时性那么强。

run└──> loop: scheduler()
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│       │ ################################################################################│       │ #轮询的方式读取陀螺仪数据│       │ ################################################################################│       ├──> <while (schedLoopRemainingCycles > 0)> │       │   ├──> nowCycles = getCycleCounter();│       │   └──> schedLoopRemainingCycles = cmpTimeCycles(nextTargetCycles, nowCycles);│       │ ################################################################################│       │ # 执行陀螺仪/滤波器/pid任务并检查rc链路中的数据可用性│       │ ################################################################################│       ├──> 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设备│       │ ################################################################################│       │ # 使用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;  //选中任务│   │ ################################################################################│   │ # 选择任务执行│   │ ################################################################################│   ├──> 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; //减少守护时间│       │ ################################################################################│       │ # 特殊任务处理│       │ ################################################################################│       └──> <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++;

3.如何使用这个程序

3.1.目标文件源码分析

BetaFlight的代码最初clone过来时,也是继承了嵌入式代码一贯的target目标板设计思路;也就是说,针对每个板子有一份对应的目录,有对应的target代码,比如:芯片、板子初始化等代码。
打开src/main/target,我们就可以看到betaflight目前支持的主控芯片型号。
在这里插入图片描述
我们要使用betaflight这个程序,通常就是修改target.c和target.h文件。
打开target.h,可以看到使用一些宏定义做了声明。

#pragma once#define TARGET_BOARD_IDENTIFIER "S411"
#define USBD_PRODUCT_STRING     "Betaflight STM32F411"
#define USE_I2C_DEVICE_1
#define USE_I2C_DEVICE_2
#define USE_I2C_DEVICE_3
#define USE_UART1
#define USE_UART2
#define USE_UART6
#define SERIAL_PORT_COUNT       (UNIFIED_SERIAL_PORT_COUNT + 3)
#define USE_INVERTER
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#define USE_SPI_DEVICE_3
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTE 0xffff
#define USE_I2C
#define I2C_FULL_RECONFIGURABILITY
#define USE_DSHOT_BITBAND
#define USE_BEEPER
#ifdef USE_SDCARD
#define USE_SDCARD_SPI
#define USE_SDCARD_SDIO
#endif
#define USE_SPI
#define SPI_FULL_RECONFIGURABILITY
#define USE_VCP
#define USE_SOFTSERIAL1
#define USE_SOFTSERIAL2
#define UNIFIED_SERIAL_PORT_COUNT       3
#define USE_USB_DETECT
#define USE_ESCSERIAL
#define USE_ADC
#define USE_CUSTOM_DEFAULTS

默认是没有任何IO配置的,用到的PIN引脚也是NONE,这就需要我们自己添加和修改。如何正确添加和修改这些配置,首先要对四轴飞行器的一些功能模块有所了解。
四轴飞行器的功能模块和相关驱动

OSD 穿越机必需
VTX图传 穿越机必需
RGB灯 蜂鸣器
GPS 气压计 光流等
四轴飞行器
基本模块
拓展模块
USB通信
IMU模块 I2C\SPI
遥控接收 串口SBUS\ELRS协议
电量检测 ADC\DMA
动力电机 PWM\DMA

基本模块是飞行器必须要有的,缺少就飞不起来;拓展模块有些是根据自己实际需要添加。驱动这些模块本质还是配置单片机的功能外设。

3.2.添加目标文件

我们可以根据自己使用的硬件平台,新建一个target,这里就以STM32F411为例。
在这里插入图片描述
下面就需要根据自己的原理图,进行配置target.c和target.h文件。
在这里插入图片描述
在target.h里通过宏定义更改配置,这里主要就是根据原理图添加对应PIN引脚

#pragma once
#define TARGET_BOARD_IDENTIFIER         "STM32F411_MyFirmware"
#define USBD_PRODUCT_STRING             "STM32F411_MyFirmware"
/* ======== LED ======== */
#define USE_LED_STRIP
#define USE_LED_STRIP_STATUS_MODE
#define LED0_PIN                        PC14
/* ======== UART ======== */
#define USE_UART
#define USE_VCP
#define USE_UART1
#define UART1_RX_PIN                    PA10
#define UART1_TX_PIN                    PA9
#define USE_UART2
#define UART2_RX_PIN                    PA3
#define UART2_TX_PIN                    PA2
#define SERIAL_PORT_COUNT               3
/* ======== SPI ======== */
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_SCK_PIN                    PA5
#define SPI1_MISO_PIN                   PA6
#define SPI1_MOSI_PIN                   PA7
#define SPI1_NSS_PIN                    PA4
#define USE_SPI_DEVICE_2
#define SPI2_SCK_PIN                    PB13
#define SPI2_MISO_PIN                   PB14
#define SPI2_MOSI_PIN                   PB15
#define USE_SPI_DEVICE_3
#define SPI3_SCK_PIN                    PB3
#define SPI3_MISO_PIN                   PB4
#define SPI3_MOSI_PIN                   PB5
/* ======== GYRO & ACC ======== */
#define USE_ACC
#define USE_GYRO
#define USE_SPI_GYRO
#define USE_ACCGYRO_BMI270
#define USE_EXTI
#define USE_GYRO_EXTI
#define GYRO_1_EXTI_PIN                 PB6
#define USE_MPU_DATA_READY_SIGNAL
#define GYRO_1_CS_PIN                   SPI1_NSS_PIN
#define GYRO_1_SPI_INSTANCE             SPI1
#define GYRO_1_ALIGN                    CW180_DEG
/* ======== OSD ======== */
#define USE_OSD
#define USE_CANVAS
#define USE_CMS
#define USE_CMS_FAILSAFE_MENU
#define USE_EXTENDED_CMS_MENUS
#define USE_MSP_DISPLAYPORT
#define USE_OSD_OVER_MSP_DISPLAYPORT
#define USE_OSD_ADJUSTMENTS
#define USE_OSD_PROFILES
#define USE_OSD_STICK_OVERLAY
#define USE_MAX7456
#define MAX7456_SPI_CS_PIN              PB12
#define MAX7456_SPI_INSTANCE            SPI2
/* ======== VTX ======== */
#define USE_VTX
#define USE_VTX_COMMON
#define USE_VTX_CONTROL
#define USE_VTX_MSP
#define USE_VTX_TABLE
#define USE_VTX_RTC6705
#define SPI_SHARED_MAX7456_AND_RTC6705
#define RTC6705_CS_PIN                  PA14
#define RTC6705_SPI_INSTANCE            SPI2
#define CMS_SKIP_EMPTY_VTX_TABLE_ENTRIES
/* ======== RX ======== */
#define USE_RX_SPI
#define USE_RX_PPM
#define USE_RX_PWM
#define USE_SERIALRX
#define USE_SERIALRX_CRSF               // Team Black Sheep Crossfire protocol
#define USE_SERIALRX_GHST               // ImmersionRC Ghost Protocol
#define USE_SERIALRX_IBUS               // FlySky and Turnigy receivers
#define USE_SERIALRX_SBUS               // Frsky and Futaba receivers
#define USE_SERIALRX_SPEKTRUM           // SRXL, DSM2 and DSMX protocol
#define USE_SERIALRX_FPORT              // FrSky FPort
#define USE_SERIALRX_XBUS               // JR
#define USE_SERIALRX_SRXL2              // Spektrum SRXL2 protocol
#define USE_SERIALRX_JETIEXBUS
#define USE_SERIALRX_SUMD               // Graupner Hott protocol
#define USE_SERIALRX_SUMH               // Graupner legacy protocol
#define USE_CRSF_V3
#define USE_CRSF_CMS_TELEMETRY
#define USE_CRSF_LINK_STATISTICS
#define USE_TELEMETRY
#define USE_TELEMETRY_FRSKY_HUB
#define USE_TELEMETRY_SMARTPORT
#define USE_TELEMETRY_CRSF
#define USE_TELEMETRY_GHST
#define USE_TELEMETRY_SRXL
#define USE_TELEMETRY_IBUS
#define USE_TELEMETRY_IBUS_EXTENDED
#define USE_TELEMETRY_JETIEXBUS
#define USE_TELEMETRY_MAVLINK
#define USE_TELEMETRY_HOTT
#define USE_TELEMETRY_LTM
#define USE_SPEKTRUM_BIND
#define USE_SPEKTRUM_BIND_PLUG
#define USE_SPEKTRUM_REAL_RSSI
#define USE_SPEKTRUM_FAKE_RSSI
#define USE_SPEKTRUM_RSSI_PERCENT_CONVERSION
#define USE_SPEKTRUM_VTX_CONTROL
#define USE_SPEKTRUM_VTX_TELEMETRY
#define USE_SPEKTRUM_CMS_TELEMETRY
#define RX_SPI_INSTANCE                 SPI3
#define RX_SPI_LED_INVERTED
#define RX_NSS_PIN                      PA15
#define RX_SPI_LED_PIN                  PC15
#define RX_SPI_EXTI_PIN                 PC13
#define RX_SPI_BIND_PIN                 PB2
#define RX_EXPRESSLRS_SPI_RESET_PIN     PB9
#define RX_EXPRESSLRS_SPI_BUSY_PIN      PA13
#define RX_EXPRESSLRS_TIMER_INSTANCE    TIM5
#define USE_TELEMETRY
#define USE_RX_EXPRESSLRS
#define USE_RX_SX1280
#define DEFAULT_RX_FEATURE              FEATURE_RX_SPI
#define RX_SPI_DEFAULT_PROTOCOL         RX_SPI_EXPRESSLRS
/* ======== ADC ======== */
#define USE_ADC
#define ADC_INSTANCE                    ADC1
#define ADC1_DMA_OPT                    0
#define VBAT_ADC_PIN                    PA1
#define CURRENT_METER_ADC_PIN           PB0
#define VBAT_SCALE_DEFAULT              110
#define CURRENT_METER_SCALE_DEFAULT     510
#define CURRENT_METER_OFFSET_DEFAULT    0
#define DEFAULT_VOLTAGE_METER_SOURCE    VOLTAGE_METER_ADC
#define DEFAULT_CURRENT_METER_SOURCE    CURRENT_METER_ADC
/* ======== ESC ======== */
#define USE_DSHOT
#define USE_DSHOT_DMAR
#define USE_DSHOT_BITBANG
#define USE_DSHOT_TELEMETRY
#define USE_DSHOT_TELEMETRY_STATS
#define USE_BRUSHED_ESC_AUTODETECT  // Detect if brushed motors are connected and set defaults appropriately to avoid motors spinning on boot
#define ENABLE_DSHOT_DMAR               DSHOT_DMAR_ON
#define DSHOT_BITBANG_DEFAULT           DSHOT_BITBANG_AUTO
/* ======== OTHER ======== */
#define USE_BLACKBOX
#define USE_SERVOS
#define USE_PINIO
#define USE_PINIOBOX
#define DEFAULT_FEATURES                (FEATURE_INFLIGHT_ACC_CAL | FEATURE_LED_STRIP | FEATURE_OSD)
#define TARGET_IO_PORTA                 0xffff
#define TARGET_IO_PORTB                 0xffff
#define TARGET_IO_PORTC                 0xffff
#define TARGET_IO_PORTD                 (BIT(2))
#define USE_BEEPER
#define USABLE_TIMER_CHANNEL_COUNT      5
#define USED_TIMERS                     ( TIM_N(2) | TIM_N(3) | TIM_N(4) )
#define USE_TARGET_CONFIG

target.c里主要是配置电机、WS2812、蜂鸣器等需要PWM的驱动。

#include <stdint.h>#include "platform.h"
#include "drivers/io.h"#include "drivers/dma.h"
#include "drivers/timer.h"
#include "drivers/timer_def.h"const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {DEF_TIM(TIM4, CH3, PB8,  TIM_USE_MOTOR,          0, 0), // M1DEF_TIM(TIM2, CH1, PA0,  TIM_USE_MOTOR,          0, 0), // M2DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR,          0, 0), // M3DEF_TIM(TIM4, CH2, PB7,  TIM_USE_MOTOR,          0, 0), // M4DEF_TIM(TIM3, CH4, PB1,  TIM_USE_LED,            0, 0) // LED Strip
};

其实target的配置,就是相当于在betaflight configurator的CLI窗口,一行一行的输入,然后把数据保存到飞控芯片的flash。

3.3.编译程序

修改好target文件之后,就可以编译生产hex文件了。使用STM32单片机做开发的应该都用过Keil进行编译程序,但是betaflight程序是要用gcc-arm编译的。
在make/tool.mk可以看到需要的工具链为gcc-arm-none-eabi-10.3-2021.10
在这里插入图片描述
关于如何安装这个工具链可以看另一篇文章
使用VScode编译betaflight固件–基于ubuntu平台
这是一种把工具链当做全局环境变量使用的方法,还有一种方法是只能在本工程使用的环境变量。
在命令行输入:

make arm_sdk_install

系统就会自动安装本工程需要的gcc-arm编译器,安装路径就在betaflight/downloads文件夹下,这样的好处就是移植方便,把代码放到另一台还没安装gcc-arm编译器的电脑上也能编译。

安装好编译器之后就可以使用make命令进行编译了。
使用方法也简单,在终端输入

make target名称

在这里插入图片描述
看到上面的提示代表成功生成固件了,文件路径就在betaflight/obj/main目录下
在这里插入图片描述

4.参考文献

1.BetaFlight开源工程结构简明介绍

2.BetaFlight开源代码框架简介

3.betaflight 代码结构

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.hqwc.cn/news/475511.html

如若内容造成侵权/违法违规/事实不符,请联系编程知识网进行投诉反馈email:809451989@qq.com,一经查实,立即删除!

相关文章

【C++学习手札】多态:掌握面向对象编程的动态绑定与继承机制(初识)

&#x1f3ac;慕斯主页&#xff1a;修仙—别有洞天 ♈️今日夜电波&#xff1a;世界上的另一个我 1:02━━━━━━️&#x1f49f;──────── 3:58 &#x1f504; ◀️ ⏸ ▶️ ☰ &am…

内存基础知识

内存作用&#xff1a;用来存放数据 int x10&#xff1b; xx1&#xff1b; 这会生成一个可执行文件&#xff08;装入模块&#xff09;然后存入内存地址中 绝对装入&#xff1a;-如果知道程序放到内存中哪个位置&#xff0c;编译程序将产生绝对地址的目标代码 可重定位装入&am…

红队APT-钓鱼篇_邮件钓鱼_Ewomail系统_网页克隆

目录 演示案例:Ewomail&Swaks-邮件伪造发信人Ewomail-邮件系统-搭建&使用Ewomail&Gophish-邮件加网页钓鱼网页钓鱼-克隆修改-二维码用户劫持网页钓鱼-克隆修改-Flash升级后门上线 演示案例: Ewomail&Swaks-邮件伪造发信人 发邮件的邮箱地址如果能伪造的话&am…

解决传统单一模态难题!多模态图学习新SOTA来了!

多模态图学习是一种结合了图神经网络和多模态数据集成的学习方法&#xff0c;它涉及了数据科学、机器学习、图神经网络、多模态分析等多个前沿领域。这种跨学科特性为我们提供了丰富的创新点和探索空间。因此&#xff0c;多模态图学习也是发表高质量论文的好方向。 通过整合和…

MyBatis基础学习

一、MyBatis简介 二、MyBatis-HelloWorld 三、MyBatis-全局配置文件 四、MyBatis-映射文件 五、MyBatis-动态SQL 六、MyBatis-缓存机制 七、MyBatis-Spring整合 八、MyBatis-逆向工程 九、MyBatis-工作原理 十、MyBatis-插件开发

ch6-homework-OpenCompass大模型评测

ch6-homework-OpenCompass大模型评测 主要内容实践教程本地复现环境配置数据集下载启动评测评测结果评估结果文件说明评测配置文件详解 基础作业进阶作业 主要内容 视频网址&#xff1a;https://www.bilibili.com/video/BV1Gg4y1U7uc/?spm_id_from333.788&vd_sourceb96c7e…

Flash extractor功能介绍

Flash extractor功能介绍 Flash Extractor软件用于恢复U盘记忆卡和SSD硬盘内存芯片数据&#xff0c;每个月出现新型号的闪存设备。每个新器件有不同的内部物理和逻辑结构。我们每周都会分析和发布更新我们的软件。里面有一个支持模型库的程序。这些驱动器可以很容易地恢复 但如…

JDBC核心技术

第1章 JDBC概述 第2章 获取数据库连接 第3章 使用PreparedStatement实现CRUD操作 第4章 操作BLOB类型字段 第5章 批量插入 第6章 数据库事务 第7章 DAO及相关实现类 第8章 数据库连接池 第9章 Apache-DBUtils实现CRUD操作图像 小部件

数据库架构师之道:MySQL安装与系统整合指南

目录 MySQL数据库安装&#xff08;centos&#xff09; 版本选择 企业版 社区版 选哪个 MySQL特点 MySQL服务端-客户端 mysql下载选择 软件包解释 安装MySQL的方式 rpm包安装 yum方式安装 源码编译安装★ 具体的编译安装步骤★★ 环境准备 free -m命令 cat /pr…

王力宏胜诉,事实胜于雄辩,真相终将大白。

♥ 为方便您进行讨论和分享&#xff0c;同时也为能带给您不一样的参与感。请您在阅读本文之前&#xff0c;点击一下“关注”&#xff0c;非常感谢您的支持&#xff01; 文 |猴哥聊娱乐 编 辑|徐 婷 校 对|侯欢庭 好的&#xff0c;以下是对“2月5日&#xff0c;王力宏工作室在…

Graph + LLM图数据库技术如何助力行业大语言模型应用落地

随着 AI 人工智能技术的迅猛发展和自然语言处理领域的研究日益深入&#xff0c;如何构建强大的大语言模型对于企业来说愈发重要&#xff0c;尤其是在特定行业领域中。 图数据库作为处理复杂数据结构的有力工具&#xff0c;为企业构建行业大语言模型提供了强大的支持。本文将探…

商品详情API接口展示

一、应用场景 适用于跨境代购业务&#xff0c;国际物流业务&#xff0c;海外代采业务&#xff0c;群控业务&#xff0c;价格监控以及品牌维权&#xff01; 二、公共参数 请求地址: https://1688/item_get 三、请求参数 请求参数&#xff1a;num_iid610947572360 四、响应…