diff --git a/src/main/osd_slave/osd_slave_init.c b/src/main/osd_slave/osd_slave_init.c deleted file mode 100644 index 49ff190360..0000000000 --- a/src/main/osd_slave/osd_slave_init.c +++ /dev/null @@ -1,302 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software 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 and Betaflight are distributed in the hope that they - * 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 this software. - * - * 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 "drivers/adc.h" -#include "drivers/bus.h" -#include "drivers/bus_i2c.h" -#include "drivers/bus_spi.h" -#include "drivers/dma.h" -#include "drivers/exti.h" -#include "drivers/inverter.h" -#include "drivers/io.h" -#include "drivers/light_led.h" -#include "drivers/nvic.h" -#include "drivers/sensor.h" -#include "drivers/serial.h" -#include "drivers/serial_softserial.h" -#include "drivers/serial_uart.h" -#include "drivers/sound_beeper.h" -#include "drivers/system.h" -#include "drivers/time.h" -#include "drivers/timer.h" -#include "drivers/transponder_ir.h" -#include "drivers/usb_io.h" - -#include "fc/config.h" -#include "fc/rc_controls.h" -#include "fc/fc_tasks.h" -#include "fc/runtime_config.h" - -#include "interface/cli.h" -#include "interface/msp.h" - -#include "msp/msp_serial.h" - -#include "io/beeper.h" -#include "io/displayport_max7456.h" -#include "io/flashfs.h" -#include "io/ledstrip.h" -#include "io/osd_slave.h" -#include "io/serial.h" -#include "io/transponder_ir.h" - -#include "osd_slave/osd_slave_init.h" - -#include "pg/adc.h" -#include "pg/bus_i2c.h" -#include "pg/bus_spi.h" -#include "pg/pg.h" -#include "pg/pg_ids.h" -#include "pg/vcd.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 - -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(); - - ensureEEPROMStructureIsValid(); - readEEPROM(); - - systemState |= SYSTEM_STATE_CONFIG_LOADED; - - debugMode = systemConfig()->debug_mode; - -#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 - -#if defined(USE_UART) && !defined(SIMULATOR_BUILD) - uartPinConfigure(serialPinConfig()); -#endif - - serialInit(false, SERIAL_PORT_NONE); - -#ifdef USE_BEEPER - beeperInit(beeperDevConfig()); -#endif -/* temp until PGs are implemented. */ -#ifdef USE_INVERTER - initInverters(); -#endif - -#ifdef TARGET_BUS_INIT - targetBusInit(); -#else - -#ifdef USE_SPI - spiPinConfigure(spiPinConfig(0)); - - // Initialize CS lines and keep them high - spiPreInit(); - -#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 - i2cHardwareConfigure(i2cConfig(0)); - - // Note: Unlike UARTs which are configured when client is present, - // I2C buses are initialized unconditionally if they are configured. - -#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 = featureIsEnabled(FEATURE_RSSI_ADC); - adcInit(adcConfig()); -#endif - - LED1_ON; - LED0_OFF; - LED2_OFF; - - for (int i = 0; i < 10; i++) { - LED1_TOGGLE; - LED0_TOGGLE; -#if defined(USE_BEEPER) - delay(25); - if (!(beeperConfig()->beeper_off_flags & BEEPER_GET_FLAG(BEEPER_SYSTEM_INIT))) BEEP_ON; - delay(25); - BEEP_OFF; -#else - delay(50); -#endif - } - LED0_OFF; - LED1_OFF; - - mspInit(); - 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 USE_LED_STRIP - ledStripInit(); - - if (featureIsEnabled(FEATURE_LED_STRIP)) { - ledStripEnable(); - } -#endif - -#ifdef USE_USB_DETECT - usbCableDetectInit(); -#endif - -#ifdef USE_TRANSPONDER - if (featureIsEnabled(FEATURE_TRANSPONDER)) { - transponderInit(); - transponderStartRepeating(); - systemState |= SYSTEM_STATE_TRANSPONDER_ENABLED; - } -#endif - - timerStart(); - - batteryInit(); - - fcTasksInit(); - - systemState |= SYSTEM_STATE_READY; -} diff --git a/src/test/unit/vtx_unittest.cc b/src/test/unit/vtx_unittest.cc index 79127146c4..7f5747a3d0 100644 --- a/src/test/unit/vtx_unittest.cc +++ b/src/test/unit/vtx_unittest.cc @@ -115,7 +115,7 @@ extern "C" { uint32_t millis(void) { return micros() / 1000; } bool rxIsReceivingSignal(void) { return simulationHaveRx; } - bool feature(uint32_t f) { return simulationFeatureFlags & f; } + bool featureIsEnabled(uint32_t f) { return simulationFeatureFlags & f; } void warningLedFlash(void) {} void warningLedDisable(void) {} void warningLedUpdate(void) {}