Removed OSD_SLAVE defines.

This commit is contained in:
mikeller 2018-08-23 23:03:22 +12:00
parent a02e1dd384
commit 6a77c5f576
9 changed files with 23 additions and 216 deletions

View File

@ -61,9 +61,7 @@
#include "sensors/battery.h"
#include "sensors/gyro.h"
#ifndef USE_OSD_SLAVE
pidProfile_t *currentPidProfile;
#endif
#ifndef RX_SPI_DEFAULT_PROTOCOL
#define RX_SPI_DEFAULT_PROTOCOL 0
@ -89,7 +87,6 @@ PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
.boardIdentifier = TARGET_BOARD_IDENTIFIER
);
#ifndef USE_OSD_SLAVE
uint8_t getCurrentPidProfileIndex(void)
{
return systemConfig()->pidProfileIndex;
@ -109,7 +106,6 @@ uint16_t getCurrentMinthrottle(void)
{
return motorConfig()->minthrottle;
}
#endif // USE_OSD_SLAVE
void resetConfigs(void)
{
@ -122,7 +118,6 @@ void resetConfigs(void)
static void activateConfig(void)
{
#ifndef USE_OSD_SLAVE
loadPidProfile();
loadControlRateProfile();
@ -139,7 +134,6 @@ static void activateConfig(void)
accInitFilters();
imuConfigure(throttleCorrectionConfig()->throttle_correction_angle, throttleCorrectionConfig()->throttle_correction_value);
#endif // USE_OSD_SLAVE
#ifdef USE_LED_STRIP
reevaluateLedConfig();
@ -148,7 +142,7 @@ static void activateConfig(void)
static void validateAndFixConfig(void)
{
#if !defined(USE_QUAD_MIXER_ONLY) && !defined(USE_OSD_SLAVE)
#if !defined(USE_QUAD_MIXER_ONLY)
// Reset unsupported mixer mode to default.
// This check will be gone when motor/servo mixers are loaded dynamically
// by configurator as a part of configuration procedure.
@ -177,7 +171,6 @@ static void validateAndFixConfig(void)
featureDisable(FEATURE_GPS);
}
#ifndef USE_OSD_SLAVE
if (systemConfig()->activeRateProfile >= CONTROL_RATE_PROFILE_COUNT) {
systemConfigMutable()->activeRateProfile = 0;
}
@ -304,7 +297,6 @@ static void validateAndFixConfig(void)
removeModeActivationCondition(BOXGPSRESCUE);
}
}
#endif // USE_OSD_SLAVE
#if defined(USE_ESC_SENSOR)
if (!findSerialPortConfig(FUNCTION_ESC_SENSOR)) {
@ -409,7 +401,6 @@ static void validateAndFixConfig(void)
#endif
}
#ifndef USE_OSD_SLAVE
void validateAndFixGyroConfig(void)
{
#ifdef USE_GYRO_DATA_ANALYSE
@ -511,13 +502,10 @@ void validateAndFixGyroConfig(void)
}
}
}
#endif // USE_OSD_SLAVE
bool readEEPROM(void)
{
#ifndef USE_OSD_SLAVE
suspendRxSignal();
#endif
// Sanity check, read flash
bool success = loadEEPROM();
@ -526,9 +514,7 @@ bool readEEPROM(void)
activateConfig();
#ifndef USE_OSD_SLAVE
resumeRxSignal();
#endif
return success;
}
@ -537,15 +523,11 @@ void writeEEPROM(void)
{
validateAndFixConfig();
#ifndef USE_OSD_SLAVE
suspendRxSignal();
#endif
writeConfigToEEPROM();
#ifndef USE_OSD_SLAVE
resumeRxSignal();
#endif
}
void writeEEPROMWithFeatures(uint32_t features)
@ -580,7 +562,6 @@ void saveConfigAndNotify(void)
beeperConfirmationBeeps(1);
}
#ifndef USE_OSD_SLAVE
void changePidProfile(uint8_t pidProfileIndex)
{
if (pidProfileIndex < MAX_PROFILE_COUNT) {
@ -590,4 +571,3 @@ void changePidProfile(uint8_t pidProfileIndex)
beeperConfirmationBeeps(pidProfileIndex + 1);
}
#endif

View File

@ -127,13 +127,11 @@ void HardFault_Handler(void)
{
LED2_ON;
#ifndef USE_OSD_SLAVE
// fall out of the sky
uint8_t requiredStateForMotors = SYSTEM_STATE_CONFIG_LOADED | SYSTEM_STATE_MOTORS_READY;
if ((systemState & requiredStateForMotors) == requiredStateForMotors) {
stopMotors();
}
#endif
#ifdef USE_TRANSPONDER
// prevent IR LEDs from burning out.

View File

@ -551,11 +551,11 @@ void init(void)
cmsInit();
#endif
#if (defined(USE_OSD) || (defined(USE_MSP_DISPLAYPORT) && defined(USE_CMS)) || defined(USE_OSD_SLAVE))
#if (defined(USE_OSD) || (defined(USE_MSP_DISPLAYPORT) && defined(USE_CMS)))
displayPort_t *osdDisplayPort = NULL;
#endif
#if defined(USE_OSD) && !defined(USE_OSD_SLAVE)
#if defined(USE_OSD)
//The OSD need to be initialised after GYRO to avoid GYRO initialisation failure on some targets
if (featureIsEnabled(FEATURE_OSD)) {
@ -570,15 +570,6 @@ void init(void)
}
#endif
#if defined(USE_OSD_SLAVE) && !defined(USE_OSD)
#if defined(USE_MAX7456)
// If there is a max7456 chip for the OSD then use it
osdDisplayPort = max7456DisplayPortInit(vcdProfile());
// osdInit will register with CMS by itself.
osdSlaveInit(osdDisplayPort);
#endif
#endif
#if defined(USE_CMS) && defined(USE_MSP_DISPLAYPORT)
// If BFOSD is not active, then register MSP_DISPLAYPORT as a CMS device.
if (!osdDisplayPort)

View File

@ -119,16 +119,6 @@ static void taskMain(timeUs_t currentTimeUs)
#endif
}
#ifdef USE_OSD_SLAVE
static bool taskSerialCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTimeUs)
{
UNUSED(currentTimeUs);
UNUSED(currentDeltaTimeUs);
return mspSerialWaiting();
}
#endif
static void taskHandleSerial(timeUs_t currentTimeUs)
{
UNUSED(currentTimeUs);
@ -145,11 +135,7 @@ static void taskHandleSerial(timeUs_t currentTimeUs)
return;
}
#endif
#ifndef OSD_SLAVE
bool evaluateMspData = ARMING_FLAG(ARMED) ? MSP_SKIP_NON_MSP_DATA : MSP_EVALUATE_NON_MSP_DATA;
#else
bool evaluateMspData = osdSlaveIsLocked ? MSP_SKIP_NON_MSP_DATA : MSP_EVALUATE_NON_MSP_DATA;;
#endif
mspSerialProcess(evaluateMspData, mspFcProcessCommand, mspFcProcessReply);
}
@ -163,7 +149,6 @@ static void taskBatteryAlerts(timeUs_t currentTimeUs)
batteryUpdateAlarms();
}
#ifndef USE_OSD_SLAVE
static void taskUpdateAccelerometer(timeUs_t currentTimeUs)
{
accUpdate(currentTimeUs, &accelerometerConfigMutable()->accelerometerTrims);
@ -190,7 +175,6 @@ static void taskUpdateRxMain(timeUs_t currentTimeUs)
updateRcCommands();
updateArmingStatus();
}
#endif
#ifdef USE_BARO
static void taskUpdateBaro(timeUs_t currentTimeUs)
@ -248,11 +232,7 @@ void fcTasksInit(void)
setTaskEnabled(TASK_BATTERY_VOLTAGE, useBatteryVoltage);
const bool useBatteryCurrent = batteryConfig()->currentMeterSource != CURRENT_METER_NONE;
setTaskEnabled(TASK_BATTERY_CURRENT, useBatteryCurrent);
#ifdef USE_OSD_SLAVE
const bool useBatteryAlerts = batteryConfig()->useVBatAlerts || batteryConfig()->useConsumptionAlerts;
#else
const bool useBatteryAlerts = batteryConfig()->useVBatAlerts || batteryConfig()->useConsumptionAlerts || featureIsEnabled(FEATURE_OSD);
#endif
setTaskEnabled(TASK_BATTERY_ALERTS, (useBatteryVoltage || useBatteryCurrent) && useBatteryAlerts);
#ifdef USE_TRANSPONDER
@ -263,9 +243,6 @@ void fcTasksInit(void)
setTaskEnabled(TASK_STACK_CHECK, true);
#endif
#ifdef USE_OSD_SLAVE
setTaskEnabled(TASK_OSD_SLAVE, osdSlaveInitialized());
#else
if (sensors(SENSOR_GYRO)) {
rescheduleTask(TASK_GYROPID, gyro.targetLooptime);
setTaskEnabled(TASK_GYROPID, true);
@ -284,21 +261,27 @@ void fcTasksInit(void)
#ifdef USE_BEEPER
setTaskEnabled(TASK_BEEPER, true);
#endif
#ifdef USE_GPS
setTaskEnabled(TASK_GPS, featureIsEnabled(FEATURE_GPS));
#endif
#ifdef USE_MAG
setTaskEnabled(TASK_COMPASS, sensors(SENSOR_MAG));
#endif
#ifdef USE_BARO
setTaskEnabled(TASK_BARO, sensors(SENSOR_BARO));
#endif
#if defined(USE_BARO) || defined(USE_GPS)
setTaskEnabled(TASK_ALTITUDE, sensors(SENSOR_BARO) || featureIsEnabled(FEATURE_GPS));
#endif
#ifdef USE_DASHBOARD
setTaskEnabled(TASK_DASHBOARD, featureIsEnabled(FEATURE_DASHBOARD));
#endif
#ifdef USE_TELEMETRY
if (featureIsEnabled(FEATURE_TELEMETRY)) {
setTaskEnabled(TASK_TELEMETRY, true);
@ -311,27 +294,35 @@ void fcTasksInit(void)
}
}
#endif
#ifdef USE_LED_STRIP
setTaskEnabled(TASK_LEDSTRIP, featureIsEnabled(FEATURE_LED_STRIP));
#endif
#ifdef USE_TRANSPONDER
setTaskEnabled(TASK_TRANSPONDER, featureIsEnabled(FEATURE_TRANSPONDER));
#endif
#ifdef USE_OSD
setTaskEnabled(TASK_OSD, featureIsEnabled(FEATURE_OSD) && osdInitialized());
#endif
#ifdef USE_BST
setTaskEnabled(TASK_BST_MASTER_PROCESS, true);
#endif
#ifdef USE_ESC_SENSOR
setTaskEnabled(TASK_ESC_SENSOR, featureIsEnabled(FEATURE_ESC_SENSOR));
#endif
#ifdef USE_ADC_INTERNAL
setTaskEnabled(TASK_ADC_INTERNAL, true);
#endif
#ifdef USE_PINIOBOX
setTaskEnabled(TASK_PINIOBOX, true);
#endif
#ifdef USE_CMS
#ifdef USE_MSP_DISPLAYPORT
setTaskEnabled(TASK_CMS, true);
@ -339,18 +330,20 @@ void fcTasksInit(void)
setTaskEnabled(TASK_CMS, featureIsEnabled(FEATURE_OSD) || featureIsEnabled(FEATURE_DASHBOARD));
#endif
#endif
#ifdef USE_VTX_CONTROL
#if defined(USE_VTX_RTC6705) || defined(USE_VTX_SMARTAUDIO) || defined(USE_VTX_TRAMP)
setTaskEnabled(TASK_VTXCTRL, true);
#endif
#endif
#ifdef USE_CAMERA_CONTROL
setTaskEnabled(TASK_CAMCTRL, true);
#endif
#ifdef USE_RCDEVICE
setTaskEnabled(TASK_RCDEVICE, rcdeviceIsEnabled());
#endif
#endif
}
cfTask_t cfTasks[TASK_COUNT] = {
@ -373,14 +366,8 @@ cfTask_t cfTasks[TASK_COUNT] = {
[TASK_SERIAL] = {
.taskName = "SERIAL",
.taskFunc = taskHandleSerial,
#ifdef USE_OSD_SLAVE
.checkFunc = taskSerialCheck,
.desiredPeriod = TASK_PERIOD_HZ(100),
.staticPriority = TASK_PRIORITY_REALTIME,
#else
.desiredPeriod = TASK_PERIOD_HZ(100), // 100 Hz should be enough to flush up to 115 bytes @ 115200 baud
.staticPriority = TASK_PRIORITY_LOW,
#endif
},
[TASK_BATTERY_ALERTS] = {
@ -421,17 +408,6 @@ cfTask_t cfTasks[TASK_COUNT] = {
},
#endif
#ifdef USE_OSD_SLAVE
[TASK_OSD_SLAVE] = {
.taskName = "OSD_SLAVE",
.checkFunc = osdSlaveCheck,
.taskFunc = osdSlaveUpdate,
.desiredPeriod = TASK_PERIOD_HZ(60), // 60 Hz
.staticPriority = TASK_PRIORITY_HIGH,
},
#else
[TASK_GYROPID] = {
.taskName = "PID",
.subTaskName = "GYRO",
@ -621,5 +597,4 @@ cfTask_t cfTasks[TASK_COUNT] = {
.staticPriority = TASK_PRIORITY_IDLE
},
#endif
#endif
};

View File

@ -147,9 +147,7 @@ typedef struct pidProfile_s {
uint8_t abs_control_error_limit; // Limit to the accumulated error
} pidProfile_t;
#ifndef USE_OSD_SLAVE
PG_DECLARE_ARRAY(pidProfile_t, MAX_PROFILE_COUNT, pidProfiles);
#endif
typedef struct pidConfig_s {
uint8_t pid_process_denom; // Processing denominator for PID controller vs gyro sampling rate

View File

@ -142,8 +142,6 @@ enum {
static uint8_t rebootMode;
#ifndef USE_OSD_SLAVE
typedef enum {
MSP_SDCARD_STATE_NOT_PRESENT = 0,
MSP_SDCARD_STATE_FATAL = 1,
@ -162,7 +160,6 @@ typedef enum {
} mspFlashFsFlags_e;
#define RATEPROFILE_MASK (1 << 7)
#endif //USE_OSD_SLAVE
#define RTC_NOT_SUPPORTED 0xff
@ -242,9 +239,7 @@ static void mspRebootFn(serialPort_t *serialPort)
{
UNUSED(serialPort);
#ifndef USE_OSD_SLAVE
stopPwmAllMotors();
#endif
switch (rebootMode) {
case MSP_REBOOT_FIRMWARE:
@ -270,7 +265,6 @@ static void mspRebootFn(serialPort_t *serialPort)
while (true) ;
}
#ifndef USE_OSD_SLAVE
static void serializeSDCardSummaryReply(sbuf_t *dst)
{
#ifdef USE_SDCARD
@ -434,7 +428,6 @@ static void serializeDataflashReadReply(sbuf_t *dst, uint32_t address, const uin
}
}
#endif // USE_FLASHFS
#endif // USE_OSD_SLAVE
/*
* Returns true if the command was processd, false otherwise.
@ -469,14 +462,10 @@ static bool mspCommonProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProce
#else
sbufWriteU16(dst, 0); // No other build targets currently have hardware revision detection.
#endif
#ifdef USE_OSD_SLAVE
sbufWriteU8(dst, 1); // 1 == OSD
#else
#if defined(USE_OSD) && defined(USE_MAX7456)
sbufWriteU8(dst, 2); // 2 == FC with OSD
#else
sbufWriteU8(dst, 0); // 0 == FC
#endif
#endif
// Board communication capabilities (uint8)
// Bit 0: 1 iff the board has VCP
@ -523,11 +512,7 @@ static bool mspCommonProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProce
case MSP_ANALOG:
sbufWriteU8(dst, (uint8_t)constrain(getBatteryVoltage(), 0, 255));
sbufWriteU16(dst, (uint16_t)constrain(getMAhDrawn(), 0, 0xFFFF)); // milliamp hours drawn from battery
#ifdef USE_OSD_SLAVE
sbufWriteU16(dst, 0); // rssi
#else
sbufWriteU16(dst, getRssi());
#endif
sbufWriteU16(dst, (int16_t)constrain(getAmperage(), -0x8000, 0x7FFF)); // send current in 0.01 A steps, range is -320A to 320A
break;
@ -699,7 +684,7 @@ static bool mspCommonProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProce
case MSP_OSD_CONFIG: {
#define OSD_FLAGS_OSD_FEATURE (1 << 0)
#define OSD_FLAGS_OSD_SLAVE (1 << 1)
//#define OSD_FLAGS_OSD_SLAVE (1 << 1)
#define OSD_FLAGS_RESERVED_1 (1 << 2)
#define OSD_FLAGS_RESERVED_2 (1 << 3)
#define OSD_FLAGS_OSD_HARDWARE_MAX_7456 (1 << 4)
@ -708,9 +693,6 @@ static bool mspCommonProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProce
#if defined(USE_OSD)
osdFlags |= OSD_FLAGS_OSD_FEATURE;
#endif
#if defined(USE_OSD_SLAVE)
osdFlags |= OSD_FLAGS_OSD_SLAVE;
#endif
#ifdef USE_MAX7456
osdFlags |= OSD_FLAGS_OSD_HARDWARE_MAX_7456;
#endif
@ -769,38 +751,6 @@ static bool mspCommonProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProce
return true;
}
#ifdef USE_OSD_SLAVE
static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
{
switch (cmdMSP) {
case MSP_STATUS_EX:
case MSP_STATUS:
sbufWriteU16(dst, getTaskDeltaTime(TASK_SERIAL));
#ifdef USE_I2C
sbufWriteU16(dst, i2cGetErrorCounter());
#else
sbufWriteU16(dst, 0);
#endif
sbufWriteU16(dst, 0); // sensors
sbufWriteU32(dst, 0); // flight modes
sbufWriteU8(dst, 0); // profile
sbufWriteU16(dst, constrain(averageSystemLoadPercent, 0, 100));
if (cmdMSP == MSP_STATUS_EX) {
sbufWriteU8(dst, 1); // max profiles
sbufWriteU8(dst, 0); // control rate profile
} else {
sbufWriteU16(dst, 0); // gyro cycle time
}
break;
default:
return false;
}
return true;
}
#else
static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
{
bool unsupportedCommand = false;
@ -1435,16 +1385,11 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
}
return !unsupportedCommand;
}
#endif // USE_OSD_SLAVE
static mspResult_e mspFcProcessOutCommandWithArg(uint8_t cmdMSP, sbuf_t *src, sbuf_t *dst, mspPostProcessFnPtr *mspPostProcessFn)
{
#if defined(USE_OSD_SLAVE)
UNUSED(dst);
#endif
switch (cmdMSP) {
#if !defined(USE_OSD_SLAVE)
case MSP_BOXNAMES:
{
const int page = sbufBytesRemaining(src) ? sbufReadU8(src) : 0;
@ -1457,7 +1402,6 @@ static mspResult_e mspFcProcessOutCommandWithArg(uint8_t cmdMSP, sbuf_t *src, sb
serializeBoxReply(dst, page, &serializeBoxPermanentIdFn);
}
break;
#endif
case MSP_REBOOT:
if (sbufBytesRemaining(src)) {
rebootMode = sbufReadU8(src);
@ -1555,34 +1499,6 @@ static void mspFcDataFlashReadCommand(sbuf_t *dst, sbuf_t *src)
}
#endif
#ifdef USE_OSD_SLAVE
static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
{
UNUSED(cmdMSP);
UNUSED(src);
switch(cmdMSP) {
case MSP_RESET_CONF:
resetEEPROM();
readEEPROM();
break;
case MSP_EEPROM_WRITE:
if (featureMaskIsCopied) {
writeEEPROMWithFeatures(featureMaskCopy);
} else {
writeEEPROM();
}
readEEPROM();
break;
default:
// we do not know how to handle the (valid) message, indicate error MSP $M!
return MSP_RESULT_ERROR;
}
return MSP_RESULT_ACK;
}
#else
static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
{
uint32_t i;
@ -2403,7 +2319,6 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
}
return MSP_RESULT_ACK;
}
#endif // USE_OSD_SLAVE
static mspResult_e mspCommonProcessInCommand(uint8_t cmdMSP, sbuf_t *src, mspPostProcessFnPtr *mspPostProcessFn)
{
@ -2507,7 +2422,7 @@ static mspResult_e mspCommonProcessInCommand(uint8_t cmdMSP, sbuf_t *src, mspPos
batteryConfigMutable()->currentMeterSource = sbufReadU8(src);
break;
#if defined(USE_OSD) || defined (USE_OSD_SLAVE)
#if defined(USE_OSD)
case MSP_SET_OSD_CONFIG:
{
const uint8_t addr = sbufReadU8(src);
@ -2581,7 +2496,7 @@ static mspResult_e mspCommonProcessInCommand(uint8_t cmdMSP, sbuf_t *src, mspPos
#else
return MSP_RESULT_ERROR;
#endif
#endif // OSD || USE_OSD_SLAVE
#endif // OSD
default:
return mspProcessInCommand(cmdMSP, src);
@ -2630,7 +2545,6 @@ void mspFcProcessReply(mspPacket_t *reply)
UNUSED(src); // potentially unused depending on compile options.
switch (reply->cmd) {
#ifndef OSD_SLAVE
case MSP_ANALOG:
{
uint8_t batteryVoltage = sbufReadU8(src);
@ -2648,50 +2562,10 @@ void mspFcProcessReply(mspPacket_t *reply)
#endif
}
break;
#endif
#ifdef USE_OSD_SLAVE
case MSP_DISPLAYPORT:
{
osdSlaveIsLocked = true; // lock it as soon as a MSP_DISPLAYPORT message is received to prevent accidental CLI/DFU mode.
const int subCmd = sbufReadU8(src);
switch (subCmd) {
case 0: // HEARTBEAT
osdSlaveHeartbeat();
break;
case 1: // RELEASE
break;
case 2: // CLEAR
osdSlaveClearScreen();
break;
case 3:
{
#define MSP_OSD_MAX_STRING_LENGTH 30 // FIXME move this
const uint8_t y = sbufReadU8(src); // row
const uint8_t x = sbufReadU8(src); // column
sbufReadU8(src); // reserved
char buf[MSP_OSD_MAX_STRING_LENGTH + 1];
const int len = MIN(sbufBytesRemaining(src), MSP_OSD_MAX_STRING_LENGTH);
sbufReadData(src, &buf, len);
buf[len] = 0;
osdSlaveWrite(x, y, buf);
}
break;
case 4:
osdSlaveDrawScreen();
break;
}
}
break;
#endif
}
}
void mspInit(void)
{
#ifndef USE_OSD_SLAVE
initActiveBoxIds();
#endif
}

View File

@ -44,7 +44,6 @@
#include "pg/piniobox.h"
#ifndef USE_OSD_SLAVE
// permanent IDs must uniquely identify BOX meaning, DO NOT REUSE THEM!
static const box_t boxes[CHECKBOX_ITEM_COUNT] = {
{ BOXARM, "ARM", 0 },
@ -343,4 +342,3 @@ int packFlightModeFlags(boxBitmask_t *mspFlightModeFlags)
// return count of used bits
return mspBoxIdx;
}
#endif // USE_OSD_SLAVE

View File

@ -166,11 +166,7 @@ static const displayPortVTable_t max7456VTable = {
displayPort_t *max7456DisplayPortInit(const vcdProfile_t *vcdProfile)
{
if (
#ifdef USE_OSD_SLAVE
!max7456Init(max7456Config(), vcdProfile, false)
#else
!max7456Init(max7456Config(), vcdProfile, systemConfig()->cpu_overclock)
#endif
) {
return NULL;
}

View File

@ -104,9 +104,6 @@ typedef enum {
#ifdef USE_OSD
TASK_OSD,
#endif
#ifdef USE_OSD_SLAVE
TASK_OSD_SLAVE,
#endif
#ifdef USE_BST
TASK_BST_MASTER_PROCESS,
#endif