diff --git a/Makefile b/Makefile
index a641d79bd9..834fcd28f2 100644
--- a/Makefile
+++ b/Makefile
@@ -90,6 +90,7 @@ FEATURES =
OFFICIAL_TARGETS = ALIENFLIGHTF3 ALIENFLIGHTF4 ANYFCF7 BETAFLIGHTF3 BLUEJAYF4 CC3D FURYF4 NAZE REVO SIRINFPV SPARKY SPRACINGF3 SPRACINGF3EVO SPRACINGF3NEO SPRACINGF4EVO STM32F3DISCOVERY
ALT_TARGETS = $(sort $(filter-out target, $(basename $(notdir $(wildcard $(ROOT)/src/main/target/*/*.mk)))))
OPBL_TARGETS = $(filter %_OPBL, $(ALT_TARGETS))
+OSD_SLAVE_TARGETS = SPRACINGF3OSD
VALID_TARGETS = $(dir $(wildcard $(ROOT)/src/main/target/*/target.mk))
VALID_TARGETS := $(subst /,, $(subst ./src/main/target/,, $(VALID_TARGETS)))
@@ -188,6 +189,15 @@ ifeq ($(filter $(TARGET),$(OPBL_TARGETS)), $(TARGET))
OPBL = yes
endif
+ifeq ($(filter $(TARGET),$(OSD_SLAVE_TARGETS)), $(TARGET))
+# build an OSD SLAVE
+OSD_SLAVE = yes
+else
+# build an FC
+FC = yes
+endif
+
+
# silently ignore if the file is not present. Allows for target specific.
-include $(ROOT)/src/main/target/$(BASE_TARGET)/target.mk
@@ -664,36 +674,53 @@ COMMON_SRC = \
drivers/bus_spi_soft.c \
drivers/display.c \
drivers/exti.c \
- drivers/gyro_sync.c \
drivers/io.c \
drivers/light_led.c \
drivers/resource.c \
+ drivers/rcc.c \
+ drivers/serial.c \
+ drivers/serial_uart.c \
+ drivers/sound_beeper.c \
+ drivers/stack_check.c \
+ drivers/system.c \
+ drivers/timer.c \
+ drivers/transponder_ir.c \
+ fc/config.c \
+ fc/fc_dispatch.c \
+ fc/fc_hardfaults.c \
+ fc/fc_msp.c \
+ fc/fc_tasks.c \
+ fc/rc_controls.c \
+ fc/runtime_config.c \
+ io/beeper.c \
+ io/serial.c \
+ io/statusindicator.c \
+ io/transponder_ir.c \
+ msp/msp_serial.c \
+ scheduler/scheduler.c \
+ sensors/battery.c \
+ sensors/current.c \
+ sensors/voltage.c \
+
+OSD_SLAVE_SRC = \
+ io/displayport_max7456.c \
+ osd_slave/osd_slave_init.c \
+ io/osd_slave.c
+
+FC_SRC = \
+ fc/fc_init.c \
+ fc/controlrate_profile.c \
+ drivers/gyro_sync.c \
drivers/rx_nrf24l01.c \
drivers/rx_spi.c \
drivers/rx_xn297.c \
drivers/pwm_esc_detect.c \
drivers/pwm_output.c \
- drivers/rcc.c \
drivers/rx_pwm.c \
- drivers/serial.c \
- drivers/serial_uart.c \
drivers/serial_softserial.c \
- drivers/sound_beeper.c \
- drivers/stack_check.c \
- drivers/system.c \
- drivers/timer.c \
- fc/config.c \
- fc/controlrate_profile.c \
- fc/fc_init.c \
- fc/fc_dispatch.c \
- fc/fc_hardfaults.c \
fc/fc_core.c \
- fc/fc_rc.c \
- fc/fc_msp.c \
- fc/fc_tasks.c \
fc/rc_adjustments.c \
- fc/rc_controls.c \
- fc/runtime_config.c \
+ fc/fc_rc.c \
fc/cli.c \
flight/altitude.c \
flight/failsafe.c \
@@ -701,13 +728,9 @@ COMMON_SRC = \
flight/mixer.c \
flight/pid.c \
flight/servos.c \
- io/beeper.c \
- io/serial.c \
io/serial_4way.c \
io/serial_4way_avrootloader.c \
io/serial_4way_stk500v2.c \
- io/statusindicator.c \
- msp/msp_serial.c \
rx/ibus.c \
rx/jetiexbus.c \
rx/msp.c \
@@ -725,11 +748,7 @@ COMMON_SRC = \
rx/sumd.c \
rx/sumh.c \
rx/xbus.c \
- scheduler/scheduler.c \
sensors/acceleration.c \
- sensors/battery.c \
- sensors/current.c \
- sensors/voltage.c \
sensors/boardalignment.c \
sensors/compass.c \
sensors/gyro.c \
@@ -761,8 +780,6 @@ COMMON_SRC = \
io/gps.c \
io/ledstrip.c \
io/osd.c \
- io/osd_slave.c \
- io/transponder_ir.c \
sensors/sonar.c \
sensors/barometer.c \
telemetry/telemetry.c \
@@ -779,10 +796,20 @@ COMMON_SRC = \
io/vtx_string.c \
io/vtx_smartaudio.c \
io/vtx_tramp.c \
- io/vtx.c \
+ io/vtx.c
+
+COMMON_DEVICE_SRC = \
$(CMSIS_SRC) \
$(DEVICE_STDPERIPH_SRC)
+ifeq ($(OSD_SLAVE),yes)
+TARGET_FLAGS := -DUSE_OSD_SLAVE $(TARGET_FLAGS)
+COMMON_SRC := $(COMMON_SRC) $(OSD_SLAVE_SRC) $(COMMON_DEVICE_SRC)
+else
+TARGET_FLAGS := -DUSE_FC $(TARGET_FLAGS)
+COMMON_SRC := $(COMMON_SRC) $(FC_SRC) $(COMMON_DEVICE_SRC)
+endif
+
SPEED_OPTIMISED_SRC := ""
SIZE_OPTIMISED_SRC := ""
diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c
index a0c06a8c2f..1c66e2826f 100644
--- a/src/main/blackbox/blackbox.c
+++ b/src/main/blackbox/blackbox.c
@@ -35,7 +35,6 @@
#include "common/maths.h"
#include "common/utils.h"
-#include "config/config_profile.h"
#include "config/feature.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c
index c69d10671a..b39fe1a926 100644
--- a/src/main/blackbox/blackbox_io.c
+++ b/src/main/blackbox/blackbox_io.c
@@ -18,7 +18,6 @@
#include "common/maths.h"
#include "common/printf.h"
-#include "config/config_profile.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
diff --git a/src/main/cms/cms.c b/src/main/cms/cms.c
index f7e106a3e1..cf0ce0bf35 100644
--- a/src/main/cms/cms.c
+++ b/src/main/cms/cms.c
@@ -45,7 +45,6 @@
#include "drivers/system.h"
// For rcData, stopAllMotors, stopPwmAllMotors
-#include "config/config_profile.h"
#include "config/feature.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
diff --git a/src/main/cms/cms_menu_blackbox.c b/src/main/cms/cms_menu_blackbox.c
index 1429a2a6f8..ac42ad85e4 100644
--- a/src/main/cms/cms_menu_blackbox.c
+++ b/src/main/cms/cms_menu_blackbox.c
@@ -40,7 +40,6 @@
#include "common/utils.h"
-#include "config/config_profile.h"
#include "config/feature.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
diff --git a/src/main/cms/cms_menu_imu.c b/src/main/cms/cms_menu_imu.c
index 7d900dcee1..4a1730c083 100644
--- a/src/main/cms/cms_menu_imu.c
+++ b/src/main/cms/cms_menu_imu.c
@@ -37,7 +37,6 @@
#include "common/utils.h"
-#include "config/config_profile.h"
#include "config/feature.h"
#include "config/parameter_group.h"
diff --git a/src/main/cms/cms_menu_ledstrip.c b/src/main/cms/cms_menu_ledstrip.c
index fb6a38ec87..c422845ffd 100644
--- a/src/main/cms/cms_menu_ledstrip.c
+++ b/src/main/cms/cms_menu_ledstrip.c
@@ -30,7 +30,6 @@
#include "cms/cms_types.h"
#include "cms/cms_menu_ledstrip.h"
-#include "config/config_profile.h"
#include "config/feature.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
diff --git a/src/main/cms/cms_menu_misc.c b/src/main/cms/cms_menu_misc.c
index 079f15515e..b257fb25f3 100644
--- a/src/main/cms/cms_menu_misc.c
+++ b/src/main/cms/cms_menu_misc.c
@@ -34,7 +34,6 @@
#include "common/utils.h"
-#include "config/config_profile.h"
#include "config/feature.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
diff --git a/src/main/cms/cms_menu_osd.c b/src/main/cms/cms_menu_osd.c
index 6508ebe9b5..4fc9f233c3 100644
--- a/src/main/cms/cms_menu_osd.c
+++ b/src/main/cms/cms_menu_osd.c
@@ -32,7 +32,6 @@
#include "common/utils.h"
-#include "config/config_profile.h"
#include "config/feature.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
diff --git a/src/main/cms/cms_menu_vtx.c b/src/main/cms/cms_menu_vtx.c
index 91bde81258..0f14e4c3ab 100644
--- a/src/main/cms/cms_menu_vtx.c
+++ b/src/main/cms/cms_menu_vtx.c
@@ -33,7 +33,6 @@
#include "common/utils.h"
-#include "config/config_profile.h"
#include "config/feature.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c
index 1050444ed7..47a9a2e669 100755
--- a/src/main/fc/cli.c
+++ b/src/main/fc/cli.c
@@ -49,7 +49,6 @@ extern uint8_t __config_end;
#include "common/utils.h"
#include "config/config_eeprom.h"
-#include "config/config_profile.h"
#include "config/feature.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
diff --git a/src/main/fc/config.c b/src/main/fc/config.c
index b808ce704e..d10116b56d 100755
--- a/src/main/fc/config.c
+++ b/src/main/fc/config.c
@@ -35,7 +35,6 @@
#include "common/maths.h"
#include "config/config_eeprom.h"
-#include "config/config_profile.h"
#include "config/feature.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
@@ -67,6 +66,7 @@
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
+#ifdef USE_FC
#include "flight/altitude.h"
#include "flight/failsafe.h"
#include "flight/imu.h"
@@ -74,6 +74,7 @@
#include "flight/navigation.h"
#include "flight/pid.h"
#include "flight/servos.h"
+#endif
#include "io/beeper.h"
#include "io/gimbal.h"
@@ -98,7 +99,9 @@
#include "telemetry/telemetry.h"
+#ifdef USE_FC
pidProfile_t *currentPidProfile;
+#endif
#ifndef DEFAULT_FEATURES
#define DEFAULT_FEATURES 0
@@ -118,13 +121,22 @@ PG_RESET_TEMPLATE(featureConfig_t, featureConfig,
PG_REGISTER_WITH_RESET_TEMPLATE(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 0);
+#ifdef USE_FC
PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
.pidProfileIndex = 0,
.activeRateProfile = 0,
.debug_mode = DEBUG_MODE,
.task_statistics = true,
- .name = { 0 }
+ .name = { 0 } // FIXME misplaced, see PG_PILOT_CONFIG in CF v1.x
);
+#endif
+
+#ifdef USE_OSD_SLAVE
+PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
+ .debug_mode = DEBUG_MODE,
+ .task_statistics = true
+);
+#endif
#ifdef BEEPER
PG_REGISTER(beeperConfig_t, beeperConfig, PG_BEEPER_CONFIG, 0);
@@ -447,6 +459,7 @@ void pgResetFn_statusLedConfig(statusLedConfig_t *statusLedConfig)
;
}
+#ifdef USE_FC
uint8_t getCurrentPidProfileIndex(void)
{
return systemConfig()->pidProfileIndex;
@@ -470,6 +483,7 @@ uint16_t getCurrentMinthrottle(void)
{
return motorConfig()->minthrottle;
}
+#endif
void resetConfigs(void)
{
@@ -481,8 +495,10 @@ void resetConfigs(void)
pgActivateProfile(0);
+#ifdef USE_FC
setPidProfile(0);
setControlRateProfile(0);
+#endif
#ifdef LED_STRIP
reevaluateLedConfig();
@@ -491,6 +507,7 @@ void resetConfigs(void)
void activateConfig(void)
{
+#ifdef USE_FC
generateThrottleCurve();
resetAdjustmentStates();
@@ -509,10 +526,12 @@ void activateConfig(void)
imuConfigure(throttleCorrectionConfig()->throttle_correction_angle);
configureAltitudeHold(currentPidProfile);
+#endif
}
void validateAndFixConfig(void)
{
+#ifdef USE_FC
if((motorConfig()->dev.motorPwmProtocol == PWM_TYPE_BRUSHED) && (motorConfig()->mincommand < 1000)){
motorConfigMutable()->mincommand = 1000;
}
@@ -571,22 +590,24 @@ void validateAndFixConfig(void)
}
#endif
- if (!isSerialConfigValid(serialConfig())) {
- pgResetFn_serialConfig(serialConfigMutable());
- }
-
// Prevent invalid notch cutoff
if (currentPidProfile->dterm_notch_cutoff >= currentPidProfile->dterm_notch_hz) {
currentPidProfile->dterm_notch_hz = 0;
}
validateAndFixGyroConfig();
+#endif
+
+ if (!isSerialConfigValid(serialConfig())) {
+ pgResetFn_serialConfig(serialConfigMutable());
+ }
#if defined(TARGET_VALIDATECONFIG)
targetValidateConfiguration();
#endif
}
+#ifdef USE_FC
void validateAndFixGyroConfig(void)
{
// Prevent invalid notch cutoff
@@ -662,16 +683,19 @@ void validateAndFixGyroConfig(void)
motorConfigMutable()->dev.motorPwmRate = maxEscRate;
}
}
+#endif
void readEEPROM(void)
{
+#ifdef USE_FC
suspendRxSignal();
+#endif
// Sanity check, read flash
if (!loadEEPROM()) {
failureMode(FAILURE_INVALID_EEPROM_CONTENTS);
}
-
+#ifdef USE_FC
if (systemConfig()->activeRateProfile >= CONTROL_RATE_PROFILE_COUNT) {// sanity check
systemConfigMutable()->activeRateProfile = 0;
}
@@ -681,20 +705,27 @@ void readEEPROM(void)
systemConfigMutable()->pidProfileIndex = 0;
}
setPidProfile(systemConfig()->pidProfileIndex);
+#endif
validateAndFixConfig();
activateConfig();
+#ifdef USE_FC
resumeRxSignal();
+#endif
}
void writeEEPROM(void)
{
+#ifdef USE_FC
suspendRxSignal();
+#endif
writeConfigToEEPROM();
+#ifdef USE_FC
resumeRxSignal();
+#endif
}
void resetEEPROM(void)
@@ -718,6 +749,7 @@ void saveConfigAndNotify(void)
beeperConfirmationBeeps(1);
}
+#ifdef USE_FC
void changePidProfile(uint8_t pidProfileIndex)
{
if (pidProfileIndex >= MAX_PROFILE_COUNT) {
@@ -727,6 +759,7 @@ void changePidProfile(uint8_t pidProfileIndex)
currentPidProfile = pidProfilesMutable(pidProfileIndex);
beeperConfirmationBeeps(pidProfileIndex + 1);
}
+#endif
void beeperOffSet(uint32_t mask)
{
diff --git a/src/main/fc/config.h b/src/main/fc/config.h
index 08d439e55e..d993d96c19 100644
--- a/src/main/fc/config.h
+++ b/src/main/fc/config.h
@@ -30,8 +30,6 @@
#include "drivers/sound_beeper.h"
#include "drivers/vcd.h"
-#define MAX_NAME_LENGTH 16
-
typedef enum {
FEATURE_RX_PPM = 1 << 0,
//FEATURE_VBAT = 1 << 1,
@@ -64,13 +62,24 @@ typedef enum {
FEATURE_ANTI_GRAVITY = 1 << 28,
} features_e;
+#define MAX_NAME_LENGTH 16
+
+#ifdef USE_FC
typedef struct systemConfig_s {
uint8_t pidProfileIndex;
uint8_t activeRateProfile;
uint8_t debug_mode;
uint8_t task_statistics;
- char name[MAX_NAME_LENGTH + 1];
+ char name[MAX_NAME_LENGTH + 1]; // FIXME misplaced, see PG_PILOT_CONFIG in CF v1.x
} systemConfig_t;
+#endif
+
+#ifdef USE_OSD_SLAVE
+typedef struct systemConfig_s {
+ uint8_t debug_mode;
+ uint8_t task_statistics;
+} systemConfig_t;
+#endif
PG_DECLARE(systemConfig_t, systemConfig);
PG_DECLARE(adcConfig_t, adcConfig);
diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c
index 6c0cf3b10b..69f0d5603d 100644
--- a/src/main/fc/fc_core.c
+++ b/src/main/fc/fc_core.c
@@ -29,7 +29,6 @@
#include "common/maths.h"
#include "common/utils.h"
-#include "config/config_profile.h"
#include "config/feature.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
diff --git a/src/main/fc/fc_hardfaults.c b/src/main/fc/fc_hardfaults.c
index 11ca57d2e2..0468c0048d 100644
--- a/src/main/fc/fc_hardfaults.c
+++ b/src/main/fc/fc_hardfaults.c
@@ -93,11 +93,14 @@ void HardFault_Handler(void)
{
LED2_ON;
+#ifdef USE_FC
// fall out of the sky
uint8_t requiredStateForMotors = SYSTEM_STATE_CONFIG_LOADED | SYSTEM_STATE_MOTORS_READY;
if ((systemState & requiredStateForMotors) == requiredStateForMotors) {
stopMotors();
}
+#endif
+
#ifdef TRANSPONDER
// prevent IR LEDs from burning out.
uint8_t requiredStateForTransponder = SYSTEM_STATE_CONFIG_LOADED | SYSTEM_STATE_TRANSPONDER_ENABLED;
diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c
index 9bcc7d2e5c..09dde1fa13 100644
--- a/src/main/fc/fc_init.c
+++ b/src/main/fc/fc_init.c
@@ -29,7 +29,6 @@
#include "common/printf.h"
#include "config/config_eeprom.h"
-#include "config/config_profile.h"
#include "config/feature.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c
index 845e1228c8..ed09f9cc88 100755
--- a/src/main/fc/fc_msp.c
+++ b/src/main/fc/fc_msp.c
@@ -34,7 +34,6 @@
#include "common/streambuf.h"
#include "config/config_eeprom.h"
-#include "config/config_profile.h"
#include "config/feature.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
@@ -109,11 +108,10 @@
#include "hardware_revision.h"
#endif
-extern uint16_t cycleTime; // FIXME dependency on mw.c
-
static const char * const flightControllerIdentifier = BETAFLIGHT_IDENTIFIER; // 4 UPPER CASE alpha numeric characters that identify the flight controller.
static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER;
+#ifdef USE_FC
static const box_t boxes[CHECKBOX_ITEM_COUNT + 1] = {
{ BOXARM, "ARM", 0 },
{ BOXANGLE, "ANGLE", 1 },
@@ -180,6 +178,7 @@ typedef enum {
} mspSDCardFlags_e;
#define RATEPROFILE_MASK (1 << 7)
+#endif
#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
#define ESC_4WAY 0xff
@@ -244,13 +243,16 @@ static void mspRebootFn(serialPort_t *serialPort)
{
UNUSED(serialPort);
+#ifdef USE_FC
stopPwmAllMotors();
+#endif
systemReset();
// control should never return here.
while (true) ;
}
+#ifdef USE_FC
const box_t *findBoxByBoxId(uint8_t boxId)
{
for (uint8_t boxIndex = 0; boxIndex < sizeof(boxes) / sizeof(box_t); boxIndex++) {
@@ -537,12 +539,13 @@ static void serializeDataflashReadReply(sbuf_t *dst, uint32_t address, const uin
}
}
#endif
+#endif
/*
* Returns true if the command was processd, false otherwise.
* May set mspPostProcessFunc to a function to be called once the command has been processed
*/
-static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFnPtr *mspPostProcessFn)
+static bool mspCommonProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFnPtr *mspPostProcessFn)
{
switch (cmdMSP) {
case MSP_API_VERSION:
@@ -585,6 +588,240 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
sbufWriteData(dst, shortGitRevision, GIT_SHORT_REVISION_LENGTH);
break;
+ case MSP_REBOOT:
+ if (mspPostProcessFn) {
+ *mspPostProcessFn = mspRebootFn;
+ }
+ break;
+
+ case MSP_ANALOG:
+ sbufWriteU8(dst, (uint8_t)constrain(getBatteryVoltage(), 0, 255));
+ sbufWriteU16(dst, (uint16_t)constrain(getMAhDrawn(), 0, 0xFFFF)); // milliamp hours drawn from battery
+ sbufWriteU16(dst, 0); // rssi
+ sbufWriteU16(dst, (int16_t)constrain(getAmperage(), -0x8000, 0x7FFF)); // send current in 0.01 A steps, range is -320A to 320A
+ break;
+
+ case MSP_DEBUG:
+ // output some useful QA statistics
+ // debug[x] = ((hse_value / 1000000) * 1000) + (SystemCoreClock / 1000000); // XX0YY [crystal clock : core clock]
+
+ for (int i = 0; i < DEBUG16_VALUE_COUNT; i++) {
+ sbufWriteU16(dst, debug[i]); // 4 variables are here for general monitoring purpose
+ }
+ break;
+
+ case MSP_UID:
+ sbufWriteU32(dst, U_ID_0);
+ sbufWriteU32(dst, U_ID_1);
+ sbufWriteU32(dst, U_ID_2);
+ break;
+
+ case MSP_FEATURE_CONFIG:
+ sbufWriteU32(dst, featureMask());
+ break;
+
+ case MSP_BATTERY_STATE: {
+ // battery characteristics
+ sbufWriteU8(dst, (uint8_t)constrain(getBatteryCellCount(), 0, 255)); // 0 indicates battery not detected.
+ sbufWriteU16(dst, batteryConfig()->batteryCapacity); // in mAh
+
+ // battery state
+ sbufWriteU8(dst, (uint8_t)constrain(getBatteryVoltage(), 0, 255)); // in 0.1V steps
+ sbufWriteU16(dst, (uint16_t)constrain(getMAhDrawn(), 0, 0xFFFF)); // milliamp hours drawn from battery
+ sbufWriteU16(dst, (int16_t)constrain(getAmperage(), -0x8000, 0x7FFF)); // send current in 0.01 A steps, range is -320A to 320A
+
+ // battery alerts
+ sbufWriteU8(dst, (uint8_t)getBatteryState());
+ break;
+ }
+ case MSP_VOLTAGE_METERS:
+ // write out id and voltage meter values, once for each meter we support
+ for (int i = 0; i < supportedVoltageMeterCount; i++) {
+
+ voltageMeter_t meter;
+ uint8_t id = (uint8_t)voltageMeterIds[i];
+ voltageMeterRead(id, &meter);
+
+ sbufWriteU8(dst, id);
+ sbufWriteU8(dst, (uint8_t)constrain(meter.filtered, 0, 255));
+ }
+ break;
+
+ case MSP_CURRENT_METERS:
+ // write out id and current meter values, once for each meter we support
+ for (int i = 0; i < supportedCurrentMeterCount; i++) {
+
+ currentMeter_t meter;
+ uint8_t id = (uint8_t)currentMeterIds[i];
+ currentMeterRead(id, &meter);
+
+ sbufWriteU8(dst, id);
+ sbufWriteU16(dst, (uint16_t)constrain(meter.mAhDrawn, 0, 0xFFFF)); // milliamp hours drawn from battery
+ sbufWriteU16(dst, (uint16_t)constrain(meter.amperage * 10, 0, 0xFFFF)); // send amperage in 0.001 A steps (mA). Negative range is truncated to zero
+ }
+ break;
+
+ case MSP_VOLTAGE_METER_CONFIG:
+ // by using a sensor type and a sub-frame length it's possible to configure any type of voltage meter,
+ // e.g. an i2c/spi/can sensor or any sensor not built directly into the FC such as ESC/RX/SPort/SBus that has
+ // different configuration requirements.
+ BUILD_BUG_ON(VOLTAGE_SENSOR_ADC_VBAT != 0); // VOLTAGE_SENSOR_ADC_VBAT should be the first index,
+ sbufWriteU8(dst, MAX_VOLTAGE_SENSOR_ADC); // voltage meters in payload
+ for (int i = VOLTAGE_SENSOR_ADC_VBAT; i < MAX_VOLTAGE_SENSOR_ADC; i++) {
+ const uint8_t adcSensorSubframeLength = 1 + 1 + 1 + 1 + 1; // length of id, type, vbatscale, vbatresdivval, vbatresdivmultipler, in bytes
+ sbufWriteU8(dst, adcSensorSubframeLength); // ADC sensor sub-frame length
+
+ sbufWriteU8(dst, voltageMeterADCtoIDMap[i]); // id of the sensor
+ sbufWriteU8(dst, VOLTAGE_SENSOR_TYPE_ADC_RESISTOR_DIVIDER); // indicate the type of sensor that the next part of the payload is for
+
+ sbufWriteU8(dst, voltageSensorADCConfig(i)->vbatscale);
+ sbufWriteU8(dst, voltageSensorADCConfig(i)->vbatresdivval);
+ sbufWriteU8(dst, voltageSensorADCConfig(i)->vbatresdivmultiplier);
+ }
+ // if we had any other voltage sensors, this is where we would output any needed configuration
+ break;
+
+ case MSP_CURRENT_METER_CONFIG: {
+ // the ADC and VIRTUAL sensors have the same configuration requirements, however this API reflects
+ // that this situation may change and allows us to support configuration of any current sensor with
+ // specialist configuration requirements.
+
+ sbufWriteU8(dst, 2); // current meters in payload (adc + virtual)
+
+ const uint8_t adcSensorSubframeLength = 1 + 1 + 2 + 2; // length of id, type, scale, offset, in bytes
+ sbufWriteU8(dst, adcSensorSubframeLength);
+ sbufWriteU8(dst, CURRENT_METER_ID_BATTERY_1); // the id of the sensor
+ sbufWriteU8(dst, CURRENT_SENSOR_ADC); // indicate the type of sensor that the next part of the payload is for
+ sbufWriteU16(dst, currentSensorADCConfig()->scale);
+ sbufWriteU16(dst, currentSensorADCConfig()->offset);
+
+ const int8_t virtualSensorSubframeLength = 1 + 1 + 2 + 2; // length of id, type, scale, offset, in bytes
+ sbufWriteU8(dst, virtualSensorSubframeLength);
+ sbufWriteU8(dst, CURRENT_METER_ID_VIRTUAL_1); // the id of the sensor
+ sbufWriteU8(dst, CURRENT_SENSOR_VIRTUAL); // indicate the type of sensor that the next part of the payload is for
+ sbufWriteU16(dst, currentSensorVirtualConfig()->scale);
+ sbufWriteU16(dst, currentSensorVirtualConfig()->offset);
+
+ // if we had any other current sensors, this is where we would output any needed configuration
+ break;
+ }
+ case MSP_BATTERY_CONFIG:
+ sbufWriteU8(dst, batteryConfig()->vbatmincellvoltage);
+ sbufWriteU8(dst, batteryConfig()->vbatmaxcellvoltage);
+ sbufWriteU8(dst, batteryConfig()->vbatwarningcellvoltage);
+ sbufWriteU16(dst, batteryConfig()->batteryCapacity);
+ sbufWriteU8(dst, batteryConfig()->voltageMeterSource);
+ sbufWriteU8(dst, batteryConfig()->currentMeterSource);
+ break;
+
+
+ case MSP_TRANSPONDER_CONFIG:
+#ifdef TRANSPONDER
+ sbufWriteU8(dst, 1); //Transponder supported
+ for (unsigned int i = 0; i < sizeof(transponderConfig()->data); i++) {
+ sbufWriteU8(dst, transponderConfig()->data[i]);
+ }
+#else
+ sbufWriteU8(dst, 0); // Transponder not supported
+#endif
+ break;
+
+ case MSP_OSD_CONFIG: {
+
+#define OSD_FLAGS_OSD_FEATURE (1 << 0)
+#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)
+
+ uint8_t osdFlags = 0;
+#if defined(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
+
+ sbufWriteU8(dst, osdFlags);
+
+#ifdef USE_MAX7456
+ // send video system (AUTO/PAL/NTSC)
+ sbufWriteU8(dst, vcdProfile()->video_system);
+#else
+ sbufWriteU8(dst, 0);
+#endif
+
+#ifdef OSD
+ // OSD specific, not applicable to OSD slaves.
+ sbufWriteU8(dst, osdConfig()->units);
+ sbufWriteU8(dst, osdConfig()->rssi_alarm);
+ sbufWriteU16(dst, osdConfig()->cap_alarm);
+ sbufWriteU16(dst, osdConfig()->time_alarm);
+ sbufWriteU16(dst, osdConfig()->alt_alarm);
+ for (int i = 0; i < OSD_ITEM_COUNT; i++) {
+ sbufWriteU16(dst, osdConfig()->item_pos[i]);
+ }
+#endif
+ break;
+ }
+
+ default:
+ return false;
+ }
+ return true;
+}
+
+#ifdef USE_OSD_SLAVE
+static bool mspOsdSlaveProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFnPtr *mspPostProcessFn)
+{
+ UNUSED(mspPostProcessFn);
+
+ switch (cmdMSP) {
+ case MSP_STATUS_EX:
+ sbufWriteU16(dst, 0); // task delta
+#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));
+ sbufWriteU8(dst, 1); // max profiles
+ sbufWriteU8(dst, 0); // control rate profile
+ break;
+
+ case MSP_STATUS:
+ sbufWriteU16(dst, 0); // task delta
+#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));
+ sbufWriteU16(dst, 0); // gyro cycle time
+ break;
+
+ default:
+ return false;
+ }
+ return true;
+}
+#endif
+
+#ifdef USE_FC
+static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFnPtr *mspPostProcessFn)
+{
+ UNUSED(mspPostProcessFn);
+
+ switch (cmdMSP) {
case MSP_STATUS_EX:
sbufWriteU16(dst, getTaskDeltaTime(TASK_GYROPID));
#ifdef USE_I2C
@@ -600,15 +837,6 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
sbufWriteU8(dst, getCurrentControlRateProfileIndex());
break;
- case MSP_NAME:
- {
- const int nameLen = strlen(systemConfig()->name);
- for (int i = 0; i < nameLen; i++) {
- sbufWriteU8(dst, systemConfig()->name[i]);
- }
- }
- break;
-
case MSP_STATUS:
sbufWriteU16(dst, getTaskDeltaTime(TASK_GYROPID));
#ifdef USE_I2C
@@ -639,6 +867,15 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
}
break;
+ case MSP_NAME:
+ {
+ const int nameLen = strlen(systemConfig()->name);
+ for (int i = 0; i < nameLen; i++) {
+ sbufWriteU8(dst, systemConfig()->name[i]);
+ }
+ }
+ break;
+
#ifdef USE_SERVOS
case MSP_SERVO:
sbufWriteData(dst, &servo, MAX_SUPPORTED_SERVOS * 2);
@@ -649,8 +886,6 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
sbufWriteU16(dst, servoParams(i)->max);
sbufWriteU16(dst, servoParams(i)->middle);
sbufWriteU8(dst, servoParams(i)->rate);
- sbufWriteU8(dst, servoParams(i)->angleAtMin);
- sbufWriteU8(dst, servoParams(i)->angleAtMax);
sbufWriteU8(dst, servoParams(i)->forwardFromChannel);
sbufWriteU32(dst, servoParams(i)->reversedSources);
}
@@ -708,11 +943,10 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
#endif
break;
- case MSP_ANALOG:
- sbufWriteU8(dst, (uint8_t)constrain(getBatteryVoltage(), 0, 255));
- sbufWriteU16(dst, (uint16_t)constrain(getMAhDrawn(), 0, 0xFFFF)); // milliamp hours drawn from battery
- sbufWriteU16(dst, rssi);
- sbufWriteU16(dst, (int16_t)constrain(getAmperage(), -0x8000, 0x7FFF)); // send current in 0.01 A steps, range is -320A to 320A
+ case MSP_BOARD_ALIGNMENT_CONFIG:
+ sbufWriteU16(dst, boardAlignment()->rollDegrees);
+ sbufWriteU16(dst, boardAlignment()->pitchDegrees);
+ sbufWriteU16(dst, boardAlignment()->yawDegrees);
break;
case MSP_ARMING_CONFIG:
@@ -836,130 +1070,11 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
break;
#endif
- case MSP_DEBUG:
- // output some useful QA statistics
- // debug[x] = ((hse_value / 1000000) * 1000) + (SystemCoreClock / 1000000); // XX0YY [crystal clock : core clock]
-
- for (int i = 0; i < DEBUG16_VALUE_COUNT; i++) {
- sbufWriteU16(dst, debug[i]); // 4 variables are here for general monitoring purpose
- }
- break;
-
case MSP_ACC_TRIM:
sbufWriteU16(dst, accelerometerConfig()->accelerometerTrims.values.pitch);
sbufWriteU16(dst, accelerometerConfig()->accelerometerTrims.values.roll);
break;
- case MSP_UID:
- sbufWriteU32(dst, U_ID_0);
- sbufWriteU32(dst, U_ID_1);
- sbufWriteU32(dst, U_ID_2);
- break;
-
- case MSP_FEATURE_CONFIG:
- sbufWriteU32(dst, featureMask());
- break;
-
- case MSP_BOARD_ALIGNMENT_CONFIG:
- sbufWriteU16(dst, boardAlignment()->rollDegrees);
- sbufWriteU16(dst, boardAlignment()->pitchDegrees);
- sbufWriteU16(dst, boardAlignment()->yawDegrees);
- break;
-
- case MSP_BATTERY_STATE: {
- // battery characteristics
- sbufWriteU8(dst, (uint8_t)constrain(getBatteryCellCount(), 0, 255)); // 0 indicates battery not detected.
- sbufWriteU16(dst, batteryConfig()->batteryCapacity); // in mAh
-
- // battery state
- sbufWriteU8(dst, (uint8_t)constrain(getBatteryVoltage(), 0, 255)); // in 0.1V steps
- sbufWriteU16(dst, (uint16_t)constrain(getMAhDrawn(), 0, 0xFFFF)); // milliamp hours drawn from battery
- sbufWriteU16(dst, (int16_t)constrain(getAmperage(), -0x8000, 0x7FFF)); // send current in 0.01 A steps, range is -320A to 320A
-
- // battery alerts
- sbufWriteU8(dst, (uint8_t)getBatteryState());
- break;
- }
- case MSP_VOLTAGE_METERS:
- // write out id and voltage meter values, once for each meter we support
- for (int i = 0; i < supportedVoltageMeterCount; i++) {
-
- voltageMeter_t meter;
- uint8_t id = (uint8_t)voltageMeterIds[i];
- voltageMeterRead(id, &meter);
-
- sbufWriteU8(dst, id);
- sbufWriteU8(dst, (uint8_t)constrain(meter.filtered, 0, 255));
- }
- break;
-
- case MSP_CURRENT_METERS:
- // write out id and current meter values, once for each meter we support
- for (int i = 0; i < supportedCurrentMeterCount; i++) {
-
- currentMeter_t meter;
- uint8_t id = (uint8_t)currentMeterIds[i];
- currentMeterRead(id, &meter);
-
- sbufWriteU8(dst, id);
- sbufWriteU16(dst, (uint16_t)constrain(meter.mAhDrawn, 0, 0xFFFF)); // milliamp hours drawn from battery
- sbufWriteU16(dst, (uint16_t)constrain(meter.amperage * 10, 0, 0xFFFF)); // send amperage in 0.001 A steps (mA). Negative range is truncated to zero
- }
- break;
-
- case MSP_VOLTAGE_METER_CONFIG:
- // by using a sensor type and a sub-frame length it's possible to configure any type of voltage meter,
- // e.g. an i2c/spi/can sensor or any sensor not built directly into the FC such as ESC/RX/SPort/SBus that has
- // different configuration requirements.
- BUILD_BUG_ON(VOLTAGE_SENSOR_ADC_VBAT != 0); // VOLTAGE_SENSOR_ADC_VBAT should be the first index,
- sbufWriteU8(dst, MAX_VOLTAGE_SENSOR_ADC); // voltage meters in payload
- for (int i = VOLTAGE_SENSOR_ADC_VBAT; i < MAX_VOLTAGE_SENSOR_ADC; i++) {
- const uint8_t adcSensorSubframeLength = 1 + 1 + 1 + 1 + 1; // length of id, type, vbatscale, vbatresdivval, vbatresdivmultipler, in bytes
- sbufWriteU8(dst, adcSensorSubframeLength); // ADC sensor sub-frame length
-
- sbufWriteU8(dst, voltageMeterADCtoIDMap[i]); // id of the sensor
- sbufWriteU8(dst, VOLTAGE_SENSOR_TYPE_ADC_RESISTOR_DIVIDER); // indicate the type of sensor that the next part of the payload is for
-
- sbufWriteU8(dst, voltageSensorADCConfig(i)->vbatscale);
- sbufWriteU8(dst, voltageSensorADCConfig(i)->vbatresdivval);
- sbufWriteU8(dst, voltageSensorADCConfig(i)->vbatresdivmultiplier);
- }
- // if we had any other voltage sensors, this is where we would output any needed configuration
- break;
-
- case MSP_CURRENT_METER_CONFIG: {
- // the ADC and VIRTUAL sensors have the same configuration requirements, however this API reflects
- // that this situation may change and allows us to support configuration of any current sensor with
- // specialist configuration requirements.
-
- sbufWriteU8(dst, 2); // current meters in payload (adc + virtual)
-
- const uint8_t adcSensorSubframeLength = 1 + 1 + 2 + 2; // length of id, type, scale, offset, in bytes
- sbufWriteU8(dst, adcSensorSubframeLength);
- sbufWriteU8(dst, CURRENT_METER_ID_BATTERY_1); // the id of the sensor
- sbufWriteU8(dst, CURRENT_SENSOR_ADC); // indicate the type of sensor that the next part of the payload is for
- sbufWriteU16(dst, currentSensorADCConfig()->scale);
- sbufWriteU16(dst, currentSensorADCConfig()->offset);
-
- const int8_t virtualSensorSubframeLength = 1 + 1 + 2 + 2; // length of id, type, scale, offset, in bytes
- sbufWriteU8(dst, virtualSensorSubframeLength);
- sbufWriteU8(dst, CURRENT_METER_ID_VIRTUAL_1); // the id of the sensor
- sbufWriteU8(dst, CURRENT_SENSOR_VIRTUAL); // indicate the type of sensor that the next part of the payload is for
- sbufWriteU16(dst, currentSensorVirtualConfig()->scale);
- sbufWriteU16(dst, currentSensorVirtualConfig()->offset);
-
- // if we had any other current sensors, this is where we would output any needed configuration
- break;
- }
- case MSP_BATTERY_CONFIG:
- sbufWriteU8(dst, batteryConfig()->vbatmincellvoltage);
- sbufWriteU8(dst, batteryConfig()->vbatmaxcellvoltage);
- sbufWriteU8(dst, batteryConfig()->vbatwarningcellvoltage);
- sbufWriteU16(dst, batteryConfig()->batteryCapacity);
- sbufWriteU8(dst, batteryConfig()->voltageMeterSource);
- sbufWriteU8(dst, batteryConfig()->currentMeterSource);
- break;
-
case MSP_MIXER_CONFIG:
sbufWriteU8(dst, mixerConfig()->mixerMode);
break;
@@ -1094,58 +1209,6 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
serializeSDCardSummaryReply(dst);
break;
- case MSP_TRANSPONDER_CONFIG:
-#ifdef TRANSPONDER
- sbufWriteU8(dst, 1); //Transponder supported
- for (unsigned int i = 0; i < sizeof(transponderConfig()->data); i++) {
- sbufWriteU8(dst, transponderConfig()->data[i]);
- }
-#else
- sbufWriteU8(dst, 0); // Transponder not supported
-#endif
- break;
-
- case MSP_OSD_CONFIG: {
-
-#define OSD_FLAGS_OSD_FEATURE (1 << 0)
-#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)
-
- uint8_t osdFlags = 0;
-#if defined(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
-
- sbufWriteU8(dst, osdFlags);
-
-#ifdef USE_MAX7456
- // send video system (AUTO/PAL/NTSC)
- sbufWriteU8(dst, vcdProfile()->video_system);
-#else
- sbufWriteU8(dst, 0);
-#endif
-
-#ifdef OSD
- // OSD specific, not applicable to OSD slaves.
- sbufWriteU8(dst, osdConfig()->units);
- sbufWriteU8(dst, osdConfig()->rssi_alarm);
- sbufWriteU16(dst, osdConfig()->cap_alarm);
- sbufWriteU16(dst, osdConfig()->time_alarm);
- sbufWriteU16(dst, osdConfig()->alt_alarm);
- for (int i = 0; i < OSD_ITEM_COUNT; i++) {
- sbufWriteU16(dst, osdConfig()->item_pos[i]);
- }
-#endif
- break;
- }
case MSP_MOTOR_3D_CONFIG:
sbufWriteU16(dst, flight3DConfig()->deadband3d_low);
sbufWriteU16(dst, flight3DConfig()->deadband3d_high);
@@ -1218,12 +1281,6 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
sbufWriteU8(dst, compassConfig()->mag_hardware);
break;
- case MSP_REBOOT:
- if (mspPostProcessFn) {
- *mspPostProcessFn = mspRebootFn;
- }
- break;
-
#if defined(VTX_COMMON)
case MSP_VTX_CONFIG:
{
@@ -1258,6 +1315,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
}
return true;
}
+#endif
#ifdef GPS
static void mspFcWpCommand(sbuf_t *dst, sbuf_t *src)
@@ -1301,6 +1359,16 @@ static void mspFcDataFlashReadCommand(sbuf_t *dst, sbuf_t *src)
}
#endif
+#ifdef USE_OSD_SLAVE
+static mspResult_e mspOsdSlaveProcessInCommand(uint8_t cmdMSP, sbuf_t *src) {
+ UNUSED(cmdMSP);
+ UNUSED(src);
+ // Nothing OSD SLAVE specific yet.
+ return MSP_RESULT_ERROR;
+}
+#endif
+
+#ifdef USE_FC
static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
{
uint32_t i;
@@ -1637,75 +1705,6 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
break;
#endif
-#ifdef TRANSPONDER
- case MSP_SET_TRANSPONDER_CONFIG:
- if (dataSize != sizeof(transponderConfig()->data)) {
- return MSP_RESULT_ERROR;
- }
- for (unsigned int i = 0; i < sizeof(transponderConfig()->data); i++) {
- transponderConfigMutable()->data[i] = sbufReadU8(src);
- }
- transponderUpdateData();
- break;
-#endif
-
-#if defined(OSD) || defined (USE_OSD_SLAVE)
- case MSP_SET_OSD_CONFIG:
- {
- const uint8_t addr = sbufReadU8(src);
- // set all the other settings
- if ((int8_t)addr == -1) {
-#ifdef USE_MAX7456
- vcdProfileMutable()->video_system = sbufReadU8(src);
-#else
- sbufReadU8(src); // Skip video system
-#endif
-#if defined(OSD)
- osdConfigMutable()->units = sbufReadU8(src);
- osdConfigMutable()->rssi_alarm = sbufReadU8(src);
- osdConfigMutable()->cap_alarm = sbufReadU16(src);
- osdConfigMutable()->time_alarm = sbufReadU16(src);
- osdConfigMutable()->alt_alarm = sbufReadU16(src);
-#endif
- } else {
-#if defined(OSD)
- // set a position setting
- const uint16_t pos = sbufReadU16(src);
- if (addr < OSD_ITEM_COUNT) {
- osdConfigMutable()->item_pos[addr] = pos;
- }
-#else
- return MSP_RESULT_ERROR;
-#endif
- }
- }
- break;
-
- case MSP_OSD_CHAR_WRITE:
-#ifdef USE_MAX7456
- {
- uint8_t font_data[64];
- const uint8_t addr = sbufReadU8(src);
- for (int i = 0; i < 54; i++) {
- font_data[i] = sbufReadU8(src);
- }
- // !!TODO - replace this with a device independent implementation
- max7456WriteNvm(addr, font_data);
- }
-#else
- return MSP_RESULT_ERROR;
-/*
- // just discard the data
- sbufReadU8(src);
- for (int i = 0; i < 54; i++) {
- sbufReadU8(src);
- }
-*/
-#endif
- break;
-#endif // OSD || USE_OSD_SLAVE
-
-
#if defined(USE_RTC6705) || defined(VTX_COMMON)
case MSP_SET_VTX_CONFIG:
{
@@ -1804,59 +1803,6 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
boardAlignmentMutable()->yawDegrees = sbufReadU16(src);
break;
- case MSP_SET_VOLTAGE_METER_CONFIG: {
- int id = sbufReadU8(src);
-
- //
- // find and configure an ADC voltage sensor
- //
- int voltageSensorADCIndex;
- for (voltageSensorADCIndex = 0; voltageSensorADCIndex < MAX_VOLTAGE_SENSOR_ADC; voltageSensorADCIndex++) {
- if (id == voltageMeterADCtoIDMap[voltageSensorADCIndex]) {
- break;
- }
- }
-
- if (voltageSensorADCIndex < MAX_VOLTAGE_SENSOR_ADC) {
- voltageSensorADCConfigMutable(voltageSensorADCIndex)->vbatscale = sbufReadU8(src);
- voltageSensorADCConfigMutable(voltageSensorADCIndex)->vbatresdivval = sbufReadU8(src);
- voltageSensorADCConfigMutable(voltageSensorADCIndex)->vbatresdivmultiplier = sbufReadU8(src);
- } else {
- // if we had any other types of voltage sensor to configure, this is where we'd do it.
- return -1;
- }
- break;
- }
-
- case MSP_SET_CURRENT_METER_CONFIG: {
- int id = sbufReadU8(src);
-
- switch (id) {
- case CURRENT_METER_ID_BATTERY_1:
- currentSensorADCConfigMutable()->scale = sbufReadU16(src);
- currentSensorADCConfigMutable()->offset = sbufReadU16(src);
- break;
- case CURRENT_METER_ID_VIRTUAL_1:
- currentSensorVirtualConfigMutable()->scale = sbufReadU16(src);
- currentSensorVirtualConfigMutable()->offset = sbufReadU16(src);
- break;
-
- default:
- return -1;
- }
-
- break;
- }
-
- case MSP_SET_BATTERY_CONFIG:
- batteryConfigMutable()->vbatmincellvoltage = sbufReadU8(src); // vbatlevel_warn1 in MWC2.3 GUI
- batteryConfigMutable()->vbatmaxcellvoltage = sbufReadU8(src); // vbatlevel_warn2 in MWC2.3 GUI
- batteryConfigMutable()->vbatwarningcellvoltage = sbufReadU8(src); // vbatlevel when buzzer starts to alert
- batteryConfigMutable()->batteryCapacity = sbufReadU16(src);
- batteryConfigMutable()->voltageMeterSource = sbufReadU8(src);
- batteryConfigMutable()->currentMeterSource = sbufReadU8(src);
- break;
-
case MSP_SET_MIXER_CONFIG:
#ifndef USE_QUAD_MIXER_ONLY
mixerConfigMutable()->mixerMode = sbufReadU8(src);
@@ -2013,6 +1959,145 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
}
return MSP_RESULT_ACK;
}
+#endif
+
+static mspResult_e mspCommonProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
+{
+// uint32_t i;
+// uint8_t value;
+ const unsigned int dataSize = sbufBytesRemaining(src);
+
+ switch (cmdMSP) {
+#ifdef TRANSPONDER
+ case MSP_SET_TRANSPONDER_CONFIG:
+ if (dataSize != sizeof(transponderConfig()->data)) {
+ return MSP_RESULT_ERROR;
+ }
+ for (unsigned int i = 0; i < sizeof(transponderConfig()->data); i++) {
+ transponderConfigMutable()->data[i] = sbufReadU8(src);
+ }
+ transponderUpdateData();
+ break;
+#endif
+
+ case MSP_SET_VOLTAGE_METER_CONFIG: {
+ int id = sbufReadU8(src);
+
+ //
+ // find and configure an ADC voltage sensor
+ //
+ int voltageSensorADCIndex;
+ for (voltageSensorADCIndex = 0; voltageSensorADCIndex < MAX_VOLTAGE_SENSOR_ADC; voltageSensorADCIndex++) {
+ if (id == voltageMeterADCtoIDMap[voltageSensorADCIndex]) {
+ break;
+ }
+ }
+
+ if (voltageSensorADCIndex < MAX_VOLTAGE_SENSOR_ADC) {
+ voltageSensorADCConfigMutable(voltageSensorADCIndex)->vbatscale = sbufReadU8(src);
+ voltageSensorADCConfigMutable(voltageSensorADCIndex)->vbatresdivval = sbufReadU8(src);
+ voltageSensorADCConfigMutable(voltageSensorADCIndex)->vbatresdivmultiplier = sbufReadU8(src);
+ } else {
+ // if we had any other types of voltage sensor to configure, this is where we'd do it.
+ return -1;
+ }
+ break;
+ }
+
+ case MSP_SET_CURRENT_METER_CONFIG: {
+ int id = sbufReadU8(src);
+
+ switch (id) {
+ case CURRENT_METER_ID_BATTERY_1:
+ currentSensorADCConfigMutable()->scale = sbufReadU16(src);
+ currentSensorADCConfigMutable()->offset = sbufReadU16(src);
+ break;
+ case CURRENT_METER_ID_VIRTUAL_1:
+ currentSensorVirtualConfigMutable()->scale = sbufReadU16(src);
+ currentSensorVirtualConfigMutable()->offset = sbufReadU16(src);
+ break;
+
+ default:
+ return -1;
+ }
+
+ break;
+ }
+
+ case MSP_SET_BATTERY_CONFIG:
+ batteryConfigMutable()->vbatmincellvoltage = sbufReadU8(src); // vbatlevel_warn1 in MWC2.3 GUI
+ batteryConfigMutable()->vbatmaxcellvoltage = sbufReadU8(src); // vbatlevel_warn2 in MWC2.3 GUI
+ batteryConfigMutable()->vbatwarningcellvoltage = sbufReadU8(src); // vbatlevel when buzzer starts to alert
+ batteryConfigMutable()->batteryCapacity = sbufReadU16(src);
+ batteryConfigMutable()->voltageMeterSource = sbufReadU8(src);
+ batteryConfigMutable()->currentMeterSource = sbufReadU8(src);
+ break;
+
+#if defined(OSD) || defined (USE_OSD_SLAVE)
+ case MSP_SET_OSD_CONFIG:
+ {
+ const uint8_t addr = sbufReadU8(src);
+ // set all the other settings
+ if ((int8_t)addr == -1) {
+#ifdef USE_MAX7456
+ vcdProfileMutable()->video_system = sbufReadU8(src);
+#else
+ sbufReadU8(src); // Skip video system
+#endif
+#if defined(OSD)
+ osdConfigMutable()->units = sbufReadU8(src);
+ osdConfigMutable()->rssi_alarm = sbufReadU8(src);
+ osdConfigMutable()->cap_alarm = sbufReadU16(src);
+ osdConfigMutable()->time_alarm = sbufReadU16(src);
+ osdConfigMutable()->alt_alarm = sbufReadU16(src);
+#endif
+ } else {
+#if defined(OSD)
+ // set a position setting
+ const uint16_t pos = sbufReadU16(src);
+ if (addr < OSD_ITEM_COUNT) {
+ osdConfigMutable()->item_pos[addr] = pos;
+ }
+#else
+ return MSP_RESULT_ERROR;
+#endif
+ }
+ }
+ break;
+
+ case MSP_OSD_CHAR_WRITE:
+#ifdef USE_MAX7456
+ {
+ uint8_t font_data[64];
+ const uint8_t addr = sbufReadU8(src);
+ for (int i = 0; i < 54; i++) {
+ font_data[i] = sbufReadU8(src);
+ }
+ // !!TODO - replace this with a device independent implementation
+ max7456WriteNvm(addr, font_data);
+ }
+#else
+ return MSP_RESULT_ERROR;
+/*
+ // just discard the data
+ sbufReadU8(src);
+ for (int i = 0; i < 54; i++) {
+ sbufReadU8(src);
+ }
+*/
+#endif
+ break;
+#endif // OSD || USE_OSD_SLAVE
+
+ default:
+#ifdef USE_OSD_SLAVE
+ return mspOsdSlaveProcessInCommand(cmdMSP, src);
+#else
+ return mspFcProcessInCommand(cmdMSP, src);
+#endif
+ }
+ return MSP_RESULT_ERROR;
+}
/*
* Returns MSP_RESULT_ACK, MSP_RESULT_ERROR or MSP_RESULT_NO_REPLY
@@ -2026,8 +2111,16 @@ mspResult_e mspFcProcessCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostPro
// initialize reply by default
reply->cmd = cmd->cmd;
- if (mspFcProcessOutCommand(cmdMSP, dst, mspPostProcessFn)) {
+ if (mspCommonProcessOutCommand(cmdMSP, dst, mspPostProcessFn)) {
ret = MSP_RESULT_ACK;
+#ifdef USE_FC
+ } else if (mspFcProcessOutCommand(cmdMSP, dst, mspPostProcessFn)) {
+ ret = MSP_RESULT_ACK;
+#endif
+#ifdef USE_OSD_SLAVE
+ } else if (mspOsdSlaveProcessOutCommand(cmdMSP, dst, mspPostProcessFn)) {
+ ret = MSP_RESULT_ACK;
+#endif
#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
} else if (cmdMSP == MSP_SET_4WAY_IF) {
mspFc4waySerialCommand(dst, src, mspPostProcessFn);
@@ -2044,7 +2137,7 @@ mspResult_e mspFcProcessCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostPro
ret = MSP_RESULT_ACK;
#endif
} else {
- ret = mspFcProcessInCommand(cmdMSP, src);
+ ret = mspCommonProcessInCommand(cmdMSP, src);
}
reply->result = ret;
return ret;
@@ -2104,7 +2197,15 @@ void mspFcProcessReply(mspPacket_t *reply)
/*
* Return a pointer to the process command function
*/
+#ifdef USE_FC
void mspFcInit(void)
{
initActiveBoxIds();
}
+#endif
+
+#ifdef USE_OSD_SLAVE
+void mspOsdSlaveInit(void)
+{
+}
+#endif
diff --git a/src/main/fc/fc_msp.h b/src/main/fc/fc_msp.h
index 7992a9f15c..c5ccb1f1c4 100644
--- a/src/main/fc/fc_msp.h
+++ b/src/main/fc/fc_msp.h
@@ -30,5 +30,6 @@ const box_t *findBoxByBoxId(uint8_t boxId);
const box_t *findBoxByPermanentId(uint8_t permenantId);
void mspFcInit(void);
+void mspOsdSlaveInit(void);
mspResult_e mspFcProcessCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostProcessFnPtr *mspPostProcessFn);
void mspFcProcessReply(mspPacket_t *reply);
diff --git a/src/main/fc/fc_rc.c b/src/main/fc/fc_rc.c
index a22c3affde..3754a4e616 100755
--- a/src/main/fc/fc_rc.c
+++ b/src/main/fc/fc_rc.c
@@ -28,7 +28,6 @@
#include "common/utils.h"
#include "common/filter.h"
-#include "config/config_profile.h"
#include "config/feature.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c
index 1274d43340..4c801d8554 100644
--- a/src/main/fc/fc_tasks.c
+++ b/src/main/fc/fc_tasks.c
@@ -29,7 +29,6 @@
#include "common/filter.h"
#include "config/feature.h"
-#include "config/config_profile.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
@@ -49,10 +48,12 @@
#include "fc/cli.h"
#include "fc/fc_dispatch.h"
+#ifdef USE_FC
#include "flight/altitude.h"
#include "flight/imu.h"
#include "flight/mixer.h"
#include "flight/pid.h"
+#endif
#include "io/beeper.h"
#include "io/dashboard.h"
@@ -130,6 +131,7 @@ void taskBatteryAlerts(timeUs_t currentTimeUs)
batteryUpdateAlarms();
}
+#ifdef USE_FC
static void taskUpdateRxMain(timeUs_t currentTimeUs)
{
processRx(currentTimeUs);
@@ -153,6 +155,7 @@ static void taskUpdateRxMain(timeUs_t currentTimeUs)
}
#endif
}
+#endif
#ifdef MAG
static void taskUpdateCompass(timeUs_t currentTimeUs)
@@ -242,6 +245,7 @@ void osdSlaveTasksInit(void)
}
#endif
+#ifdef USE_FC
void fcTasksInit(void)
{
schedulerInit();
@@ -343,6 +347,7 @@ void fcTasksInit(void)
setTaskEnabled(TASK_GYRO_DATA_ANALYSE, true);
#endif
}
+#endif
cfTask_t cfTasks[TASK_COUNT] = {
[TASK_SYSTEM] = {
@@ -352,6 +357,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
.staticPriority = TASK_PRIORITY_MEDIUM_HIGH,
},
+#ifdef USE_FC
[TASK_GYROPID] = {
.taskName = "PID",
.subTaskName = "GYRO",
@@ -381,6 +387,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
.desiredPeriod = TASK_PERIOD_HZ(50), // If event-based scheduling doesn't work, fallback to periodic scheduling
.staticPriority = TASK_PRIORITY_HIGH,
},
+#endif
[TASK_SERIAL] = {
.taskName = "SERIAL",
@@ -395,12 +402,14 @@ cfTask_t cfTasks[TASK_COUNT] = {
#endif
},
+#ifdef USE_FC
[TASK_DISPATCH] = {
.taskName = "DISPATCH",
.taskFunc = dispatchProcess,
.desiredPeriod = TASK_PERIOD_HZ(1000),
.staticPriority = TASK_PRIORITY_HIGH,
},
+#endif
[TASK_BATTERY_ALERTS] = {
.taskName = "BATTERY_ALERTS",
@@ -421,6 +430,8 @@ cfTask_t cfTasks[TASK_COUNT] = {
.desiredPeriod = TASK_PERIOD_HZ(50),
.staticPriority = TASK_PRIORITY_MEDIUM,
},
+#ifdef USE_FC
+
#ifdef BEEPER
[TASK_BEEPER] = {
.taskName = "BEEPER",
@@ -474,6 +485,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
.staticPriority = TASK_PRIORITY_LOW,
},
#endif
+#endif
#ifdef TRANSPONDER
[TASK_TRANSPONDER] = {
@@ -484,6 +496,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
},
#endif
+#ifdef USE_FC
#ifdef USE_DASHBOARD
[TASK_DASHBOARD] = {
.taskName = "DASHBOARD",
@@ -500,6 +513,8 @@ cfTask_t cfTasks[TASK_COUNT] = {
.staticPriority = TASK_PRIORITY_LOW,
},
#endif
+#endif
+
#ifdef USE_OSD_SLAVE
[TASK_OSD_SLAVE] = {
.taskName = "OSD_SLAVE",
@@ -509,6 +524,8 @@ cfTask_t cfTasks[TASK_COUNT] = {
.staticPriority = TASK_PRIORITY_HIGH,
},
#endif
+
+#ifdef USE_FC
#ifdef TELEMETRY
[TASK_TELEMETRY] = {
.taskName = "TELEMETRY",
@@ -580,4 +597,5 @@ cfTask_t cfTasks[TASK_COUNT] = {
.staticPriority = TASK_PRIORITY_MEDIUM,
},
#endif
+#endif
};
diff --git a/src/main/flight/navigation.c b/src/main/flight/navigation.c
index 5f98d4ddca..32c032932b 100644
--- a/src/main/flight/navigation.c
+++ b/src/main/flight/navigation.c
@@ -31,7 +31,6 @@
#include "common/maths.h"
#include "common/time.h"
-#include "config/config_profile.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c
index 002bec1d89..7c13587f0f 100644
--- a/src/main/flight/pid.c
+++ b/src/main/flight/pid.c
@@ -32,7 +32,6 @@
#include "config/config_reset.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
-#include "config/config_profile.h"
#include "fc/fc_core.h"
#include "fc/fc_rc.h"
diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h
index ce8acddfb9..94f87d3e5e 100644
--- a/src/main/flight/pid.h
+++ b/src/main/flight/pid.h
@@ -85,11 +85,6 @@ typedef struct pidProfile_s {
uint16_t rateAccelLimit; // accel limiter roll/pitch deg/sec/ms
} pidProfile_t;
-#if FLASH_SIZE <= 128
-#define MAX_PROFILE_COUNT 2
-#else
-#define MAX_PROFILE_COUNT 3
-#endif
PG_DECLARE_ARRAY(pidProfile_t, MAX_PROFILE_COUNT, pidProfiles);
typedef struct pidConfig_s {
diff --git a/src/main/io/dashboard.c b/src/main/io/dashboard.c
index 2a65a6e63a..55e273c999 100644
--- a/src/main/io/dashboard.c
+++ b/src/main/io/dashboard.c
@@ -43,7 +43,6 @@
#include "common/typeconversion.h"
#include "config/feature.h"
-#include "config/config_profile.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
diff --git a/src/main/io/ledstrip.c b/src/main/io/ledstrip.c
index 272bad32ab..9740daa504 100644
--- a/src/main/io/ledstrip.c
+++ b/src/main/io/ledstrip.c
@@ -34,7 +34,6 @@
#include "common/typeconversion.h"
#include "common/utils.h"
-#include "config/config_profile.h"
#include "config/feature.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
diff --git a/src/main/io/osd.c b/src/main/io/osd.c
index 0769775c64..b10208e206 100644
--- a/src/main/io/osd.c
+++ b/src/main/io/osd.c
@@ -48,7 +48,6 @@
#include "common/typeconversion.h"
#include "common/utils.h"
-#include "config/config_profile.h"
#include "config/feature.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
@@ -75,8 +74,8 @@
#include "fc/runtime_config.h"
#include "flight/altitude.h"
+#include "flight/pid.h"
#include "flight/imu.h"
-#include "flight/altitude.h"
#include "rx/rx.h"
diff --git a/src/main/osd_slave/osd_slave_init.c b/src/main/osd_slave/osd_slave_init.c
new file mode 100644
index 0000000000..4e68ca8fa7
--- /dev/null
+++ b/src/main/osd_slave/osd_slave_init.c
@@ -0,0 +1,285 @@
+/*
+ * This file is part of Cleanflight.
+ *
+ * Cleanflight is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * Cleanflight is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Cleanflight. If not, see .
+ */
+
+#include
+#include
+#include
+
+#include "platform.h"
+
+#include "blackbox/blackbox.h"
+
+#include "common/axis.h"
+#include "common/color.h"
+#include "common/maths.h"
+#include "common/printf.h"
+
+#include "config/config_eeprom.h"
+#include "config/feature.h"
+#include "config/parameter_group.h"
+#include "config/parameter_group_ids.h"
+
+#include "drivers/nvic.h"
+#include "drivers/sensor.h"
+#include "drivers/system.h"
+#include "drivers/dma.h"
+#include "drivers/io.h"
+#include "drivers/light_led.h"
+#include "drivers/sound_beeper.h"
+#include "drivers/timer.h"
+#include "drivers/serial.h"
+#include "drivers/serial_softserial.h"
+#include "drivers/serial_uart.h"
+#include "drivers/adc.h"
+#include "drivers/bus_i2c.h"
+#include "drivers/bus_spi.h"
+#include "drivers/inverter.h"
+#include "drivers/usb_io.h"
+#include "drivers/transponder_ir.h"
+#include "drivers/exti.h"
+
+#include "fc/config.h"
+#include "osd_slave/osd_slave_init.h"
+#include "fc/fc_msp.h"
+#include "fc/fc_tasks.h"
+#include "fc/rc_controls.h"
+#include "fc/runtime_config.h"
+#include "fc/cli.h"
+
+#include "msp/msp_serial.h"
+
+#include "rx/rx.h"
+#include "rx/spektrum.h"
+
+#include "io/beeper.h"
+#include "io/displayport_max7456.h"
+#include "io/serial.h"
+#include "io/flashfs.h"
+#include "io/ledstrip.h"
+#include "io/transponder_ir.h"
+#include "io/osd_slave.h"
+
+#include "scheduler/scheduler.h"
+
+#include "sensors/acceleration.h"
+#include "sensors/barometer.h"
+#include "sensors/battery.h"
+
+#ifdef USE_HARDWARE_REVISION_DETECTION
+#include "hardware_revision.h"
+#endif
+
+#include "build/build_config.h"
+#include "build/debug.h"
+
+#ifdef TARGET_PREINIT
+void targetPreInit(void);
+#endif
+
+#ifdef TARGET_BUS_INIT
+void targetBusInit(void);
+#endif
+
+uint8_t systemState = SYSTEM_STATE_INITIALISING;
+
+void processLoopback(void)
+{
+}
+
+
+#ifdef BUS_SWITCH_PIN
+void busSwitchInit(void)
+{
+static IO_t busSwitchResetPin = IO_NONE;
+
+ busSwitchResetPin = IOGetByTag(IO_TAG(BUS_SWITCH_PIN));
+ IOInit(busSwitchResetPin, OWNER_SYSTEM, 0);
+ IOConfigGPIO(busSwitchResetPin, IOCFG_OUT_PP);
+
+ // ENABLE
+ IOLo(busSwitchResetPin);
+}
+#endif
+
+void init(void)
+{
+#ifdef USE_HAL_DRIVER
+ HAL_Init();
+#endif
+
+ printfSupportInit();
+
+ systemInit();
+
+ // initialize IO (needed for all IO operations)
+ IOInitGlobal();
+
+#ifdef USE_HARDWARE_REVISION_DETECTION
+ detectHardwareRevision();
+#endif
+
+ initEEPROM();
+
+ ensureEEPROMContainsValidData();
+ readEEPROM();
+
+ systemState |= SYSTEM_STATE_CONFIG_LOADED;
+
+ debugMode = systemConfig()->debug_mode;
+
+ // Latch active features to be used for feature() in the remainder of init().
+ latchActiveFeatures();
+
+#ifdef TARGET_PREINIT
+ targetPreInit();
+#endif
+
+ ledInit(statusLedConfig());
+ LED2_ON;
+
+#ifdef USE_EXTI
+ EXTIInit();
+#endif
+
+ delay(100);
+
+ timerInit(); // timer must be initialized before any channel is allocated
+
+#ifdef BUS_SWITCH_PIN
+ busSwitchInit();
+#endif
+
+ serialInit(false, SERIAL_PORT_NONE);
+
+#ifdef BEEPER
+ beeperInit(beeperDevConfig());
+#endif
+/* temp until PGs are implemented. */
+#ifdef USE_INVERTER
+ initInverters();
+#endif
+
+#ifdef TARGET_BUS_INIT
+ targetBusInit();
+#else
+
+#ifdef USE_SPI
+#ifdef USE_SPI_DEVICE_1
+ spiInit(SPIDEV_1);
+#endif
+#ifdef USE_SPI_DEVICE_2
+ spiInit(SPIDEV_2);
+#endif
+#ifdef USE_SPI_DEVICE_3
+ spiInit(SPIDEV_3);
+#endif
+#ifdef USE_SPI_DEVICE_4
+ spiInit(SPIDEV_4);
+#endif
+#endif /* USE_SPI */
+
+#ifdef USE_I2C
+#ifdef USE_I2C_DEVICE_1
+ i2cInit(I2CDEV_1);
+#endif
+#ifdef USE_I2C_DEVICE_2
+ i2cInit(I2CDEV_2);
+#endif
+#ifdef USE_I2C_DEVICE_3
+ i2cInit(I2CDEV_3);
+#endif
+#ifdef USE_I2C_DEVICE_4
+ i2cInit(I2CDEV_4);
+#endif
+#endif /* USE_I2C */
+
+#endif /* TARGET_BUS_INIT */
+
+#ifdef USE_HARDWARE_REVISION_DETECTION
+ updateHardwareRevision();
+#endif
+
+#ifdef USE_ADC
+ adcConfigMutable()->vbat.enabled = (batteryConfig()->voltageMeterSource == VOLTAGE_METER_ADC);
+ adcConfigMutable()->current.enabled = (batteryConfig()->currentMeterSource == CURRENT_METER_ADC);
+
+ adcConfigMutable()->rssi.enabled = feature(FEATURE_RSSI_ADC);
+ adcInit(adcConfig());
+#endif
+
+ LED1_ON;
+ LED0_OFF;
+ LED2_OFF;
+
+ for (int i = 0; i < 10; i++) {
+ LED1_TOGGLE;
+ LED0_TOGGLE;
+ delay(25);
+ if (!(getBeeperOffMask() & (1 << (BEEPER_SYSTEM_INIT - 1)))) BEEP_ON;
+ delay(25);
+ BEEP_OFF;
+ }
+ LED0_OFF;
+ LED1_OFF;
+
+ mspOsdSlaveInit();
+ mspSerialInit();
+
+#ifdef USE_CLI
+ cliInit(serialConfig());
+#endif
+
+ displayPort_t *osdDisplayPort = NULL;
+
+#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
+
+#ifdef LED_STRIP
+ ledStripInit();
+
+ if (feature(FEATURE_LED_STRIP)) {
+ ledStripEnable();
+ }
+#endif
+
+#ifdef USB_DETECT_PIN
+ usbCableDetectInit();
+#endif
+
+#ifdef TRANSPONDER
+ if (feature(FEATURE_TRANSPONDER)) {
+ transponderInit();
+ transponderStartRepeating();
+ systemState |= SYSTEM_STATE_TRANSPONDER_ENABLED;
+ }
+#endif
+
+ timerStart();
+
+ batteryInit();
+
+ // Latch active features AGAIN since some may be modified by init().
+ latchActiveFeatures();
+
+ osdSlaveTasksInit();
+
+ systemState |= SYSTEM_STATE_READY;
+}
diff --git a/src/main/config/config_profile.h b/src/main/osd_slave/osd_slave_init.h
similarity index 73%
rename from src/main/config/config_profile.h
rename to src/main/osd_slave/osd_slave_init.h
index c741b2a557..97c9b59ed6 100644
--- a/src/main/config/config_profile.h
+++ b/src/main/osd_slave/osd_slave_init.h
@@ -17,8 +17,13 @@
#pragma once
-#include "flight/pid.h"
+typedef enum {
+ SYSTEM_STATE_INITIALISING = 0,
+ SYSTEM_STATE_CONFIG_LOADED = (1 << 0),
+ SYSTEM_STATE_TRANSPONDER_ENABLED = (1 << 3),
+ SYSTEM_STATE_READY = (1 << 7)
+} systemState_e;
-typedef struct profile_s {
- pidProfile_t pidProfile;
-} profile_t;
+extern uint8_t systemState;
+
+void init(void);
diff --git a/src/main/platform.h b/src/main/platform.h
index 1130c74d57..4055749f98 100644
--- a/src/main/platform.h
+++ b/src/main/platform.h
@@ -82,6 +82,11 @@
#error "Invalid chipset specified. Update platform.h"
#endif
-#include "target/common.h"
+#ifdef USE_OSD_SLAVE
+#include "target/common_osd_slave.h"
#include "target.h"
-#include "target/common_post.h"
+#else
+#include "target/common_fc_pre.h"
+#include "target.h"
+#include "target/common_fc_post.h"
+#endif
diff --git a/src/main/target/COLIBRI_RACE/i2c_bst.c b/src/main/target/COLIBRI_RACE/i2c_bst.c
index 3039c52728..feb3a0b831 100644
--- a/src/main/target/COLIBRI_RACE/i2c_bst.c
+++ b/src/main/target/COLIBRI_RACE/i2c_bst.c
@@ -69,7 +69,6 @@
#include "flight/servos.h"
#include "config/config_eeprom.h"
-#include "config/config_profile.h"
#include "config/feature.h"
#include "bus_bst.h"
diff --git a/src/main/target/SPRACINGF3OSD/target.h b/src/main/target/SPRACINGF3OSD/target.h
index 6414d2f902..2b0b1a0531 100644
--- a/src/main/target/SPRACINGF3OSD/target.h
+++ b/src/main/target/SPRACINGF3OSD/target.h
@@ -88,20 +88,6 @@
#define TRANSPONDER
-#define USE_OSD_SLAVE
-
-#undef OSD
-#undef GPS
-#undef BLACKBOX
-#undef TELEMETRY
-#undef USE_SERVOS
-#undef VTX_COMMON
-#undef VTX_CONTROL
-#undef VTX_SMARTAUDIO
-#undef VTX_TRAMP
-#undef USE_MSP_DISPLAYPORT
-
-
#define DEFAULT_FEATURES (FEATURE_TRANSPONDER)
// IO - assuming 303 in 64pin package, TODO
diff --git a/src/main/target/common_post.h b/src/main/target/common_fc_post.h
similarity index 100%
rename from src/main/target/common_post.h
rename to src/main/target/common_fc_post.h
diff --git a/src/main/target/common.h b/src/main/target/common_fc_pre.h
similarity index 97%
rename from src/main/target/common.h
rename to src/main/target/common_fc_pre.h
index bc8d2a1572..6a9f59238f 100644
--- a/src/main/target/common.h
+++ b/src/main/target/common_fc_pre.h
@@ -81,6 +81,12 @@
#define USE_SERIALRX_SUMH // Graupner legacy protocol
#define USE_SERIALRX_XBUS // JR
+#if (FLASH_SIZE > 64)
+#define MAX_PROFILE_COUNT 3
+#else
+#define MAX_PROFILE_COUNT 2
+#endif
+
#if (FLASH_SIZE > 64)
#define BLACKBOX
#define LED_STRIP
diff --git a/src/main/target/common_osd_slave.h b/src/main/target/common_osd_slave.h
new file mode 100644
index 0000000000..fa4be9f2a8
--- /dev/null
+++ b/src/main/target/common_osd_slave.h
@@ -0,0 +1,60 @@
+/*
+ * This file is part of Cleanflight.
+ *
+ * Cleanflight is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * Cleanflight is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Cleanflight. If not, see .
+ */
+
+#pragma once
+
+#define USE_PARAMETER_GROUPS
+// type conversion warnings.
+// -Wconversion can be turned on to enable the process of eliminating these warnings
+//#pragma GCC diagnostic warning "-Wconversion"
+#pragma GCC diagnostic ignored "-Wsign-conversion"
+// -Wpadded can be turned on to check padding of structs
+//#pragma GCC diagnostic warning "-Wpadded"
+
+//#define SCHEDULER_DEBUG // define this to use scheduler debug[] values. Undefined by default for performance reasons
+#define DEBUG_MODE DEBUG_NONE // change this to change initial debug mode
+
+#define I2C1_OVERCLOCK true
+#define I2C2_OVERCLOCK true
+
+#define MAX_PROFILE_COUNT 0
+
+#ifdef STM32F1
+#define MINIMAL_CLI
+#endif
+
+#ifdef STM32F3
+#define MINIMAL_CLI
+#endif
+
+#ifdef STM32F4
+#define I2C3_OVERCLOCK true
+#endif
+
+#ifdef STM32F7
+#define I2C3_OVERCLOCK true
+#define I2C4_OVERCLOCK true
+#endif
+
+#if defined(STM32F4) || defined(STM32F7)
+#define SCHEDULER_DELAY_LIMIT 10
+#else
+#define SCHEDULER_DELAY_LIMIT 100
+#endif
+
+//CLI needs FC dependencies removed before we can compile it, disabling for now
+//#define USE_CLI
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index 8210774ce4..c6106da7f5 100755
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -32,7 +32,6 @@
#include "common/axis.h"
#include "common/color.h"
-#include "config/config_profile.h"
#include "config/feature.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
diff --git a/src/main/telemetry/smartport.c b/src/main/telemetry/smartport.c
index 9be06c9ff7..abff32b1b4 100644
--- a/src/main/telemetry/smartport.c
+++ b/src/main/telemetry/smartport.c
@@ -16,7 +16,6 @@
#include "common/maths.h"
#include "common/utils.h"
-#include "config/config_profile.h"
#include "config/feature.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
diff --git a/src/test/Makefile b/src/test/Makefile
index 3344a7cd3a..efb393aeef 100644
--- a/src/test/Makefile
+++ b/src/test/Makefile
@@ -190,7 +190,7 @@ COMMON_FLAGS = \
-ggdb3 \
-pthread \
-O0 \
- -DUNIT_TEST \
+ -DUNIT_TEST -DUSE_FC\
-isystem $(GTEST_DIR)/inc \
-MMD -MP
diff --git a/src/test/unit/platform.h b/src/test/unit/platform.h
index e3cbbab9eb..06586546df 100644
--- a/src/test/unit/platform.h
+++ b/src/test/unit/platform.h
@@ -23,6 +23,7 @@
#define U_ID_1 1
#define U_ID_2 2
+#define MAX_PROFILE_COUNT 3
#define MAG
#define BARO
#define GPS