Adding preliminary support for STM32F767 (Nucleo-144 F767ZI)

boxcar_dstar_correlator_48k
Andy CA6JAU 2017-08-24 22:24:27 -03:00
parent 6c6b6c19fc
commit a60059bc90
10 changed files with 452 additions and 16 deletions

View File

@ -21,6 +21,8 @@
#if defined(STM32F4XX) || defined(STM32F4)
#include "stm32f4xx.h"
#elif defined(STM32F7XX)
#include "stm32f7xx.h"
#elif defined(STM32F105xC)
#include "stm32f1xx.h"
#include "STM32Utils.h"
@ -30,6 +32,8 @@
#if defined(__SAM3X8E__) || defined(STM32F105xC)
#define ARM_MATH_CM3
#elif defined(STM32F7XX)
#define ARM_MATH_CM7
#elif defined(STM32F4XX) || defined(STM32F4) || defined(__MK20DX256__) || defined(__MK64FX512__) || defined(__MK66FX1M0__)
#define ARM_MATH_CM4
#else

View File

@ -22,7 +22,7 @@
#include "Globals.h"
#include "IO.h"
#if defined(STM32F4XX) || defined(STM32F4)
#if defined(STM32F4XX) || defined(STM32F4) || defined(STM32F7XX)
#if defined(STM32F4_DISCOVERY)
/*
@ -333,8 +333,101 @@ EXT_CLK PB8 input CN5 Pin10
#error "Either STM32F4_NUCLEO_MORPHO_HEADER or STM32F4_NUCLEO_ARDUINO_HEADER need to be defined in Config.h"
#endif
#elif defined(STM32F7_NUCLEO)
/*
Pin definitions for STM32F7 Nucleo boards (ST Morpho header):
PTT PB13 output CN10 Pin30
COSLED PB14 output CN10 Pin28
LED PB0 output CN10 Pin11
COS PB15 input CN10 Pin26
DSTAR PB10 output CN10 Pin25
DMR PB4 output CN10 Pin27
YSF PB5 output CN10 Pin29
P25 PB3 output CN10 Pin
MDSTAR PC4 output CN7 Pin34
MDMR PC5 output CN7 Pin6
MYSF PC2 output CN7 Pin35
MP25 PC3 output CN7 Pin37
RX PA0 analog input CN7 Pin28
RSSI PA1 analog input CN7 Pin30
TX PA4 analog output CN7 Pin32
EXT_CLK PA15 input CN7 Pin18
*/
#define PIN_COS GPIO_Pin_15
#define PORT_COS GPIOB
#define RCC_Per_COS RCC_AHB1Periph_GPIOB
#define PIN_PTT GPIO_Pin_13
#define PORT_PTT GPIOB
#define RCC_Per_PTT RCC_AHB1Periph_GPIOB
#define PIN_COSLED GPIO_Pin_14
#define PORT_COSLED GPIOB
#define RCC_Per_COSLED RCC_AHB1Periph_GPIOB
#define PIN_LED GPIO_Pin_0
#define PORT_LED GPIOB
#define RCC_Per_LED RCC_AHB1Periph_GPIOB
#define PIN_P25 GPIO_Pin_3
#define PORT_P25 GPIOB
#define RCC_Per_P25 RCC_AHB1Periph_GPIOB
#define PIN_DSTAR GPIO_Pin_10
#define PORT_DSTAR GPIOB
#define RCC_Per_DSTAR RCC_AHB1Periph_GPIOB
#define PIN_DMR GPIO_Pin_4
#define PORT_DMR GPIOB
#define RCC_Per_DMR RCC_AHB1Periph_GPIOB
#define PIN_YSF GPIO_Pin_5
#define PORT_YSF GPIOB
#define RCC_Per_YSF RCC_AHB1Periph_GPIOB
#if defined(STM32F4_NUCLEO_MODE_PINS)
#define PIN_MP25 GPIO_Pin_3
#define PORT_MP25 GPIOC
#define RCC_Per_MP25 RCC_AHB1Periph_GPIOC
#define PIN_MDSTAR GPIO_Pin_4
#define PORT_MDSTAR GPIOC
#define RCC_Per_MDSTAR RCC_AHB1Periph_GPIOC
#define PIN_MDMR GPIO_Pin_5
#define PORT_MDMR GPIOC
#define RCC_Per_MDMR RCC_AHB1Periph_GPIOC
#define PIN_MYSF GPIO_Pin_2
#define PORT_MYSF GPIOC
#define RCC_Per_MYSF RCC_AHB1Periph_GPIOC
#endif
#define PIN_EXT_CLK GPIO_Pin_15
#define SRC_EXT_CLK GPIO_PinSource15
#define PORT_EXT_CLK GPIOA
#define PIN_RX GPIO_Pin_0
#define PIN_RX_CH ADC_Channel_0
#define PORT_RX GPIOA
#define RCC_Per_RX RCC_AHB1Periph_GPIOA
#define PIN_RSSI GPIO_Pin_1
#define PIN_RSSI_CH ADC_Channel_1
#define PORT_RSSI GPIOA
#define RCC_Per_RSSI RCC_AHB1Periph_GPIOA
#define PIN_TX GPIO_Pin_4
#define PIN_TX_CH DAC_Channel_1
#else
#error "Either STM32F4_DISCOVERY, STM32F4_PI or STM32F4_NUCLEO need to be defined"
#error "Either STM32F4_DISCOVERY, STM32F4_PI, STM32F4_NUCLEO or STM32F7_NUCLEO need to be defined"
#endif
const uint16_t DC_OFFSET = 2048U;

View File

@ -18,7 +18,7 @@
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
#if defined(STM32F4XX) || defined(STM32F4) || defined(STM32F105xC)
#if defined(STM32F4XX) || defined(STM32F4) || defined(STM32F7XX) || defined(STM32F105xC)
#include "Config.h"
#include "Globals.h"

173
Makefile.F7 100644
View File

@ -0,0 +1,173 @@
# Copyright (C) 2016,2017 by Andy Uribe CA6JAU
# Copyright (C) 2016 by Jim McLaughlin KI6ZUM
# This program 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 2 of the License, or
# (at your option) any later version.
# This program 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 this program; if not, write to the Free Software
# Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
# GNU ARM Embedded Toolchain
CC=arm-none-eabi-gcc
CXX=arm-none-eabi-g++
LD=arm-none-eabi-ld
AR=arm-none-eabi-ar
AS=arm-none-eabi-as
CP=arm-none-eabi-objcopy
OD=arm-none-eabi-objdump
NM=arm-none-eabi-nm
SIZE=arm-none-eabi-size
A2L=arm-none-eabi-addr2line
# Directory Structure
BINDIR=bin
# Find source files
# "SystemRoot" is only defined in Windows
ifdef SYSTEMROOT
ASOURCES=$(shell dir /S /B *.s)
CSOURCES=$(shell dir /S /B *.c)
CXXSOURCES=$(shell dir /S /B *.cpp)
CLEANCMD=del /S *.o *.hex *.bin *.elf GitVersion.h
MDBIN=md $@
else ifdef SystemRoot
ASOURCES=$(shell dir /S /B *.s)
CSOURCES=$(shell dir /S /B *.c)
CXXSOURCES=$(shell dir /S /B *.cpp)
CLEANCMD=del /S *.o *.hex *.bin *.elf GitVersion.h
MDBIN=md $@
else
ASOURCES=$(shell find . -name '*.s')
CSOURCES=$(shell find . -name '*.c')
CXXSOURCES=$(shell find . -name '*.cpp')
CLEANCMD=rm -f $(OBJECTS) $(BINDIR)/$(BINELF) $(BINDIR)/$(BINHEX) $(BINDIR)/$(BINBIN) GitVersion.h
MDBIN=mkdir $@
endif
# Default reference oscillator frequencies
ifndef $(OSC)
ifeq ($(MAKECMDGOALS),pi)
OSC=12000000
else
OSC=8000000
endif
endif
# Find header directories
INC= . STM32F7XX_Lib/CMSIS/Include/ STM32F7XX_Lib/Device/ STM32F7XX_Lib/STM32F7xx_StdPeriph_Driver/inc/
INCLUDES=$(INC:%=-I%)
# Find libraries
INCLUDES_LIBS=STM32F7XX_Lib/CMSIS/Lib/GCC/libarm_cortexM7lfsp_math.a
LINK_LIBS=
# Create object list
OBJECTS=$(ASOURCES:%.s=%.o)
OBJECTS+=$(CSOURCES:%.c=%.o)
OBJECTS+=$(CXXSOURCES:%.cpp=%.o)
# Define output files ELF & IHEX
BINELF=outp.elf
BINHEX=outp.hex
BINBIN=outp.bin
# MCU FLAGS
MCFLAGS=-mcpu=cortex-m7 -mthumb -mlittle-endian -mfpu=fpv5-sp-d16 -mfloat-abi=hard -mthumb-interwork
# COMPILE FLAGS
# STM32F7 Nucleo-144-F767ZI board:
DEFS_NUCLEO=-DUSE_HAL_DRIVER -DSTM32F767xx -DSTM32F7XX -DSTM32F7_NUCLEO -DHSE_VALUE=$(OSC) -DMADEBYMAKEFILE
CFLAGS=-c $(MCFLAGS) $(INCLUDES)
CXXFLAGS=-c $(MCFLAGS) $(INCLUDES)
# LINKER FLAGS
LDSCRIPT=stm32f7xx_link.ld
LDFLAGS =-T $(LDSCRIPT) $(MCFLAGS) --specs=nosys.specs $(INCLUDES_LIBS) $(LINK_LIBS)
# Build Rules
.PHONY: all release nucleo debug clean
# Default target: STM32F7 Nucleo-144-F767ZI board
all: nucleo
nucleo: GitVersion.h
nucleo: CFLAGS+=$(DEFS_NUCLEO) -Os -ffunction-sections -fdata-sections -fno-builtin -Wno-implicit -DCUSTOM_NEW -DNO_EXCEPTIONS
nucleo: CXXFLAGS+=$(DEFS_NUCLEO) -Os -fno-exceptions -ffunction-sections -fdata-sections -fno-builtin -fno-rtti -DCUSTOM_NEW -DNO_EXCEPTIONS
nucleo: LDFLAGS+=-Os --specs=nano.specs
nucleo: release
debug: CFLAGS+=-g
debug: CXXFLAGS+=-g
debug: LDFLAGS+=-g
debug: release
release: $(BINDIR)
release: $(BINDIR)/$(BINHEX)
release: $(BINDIR)/$(BINBIN)
$(BINDIR):
$(MDBIN)
$(BINDIR)/$(BINHEX): $(BINDIR)/$(BINELF)
$(CP) -O ihex $< $@
@echo "Objcopy from ELF to IHEX complete!\n"
$(BINDIR)/$(BINBIN): $(BINDIR)/$(BINELF)
$(CP) -O binary $< $@
@echo "Objcopy from ELF to BINARY complete!\n"
$(BINDIR)/$(BINELF): $(OBJECTS)
$(CXX) $(OBJECTS) $(LDFLAGS) -o $@
@echo "Linking complete!\n"
$(SIZE) $(BINDIR)/$(BINELF)
%.o: %.cpp
$(CXX) $(CXXFLAGS) $< -o $@
@echo "Compiled "$<"!\n"
%.o: %.c
$(CC) $(CFLAGS) $< -o $@
@echo "Compiled "$<"!\n"
%.o: %.s
$(CC) $(CFLAGS) $< -o $@
@echo "Assambled "$<"!\n"
clean:
$(CLEANCMD)
deploy:
ifneq ($(wildcard /usr/bin/openocd),)
/usr/bin/openocd -f /usr/share/openocd/scripts/interface/stlink-v2-1.cfg -f /usr/share/openocd/scripts/target/stm32f7x.cfg -c "program bin/$(BINELF) verify reset exit"
endif
ifneq ($(wildcard /usr/local/bin/openocd),)
/usr/local/bin/openocd -f /usr/local/share/openocd/scripts/interface/stlink-v2-1.cfg -f /usr/local/share/openocd/scripts/target/stm32f7x.cfg -c "program bin/$(BINELF) verify reset exit"
endif
ifneq ($(wildcard /opt/openocd/bin/openocd),)
/opt/openocd/bin/openocd -f /opt/openocd/share/openocd/scripts/interface/stlink-v2-1.cfg -f /opt/openocd/share/openocd/scripts/target/stm32f7x.cfg -c "program bin/$(BINELF) verify reset exit"
endif
# Export the current git version if the index file exists, else 000...
GitVersion.h:
ifdef SYSTEMROOT
echo #define GITVERSION "0000000" > $@
else ifdef SystemRoot
echo #define GITVERSION "0000000" > $@
else
ifneq ("$(wildcard .git/index)","")
echo "#define GITVERSION \"$(shell git rev-parse --short HEAD)\"" > $@
else
echo "#define GITVERSION \"0000000\"" > $@
endif
endif

View File

@ -24,6 +24,9 @@ Boston, MA 02110-1301, USA.
#if defined(STM32F4XX) || defined(STM32F4)
#include "stm32f4xx.h"
#include <cstddef>
#elif defined(STM32F7XX)
#include "stm32f7xx.h"
#include <cstddef>
#elif defined(STM32F105xC)
#include "stm32f1xx.h"
#include <cstddef>

View File

@ -24,6 +24,9 @@ Boston, MA 02110-1301, USA.
#if defined(STM32F4XX) || defined(STM32F4)
#include "stm32f4xx.h"
#include <cstddef>
#elif defined(STM32F7XX)
#include "stm32f7xx.h"
#include <cstddef>
#elif defined(STM32F105xC)
#include "stm32f1xx.h"
#include <cstddef>

View File

@ -24,6 +24,9 @@ Boston, MA 02110-1301, USA.
#if defined(STM32F4XX) || defined(STM32F4)
#include "stm32f4xx.h"
#include <cstddef>
#elif defined(STM32F7XX)
#include "stm32f7xx.h"
#include <cstddef>
#elif defined(STM32F105xC)
#include "stm32f1xx.h"
#include <cstddef>

View File

@ -37,7 +37,7 @@ UART5 - TXD PC12 - RXD PD2 (Discovery, Pi and Nucleo with Morpho header)
*/
#if defined(STM32F4XX) || defined(STM32F4)
#if defined(STM32F4XX) || defined(STM32F4) || defined(STM32F7XX)
#define TX_SERIAL_FIFO_SIZE 512U
#define RX_SERIAL_FIFO_SIZE 512U
@ -432,7 +432,7 @@ void WriteUSART2(const uint8_t* data, uint16_t length)
#endif
/* ************* USART3 ***************** */
#if defined(STM32F4_DISCOVERY) || defined(STM32F4_PI)
#if defined(STM32F4_DISCOVERY) || defined(STM32F4_PI) || defined(STM32F7_NUCLEO)
volatile uint8_t TXSerialfifo3[TX_SERIAL_FIFO_SIZE];
volatile uint8_t RXSerialfifo3[RX_SERIAL_FIFO_SIZE];
@ -541,17 +541,34 @@ void USART3_IRQHandler()
}
}
#if defined(STM32F7_NUCLEO)
// USART3 - TXD PD8 - RXD PD9
#define USART3_GPIO_PinSource_TX GPIO_PinSource8
#define USART3_GPIO_PinSource_RX GPIO_PinSource9
#define USART3_GPIO_Pin_TX GPIO_Pin_8
#define USART3_GPIO_Pin_RX GPIO_Pin_9
#define USART3_GPIO_PORT GPIOD
#define USART3_RCC_Periph RCC_AHB1Periph_GPIOD
#else
// USART3 - TXD PC10 - RXD PC11
#define USART3_GPIO_PinSource_TX GPIO_PinSource10
#define USART3_GPIO_PinSource_RX GPIO_PinSource11
#define USART3_GPIO_Pin_TX GPIO_Pin_10
#define USART3_GPIO_Pin_RX GPIO_Pin_11
#define USART3_GPIO_PORT GPIOC
#define USART3_RCC_Periph RCC_AHB1Periph_GPIOC
#endif
void InitUSART3(int speed)
{
// USART3 - TXD PC10 - RXD PC11
GPIO_InitTypeDef GPIO_InitStructure;
USART_InitTypeDef USART_InitStructure;
NVIC_InitTypeDef NVIC_InitStructure;
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOC, ENABLE);
RCC_AHB1PeriphClockCmd(USART3_RCC_Periph, ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE);
GPIO_PinAFConfig(GPIOC, GPIO_PinSource10, GPIO_AF_USART3);
GPIO_PinAFConfig(GPIOC, GPIO_PinSource11, GPIO_AF_USART3);
GPIO_PinAFConfig(USART3_GPIO_PORT, USART3_GPIO_PinSource_TX, GPIO_AF_USART3);
GPIO_PinAFConfig(USART3_GPIO_PORT, USART3_GPIO_PinSource_RX, GPIO_AF_USART3);
// USART IRQ init
NVIC_InitStructure.NVIC_IRQChannel = USART3_IRQn;
@ -565,9 +582,9 @@ void InitUSART3(int speed)
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10 | GPIO_Pin_11; // Tx | Rx
GPIO_InitStructure.GPIO_Pin = USART3_GPIO_Pin_TX | USART3_GPIO_Pin_RX; // Tx | Rx
GPIO_InitStructure.GPIO_Speed = GPIO_Fast_Speed;
GPIO_Init(GPIOC, &GPIO_InitStructure);
GPIO_Init(USART3_GPIO_PORT, &GPIO_InitStructure);
// Configure USART baud rate
USART_StructInit(&USART_InitStructure);
@ -822,7 +839,7 @@ void CSerialPort::beginInt(uint8_t n, int speed)
{
switch (n) {
case 1U:
#if defined(STM32F4_DISCOVERY)
#if defined(STM32F4_DISCOVERY) || defined(STM32F7_NUCLEO)
InitUSART3(speed);
#elif defined(STM32F4_PI)
InitUSART1(speed);
@ -846,7 +863,7 @@ int CSerialPort::availableInt(uint8_t n)
{
switch (n) {
case 1U:
#if defined(STM32F4_DISCOVERY)
#if defined(STM32F4_DISCOVERY) || defined(STM32F7_NUCLEO)
return AvailUSART3();
#elif defined(STM32F4_PI)
return AvailUSART1();
@ -868,7 +885,7 @@ int CSerialPort::availableForWriteInt(uint8_t n)
{
switch (n) {
case 1U:
#if defined(STM32F4_DISCOVERY)
#if defined(STM32F4_DISCOVERY) || defined(STM32F7_NUCLEO)
return AvailForWriteUSART3();
#elif defined(STM32F4_PI)
return AvailForWriteUSART1();
@ -890,7 +907,7 @@ uint8_t CSerialPort::readInt(uint8_t n)
{
switch (n) {
case 1U:
#if defined(STM32F4_DISCOVERY)
#if defined(STM32F4_DISCOVERY) || defined(STM32F7_NUCLEO)
return ReadUSART3();
#elif defined(STM32F4_PI)
return ReadUSART1();
@ -912,7 +929,7 @@ void CSerialPort::writeInt(uint8_t n, const uint8_t* data, uint16_t length, bool
{
switch (n) {
case 1U:
#if defined(STM32F4_DISCOVERY)
#if defined(STM32F4_DISCOVERY) || defined(STM32F7_NUCLEO)
WriteUSART3(data, length);
if (flush)
TXSerialFlush3();

View File

@ -22,6 +22,9 @@
#if defined(STM32F4XX) || defined(STM32F4)
#include "stm32f4xx.h"
#include <cstddef>
#elif defined(STM32F7XX)
#include "stm32f7xx.h"
#include <cstddef>
#elif defined(STM32F105xC)
#include "stm32f1xx.h"
#include <cstddef>

137
stm32f7xx_link.ld 100644
View File

@ -0,0 +1,137 @@
/*
* Copyright (C) 2017 by Andy Uribe CA6JAU
*
* This program 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 2 of the License, or
* (at your option) any later version.
*
* This program 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 this program; if not, write to the Free Software
* Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
*/
/* Required amount of heap and stack */
_min_heap_size = 0x1000;
_min_stack_size = 0x0800;
/* The entry point in the interrupt vector table */
ENTRY(Reset_Handler)
/* Memory areas */
MEMORY
{
ROM (rx) : ORIGIN = 0x08000000, LENGTH = 2048K /* FLASH */
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 512K /* Main RAM */
}
/* Stack start address (end of 512K RAM) */
_estack = ORIGIN(RAM) + LENGTH(RAM);
SECTIONS
{
.text :
{
/* The interrupt vector table */
. = ALIGN(4);
KEEP(*(.isr_vector .isr_vector.*))
/* The program code */
. = ALIGN(4);
*(.text .text*)
*(.rodata .rodata*)
/* ARM-Thumb code */
*(.glue_7) *(.glue_7t)
. = ALIGN(4);
KEEP(*(.init))
KEEP(*(.fini))
/* EABI C++ global constructors support */
. = ALIGN(4);
__preinit_array_start = .;
KEEP (*(.preinit_array))
__preinit_array_end = .;
/* EABI C++ global constructors support */
. = ALIGN(4);
__init_array_start = .;
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array))
__init_array_end = .;
/* EABI C++ global constructors support */
. = ALIGN(4);
__fini_array_start = .;
KEEP (*(.fini_array))
KEEP (*(SORT(.fini_array.*)))
__fini_array_end = .;
} > ROM
/* ARM sections containing exception unwinding information */
.ARM.extab : {
__extab_start = .;
*(.ARM.extab* .gnu.linkonce.armextab.*)
__extab_end = .;
} > ROM
/* ARM index entries for section unwinding */
.ARM.exidx : {
__exidx_start = .;
*(.ARM.exidx*)
__exidx_end = .;
} > ROM
/* Start address for the initialization values of the .data section */
_sidata = .;
/* The .data section (initialized data) */
.data : AT ( _sidata )
{
. = ALIGN(4);
_sdata = . ; /* Start address for the .data section */
*(.data .data*)
. = ALIGN(4);
_edata = . ; /* End address for the .data section */
} > RAM
/* The .bss section (uninitialized data) */
.bss :
{
. = ALIGN(4);
_sbss = .; /* Start address for the .bss section */
__bss_start__ = _sbss;
*(.bss)
*(.bss*)
*(COMMON)
. = ALIGN(4);
_ebss = . ; /* End address for the .bss section */
__bss_end__ = _ebss;
} > RAM
/* Space for heap and stack */
.heap_stack :
{
end = . ; /* 'end' symbol defines heap location */
_end = end ;
. = . + _min_heap_size; /* Additional space for heap and stack */
. = . + _min_stack_size;
} > RAM
/* Remove information from the standard libraries */
/DISCARD/ :
{
libc.a ( * )
libm.a ( * )
libgcc.a ( * )
}
}