1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-24 16:55:36 +03:00

Merge pull request #11699 from blckmn/remove_opbl

Removing OPBL support.
This commit is contained in:
haslinghuis 2022-07-04 15:01:06 +02:00 committed by GitHub
commit 86bd708e4c
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
11 changed files with 0 additions and 291 deletions

View file

@ -21,9 +21,6 @@ TARGET ?= STM32F405
# Compile-time options
OPTIONS ?=
# compile for OpenPilot BootLoader support
OPBL ?= no
# compile for External Storage Bootloader support
EXST ?= no
@ -187,12 +184,7 @@ endif
TARGET_DIR = $(ROOT)/src/main/target/$(BASE_TARGET)
TARGET_DIR_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c))
ifeq ($(OPBL),yes)
TARGET_FLAGS := -DOPBL $(TARGET_FLAGS)
.DEFAULT_GOAL := binary
else
.DEFAULT_GOAL := hex
endif
ifeq ($(CUSTOM_DEFAULTS_EXTENDED),yes)
TARGET_FLAGS += -DUSE_CUSTOM_DEFAULTS=

View file

@ -1,177 +0,0 @@
# Board - CC3D
The OpenPilot Copter Control 3D aka CC3D is a board more tuned to Acrobatic flying or GPS based
auto-piloting. It only has one sensor, the MPU6000 SPI based Accelerometer/Gyro.
It also features a 16Mbit SPI based EEPROM chip. It has 6 ports labeled as inputs (one pin each)
and 6 ports labeled as motor/servo outputs (3 pins each).
If issues are found with this board please report via the [github issue tracker](https://github.com/cleanflight/cleanflight/issues).
The board has a USB port directly connected to the processor. Other boards like the Naze and Flip32
have an on-board USB to uart adapter which connect to the processor's serial port instead.
The board cannot currently be used for hexacopters/octocopters.
Tricopter & Airplane support is untested, please report success or failure if you try it.
# Pinouts
The 8 pin RC_Input connector has the following pinouts when used in RX_PPM/RX_SERIAL mode
| Pin | Function | Notes |
| --- | --------- | -------------------------------- |
| 1 | Ground | |
| 2 | +5V | |
| 3 | Unused | |
| 4 | SoftSerial1 TX / Sonar trigger | |
| 5 | SoftSerial1 RX / Sonar Echo / RSSI_ADC | Used either for SOFTSERIAL, SONAR or RSSI_ADC*. Only one feature can be enabled at any time. |
| 6 | Current | Enable `feature CURRENT_METER`. Connect to the output of a current sensor, 0v-3.3v input |
| 7 | Battery Voltage sensor | Enable `feature VBAT`. Connect to main battery using a voltage divider, 0v-3.3v input |
| 8 | PPM Input | Enable `feature RX_PPM` |
*Connect to the output of a PWM-RSSI conditioner, 0v-3.3v input.
The 6 pin RC_Output connector has the following pinouts when used in RX_PPM/RX_SERIAL mode
| Pin | Function | Notes |
| --- | ----------| ------|
| 1 | MOTOR 1 | |
| 2 | MOTOR 2 | |
| 3 | MOTOR 3 | |
| 4 | MOTOR 4 | |
| 5 | LED Strip | |
| 6 | Unused | |
The 8 pin RC_Input connector has the following pinouts when used in RX_PARALLEL_PWM mode
| Pin | Function | Notes |
| --- | ---------| ------|
| 1 | Ground | |
| 2 | +5V | |
| 3 | Unused | |
| 4 | CH1 | |
| 5 | CH2 | |
| 6 | CH3 | |
| 7 | CH4/Battery Voltage sensor | CH4 if battery voltage sensor is disabled |
| 8 | CH5/CH4 | CH4 if battery voltage monitor is enabled|
The 6 pin RC_Output connector has the following pinouts when used in RX_PARALLEL_PWM mode
| Pin | Function | Notes |
| --- | ---------| ------|
| 1 | MOTOR 1 | |
| 2 | MOTOR 2 | |
| 3 | MOTOR 3 | |
| 4 | MOTOR 4 | |
| 5 | Unused | |
| 6 | Unused | |
# Serial Ports
| Value | Identifier | Board Markings | Notes |
| ----- | ------------ | -------------- | ------------------------------------------|
| 1 | VCP | USB PORT | |
| 2 | USART1 | MAIN PORT | Connected to an MCU controllable inverter |
| 3 | USART3 | FLEX PORT | |
| 4 | SoftSerial | RC connector | Pins 4 and 5 (Tx and Rx respectively) |
The SoftSerial port is not available when RX_PARALLEL_PWM is used. The transmission data rate is limited to 19200 baud.
To connect the GUI to the flight controller you just need a USB cable to use the Virtual Com Port (VCP) or you can use UART1 (Main Port).
CLI access is only available via the VCP by default.
# Main Port
The main port has MSP support enabled on it by default.
The main port is connected to an inverter which is automatically enabled as required. For example, if the main port is used for SBus Serial RX then an external inverter is not required.
# Flex Port
The flex port will be enabled in I2C mode unless USART3 is used. You can connect external I2C sensors and displays to this port.
You cannot use USART3 and I2C at the same time.
## Flex port pinout
| Pin | Signal | Notes |
| --- | ------------------ | ----------------------- |
| 1 | GND | |
| 2 | VCC unregulated | |
| 3 | I2C SCL / UART3 TX | 3.3v level |
| 4 | I2C SDA / UART3 RX | 3.3v level (5v tolerant |
# Flashing
Since CleanFlight version 1.11.0 "single binary image mode" is the only way to get CleanFlight on CC3D. Prior the version 1.11.0 there was a possibility to use "OpenPilot Bootloader compatible image mode", which allows you to easily switch between OpenPilot and CleanFlight, please refer to documentation from releases prior to 1.11.0 for more details.
## Single binary image mode.
The entire flash ram on the target processor is flashed with a single image.
The image can be flashed by using a USB to UART adapter connected to the main port when the CC3D is put into the STM32 bootloader mode, achieved by powering on the CC3D with the SBL/3.3v pads bridged.
# Restoring OpenPilot bootloader
If you have a JLink debugger, you can use JLinkExe to flash the open pilot bootloader.
1. Run JLinkExe `/Applications/SEGGER/JLink/JLinkExe`
2. `device STM32F103CB`
3. `r`
4. `h`
5. `loadbin opbl.bin, 0x08000000`
6. `q`
7. Re-plug CC3D.
Here's an example session:
```
$ /Applications/SEGGER/JLink/JLinkExe
SEGGER J-Link Commander V4.90c ('?' for help)
Compiled Aug 29 2014 09:52:38
DLL version V4.90c, compiled Aug 29 2014 09:52:33
Firmware: J-Link ARM-OB STM32 compiled Aug 22 2012 19:52:04
Hardware: V7.00
S/N: -1
Feature(s): RDI,FlashDL,FlashBP,JFlash,GDBFull
VTarget = 3.300V
Info: Could not measure total IR len. TDO is constant high.
Info: Could not measure total IR len. TDO is constant high.
No devices found on JTAG chain. Trying to find device on SWD.
Info: Found SWD-DP with ID 0x1BA01477
Info: Found Cortex-M3 r1p1, Little endian.
Info: FPUnit: 6 code (BP) slots and 2 literal slots
Info: TPIU fitted.
Cortex-M3 identified.
Target interface speed: 100 kHz
J-Link>device STM32F103CB
Info: Device "STM32F103CB" selected (128 KB flash, 20 KB RAM).
Reconnecting to target...
Info: Found SWD-DP with ID 0x1BA01477
Info: Found SWD-DP with ID 0x1BA01477
Info: Found Cortex-M3 r1p1, Little endian.
Info: FPUnit: 6 code (BP) slots and 2 literal slots
Info: TPIU fitted.
J-Link>r
Reset delay: 0 ms
Reset type NORMAL: Resets core & peripherals via SYSRESETREQ & VECTRESET bit.
J-Link>h
PC = 0800010C, CycleCnt = 00000000
R0 = 0000000C, R1 = 0000003F, R2 = 00000000, R3 = 00000008
R4 = 00003000, R5 = 023ACEFC, R6 = 200000F0, R7 = 20000304
R8 = 023B92BC, R9 = 00000000, R10= ED691105, R11= F626177C
R12= 000F0000
SP(R13)= 20000934, MSP= 20000934, PSP= 20000934, R14(LR) = FFFFFFFF
XPSR = 01000000: APSR = nzcvq, EPSR = 01000000, IPSR = 000 (NoException)
CFBP = 00000000, CONTROL = 00, FAULTMASK = 00, BASEPRI = 00, PRIMASK = 00
J-Link>loadbin opbl.bin, 0x08000000
Downloading file [opbl.bin]...
WARNING: CPU is running at low speed (8004 kHz).
Info: J-Link: Flash download: Flash download into internal flash skipped. Flash contents already match
Info: J-Link: Flash download: Total time needed: 0.898s (Prepare: 0.709s, Compare: 0.128s, Erase: 0.000s, Program: 0.000s, Verify: 0.000s, Restore: 0.059s)
O.K.
J-Link>q
$
```

View file

@ -2,16 +2,6 @@
# F4 Make file include
#
ifeq ($(OPBL),yes)
ifeq ($(TARGET), $(filter $(TARGET),$(F405_TARGETS)))
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405_opbl.ld
else ifeq ($(TARGET), $(filter $(TARGET),$(F411_TARGETS)))
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f411_opbl.ld
else
$(error No OPBL linker script specified for $(TARGET`))
endif
endif
#CMSIS
ifeq ($(PERIPH_DRIVER), HAL)
CMSIS_DIR := $(ROOT)/lib/main/STM32F4/Drivers/CMSIS

View file

@ -9,10 +9,6 @@ BASE_TARGET := $(call get_base_target,$(TARGET))
# silently ignore if the file is not present. Allows for target specific.
-include $(ROOT)/src/main/target/$(BASE_TARGET)/$(TARGET).mk
ifeq ($(filter $(TARGET),$(OPBL_TARGETS)), $(TARGET))
OPBL = yes
endif
# silently ignore if the file is not present. Allows for target defaults.
-include $(ROOT)/src/main/target/$(BASE_TARGET)/target.mk

View file

@ -6,7 +6,6 @@ BASE_ALT_PAIRS = $(join $(BASE_TARGET_NAMES:=/),$(ALT_TARGET_NAMES))
ALT_TARGETS = $(sort $(notdir $(BASE_ALT_PAIRS)))
BASE_TARGETS = $(sort $(notdir $(patsubst %/,%,$(dir $(wildcard $(ROOT)/src/main/target/*/target.mk)))))
NOBUILD_TARGETS = $(sort $(filter-out target,$(basename $(notdir $(wildcard $(ROOT)/src/main/target/*/*.nomk)))))
OPBL_TARGETS = $(sort $(filter %_OPBL,$(ALT_TARGETS)))
VALID_TARGETS = $(sort $(filter-out $(NOBUILD_TARGETS),$(BASE_TARGETS) $(ALT_TARGETS)))
# For alt targets, returns their base target name.

View file

@ -1,41 +0,0 @@
/*
*****************************************************************************
**
** File : stm32_flash_f405.ld
**
** Abstract : Linker script for STM32F405RG Device with
** 1024KByte FLASH, 128KByte RAM 64KByte CCM (RAM)
**
*****************************************************************************
*/
/*
0x08000000 to 0x080FFFFF 1024K full flash,
0x08000000 to 0x08003FFF 16K OPBL,
0x08004000 to 0x08007FFF 16K isr vector, startup code,
0x08008000 to 0x0800BFFF 16K config, // FLASH_Sector_2
0x0800C000 to 0x080FFFFF 976K firmware,
*/
/* Specify the memory areas */
MEMORY
{
FLASH (rx) : ORIGIN = 0x08004000, LENGTH = 16K
FLASH_CONFIG (r): ORIGIN = 0x08008000, LENGTH = 16K
FLASH1 (rx) : ORIGIN = 0x0800C000, LENGTH = 976K
SYSTEM_MEMORY (rx): ORIGIN = 0x1FFF0000, LENGTH = 29K
RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
CCM (rwx) : ORIGIN = 0x10000000, LENGTH = 64K
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
}
REGION_ALIAS("STACKRAM", CCM)
REGION_ALIAS("FASTRAM", CCM)
/* Put various bits and bobs of data into the main chunk of flash as we have enough of it */
REGION_ALIAS("MOVABLE_FLASH", FLASH1)
INCLUDE "stm32_flash_f4_split.ld"

View file

@ -1,40 +0,0 @@
/*
*****************************************************************************
**
** File : stm32_flash_f411_opbl.ld
**
** Abstract : Linker script for STM32F411 Device with
** 512KByte FLASH, 128KByte RAM
**
*****************************************************************************
*/
/*
0x08000000 to 0x0807FFFF 512K full flash,
0x08000000 to 0x08003FFF 16K OPBL,
0x08004000 to 0x08007FFF 16K isr vector, startup code,
0x08008000 to 0x0800BFFF 16K config, // FLASH_Sector_2
0x0800C000 to 0x0807FFFF 464K firmware,
*/
/* Specify the memory areas */
MEMORY
{
FLASH (rx) : ORIGIN = 0x08004000, LENGTH = 16K
FLASH_CONFIG (r) : ORIGIN = 0x08008000, LENGTH = 16K
FLASH1 (rx) : ORIGIN = 0x0800C000, LENGTH = 464K
SYSTEM_MEMORY (rx): ORIGIN = 0x1FFF0000, LENGTH = 29K
RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
}
REGION_ALIAS("STACKRAM", RAM)
REGION_ALIAS("FASTRAM", RAM)
/* Put various bits and bobs of data into the free space after the vector table in sector 0 to save flash space. */
REGION_ALIAS("MOVABLE_FLASH", FLASH)
INCLUDE "stm32_flash_f4_split.ld"

View file

@ -46,10 +46,6 @@
#define TARGET_BOARD_IDENTIFIER "REVO"
#define USBD_PRODUCT_STRING "Revolution"
#ifdef OPBL
#define USBD_SERIALNUMBER_STRING "0x8020000"
#endif
#endif
#define LED0_PIN PB5

View file

@ -25,9 +25,6 @@
#define TARGET_BOARD_IDENTIFIER "REVN"
#define USBD_PRODUCT_STRING "Revo Nano"
#ifdef OPBL
#define USBD_SERIALNUMBER_STRING "0x8010000"
#endif
#define LED0_PIN PC14
#define LED1_PIN PC13

View file

@ -22,9 +22,6 @@
#define TARGET_BOARD_IDENTIFIER "SPK2"
#define USBD_PRODUCT_STRING "Sparky 2.0"
#ifdef OPBL
#define USBD_SERIALNUMBER_STRING "0x8020000"
#endif
#define LED0_PIN PB5
#define LED1_PIN PB4