1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-17 13:25:30 +03:00

Merge pull request #4232 from martinbudden/bf_osd_slave_tidy

Tidy use of USE_OSD_SLAVE
This commit is contained in:
Martin Budden 2017-10-09 15:11:21 +01:00 committed by GitHub
commit e760f73edc
9 changed files with 166 additions and 219 deletions

View file

@ -279,7 +279,7 @@ uint16_t getCurrentMinthrottle(void)
{ {
return motorConfig()->minthrottle; return motorConfig()->minthrottle;
} }
#endif #endif // USE_OSD_SLAVE
void resetConfigs(void) void resetConfigs(void)
{ {
@ -319,7 +319,7 @@ void activateConfig(void)
setAccelerationFilter(accelerometerConfig()->acc_lpf_hz); setAccelerationFilter(accelerometerConfig()->acc_lpf_hz);
imuConfigure(throttleCorrectionConfig()->throttle_correction_angle); imuConfigure(throttleCorrectionConfig()->throttle_correction_angle);
#endif #endif // USE_OSD_SLAVE
} }
void validateAndFixConfig(void) void validateAndFixConfig(void)
@ -592,7 +592,7 @@ void validateAndFixGyroConfig(void)
} }
} }
} }
#endif #endif // USE_OSD_SLAVE
void readEEPROM(void) void readEEPROM(void)
{ {

View file

@ -63,7 +63,13 @@ typedef struct pilotConfig_s {
char name[MAX_NAME_LENGTH + 1]; char name[MAX_NAME_LENGTH + 1];
} pilotConfig_t; } pilotConfig_t;
#ifndef USE_OSD_SLAVE #ifdef USE_OSD_SLAVE
typedef struct systemConfig_s {
uint8_t debug_mode;
uint8_t task_statistics;
char boardIdentifier[sizeof(TARGET_BOARD_IDENTIFIER) + 1];
} systemConfig_t;
#else
typedef struct systemConfig_s { typedef struct systemConfig_s {
uint8_t pidProfileIndex; uint8_t pidProfileIndex;
uint8_t activeRateProfile; uint8_t activeRateProfile;
@ -75,15 +81,8 @@ typedef struct systemConfig_s {
uint8_t powerOnArmingGraceTime; // in seconds uint8_t powerOnArmingGraceTime; // in seconds
char boardIdentifier[sizeof(TARGET_BOARD_IDENTIFIER) + 1]; char boardIdentifier[sizeof(TARGET_BOARD_IDENTIFIER) + 1];
} systemConfig_t; } systemConfig_t;
#endif #endif // USE_OSD_SLAVE
#ifdef USE_OSD_SLAVE
typedef struct systemConfig_s {
uint8_t debug_mode;
uint8_t task_statistics;
char boardIdentifier[sizeof(TARGET_BOARD_IDENTIFIER) + 1];
} systemConfig_t;
#endif
PG_DECLARE(pilotConfig_t, pilotConfig); PG_DECLARE(pilotConfig_t, pilotConfig);
PG_DECLARE(systemConfig_t, systemConfig); PG_DECLARE(systemConfig_t, systemConfig);

View file

@ -532,7 +532,7 @@ void init(void)
imuInit(); imuInit();
mspFcInit(); mspInit();
mspSerialInit(); mspSerialInit();
#ifdef USE_CLI #ifdef USE_CLI
@ -724,11 +724,7 @@ void init(void)
setArmingDisabled(ARMING_DISABLED_BOOT_GRACE_TIME); setArmingDisabled(ARMING_DISABLED_BOOT_GRACE_TIME);
#ifdef USE_OSD_SLAVE
osdSlaveTasksInit();
#else
fcTasksInit(); fcTasksInit();
#endif
systemState |= SYSTEM_STATE_READY; systemState |= SYSTEM_STATE_READY;
} }

View file

@ -675,7 +675,7 @@ static bool mspCommonProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProce
} }
#ifdef USE_OSD_SLAVE #ifdef USE_OSD_SLAVE
static bool mspOsdSlaveProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst) static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
{ {
switch (cmdMSP) { switch (cmdMSP) {
case MSP_STATUS_EX: case MSP_STATUS_EX:
@ -703,10 +703,10 @@ static bool mspOsdSlaveProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
} }
return true; return true;
} }
#endif
#ifndef USE_OSD_SLAVE #else
static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
{ {
switch (cmdMSP) { switch (cmdMSP) {
case MSP_STATUS_EX: case MSP_STATUS_EX:
@ -743,7 +743,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
// 1 byte, flag count // 1 byte, flag count
sbufWriteU8(dst, NUM_ARMING_DISABLE_FLAGS); sbufWriteU8(dst, NUM_ARMING_DISABLE_FLAGS);
// 4 bytes, flags // 4 bytes, flags
uint32_t armingDisableFlags = getArmingDisableFlags(); const uint32_t armingDisableFlags = getArmingDisableFlags();
sbufWriteU32(dst, armingDisableFlags); sbufWriteU32(dst, armingDisableFlags);
} }
break; break;
@ -1246,7 +1246,7 @@ static mspResult_e mspFcProcessOutCommandWithArg(uint8_t cmdMSP, sbuf_t *arg, sb
} }
return MSP_RESULT_ACK; return MSP_RESULT_ACK;
} }
#endif #endif // USE_OSD_SLAVE
#ifdef GPS #ifdef GPS
static void mspFcWpCommand(sbuf_t *dst, sbuf_t *src) static void mspFcWpCommand(sbuf_t *dst, sbuf_t *src)
@ -1295,15 +1295,16 @@ static void mspFcDataFlashReadCommand(sbuf_t *dst, sbuf_t *src)
#endif #endif
#ifdef USE_OSD_SLAVE #ifdef USE_OSD_SLAVE
static mspResult_e mspOsdSlaveProcessInCommand(uint8_t cmdMSP, sbuf_t *src) { static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
{
UNUSED(cmdMSP); UNUSED(cmdMSP);
UNUSED(src); UNUSED(src);
return MSP_RESULT_ERROR; return MSP_RESULT_ERROR;
} }
#endif
#ifndef USE_OSD_SLAVE #else
static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
{ {
uint32_t i; uint32_t i;
uint8_t value; uint8_t value;
@ -1928,7 +1929,7 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
} }
return MSP_RESULT_ACK; return MSP_RESULT_ACK;
} }
#endif #endif // USE_OSD_SLAVE
static mspResult_e mspCommonProcessInCommand(uint8_t cmdMSP, sbuf_t *src) static mspResult_e mspCommonProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
{ {
@ -2103,11 +2104,7 @@ static mspResult_e mspCommonProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
#endif // OSD || USE_OSD_SLAVE #endif // OSD || USE_OSD_SLAVE
default: default:
#ifdef USE_OSD_SLAVE return mspProcessInCommand(cmdMSP, src);
return mspOsdSlaveProcessInCommand(cmdMSP, src);
#else
return mspFcProcessInCommand(cmdMSP, src);
#endif
} }
return MSP_RESULT_ACK; return MSP_RESULT_ACK;
} }
@ -2126,16 +2123,12 @@ mspResult_e mspFcProcessCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostPro
if (mspCommonProcessOutCommand(cmdMSP, dst, mspPostProcessFn)) { if (mspCommonProcessOutCommand(cmdMSP, dst, mspPostProcessFn)) {
ret = MSP_RESULT_ACK; ret = MSP_RESULT_ACK;
#ifndef USE_OSD_SLAVE } else if (mspProcessOutCommand(cmdMSP, dst)) {
} else if (mspFcProcessOutCommand(cmdMSP, dst)) {
ret = MSP_RESULT_ACK; ret = MSP_RESULT_ACK;
#ifndef USE_OSD_SLAVE
} else if ((ret = mspFcProcessOutCommandWithArg(cmdMSP, src, dst)) != MSP_RESULT_CMD_UNKNOWN) { } else if ((ret = mspFcProcessOutCommandWithArg(cmdMSP, src, dst)) != MSP_RESULT_CMD_UNKNOWN) {
/* ret */; /* ret */;
#endif #endif
#ifdef USE_OSD_SLAVE
} else if (mspOsdSlaveProcessOutCommand(cmdMSP, dst)) {
ret = MSP_RESULT_ACK;
#endif
#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE #ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
} else if (cmdMSP == MSP_SET_4WAY_IF) { } else if (cmdMSP == MSP_SET_4WAY_IF) {
mspFc4waySerialCommand(dst, src, mspPostProcessFn); mspFc4waySerialCommand(dst, src, mspPostProcessFn);
@ -2180,8 +2173,8 @@ void mspFcProcessReply(mspPacket_t *reply)
#ifdef USE_MSP_CURRENT_METER #ifdef USE_MSP_CURRENT_METER
currentMeterMSPSet(amperage, mAhDrawn); currentMeterMSPSet(amperage, mAhDrawn);
#endif #endif
break;
} }
break;
#endif #endif
#ifdef USE_OSD_SLAVE #ifdef USE_OSD_SLAVE
@ -2189,56 +2182,47 @@ void mspFcProcessReply(mspPacket_t *reply)
{ {
osdSlaveIsLocked = true; // lock it as soon as a MSP_DISPLAYPORT message is received to prevent accidental CLI/DFU mode. osdSlaveIsLocked = true; // lock it as soon as a MSP_DISPLAYPORT message is received to prevent accidental CLI/DFU mode.
int subCmd = sbufReadU8(src); const int subCmd = sbufReadU8(src);
switch (subCmd) { switch (subCmd) {
case 0: // HEARTBEAT case 0: // HEARTBEAT
//debug[0]++; //debug[0]++;
osdSlaveHeartbeat(); osdSlaveHeartbeat();
break; break;
case 1: // RELEASE case 1: // RELEASE
//debug[1]++; //debug[1]++;
break; break;
case 2: // CLEAR case 2: // CLEAR
//debug[2]++; //debug[2]++;
osdSlaveClearScreen(); osdSlaveClearScreen();
break; break;
case 3: { case 3:
{
//debug[3]++; //debug[3]++;
#define MSP_OSD_MAX_STRING_LENGTH 30 // FIXME move this #define MSP_OSD_MAX_STRING_LENGTH 30 // FIXME move this
const uint8_t y = sbufReadU8(src); // row const uint8_t y = sbufReadU8(src); // row
const uint8_t x = sbufReadU8(src); // column const uint8_t x = sbufReadU8(src); // column
const uint8_t reserved = sbufReadU8(src); sbufReadU8(src); // reserved
UNUSED(reserved);
char buf[MSP_OSD_MAX_STRING_LENGTH + 1]; char buf[MSP_OSD_MAX_STRING_LENGTH + 1];
const int len = MIN(sbufBytesRemaining(src), MSP_OSD_MAX_STRING_LENGTH); const int len = MIN(sbufBytesRemaining(src), MSP_OSD_MAX_STRING_LENGTH);
sbufReadData(src, &buf, len); sbufReadData(src, &buf, len);
buf[len] = 0; buf[len] = 0;
osdSlaveWrite(x, y, buf); osdSlaveWrite(x, y, buf);
break;
}
case 4: {
osdSlaveDrawScreen();
} }
break;
case 4:
osdSlaveDrawScreen();
break;
} }
break;
} }
break;
#endif #endif
} }
} }
#ifdef USE_OSD_SLAVE void mspInit(void)
void mspOsdSlaveInit(void)
{
}
#else
void mspFcInit(void)
{ {
#ifndef USE_OSD_SLAVE
initActiveBoxIds(); initActiveBoxIds();
#endif
} }
#endif // USE_OSD_SLAVE

View file

@ -19,8 +19,7 @@
#include "msp/msp.h" #include "msp/msp.h"
void mspFcInit(void); void mspInit(void);
void mspOsdSlaveInit(void);
mspResult_e mspFcProcessCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostProcessFnPtr *mspPostProcessFn); mspResult_e mspFcProcessCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostProcessFnPtr *mspPostProcessFn);
void mspFcProcessReply(mspPacket_t *reply); void mspFcProcessReply(mspPacket_t *reply);

View file

@ -21,36 +21,32 @@
#include <platform.h> #include <platform.h>
#include "cms/cms.h"
#include "build/debug.h" #include "build/debug.h"
#include "common/axis.h" #include "cms/cms.h"
#include "common/color.h" #include "common/color.h"
#include "common/utils.h" #include "common/utils.h"
#include "common/filter.h"
#include "config/feature.h" #include "config/feature.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
#include "drivers/sensor.h"
#include "drivers/accgyro/accgyro.h" #include "drivers/accgyro/accgyro.h"
#include "drivers/camera_control.h"
#include "drivers/compass/compass.h" #include "drivers/compass/compass.h"
#include "drivers/sensor.h"
#include "drivers/serial.h" #include "drivers/serial.h"
#include "drivers/stack_check.h" #include "drivers/stack_check.h"
#include "drivers/vtx_common.h"
#include "drivers/transponder_ir.h" #include "drivers/transponder_ir.h"
#include "drivers/camera_control.h" #include "drivers/vtx_common.h"
#include "fc/cli.h"
#include "fc/config.h" #include "fc/config.h"
#include "fc/fc_core.h"
#include "fc/fc_dispatch.h"
#include "fc/fc_msp.h" #include "fc/fc_msp.h"
#include "fc/fc_tasks.h" #include "fc/fc_tasks.h"
#include "fc/fc_core.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/runtime_config.h" #include "fc/runtime_config.h"
#include "fc/cli.h"
#include "fc/fc_dispatch.h"
#include "flight/altitude.h" #include "flight/altitude.h"
#include "flight/imu.h" #include "flight/imu.h"
@ -63,6 +59,7 @@
#include "io/ledstrip.h" #include "io/ledstrip.h"
#include "io/osd.h" #include "io/osd.h"
#include "io/osd_slave.h" #include "io/osd_slave.h"
#include "io/rcsplit.h"
#include "io/serial.h" #include "io/serial.h"
#include "io/transponder_ir.h" #include "io/transponder_ir.h"
#include "io/vtx_tramp.h" // Will be gone #include "io/vtx_tramp.h" // Will be gone
@ -71,21 +68,19 @@
#include "rx/rx.h" #include "rx/rx.h"
#include "sensors/sensors.h"
#include "sensors/acceleration.h" #include "sensors/acceleration.h"
#include "sensors/barometer.h" #include "sensors/barometer.h"
#include "sensors/battery.h" #include "sensors/battery.h"
#include "sensors/compass.h" #include "sensors/compass.h"
#include "sensors/gyro.h"
#include "sensors/sonar.h"
#include "sensors/esc_sensor.h" #include "sensors/esc_sensor.h"
#include "sensors/gyro.h"
#include "sensors/sensors.h"
#include "sensors/sonar.h"
#include "scheduler/scheduler.h" #include "scheduler/scheduler.h"
#include "telemetry/telemetry.h" #include "telemetry/telemetry.h"
#include "io/osd_slave.h"
#include "io/rcsplit.h"
#ifdef USE_BST #ifdef USE_BST
void taskBstMasterProcess(timeUs_t currentTimeUs); void taskBstMasterProcess(timeUs_t currentTimeUs);
@ -95,17 +90,9 @@ void taskBstMasterProcess(timeUs_t currentTimeUs);
#define TASK_PERIOD_MS(ms) ((ms) * 1000) #define TASK_PERIOD_MS(ms) ((ms) * 1000)
#define TASK_PERIOD_US(us) (us) #define TASK_PERIOD_US(us) (us)
#ifndef USE_OSD_SLAVE bool taskSerialCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTimeUs)
static void taskUpdateAccelerometer(timeUs_t currentTimeUs)
{ {
UNUSED(currentTimeUs); UNUSED(currentTimeUs);
accUpdate(&accelerometerConfigMutable()->accelerometerTrims);
}
#endif
bool taskSerialCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTimeUs) {
UNUSED(currentTimeUs);
UNUSED(currentDeltaTimeUs); UNUSED(currentDeltaTimeUs);
return mspSerialWaiting(); return mspSerialWaiting();
@ -140,6 +127,13 @@ void taskBatteryAlerts(timeUs_t currentTimeUs)
} }
#ifndef USE_OSD_SLAVE #ifndef USE_OSD_SLAVE
static void taskUpdateAccelerometer(timeUs_t currentTimeUs)
{
UNUSED(currentTimeUs);
accUpdate(&accelerometerConfigMutable()->accelerometerTrims);
}
static void taskUpdateRxMain(timeUs_t currentTimeUs) static void taskUpdateRxMain(timeUs_t currentTimeUs)
{ {
processRx(currentTimeUs); processRx(currentTimeUs);
@ -227,39 +221,13 @@ void taskVtxControl(uint32_t currentTime)
} }
#endif #endif
#ifdef USE_OSD_SLAVE
void osdSlaveTasksInit(void)
{
schedulerInit();
setTaskEnabled(TASK_SERIAL, true);
bool useBatteryVoltage = batteryConfig()->voltageMeterSource != VOLTAGE_METER_NONE;
setTaskEnabled(TASK_BATTERY_VOLTAGE, useBatteryVoltage);
bool useBatteryCurrent = batteryConfig()->currentMeterSource != CURRENT_METER_NONE;
setTaskEnabled(TASK_BATTERY_CURRENT, useBatteryCurrent);
bool useBatteryAlerts = (batteryConfig()->useVBatAlerts || batteryConfig()->useConsumptionAlerts);
setTaskEnabled(TASK_BATTERY_ALERTS, (useBatteryVoltage || useBatteryCurrent) && useBatteryAlerts);
#ifdef TRANSPONDER
setTaskEnabled(TASK_TRANSPONDER, feature(FEATURE_TRANSPONDER));
#endif
setTaskEnabled(TASK_OSD_SLAVE, true);
#ifdef STACK_CHECK
setTaskEnabled(TASK_STACK_CHECK, true);
#endif
}
#endif
#ifndef USE_OSD_SLAVE
#ifdef USE_CAMERA_CONTROL #ifdef USE_CAMERA_CONTROL
void taskCameraControl(uint32_t currentTime) void taskCameraControl(uint32_t currentTime)
{ {
if (ARMING_FLAG(ARMED)) if (ARMING_FLAG(ARMED)) {
return; return;
}
cameraControlProcess(currentTime); cameraControlProcess(currentTime);
} }
@ -268,7 +236,30 @@ void taskCameraControl(uint32_t currentTime)
void fcTasksInit(void) void fcTasksInit(void)
{ {
schedulerInit(); schedulerInit();
setTaskEnabled(TASK_SERIAL, true);
const bool useBatteryVoltage = batteryConfig()->voltageMeterSource != VOLTAGE_METER_NONE;
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 || feature(FEATURE_OSD);
#endif
setTaskEnabled(TASK_BATTERY_ALERTS, (useBatteryVoltage || useBatteryCurrent) && useBatteryAlerts);
#ifdef TRANSPONDER
setTaskEnabled(TASK_TRANSPONDER, feature(FEATURE_TRANSPONDER));
#endif
#ifdef STACK_CHECK
setTaskEnabled(TASK_STACK_CHECK, true);
#endif
#ifdef USE_OSD_SLAVE
setTaskEnabled(TASK_OSD_SLAVE, true);
#else
if (sensors(SENSOR_GYRO)) { if (sensors(SENSOR_GYRO)) {
rescheduleTask(TASK_GYROPID, gyro.targetLooptime); rescheduleTask(TASK_GYROPID, gyro.targetLooptime);
setTaskEnabled(TASK_GYROPID, true); setTaskEnabled(TASK_GYROPID, true);
@ -280,16 +271,9 @@ void fcTasksInit(void)
} }
setTaskEnabled(TASK_ATTITUDE, sensors(SENSOR_ACC)); setTaskEnabled(TASK_ATTITUDE, sensors(SENSOR_ACC));
setTaskEnabled(TASK_SERIAL, true);
rescheduleTask(TASK_SERIAL, TASK_PERIOD_HZ(serialConfig()->serial_update_rate_hz)); rescheduleTask(TASK_SERIAL, TASK_PERIOD_HZ(serialConfig()->serial_update_rate_hz));
bool useBatteryVoltage = batteryConfig()->voltageMeterSource != VOLTAGE_METER_NONE;
setTaskEnabled(TASK_BATTERY_VOLTAGE, useBatteryVoltage);
bool useBatteryCurrent = batteryConfig()->currentMeterSource != CURRENT_METER_NONE;
setTaskEnabled(TASK_BATTERY_CURRENT, useBatteryCurrent);
bool useBatteryAlerts = batteryConfig()->useVBatAlerts || batteryConfig()->useConsumptionAlerts || feature(FEATURE_OSD);
setTaskEnabled(TASK_BATTERY_ALERTS, (useBatteryVoltage || useBatteryCurrent) && useBatteryAlerts);
setTaskEnabled(TASK_RX, true); setTaskEnabled(TASK_RX, true);
@ -341,9 +325,6 @@ void fcTasksInit(void)
#ifdef OSD #ifdef OSD
setTaskEnabled(TASK_OSD, feature(FEATURE_OSD)); setTaskEnabled(TASK_OSD, feature(FEATURE_OSD));
#endif #endif
#ifdef USE_OSD_SLAVE
setTaskEnabled(TASK_OSD_SLAVE, true);
#endif
#ifdef USE_BST #ifdef USE_BST
setTaskEnabled(TASK_BST_MASTER_PROCESS, true); setTaskEnabled(TASK_BST_MASTER_PROCESS, true);
#endif #endif
@ -357,9 +338,6 @@ void fcTasksInit(void)
setTaskEnabled(TASK_CMS, feature(FEATURE_OSD) || feature(FEATURE_DASHBOARD)); setTaskEnabled(TASK_CMS, feature(FEATURE_OSD) || feature(FEATURE_DASHBOARD));
#endif #endif
#endif #endif
#ifdef STACK_CHECK
setTaskEnabled(TASK_STACK_CHECK, true);
#endif
#ifdef VTX_CONTROL #ifdef VTX_CONTROL
#if defined(VTX_RTC6705) || defined(VTX_SMARTAUDIO) || defined(VTX_TRAMP) #if defined(VTX_RTC6705) || defined(VTX_SMARTAUDIO) || defined(VTX_TRAMP)
setTaskEnabled(TASK_VTXCTRL, true); setTaskEnabled(TASK_VTXCTRL, true);
@ -371,8 +349,8 @@ void fcTasksInit(void)
#ifdef USE_RCSPLIT #ifdef USE_RCSPLIT
setTaskEnabled(TASK_RCSPLIT, rcSplitIsEnabled()); setTaskEnabled(TASK_RCSPLIT, rcSplitIsEnabled());
#endif #endif
}
#endif #endif
}
cfTask_t cfTasks[TASK_COUNT] = { cfTask_t cfTasks[TASK_COUNT] = {
[TASK_SYSTEM] = { [TASK_SYSTEM] = {
@ -382,7 +360,68 @@ cfTask_t cfTasks[TASK_COUNT] = {
.staticPriority = TASK_PRIORITY_MEDIUM_HIGH, .staticPriority = TASK_PRIORITY_MEDIUM_HIGH,
}, },
#ifndef USE_OSD_SLAVE [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] = {
.taskName = "BATTERY_ALERTS",
.taskFunc = taskBatteryAlerts,
.desiredPeriod = TASK_PERIOD_HZ(5), // 5 Hz
.staticPriority = TASK_PRIORITY_MEDIUM,
},
[TASK_BATTERY_VOLTAGE] = {
.taskName = "BATTERY_VOLTAGE",
.taskFunc = batteryUpdateVoltage,
.desiredPeriod = TASK_PERIOD_HZ(50),
.staticPriority = TASK_PRIORITY_MEDIUM,
},
[TASK_BATTERY_CURRENT] = {
.taskName = "BATTERY_CURRENT",
.taskFunc = batteryUpdateCurrentMeter,
.desiredPeriod = TASK_PERIOD_HZ(50),
.staticPriority = TASK_PRIORITY_MEDIUM,
},
#ifdef TRANSPONDER
[TASK_TRANSPONDER] = {
.taskName = "TRANSPONDER",
.taskFunc = transponderUpdate,
.desiredPeriod = TASK_PERIOD_HZ(250), // 250 Hz, 4ms
.staticPriority = TASK_PRIORITY_LOW,
},
#endif
#ifdef STACK_CHECK
[TASK_STACK_CHECK] = {
.taskName = "STACKCHECK",
.taskFunc = taskStackCheck,
.desiredPeriod = TASK_PERIOD_HZ(10), // 10 Hz
.staticPriority = TASK_PRIORITY_IDLE,
},
#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] = { [TASK_GYROPID] = {
.taskName = "PID", .taskName = "PID",
.subTaskName = "GYRO", .subTaskName = "GYRO",
@ -412,50 +451,13 @@ cfTask_t cfTasks[TASK_COUNT] = {
.desiredPeriod = TASK_PERIOD_HZ(50), // If event-based scheduling doesn't work, fallback to periodic scheduling .desiredPeriod = TASK_PERIOD_HZ(50), // If event-based scheduling doesn't work, fallback to periodic scheduling
.staticPriority = TASK_PRIORITY_HIGH, .staticPriority = TASK_PRIORITY_HIGH,
}, },
#endif
[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
},
#ifndef USE_OSD_SLAVE
[TASK_DISPATCH] = { [TASK_DISPATCH] = {
.taskName = "DISPATCH", .taskName = "DISPATCH",
.taskFunc = dispatchProcess, .taskFunc = dispatchProcess,
.desiredPeriod = TASK_PERIOD_HZ(1000), .desiredPeriod = TASK_PERIOD_HZ(1000),
.staticPriority = TASK_PRIORITY_HIGH, .staticPriority = TASK_PRIORITY_HIGH,
}, },
#endif
[TASK_BATTERY_ALERTS] = {
.taskName = "BATTERY_ALERTS",
.taskFunc = taskBatteryAlerts,
.desiredPeriod = TASK_PERIOD_HZ(5), // 5 Hz
.staticPriority = TASK_PRIORITY_MEDIUM,
},
[TASK_BATTERY_VOLTAGE] = {
.taskName = "BATTERY_VOLTAGE",
.taskFunc = batteryUpdateVoltage,
.desiredPeriod = TASK_PERIOD_HZ(50),
.staticPriority = TASK_PRIORITY_MEDIUM,
},
[TASK_BATTERY_CURRENT] = {
.taskName = "BATTERY_CURRENT",
.taskFunc = batteryUpdateCurrentMeter,
.desiredPeriod = TASK_PERIOD_HZ(50),
.staticPriority = TASK_PRIORITY_MEDIUM,
},
#ifndef USE_OSD_SLAVE
#ifdef BEEPER #ifdef BEEPER
[TASK_BEEPER] = { [TASK_BEEPER] = {
@ -510,18 +512,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
.staticPriority = TASK_PRIORITY_LOW, .staticPriority = TASK_PRIORITY_LOW,
}, },
#endif #endif
#endif
#ifdef TRANSPONDER
[TASK_TRANSPONDER] = {
.taskName = "TRANSPONDER",
.taskFunc = transponderUpdate,
.desiredPeriod = TASK_PERIOD_HZ(250), // 250 Hz, 4ms
.staticPriority = TASK_PRIORITY_LOW,
},
#endif
#ifndef USE_OSD_SLAVE
#ifdef USE_DASHBOARD #ifdef USE_DASHBOARD
[TASK_DASHBOARD] = { [TASK_DASHBOARD] = {
.taskName = "DASHBOARD", .taskName = "DASHBOARD",
@ -530,6 +521,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
.staticPriority = TASK_PRIORITY_LOW, .staticPriority = TASK_PRIORITY_LOW,
}, },
#endif #endif
#ifdef OSD #ifdef OSD
[TASK_OSD] = { [TASK_OSD] = {
.taskName = "OSD", .taskName = "OSD",
@ -538,19 +530,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
.staticPriority = TASK_PRIORITY_LOW, .staticPriority = TASK_PRIORITY_LOW,
}, },
#endif #endif
#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,
},
#endif
#ifndef USE_OSD_SLAVE
#ifdef TELEMETRY #ifdef TELEMETRY
[TASK_TELEMETRY] = { [TASK_TELEMETRY] = {
.taskName = "TELEMETRY", .taskName = "TELEMETRY",
@ -596,15 +576,6 @@ cfTask_t cfTasks[TASK_COUNT] = {
}, },
#endif #endif
#ifdef STACK_CHECK
[TASK_STACK_CHECK] = {
.taskName = "STACKCHECK",
.taskFunc = taskStackCheck,
.desiredPeriod = TASK_PERIOD_HZ(10), // 10 Hz
.staticPriority = TASK_PRIORITY_IDLE,
},
#endif
#ifdef VTX_CONTROL #ifdef VTX_CONTROL
[TASK_VTXCTRL] = { [TASK_VTXCTRL] = {
.taskName = "VTXCTRL", .taskName = "VTXCTRL",

View file

@ -20,4 +20,3 @@
#define LOOPTIME_SUSPEND_TIME 3 // Prevent too long busy wait times #define LOOPTIME_SUSPEND_TIME 3 // Prevent too long busy wait times
void fcTasksInit(void); void fcTasksInit(void);
void osdSlaveTasksInit(void);

View file

@ -17,7 +17,6 @@
#pragma once #pragma once
#ifndef USE_OSD_SLAVE
#include <stdbool.h> #include <stdbool.h>
#include "common/time.h" #include "common/time.h"
#include "config/parameter_group.h" #include "config/parameter_group.h"
@ -108,7 +107,9 @@ typedef struct pidProfile_s {
uint16_t itermLimit; uint16_t itermLimit;
} pidProfile_t; } pidProfile_t;
#ifndef USE_OSD_SLAVE
PG_DECLARE_ARRAY(pidProfile_t, MAX_PROFILE_COUNT, pidProfiles); PG_DECLARE_ARRAY(pidProfile_t, MAX_PROFILE_COUNT, pidProfiles);
#endif
typedef struct pidConfig_s { typedef struct pidConfig_s {
uint8_t pid_process_denom; // Processing denominator for PID controller vs gyro sampling rate uint8_t pid_process_denom; // Processing denominator for PID controller vs gyro sampling rate
@ -133,5 +134,3 @@ void pidInitFilters(const pidProfile_t *pidProfile);
void pidInitConfig(const pidProfile_t *pidProfile); void pidInitConfig(const pidProfile_t *pidProfile);
void pidInit(const pidProfile_t *pidProfile); void pidInit(const pidProfile_t *pidProfile);
void pidCopyProfile(uint8_t dstPidProfileIndex, uint8_t srcPidProfileIndex); void pidCopyProfile(uint8_t dstPidProfileIndex, uint8_t srcPidProfileIndex);
#endif

View file

@ -244,7 +244,7 @@ void init(void)
LED0_OFF; LED0_OFF;
LED1_OFF; LED1_OFF;
mspOsdSlaveInit(); mspInit();
mspSerialInit(); mspSerialInit();
#ifdef USE_CLI #ifdef USE_CLI
@ -287,7 +287,7 @@ void init(void)
// Latch active features AGAIN since some may be modified by init(). // Latch active features AGAIN since some may be modified by init().
latchActiveFeatures(); latchActiveFeatures();
osdSlaveTasksInit(); fcTasksInit();
systemState |= SYSTEM_STATE_READY; systemState |= SYSTEM_STATE_READY;
} }