diff --git a/Makefile b/Makefile index aeb62b3465..1bae31e61a 100755 --- a/Makefile +++ b/Makefile @@ -20,6 +20,9 @@ TARGET ?= NAZE # Compile-time options OPTIONS ?= +# compile for OpenPilot BootLoader support +OPBL ?=no + # Debugger optons, must be empty or GDB DEBUG ?= @@ -36,14 +39,20 @@ FLASH_SIZE ?= FORKNAME = inav 64K_TARGETS = CJMCU -128K_TARGETS = ALIENWIIF1 CC3D NAZE OLIMEXINO RMDO +128K_TARGETS = ALIENWIIF1 CC3D CC3D_OPBL NAZE OLIMEXINO RMDO 256K_TARGETS = ALIENWIIF3 CHEBUZZF3 COLIBRI_RACE EUSTM32F103RC LUX_RACE MOTOLAB NAZE32PRO PORT103R SPARKY SPRACINGF3 STM32F3DISCOVERY F3_TARGETS = ALIENWIIF3 CHEBUZZF3 COLIBRI_RACE LUX_RACE MOTOLAB NAZE32PRO RMDO SPARKY SPRACINGF3 STM32F3DISCOVERY VALID_TARGETS = $(64K_TARGETS) $(128K_TARGETS) $(256K_TARGETS) -VCP_TARGETS = CC3D ALIENWIIF3 CHEBUZZF3 COLIBRI_RACE LUX_RACE MOTOLAB NAZE32PRO SPARKY STM32F3DISCOVERY +VCP_TARGETS = CC3D CC3D_OPBL ALIENWIIF3 CHEBUZZF3 COLIBRI_RACE LUX_RACE MOTOLAB NAZE32PRO SPARKY STM32F3DISCOVERY + +# Valid targets for OP BootLoader support +OPBL_TARGETS = CC3D_OPBL +ifneq ($(filter $(TARGET),$(OPBL_TARGETS)),) +OPBL=yes +endif # Configure default flash sizes for the targets ifeq ($(FLASH_SIZE),) @@ -227,6 +236,15 @@ ifeq ($(TARGET),$(filter $(TARGET),RMDO IRCFUSIONF3)) TARGET_FLAGS := $(TARGET_FLAGS) -DSPRACINGF3 endif +ifeq ($(TARGET),$(filter $(TARGET),CC3D CC3D_OPBL)) +TARGET_FLAGS := $(TARGET_FLAGS) -DCC3D +ifeq ($(TARGET),CC3D_OPBL) +TARGET_FLAGS := $(TARGET_FLAGS) -DCC3D_OPBL +CC3D_OPBL_SRC = $(CC3D_SRC) +endif +TARGET_DIR = $(ROOT)/src/main/target/CC3D +endif + INCLUDE_DIRS := $(INCLUDE_DIRS) \ $(TARGET_DIR) @@ -753,10 +771,21 @@ TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $( TARGET_DEPS = $(addsuffix .d,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $($(TARGET)_SRC)))) TARGET_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).map + ## Default make goal: ## hex : Make filetype hex only .DEFAULT_GOAL := hex +ifeq ($(OPBL),yes) +ifneq ($(filter $(TARGET),$(OPBL_TARGETS)),) +TARGET_FLAGS := -DOPBL $(TARGET_FLAGS) +LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k_opbl.ld +.DEFAULT_GOAL := binary +else +$(error OPBL specified with an unsupported target) +endif +endif + ## Optional make goals: ## all : Make all filetypes, binary and hex all: hex bin @@ -800,8 +829,6 @@ st-flash_$(TARGET): $(TARGET_BIN) ## st-flash : flash firmware (.bin) onto flight controller st-flash: st-flash_$(TARGET) -binary: $(TARGET_BIN) - unbrick_$(TARGET): $(TARGET_HEX) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index 950ef00225..d50b321e22 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -1139,6 +1139,7 @@ static bool processInCommand(void) updateMagHoldHeading(read16()); break; case MSP_SET_RAW_RC: +#ifndef SKIP_RX_MSP { uint8_t channelCount = currentPort->dataSize / sizeof(uint16_t); if (channelCount > MAX_SUPPORTED_RC_CHANNEL_COUNT) { @@ -1153,6 +1154,7 @@ static bool processInCommand(void) rxMspFrameReceive(frame, channelCount); } } +#endif break; case MSP_SET_ARMING_CONFIG: masterConfig.auto_disarm_delay = read8(); diff --git a/src/main/rx/msp.c b/src/main/rx/msp.c index 86399a9094..ce5ff2becd 100644 --- a/src/main/rx/msp.c +++ b/src/main/rx/msp.c @@ -22,11 +22,11 @@ #include "build_config.h" -#include "drivers/system.h" +#ifndef SKIP_RX_MSP +#include "drivers/system.h" #include "drivers/serial.h" #include "drivers/serial_uart.h" -#include "io/serial.h" #include "rx/rx.h" #include "rx/msp.h" @@ -71,3 +71,4 @@ void rxMspInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadR if (callback) *callback = rxMspReadRawRC; } +#endif diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c index da2a22809f..c095977819 100644 --- a/src/main/rx/rx.c +++ b/src/main/rx/rx.c @@ -177,9 +177,11 @@ void rxInit(rxConfig_t *rxConfig, modeActivationCondition_t *modeActivationCondi } #endif +#ifndef SKIP_RX_MSP if (feature(FEATURE_RX_MSP)) { rxMspInit(rxConfig, &rxRuntimeConfig, &rcReadRawFunc); } +#endif if (feature(FEATURE_RX_PPM) || feature(FEATURE_RX_PARALLEL_PWM)) { rxRefreshRate = 20000; @@ -330,6 +332,7 @@ void updateRx(uint32_t currentTime) } #endif +#ifndef SKIP_RX_MSP if (feature(FEATURE_RX_MSP)) { rxDataReceived = rxMspFrameComplete(); @@ -339,6 +342,7 @@ void updateRx(uint32_t currentTime) needRxSignalBefore = currentTime + DELAY_5_HZ; } } +#endif if (feature(FEATURE_RX_PPM)) { if (isPPMDataBeingReceived()) { diff --git a/src/main/target/CC3D/target.h b/src/main/target/CC3D/target.h index 7d82d19d7b..9ede87703e 100644 --- a/src/main/target/CC3D/target.h +++ b/src/main/target/CC3D/target.h @@ -158,6 +158,15 @@ //Disables uncommon predefined mixer settings like BiCopter, H6 and similar exotics #define DISABLE_UNCOMMON_MIXERS +#ifdef CC3D_OPBL +#define USE_QUAD_MIXER_ONLY +#undef USE_SERVOS +#undef TELEMETRY +#undef TELEMETRY_LTM +#undef SERIAL_RX +//#define SKIP_RX_MSP +#endif + // DEBUG //#define HIL //#define USE_FAKE_MAG diff --git a/src/main/target/stm32_flash_f103_128k_opbl.ld b/src/main/target/stm32_flash_f103_128k_opbl.ld new file mode 100644 index 0000000000..643ddcff23 --- /dev/null +++ b/src/main/target/stm32_flash_f103_128k_opbl.ld @@ -0,0 +1,22 @@ +/* +***************************************************************************** +** +** File : stm32_flash.ld +** +** Abstract : Linker script for STM32F103CB Device with +** 128KByte FLASH, 20KByte RAM +** +***************************************************************************** +*/ + +/* Specify the memory areas. */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08003000, LENGTH = 124K - 0x03000 /* last 4kb used for config storage first 12k for OP Bootloader */ + FLASH_CONFIG (r) : ORIGIN = 0x0801F000, LENGTH = 4K + + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 20K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +INCLUDE "stm32_flash.ld"