Skip to content

Commit

Permalink
main_f7: use opencm3_stm32f7 library for stm32f7 targets
Browse files Browse the repository at this point in the history
Upstream libopencm3 has added the support to pwr, rcc, and usart
driver for stm32f7 targets, however the USB driver is still missing.
This patch enables the use of opencm3_stm32f7 library for stm32f7 targets
and with trick in Makefile to use usb driver from stm32f4, changes include:

* Align RCC definition with master

* Align PWR definition with master

* Align rcc_clock_scale definition with master and enable
  overdrive to get a maximum CPU frequency at 216MHz

* Refine rules in the Makefile to support compile and link the USB driver
  in stm32f4, and others in stm32f7, stm32f3
  • Loading branch information
Lampoo authored and LorenzMeier committed Jul 12, 2018
1 parent 167ef23 commit 131dfba
Show file tree
Hide file tree
Showing 6 changed files with 49 additions and 35 deletions.
1 change: 1 addition & 0 deletions Makefile
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#
# Paths to common dependencies
#
export BUILD_DIR_ROOT ?= build
export BL_BASE ?= $(wildcard .)
export LIBOPENCM3 ?= $(wildcard libopencm3)
export LIBKINETIS ?= $(wildcard lib/kinetis/NXP_Kinetis_Bootloader_2_0_0)
Expand Down
4 changes: 4 additions & 0 deletions Makefile.f3
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,10 @@ FLAGS += -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 \
-lopencm3_stm32f3 \
$(EXTRAFLAGS)

# libopencm3 doesn't have USB driver in stm32f3 library, tell it to use the one from stm32f4
# for the cdcacm
$(BUILD_DIR_ROOT)/$(TARGET_FILE_NAME)/stm32/cdcacm.o : FLAGS+=-DSTM32F4

#
# General rules for making dependency and object files
# This is where the compiler is called
Expand Down
18 changes: 10 additions & 8 deletions Makefile.f7
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
# PX4 bootloader build rules for STM32F7 targets.
# Since the STM32F7 is not supported fully in libopencm3 at this time,
# this build is a bit of a hack to use the similar IP blocks of the F469
# for RCC and USB by telling libopencm3 it is an STM32F4
# for USB by telling libopencm3 it is an STM32F4
ARCH=stm32
OPENOCD ?= openocd

Expand All @@ -13,15 +13,17 @@ JTAGCONFIG ?= interface/olimex-jtag-tiny.cfg
PX4_BOOTLOADER_DELAY ?= 5000

SRCS = $(COMMON_SRCS) $(addprefix $(ARCH)/,$(ARCH_SRCS)) main_f7.c
LIBS = opencm3_stm32f7 opencm3_stm32f4

FLAGS += -g -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 \
-DTARGET_HW_$(TARGET_HW) \
-DSTM32F4 \
-T$(LINKER_FILE) \
-L$(LIBOPENCM3)/lib \
-lopencm3_stm32f4 \
$(EXTRAFLAGS)
FLAGS += -g -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 \
-DTARGET_HW_$(TARGET_HW) \
-T$(LINKER_FILE) \
-L$(LIBOPENCM3)/lib $(addprefix -l, $(LIBS)) \
-DSTM32F7

# libopencm3 doesn't have USB driver in stm32f7 library, tell it to use the one from stm32f4
# for the cdcacm
$(BUILD_DIR_ROOT)/$(TARGET_FILE_NAME)/stm32/cdcacm.o : FLAGS+=-DSTM32F4
#
# General rules for making dependency and object files
# This is where the compiler is called
Expand Down
13 changes: 6 additions & 7 deletions hw_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,7 @@
* USBPRODUCTID 0x0011 - PID Should match defconfig
* BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom
* delay provided by an APP FW
* BOARD_TYPE 9 - Must match .prototype boad_id
* BOARD_TYPE 9 - Must match .prototype boad_id
* _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection
* BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector
* BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector
Expand Down Expand Up @@ -349,7 +348,7 @@
# define BOARD_PIN_LED_ACTIVITY GPIO7 // BLUE
# define BOARD_PIN_LED_BOOTLOADER GPIO6 // GREEN
# define BOARD_PORT_LEDS GPIOC
# define BOARD_CLOCK_LEDS RCC_AHB1ENR_IOPCEN
# define BOARD_CLOCK_LEDS RCC_AHB1ENR_GPIOCEN
# define BOARD_LED_ON gpio_clear
# define BOARD_LED_OFF gpio_set

Expand All @@ -362,7 +361,7 @@
# define BOARD_PIN_TX GPIO5
# define BOARD_PIN_RX GPIO6
# define BOARD_USART_PIN_CLOCK_REGISTER RCC_AHB1ENR
# define BOARD_USART_PIN_CLOCK_BIT RCC_AHB1ENR_IOPDEN
# define BOARD_USART_PIN_CLOCK_BIT RCC_AHB1ENR_GPIODEN
# define SERIAL_BREAK_DETECT_DISABLED 1

/*
Expand Down Expand Up @@ -853,7 +852,7 @@
# define FLASH_SECTOR_SIZE 4096
# define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024)
# define BOARD_FLASH_SECTORS ((BOARD_FLASH_SIZE / FLASH_SECTOR_SIZE)- \
(BOOTLOADER_RESERVATION_SIZE/FLASH_SECTOR_SIZE))
(BOOTLOADER_RESERVATION_SIZE/FLASH_SECTOR_SIZE))

# define OSC_FREQ 16

Expand Down Expand Up @@ -958,7 +957,7 @@
# define BOARD_PIN_LED_ACTIVITY GPIO7 // BLUE
# define BOARD_PIN_LED_BOOTLOADER GPIO6 // GREEN
# define BOARD_PORT_LEDS GPIOC
# define BOARD_CLOCK_LEDS RCC_AHB1ENR_IOPCEN
# define BOARD_CLOCK_LEDS RCC_AHB1ENR_GPIOCEN
# define BOARD_LED_ON gpio_clear
# define BOARD_LED_OFF gpio_set

Expand All @@ -971,7 +970,7 @@
# define BOARD_PIN_TX GPIO5
# define BOARD_PIN_RX GPIO6
# define BOARD_USART_PIN_CLOCK_REGISTER RCC_AHB1ENR
# define BOARD_USART_PIN_CLOCK_BIT RCC_AHB1ENR_IOPDEN
# define BOARD_USART_PIN_CLOCK_BIT RCC_AHB1ENR_GPIODEN
# define SERIAL_BREAK_DETECT_DISABLED 1

/*
Expand Down
34 changes: 21 additions & 13 deletions main_f7.c
Original file line number Diff line number Diff line change
Expand Up @@ -6,13 +6,13 @@
#include "hw_config.h"

#include <stdlib.h>

#include <libopencm3/stm32/rcc.h>
#include <libopencm3/stm32/gpio.h>
#include <libopencm3/stm32/flash.h>
#include <libopencm3/stm32/usart.h>
#include <libopencm3/cm3/systick.h>
#include <libopencm3/stm32/pwr.h>
# include <libopencm3/stm32/timer.h>

#include "bl.h"
#include "uart.h"
Expand Down Expand Up @@ -134,18 +134,24 @@ static void board_init(void);
#define POWER_DOWN_RTC_SIGNATURE 0xdeaddead // Written by app fw to not re-power on.
#define BOOT_RTC_REG MMIO32(RTC_BASE + 0x50)

/* standard clocking for all F7 boards */
/* standard clocking for all F7 boards: 216MHz w/ overdrive
*
* f_voc = f_osc * (PLLN / PLLM) = OSC_FREQ * PLLN / OSC_FREQ = PLLN = 432
* f_pll = f_voc / PLLP = PLLN / PLLP = 216
* f_usb_sdmmc = f_voc / PLLQ = 48
*/
static const struct rcc_clock_scale clock_setup = {
.pllm = 8,
.plln = 216,
/* 216MHz */
.pllm = OSC_FREQ,
.plln = 432,
.pllp = 2,
.pllq = 9,
.pllr = 2,
.flash_config = FLASH_ACR_ICEN | FLASH_ACR_DCEN | FLASH_ACR_LATENCY_7WS,
.hpre = RCC_CFGR_HPRE_DIV_NONE,
.ppre1 = RCC_CFGR_PPRE_DIV_4,
.ppre2 = RCC_CFGR_PPRE_DIV_2,
.power_save = 0,
.flash_config = FLASH_ACR_ICEN | FLASH_ACR_DCEN | FLASH_ACR_LATENCY_5WS,
.vos_scale = PWR_SCALE1, /** <= 180MHz w/o overdrive, <= 216MHz w/ overdrive */
.overdrive = 1,
.apb1_frequency = 54000000,
.apb2_frequency = 108000000,
};
Expand All @@ -154,14 +160,14 @@ static uint32_t
board_get_rtc_signature()
{
/* enable the backup registers */
PWR_CR |= PWR_CR_DBP;
PWR_CR1 |= PWR_CR1_DBP;
RCC_BDCR |= RCC_BDCR_RTCEN;

uint32_t result = BOOT_RTC_REG;

/* disable the backup registers */
RCC_BDCR &= RCC_BDCR_RTCEN;
PWR_CR &= ~PWR_CR_DBP;
PWR_CR1 &= ~PWR_CR1_DBP;

return result;
}
Expand All @@ -170,14 +176,14 @@ static void
board_set_rtc_signature(uint32_t sig)
{
/* enable the backup registers */
PWR_CR |= PWR_CR_DBP;
PWR_CR1 |= PWR_CR1_DBP;
RCC_BDCR |= RCC_BDCR_RTCEN;

BOOT_RTC_REG = sig;

/* disable the backup registers */
RCC_BDCR &= RCC_BDCR_RTCEN;
PWR_CR &= ~PWR_CR_DBP;
PWR_CR1 &= ~PWR_CR1_DBP;
}

static bool
Expand Down Expand Up @@ -315,9 +321,11 @@ board_init(void)
#endif

#if INTERFACE_USB

/* enable Port A GPIO9 to sample VBUS */
rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPAEN);
rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_GPIOAEN);
# if defined(USE_VBUS_PULL_DOWN)
gpio_mode_setup(GPIOA, GPIO_MODE_INPUT, GPIO_PUPD_PULLDOWN, GPIO9);
# endif
#endif

#if INTERFACE_USART
Expand Down
14 changes: 7 additions & 7 deletions rules.mk
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
# Common rules for makefiles for the PX4 bootloaders
#

BUILD_DIR = build/$(TARGET_FILE_NAME)
BUILD_DIR = $(BUILD_DIR_ROOT)/$(TARGET_FILE_NAME)

COBJS := $(addprefix $(BUILD_DIR)/, $(patsubst %.c,%.o,$(SRCS)))
AOBJS := $(addprefix $(BUILD_DIR)/, $(patsubst %.S,%.o,$(ASRCS)))
Expand All @@ -16,17 +16,17 @@ BINARY = $(BUILD_DIR)/$(TARGET_FILE_NAME).bin
all: debug $(BUILD_DIR) $(ELF) $(BINARY)

debug:
@echo SRCS=$(SRCS)
@echo COBJS=$(COBJS)
@echo ASRCS=$(ASRCS)
@echo AOBJS=$(AOBJS)
@echo SUBDIRS=$(SUBDIRS)
# @echo SRCS=$(SRCS)
# @echo COBJS=$(COBJS)
# @echo ASRCS=$(ASRCS)
# @echo AOBJS=$(AOBJS)
# @echo SUBDIRS=$(SUBDIRS)


# Compile and generate dependency files
$(BUILD_DIR)/%.o: %.c
@echo Generating object $@
$(CC) -c -MMD $(FLAGS) -o $@ $*.c
$(CC) -c -MMD $(FLAGS) -o $@ $<

$(BUILD_DIR)/%.o: %.S
@echo Generating object $@
Expand Down

0 comments on commit 131dfba

Please sign in to comment.