This commit is contained in:
rusefi 2018-11-16 08:03:35 -05:00
commit 437ea64ab3
64 changed files with 8097 additions and 329 deletions

View File

@ -108,11 +108,27 @@ ifeq ($(PROJECT_BOARD),)
endif
DDEFS += -D$(PROJECT_BOARD)
ifeq ($(PROJECT_CPU),)
PROJECT_CPU = ST_STM32F4
endif
DDEFS += -D$(PROJECT_CPU)
# CPU-dependent defs
ifeq ($(PROJECT_CPU),ST_STM32F7)
CPU_STARTUP = startup_stm32f7xx.mk
CPU_PLATFORM = STM32F7xx/platform.mk
CPU_HWLAYER = stm32f7
else # ST_STM32F4
CPU_STARTUP = startup_stm32f4xx.mk
CPU_PLATFORM = STM32F4xx/platform.mk
CPU_HWLAYER = stm32f4
endif
# Startup files.
include $(CHIBIOS)/os/common/startup/ARMCMx/compilers/GCC/mk/startup_stm32f4xx.mk
include $(CHIBIOS)/os/common/startup/ARMCMx/compilers/GCC/mk/$(CPU_STARTUP)
# HAL-OSAL files (optional).
include $(CHIBIOS_CONTRIB)/os/hal/hal.mk
include $(CHIBIOS)/os/hal/ports/STM32/STM32F4xx/platform.mk
include $(CHIBIOS)/os/hal/ports/STM32/$(CPU_PLATFORM)
include $(CHIBIOS)/os/hal/osal/rt/osal.mk
# RTOS files (optional).
include $(CHIBIOS)/os/rt/rt.mk
@ -254,7 +270,7 @@ INCDIR = $(CHIBIOS)/os/license \
hw_layer/lcd \
hw_layer/sensors \
hw_layer/mass_storage \
hw_layer/stm32f4 \
hw_layer/$(CPU_HWLAYER) \
development \
development/hw_layer \
development/test \

View File

@ -0,0 +1,10 @@
rem
rem STM32F767 version of the firmware for Nucleo-F767ZI board
rem
cd ../../..
set PROJECT_BOARD=NUCLEO_F767
set PROJECT_CPU=ST_STM32F7
set EXTRA_PARAMS="-DDUMMY -DSTM32F767xx -DEFI_ENABLE_ASSERTS=FALSE -DCH_DBG_ENABLE_CHECKS=FALSE -DCH_DBG_ENABLE_TRACE=FALSE -DCH_DBG_ENABLE_ASSERTS=FALSE -DCH_DBG_ENABLE_STACK_CHECK=FALSE -DCH_DBG_FILL_THREADS=FALSE -DCH_DBG_THREADS_PROFILING=FALSE"
set DEBUG_LEVEL_OPT="-O2"
call compile_and_program.bat -r

View File

@ -0,0 +1,132 @@
/*
ChibiOS - Copyright (C) 2006..2016 Giovanni Di Sirio
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
/*
* STM32F76xxI generic setup.
*
* RAM0 - Data, Heap.
* RAM3 - Main Stack, Process Stack, BSS, NOCACHE, ETH.
*
* Notes:
* BSS is placed in DTCM RAM in order to simplify DMA buffers management.
*/
MEMORY
{
flash0 : org = 0x08000000, len = 2M /* Flash as AXIM (writable) */
flash1 : org = 0x00200000, len = 2M /* Flash as ITCM */
flash2 : org = 0x00000000, len = 0
flash3 : org = 0x00000000, len = 0
flash4 : org = 0x00000000, len = 0
flash5 : org = 0x00000000, len = 0
flash6 : org = 0x00000000, len = 0
flash7 : org = 0x00000000, len = 0
ram0 : org = 0x20020000, len = 384k /* SRAM1 + SRAM2 */
ram1 : org = 0x20020000, len = 368k /* SRAM1 */
ram2 : org = 0x2007C000, len = 16k /* SRAM2 */
ram3 : org = 0x20000000, len = 128k /* DTCM-RAM */
ram4 : org = 0x00000000, len = 16k /* ITCM-RAM */
ram5 : org = 0x40024000, len = 4k /* BCKP SRAM */
ram6 : org = 0x00000000, len = 0
ram7 : org = 0x00000000, len = 0
}
/* For each data/text section two region are defined, a virtual region
and a load region (_LMA suffix).*/
/* Flash region to be used for exception vectors.*/
REGION_ALIAS("VECTORS_FLASH", flash1);
REGION_ALIAS("VECTORS_FLASH_LMA", flash0);
/* Flash region to be used for constructors and destructors.*/
REGION_ALIAS("XTORS_FLASH", flash1);
REGION_ALIAS("XTORS_FLASH_LMA", flash0);
/* Flash region to be used for code text.*/
REGION_ALIAS("TEXT_FLASH", flash1);
REGION_ALIAS("TEXT_FLASH_LMA", flash0);
/* Flash region to be used for read only data.*/
REGION_ALIAS("RODATA_FLASH", flash0);
REGION_ALIAS("RODATA_FLASH_LMA", flash0);
/* Flash region to be used for various.*/
REGION_ALIAS("VARIOUS_FLASH", flash1);
REGION_ALIAS("VARIOUS_FLASH_LMA", flash0);
/* Flash region to be used for RAM(n) initialization data.*/
REGION_ALIAS("RAM_INIT_FLASH_LMA", flash0);
/* RAM region to be used for Main stack. This stack accommodates the processing
of all exceptions and interrupts.*/
REGION_ALIAS("MAIN_STACK_RAM", ram0);
/* RAM region to be used for the process stack. This is the stack used by
the main() function.*/
REGION_ALIAS("PROCESS_STACK_RAM", ram0);
/* RAM region to be used for data segment.*/
REGION_ALIAS("DATA_RAM", ram0);
REGION_ALIAS("DATA_RAM_LMA", flash0);
/* RAM region to be used for BSS segment.*/
REGION_ALIAS("BSS_RAM", ram0);
/* RAM region to be used for the default heap.*/
REGION_ALIAS("HEAP_RAM", ram0);
/* Stack rules inclusion.*/
INCLUDE rules_stacks.ld
/*===========================================================================*/
/* Custom sections for STM32F7xx. */
/*===========================================================================*/
/* RAM region to be used for nocache segment.*/
REGION_ALIAS("NOCACHE_RAM", ram3);
/* RAM region to be used for eth segment.*/
REGION_ALIAS("ETH_RAM", ram3);
SECTIONS
{
/* Special section for non cache-able areas.*/
.nocache (NOLOAD) : ALIGN(4)
{
__nocache_base__ = .;
*(.nocache)
*(.nocache.*)
*(.bss.__nocache_*)
. = ALIGN(4);
__nocache_end__ = .;
} > NOCACHE_RAM
/* Special section for Ethernet DMA non cache-able areas.*/
.eth (NOLOAD) : ALIGN(4)
{
__eth_base__ = .;
*(.eth)
*(.eth.*)
*(.bss.__eth_*)
. = ALIGN(4);
__eth_end__ = .;
} > ETH_RAM
}
/* Code rules inclusion.*/
INCLUDE rules_code.ld
/* Data rules inclusion.*/
INCLUDE rules_data.ld

View File

@ -0,0 +1,137 @@
/*
ChibiOS - Copyright (C) 2006..2016 Giovanni Di Sirio
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
/*
* This file has been automatically generated using ChibiStudio board
* generator plugin. Do not edit manually.
*/
#include "hal.h"
#if HAL_USE_PAL || defined(__DOXYGEN__)
/**
* @brief PAL setup.
* @details Digital I/O ports static configuration as defined in @p board.h.
* This variable is used by the HAL when initializing the PAL driver.
*/
const PALConfig pal_default_config = {
#if STM32_HAS_GPIOA
{VAL_GPIOA_MODER, VAL_GPIOA_OTYPER, VAL_GPIOA_OSPEEDR, VAL_GPIOA_PUPDR,
VAL_GPIOA_ODR, VAL_GPIOA_AFRL, VAL_GPIOA_AFRH},
#endif
#if STM32_HAS_GPIOB
{VAL_GPIOB_MODER, VAL_GPIOB_OTYPER, VAL_GPIOB_OSPEEDR, VAL_GPIOB_PUPDR,
VAL_GPIOB_ODR, VAL_GPIOB_AFRL, VAL_GPIOB_AFRH},
#endif
#if STM32_HAS_GPIOC
{VAL_GPIOC_MODER, VAL_GPIOC_OTYPER, VAL_GPIOC_OSPEEDR, VAL_GPIOC_PUPDR,
VAL_GPIOC_ODR, VAL_GPIOC_AFRL, VAL_GPIOC_AFRH},
#endif
#if STM32_HAS_GPIOD
{VAL_GPIOD_MODER, VAL_GPIOD_OTYPER, VAL_GPIOD_OSPEEDR, VAL_GPIOD_PUPDR,
VAL_GPIOD_ODR, VAL_GPIOD_AFRL, VAL_GPIOD_AFRH},
#endif
#if STM32_HAS_GPIOE
{VAL_GPIOE_MODER, VAL_GPIOE_OTYPER, VAL_GPIOE_OSPEEDR, VAL_GPIOE_PUPDR,
VAL_GPIOE_ODR, VAL_GPIOE_AFRL, VAL_GPIOE_AFRH},
#endif
#if STM32_HAS_GPIOF
{VAL_GPIOF_MODER, VAL_GPIOF_OTYPER, VAL_GPIOF_OSPEEDR, VAL_GPIOF_PUPDR,
VAL_GPIOF_ODR, VAL_GPIOF_AFRL, VAL_GPIOF_AFRH},
#endif
#if STM32_HAS_GPIOG
{VAL_GPIOG_MODER, VAL_GPIOG_OTYPER, VAL_GPIOG_OSPEEDR, VAL_GPIOG_PUPDR,
VAL_GPIOG_ODR, VAL_GPIOG_AFRL, VAL_GPIOG_AFRH},
#endif
#if STM32_HAS_GPIOH
{VAL_GPIOH_MODER, VAL_GPIOH_OTYPER, VAL_GPIOH_OSPEEDR, VAL_GPIOH_PUPDR,
VAL_GPIOH_ODR, VAL_GPIOH_AFRL, VAL_GPIOH_AFRH},
#endif
#if STM32_HAS_GPIOI
{VAL_GPIOI_MODER, VAL_GPIOI_OTYPER, VAL_GPIOI_OSPEEDR, VAL_GPIOI_PUPDR,
VAL_GPIOI_ODR, VAL_GPIOI_AFRL, VAL_GPIOI_AFRH},
#endif
#if STM32_HAS_GPIOJ
{VAL_GPIOJ_MODER, VAL_GPIOJ_OTYPER, VAL_GPIOJ_OSPEEDR, VAL_GPIOJ_PUPDR,
VAL_GPIOJ_ODR, VAL_GPIOJ_AFRL, VAL_GPIOJ_AFRH},
#endif
#if STM32_HAS_GPIOK
{VAL_GPIOK_MODER, VAL_GPIOK_OTYPER, VAL_GPIOK_OSPEEDR, VAL_GPIOK_PUPDR,
VAL_GPIOK_ODR, VAL_GPIOK_AFRL, VAL_GPIOK_AFRH}
#endif
};
#endif
/**
* @brief Early initialization code.
* @details This initialization must be performed just after stack setup
* and before any other initialization.
*/
void __early_init(void) {
stm32_clock_init();
}
#if HAL_USE_SDC || defined(__DOXYGEN__)
/**
* @brief SDC card detection.
*/
bool sdc_lld_is_card_inserted(SDCDriver *sdcp) {
(void)sdcp;
/* TODO: Fill the implementation.*/
return true;
}
/**
* @brief SDC card write protection detection.
*/
bool sdc_lld_is_write_protected(SDCDriver *sdcp) {
(void)sdcp;
/* TODO: Fill the implementation.*/
return false;
}
#endif /* HAL_USE_SDC */
#if HAL_USE_MMC_SPI || defined(__DOXYGEN__)
/**
* @brief MMC_SPI card detection.
*/
bool mmc_lld_is_card_inserted(MMCDriver *mmcp) {
(void)mmcp;
/* TODO: Fill the implementation.*/
return true;
}
/**
* @brief MMC_SPI card write protection detection.
*/
bool mmc_lld_is_write_protected(MMCDriver *mmcp) {
(void)mmcp;
/* TODO: Fill the implementation.*/
return false;
}
#endif
/**
* @brief Board-specific initialization code.
* @todo Add your board-specific code, if any.
*/
void boardInit(void) {
}

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,11 @@
# List of all the board related files.
BOARDSRC = $(PROJECT_DIR)/config/boards/NUCLEO_F767/board.c
BOARDSRC_CPP = $(PROJECT_DIR)/config/boards/NUCLEO_F767/board_configuration.cpp
# Required include directories
BOARDINC = $(PROJECT_DIR)/config/boards/NUCLEO_F767 $(PROJECT_DIR)/config/stm32f7ems
LDSCRIPT= $(PROJECT_DIR)/config/boards/NUCLEO_F767/STM32F76xxI.ld
# Override DEFAULT_ENGINE_TYPE
DDEFS += -DDEFAULT_ENGINE_TYPE=CUSTOM_ENGINE -DSTM32F767xx

View File

@ -0,0 +1,87 @@
/**
* @file boards/NUCLEO_F767/board_configuration.cpp
*
* @brief In this file we can override engine_configuration.cpp.
*
* @author andreika, (c) 2018
*/
#include "global.h"
#include "engine.h"
#include "engine_math.h"
#include "allsensors.h"
#include "fsio_impl.h"
#include "engine_configuration.h"
EXTERN_ENGINE;
// Warning! This is a test config!
#undef SERIAL_SPEED
#define SERIAL_SPEED 115200
void setPinConfigurationOverrides(void) {
}
void setSerialConfigurationOverrides(void) {
boardConfiguration->useSerialPort = true;
engineConfiguration->binarySerialTxPin = GPIOD_8;
engineConfiguration->binarySerialRxPin = GPIOD_9;
engineConfiguration->consoleSerialTxPin = GPIOD_8;
engineConfiguration->consoleSerialRxPin = GPIOD_9;
boardConfiguration->tunerStudioSerialSpeed = SERIAL_SPEED;
engineConfiguration->uartConsoleSerialSpeed = SERIAL_SPEED;
}
void setSdCardConfigurationOverrides(void) {
}
/**
* @brief Board-specific configuration code overrides.
* @todo Add your board-specific code, if any.
*/
void setBoardConfigurationOverrides(void) {
setSerialConfigurationOverrides();
engineConfiguration->communicationLedPin = GPIOB_7; // blue LED
engineConfiguration->runningLedPin = GPIOB_0; //green LED
engineConfiguration->fatalErrorPin = GPIOB_14; //red LED
engineConfiguration->warninigLedPin = GPIO_UNASSIGNED;
engineConfiguration->configResetPin = GPIO_UNASSIGNED;
#if 0
engineConfiguration->vbattAdcChannel = EFI_ADC_13;
engineConfiguration->adcVcc = ADC_VCC;
#endif
engineConfiguration->baroSensor.hwChannel = EFI_ADC_NONE;
engineConfiguration->pedalPositionChannel = EFI_ADC_NONE;
// not used
engineConfiguration->dizzySparkOutputPin = GPIO_UNASSIGNED;
engineConfiguration->externalKnockSenseAdc = EFI_ADC_NONE;
engineConfiguration->displayMode = DM_NONE;
boardConfiguration->HD44780_rs = GPIO_UNASSIGNED;
boardConfiguration->HD44780_e = GPIO_UNASSIGNED;
boardConfiguration->HD44780_db4 = GPIO_UNASSIGNED;
boardConfiguration->HD44780_db5 = GPIO_UNASSIGNED;
boardConfiguration->HD44780_db6 = GPIO_UNASSIGNED;
boardConfiguration->HD44780_db7 = GPIO_UNASSIGNED;
boardConfiguration->digitalPotentiometerChipSelect[0] = GPIO_UNASSIGNED;
boardConfiguration->digitalPotentiometerChipSelect[1] = GPIO_UNASSIGNED;
boardConfiguration->digitalPotentiometerChipSelect[2] = GPIO_UNASSIGNED;
boardConfiguration->digitalPotentiometerChipSelect[3] = GPIO_UNASSIGNED;
boardConfiguration->triggerSimulatorPins[1] = GPIO_UNASSIGNED;
boardConfiguration->triggerSimulatorPins[2] = GPIO_UNASSIGNED;
boardConfiguration->triggerSimulatorPinModes[1] = OM_DEFAULT;
boardConfiguration->triggerSimulatorPinModes[2] = OM_DEFAULT;
boardConfiguration->vehicleSpeedSensorInputPin = GPIO_UNASSIGNED;
boardConfiguration->boardTestModeJumperPin = GPIO_UNASSIGNED;
boardConfiguration->acRelayPin = GPIO_UNASSIGNED;
boardConfiguration->digitalPotentiometerSpiDevice = SPI_NONE;
boardConfiguration->max31855spiDevice = SPI_NONE;
/////////////////////////////////////////////////////////
boardConfiguration->is_enabled_spi_1 = false;
boardConfiguration->is_enabled_spi_2 = false;
boardConfiguration->is_enabled_spi_3 = false;
}

View File

@ -0,0 +1 @@
STMicroelectronics STM32 Nucleo144-F767ZI board.

View File

@ -0,0 +1,8 @@
/* Stack rules inclusion.*/
INCLUDE rules_stacks.ld
/* Code rules inclusion.*/
INCLUDE rules_code.ld
/* Data rules inclusion.*/
INCLUDE rules_data.ld

View File

@ -0,0 +1,77 @@
/*
ChibiOS - Copyright (C) 2006..2016 Giovanni Di Sirio
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
ENTRY(Reset_Handler)
SECTIONS
{
.vectors : ALIGN(16)
{
KEEP(*(.vectors))
} > VECTORS_FLASH AT > VECTORS_FLASH_LMA
.xtors : ALIGN(4)
{
__init_array_start = .;
KEEP(*(SORT(.init_array.*)))
KEEP(*(.init_array))
__init_array_end = .;
__fini_array_start = .;
KEEP(*(.fini_array))
KEEP(*(SORT(.fini_array.*)))
__fini_array_end = .;
} > XTORS_FLASH AT > XTORS_FLASH_LMA
.text ALIGN(16) : ALIGN(16)
{
*(.text)
*(.text.*)
*(.glue_7t)
*(.glue_7)
*(.gcc*)
} > TEXT_FLASH AT > TEXT_FLASH_LMA
.rodata : ALIGN(4)
{
. = ALIGN(4);
__rodata_base__ = .;
*(.rodata)
*(.rodata.*)
. = ALIGN(4);
__rodata_end__ = .;
} > RODATA_FLASH AT > RODATA_FLASH_LMA
.ARM.extab :
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} > VARIOUS_FLASH AT > VARIOUS_FLASH_LMA
.ARM.exidx : {
__exidx_start = .;
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
__exidx_end = .;
} > VARIOUS_FLASH AT > VARIOUS_FLASH_LMA
.eh_frame_hdr :
{
*(.eh_frame_hdr)
} > VARIOUS_FLASH AT > VARIOUS_FLASH_LMA
.eh_frame : ONLY_IF_RO
{
*(.eh_frame)
} > VARIOUS_FLASH AT > VARIOUS_FLASH_LMA
}

View File

@ -0,0 +1,273 @@
/*
ChibiOS - Copyright (C) 2006..2016 Giovanni Di Sirio
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
__ram0_start__ = ORIGIN(ram0);
__ram0_size__ = LENGTH(ram0);
__ram0_end__ = __ram0_start__ + __ram0_size__;
__ram1_start__ = ORIGIN(ram1);
__ram1_size__ = LENGTH(ram1);
__ram1_end__ = __ram1_start__ + __ram1_size__;
__ram2_start__ = ORIGIN(ram2);
__ram2_size__ = LENGTH(ram2);
__ram2_end__ = __ram2_start__ + __ram2_size__;
__ram3_start__ = ORIGIN(ram3);
__ram3_size__ = LENGTH(ram3);
__ram3_end__ = __ram3_start__ + __ram3_size__;
__ram4_start__ = ORIGIN(ram4);
__ram4_size__ = LENGTH(ram4);
__ram4_end__ = __ram4_start__ + __ram4_size__;
__ram5_start__ = ORIGIN(ram5);
__ram5_size__ = LENGTH(ram5);
__ram5_end__ = __ram5_start__ + __ram5_size__;
__ram6_start__ = ORIGIN(ram6);
__ram6_size__ = LENGTH(ram6);
__ram6_end__ = __ram6_start__ + __ram6_size__;
__ram7_start__ = ORIGIN(ram7);
__ram7_size__ = LENGTH(ram7);
__ram7_end__ = __ram7_start__ + __ram7_size__;
ENTRY(Reset_Handler)
SECTIONS
{
.data : ALIGN(4)
{
. = ALIGN(4);
PROVIDE(_textdata = LOADADDR(.data));
PROVIDE(_data = .);
_textdata_start = LOADADDR(.data);
_data_start = .;
*(.data)
*(.data.*)
*(.ramtext)
. = ALIGN(4);
PROVIDE(_edata = .);
_data_end = .;
} > DATA_RAM AT > DATA_RAM_LMA
.bss (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
_bss_start = .;
*(.bss)
*(.bss.*)
*(COMMON)
. = ALIGN(4);
_bss_end = .;
PROVIDE(end = .);
} > BSS_RAM
.ram0_init : ALIGN(4)
{
. = ALIGN(4);
__ram0_init_text__ = LOADADDR(.ram0_init);
__ram0_init__ = .;
KEEP(*(.ram0_init))
KEEP(*(.ram0_init.*))
. = ALIGN(4);
} > ram0 AT > RAM_INIT_FLASH_LMA
.ram0 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram0_clear__ = .;
*(.ram0_clear)
*(.ram0_clear.*)
. = ALIGN(4);
__ram0_noinit__ = .;
*(.ram0)
*(.ram0.*)
. = ALIGN(4);
__ram0_free__ = .;
} > ram0
.ram1_init : ALIGN(4)
{
. = ALIGN(4);
__ram1_init_text__ = LOADADDR(.ram1_init);
__ram1_init__ = .;
KEEP(*(.ram1_init))
KEEP(*(.ram1_init.*))
. = ALIGN(4);
} > ram1 AT > RAM_INIT_FLASH_LMA
.ram1 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram1_clear__ = .;
*(.ram1_clear)
*(.ram1_clear.*)
. = ALIGN(4);
__ram1_noinit__ = .;
*(.ram1)
*(.ram1.*)
. = ALIGN(4);
__ram1_free__ = .;
} > ram1
.ram2_init : ALIGN(4)
{
. = ALIGN(4);
__ram2_init_text__ = LOADADDR(.ram2_init);
__ram2_init__ = .;
KEEP(*(.ram2_init))
KEEP(*(.ram2_init.*))
. = ALIGN(4);
} > ram2 AT > RAM_INIT_FLASH_LMA
.ram2 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram2_clear__ = .;
*(.ram2_clear)
*(.ram2_clear.*)
. = ALIGN(4);
__ram2_noinit__ = .;
*(.ram2)
*(.ram2.*)
. = ALIGN(4);
__ram2_free__ = .;
} > ram2
.ram3_init : ALIGN(4)
{
. = ALIGN(4);
__ram3_init_text__ = LOADADDR(.ram3_init);
__ram3_init__ = .;
KEEP(*(.ram3_init))
KEEP(*(.ram3_init.*))
. = ALIGN(4);
} > ram3 AT > RAM_INIT_FLASH_LMA
.ram3 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram3_clear__ = .;
*(.ram3_clear)
*(.ram3_clear.*)
. = ALIGN(4);
__ram3_noinit__ = .;
*(.ram3)
*(.ram3.*)
. = ALIGN(4);
__ram3_free__ = .;
} > ram3
.ram4_init : ALIGN(4)
{
. = ALIGN(4);
__ram4_init_text__ = LOADADDR(.ram4_init);
__ram4_init__ = .;
KEEP(*(.ram4_init))
KEEP(*(.ram4_init.*))
. = ALIGN(4);
} > ram4 AT > RAM_INIT_FLASH_LMA
.ram4 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram4_clear__ = .;
*(.ram4_clear)
*(.ram4_clear.*)
. = ALIGN(4);
__ram4_noinit__ = .;
*(.ram4)
*(.ram4.*)
. = ALIGN(4);
__ram4_free__ = .;
} > ram4
.ram5_init : ALIGN(4)
{
. = ALIGN(4);
__ram5_init_text__ = LOADADDR(.ram5_init);
__ram5_init__ = .;
KEEP(*(.ram5_init))
KEEP(*(.ram5_init.*))
. = ALIGN(4);
} > ram5 AT > RAM_INIT_FLASH_LMA
.ram5 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram5_clear__ = .;
*(.ram5_clear)
*(.ram5_clear.*)
. = ALIGN(4);
__ram5_noinit__ = .;
*(.ram5)
*(.ram5.*)
. = ALIGN(4);
__ram5_free__ = .;
} > ram5
.ram6_init : ALIGN(4)
{
. = ALIGN(4);
__ram6_init_text__ = LOADADDR(.ram6_init);
__ram6_init__ = .;
KEEP(*(.ram6_init))
KEEP(*(.ram6_init.*))
. = ALIGN(4);
} > ram6 AT > RAM_INIT_FLASH_LMA
.ram6 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram6_clear__ = .;
*(.ram6_clear)
*(.ram6_clear.*)
. = ALIGN(4);
__ram6_noinit__ = .;
*(.ram6)
*(.ram6.*)
. = ALIGN(4);
__ram6_free__ = .;
} > ram6
.ram7_init : ALIGN(4)
{
. = ALIGN(4);
__ram7_init_text__ = LOADADDR(.ram7_init);
__ram7_init__ = .;
KEEP(*(.ram7_init))
KEEP(*(.ram7_init.*))
. = ALIGN(4);
} > ram7 AT > RAM_INIT_FLASH_LMA
.ram7 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram7_clear__ = .;
*(.ram7_clear)
*(.ram7_clear.*)
. = ALIGN(4);
__ram7_noinit__ = .;
*(.ram7)
*(.ram7.*)
. = ALIGN(4);
__ram7_free__ = .;
} > ram7
/* The default heap uses the (statically) unused part of a RAM section.*/
.heap (NOLOAD) :
{
. = ALIGN(8);
__heap_base__ = .;
. = ORIGIN(HEAP_RAM) + LENGTH(HEAP_RAM);
__heap_end__ = .;
} > HEAP_RAM
}

View File

@ -0,0 +1,38 @@
/*
ChibiOS - Copyright (C) 2006..2016 Giovanni Di Sirio
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
SECTIONS
{
/* Special section for exceptions stack.*/
.mstack :
{
. = ALIGN(8);
__main_stack_base__ = .;
. += __main_stack_size__;
. = ALIGN(8);
__main_stack_end__ = .;
} > MAIN_STACK_RAM
/* Special section for process stack.*/
.pstack :
{
__process_stack_base__ = .;
__main_thread_stack_base__ = .;
. += __process_stack_size__;
. = ALIGN(8);
__process_stack_end__ = .;
__main_thread_stack_end__ = .;
} > PROCESS_STACK_RAM
}

View File

@ -182,9 +182,9 @@ void setCustomEngineConfiguration(DECLARE_ENGINE_PARAMETER_SIGNATURE) {
// todo: 8.2 or 10k?
engineConfiguration->vbattDividerCoeff = ((float) (10 + 33)) / 10 * 2;
#if EFI_PROD_CODE
#if EFI_CAN_SUPPORT || defined(__DOXYGEN__)
enableFrankensoCan();
#endif /* EFI_PROD_CODE */
#endif /* EFI_CAN_SUPPORT */
}
void setFrankensoBoardTestConfiguration(DECLARE_ENGINE_PARAMETER_SIGNATURE) {

View File

@ -164,8 +164,8 @@ void setHonda600(DECLARE_ENGINE_PARAMETER_SIGNATURE) {
// todo: 8.2 or 10k?
engineConfiguration->vbattDividerCoeff = ((float) (10 + 33)) / 10 * 2;
#if EFI_PROD_CODE
#if EFI_CAN_SUPPORT || defined(__DOXYGEN__)
enableFrankensoCan();
#endif
#endif /* EFI_CAN_SUPPORT */
}

View File

@ -305,6 +305,14 @@ void setMazdaMiata2003EngineConfiguration(DECLARE_ENGINE_PARAMETER_SIGNATURE) {
// set cranking_fuel 4
engineConfiguration->cranking.baseFuel = 4; // this value for return-less NB miata fuel system, higher pressure
/**
* Saab attempt
* Saab coil on #1 PD8 extra blue wire
* Miata coil on #2 PC9 - orange ECU wire "2&3"
* Saab coil on #3 PD9 extra white wire
* Miata coil on #4 PE14 - white ECU wire "1&4"
*/
boardConfiguration->ignitionPins[0] = GPIOE_14;
boardConfiguration->ignitionPins[1] = GPIO_UNASSIGNED;
boardConfiguration->ignitionPins[2] = GPIOC_9;
@ -368,7 +376,7 @@ void setMazdaMiata2003EngineConfiguration(DECLARE_ENGINE_PARAMETER_SIGNATURE) {
*/
engineConfiguration->injector.flow = 265;
boardConfiguration->malfunctionIndicatorPin = GPIOD_9;
// boardConfiguration->malfunctionIndicatorPin = GPIOD_9;
// boardConfiguration->malfunctionIndicatorPinMode = OM_INVERTED;
// todo: blue jumper wire - what is it?!

View File

@ -0,0 +1,571 @@
/*
ChibiOS - Copyright (C) 2006..2016 Giovanni Di Sirio
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
/**
* @file templates/chconf.h
* @brief Configuration file template.
* @details A copy of this file must be placed in each project directory, it
* contains the application specific kernel settings.
*
* @addtogroup config
* @details Kernel related settings and hooks.
* @{
*/
#ifndef CHCONF_H
#define CHCONF_H
#define _CHIBIOS_RT_CONF_
#if !defined(EFI_CLOCK_LOCKS) || defined(__DOXYGEN__)
#define EFI_CLOCK_LOCKS FALSE
#endif /* EFI_CLOCK_LOCKS */
#if EFI_CLOCK_LOCKS
#ifdef __cplusplus
extern "C"
{
#endif /* __cplusplus */
#ifndef __ASSEMBLER__
void onLockHook(void);
void onUnlockHook(void);
#endif /* __ASSEMBLER__ */
#ifdef __cplusplus
}
#endif /* __cplusplus */
#define ON_LOCK_HOOK onLockHook()
#define ON_UNLOCK_HOOK onUnlockHook()
#else /* EFI_CLOCK_LOCKS */
#define ON_LOCK_HOOK
#define ON_UNLOCK_HOOK
#endif /* EFI_CLOCK_LOCKS */
/*===========================================================================*/
/**
* @name System timers settings
* @{
*/
/*===========================================================================*/
/**
* @brief System time counter resolution.
* @note Allowed values are 16 or 32 bits.
*/
#define CH_CFG_ST_RESOLUTION 32
/**
* @brief System tick frequency.
* @details Frequency of the system timer that drives the system ticks. This
* setting also defines the system tick time unit.
*/
#define CH_CFG_ST_FREQUENCY 10000
/**
* @brief Time delta constant for the tick-less mode.
* @note If this value is zero then the system uses the classic
* periodic tick. This value represents the minimum number
* of ticks that is safe to specify in a timeout directive.
* The value one is not valid, timeouts are rounded up to
* this value.
*/
#define CH_CFG_ST_TIMEDELTA 2
/** @} */
/*===========================================================================*/
/**
* @name Kernel parameters and options
* @{
*/
/*===========================================================================*/
/**
* @brief Round robin interval.
* @details This constant is the number of system ticks allowed for the
* threads before preemption occurs. Setting this value to zero
* disables the preemption for threads with equal priority and the
* round robin becomes cooperative. Note that higher priority
* threads can still preempt, the kernel is always preemptive.
* @note Disabling the round robin preemption makes the kernel more compact
* and generally faster.
* @note The round robin preemption is not supported in tickless mode and
* must be set to zero in that case.
*/
#define CH_CFG_TIME_QUANTUM 0
/**
* @brief Managed RAM size.
* @details Size of the RAM area to be managed by the OS. If set to zero
* then the whole available RAM is used. The core memory is made
* available to the heap allocator and/or can be used directly through
* the simplified core memory allocator.
*
* @note In order to let the OS manage the whole RAM the linker script must
* provide the @p __heap_base__ and @p __heap_end__ symbols.
* @note Requires @p CH_CFG_USE_MEMCORE.
*/
#define CH_CFG_MEMCORE_SIZE 0
/**
* @brief Idle thread automatic spawn suppression.
* @details When this option is activated the function @p chSysInit()
* does not spawn the idle thread. The application @p main()
* function becomes the idle thread and must implement an
* infinite loop.
*/
#define CH_CFG_NO_IDLE_THREAD FALSE
/** @} */
/*===========================================================================*/
/**
* @name Performance options
* @{
*/
/*===========================================================================*/
/**
* @brief OS optimization.
* @details If enabled then time efficient rather than space efficient code
* is used when two possible implementations exist.
*
* @note This is not related to the compiler optimization options.
* @note The default is @p TRUE.
*/
#define CH_CFG_OPTIMIZE_SPEED TRUE
/** @} */
/*===========================================================================*/
/**
* @name Subsystem options
* @{
*/
/*===========================================================================*/
/**
* @brief Time Measurement APIs.
* @details If enabled then the time measurement APIs are included in
* the kernel.
*
* @note The default is @p TRUE.
*/
#define CH_CFG_USE_TM TRUE
/**
* @brief Threads registry APIs.
* @details If enabled then the registry APIs are included in the kernel.
*
* @note The default is @p TRUE.
*/
#define CH_CFG_USE_REGISTRY TRUE
/**
* @brief Threads synchronization APIs.
* @details If enabled then the @p chThdWait() function is included in
* the kernel.
*
* @note The default is @p TRUE.
*/
#define CH_CFG_USE_WAITEXIT TRUE
/**
* @brief Semaphores APIs.
* @details If enabled then the Semaphores APIs are included in the kernel.
*
* @note The default is @p TRUE.
*/
#define CH_CFG_USE_SEMAPHORES TRUE
/**
* @brief Semaphores queuing mode.
* @details If enabled then the threads are enqueued on semaphores by
* priority rather than in FIFO order.
*
* @note The default is @p FALSE. Enable this if you have special
* requirements.
* @note Requires @p CH_CFG_USE_SEMAPHORES.
*/
#define CH_CFG_USE_SEMAPHORES_PRIORITY FALSE
/**
* @brief Mutexes APIs.
* @details If enabled then the mutexes APIs are included in the kernel.
*
* @note The default is @p TRUE.
*/
#define CH_CFG_USE_MUTEXES TRUE
/**
* @brief Enables recursive behavior on mutexes.
* @note Recursive mutexes are heavier and have an increased
* memory footprint.
*
* @note The default is @p FALSE.
* @note Requires @p CH_CFG_USE_MUTEXES.
*/
#define CH_CFG_USE_MUTEXES_RECURSIVE FALSE
/**
* @brief Conditional Variables APIs.
* @details If enabled then the conditional variables APIs are included
* in the kernel.
*
* @note The default is @p TRUE.
* @note Requires @p CH_CFG_USE_MUTEXES.
*/
#define CH_CFG_USE_CONDVARS TRUE
/**
* @brief Conditional Variables APIs with timeout.
* @details If enabled then the conditional variables APIs with timeout
* specification are included in the kernel.
*
* @note The default is @p TRUE.
* @note Requires @p CH_CFG_USE_CONDVARS.
*/
#define CH_CFG_USE_CONDVARS_TIMEOUT TRUE
/**
* @brief Events Flags APIs.
* @details If enabled then the event flags APIs are included in the kernel.
*
* @note The default is @p TRUE.
*/
#define CH_CFG_USE_EVENTS TRUE
/**
* @brief Events Flags APIs with timeout.
* @details If enabled then the events APIs with timeout specification
* are included in the kernel.
*
* @note The default is @p TRUE.
* @note Requires @p CH_CFG_USE_EVENTS.
*/
#define CH_CFG_USE_EVENTS_TIMEOUT TRUE
/**
* @brief Synchronous Messages APIs.
* @details If enabled then the synchronous messages APIs are included
* in the kernel.
*
* @note The default is @p TRUE.
*/
#define CH_CFG_USE_MESSAGES TRUE
/**
* @brief Synchronous Messages queuing mode.
* @details If enabled then messages are served by priority rather than in
* FIFO order.
*
* @note The default is @p FALSE. Enable this if you have special
* requirements.
* @note Requires @p CH_CFG_USE_MESSAGES.
*/
#define CH_CFG_USE_MESSAGES_PRIORITY FALSE
/**
* @brief Mailboxes APIs.
* @details If enabled then the asynchronous messages (mailboxes) APIs are
* included in the kernel.
*
* @note The default is @p TRUE.
* @note Requires @p CH_CFG_USE_SEMAPHORES.
*/
#define CH_CFG_USE_MAILBOXES TRUE
/**
* @brief Core Memory Manager APIs.
* @details If enabled then the core memory manager APIs are included
* in the kernel.
*
* @note The default is @p TRUE.
*/
#define CH_CFG_USE_MEMCORE TRUE
/**
* @brief Heap Allocator APIs.
* @details If enabled then the memory heap allocator APIs are included
* in the kernel.
*
* @note The default is @p TRUE.
* @note Requires @p CH_CFG_USE_MEMCORE and either @p CH_CFG_USE_MUTEXES or
* @p CH_CFG_USE_SEMAPHORES.
* @note Mutexes are recommended.
*/
#define CH_CFG_USE_HEAP TRUE
/**
* @brief Memory Pools Allocator APIs.
* @details If enabled then the memory pools allocator APIs are included
* in the kernel.
*
* @note The default is @p TRUE.
*/
#define CH_CFG_USE_MEMPOOLS TRUE
/**
* @brief Dynamic Threads APIs.
* @details If enabled then the dynamic threads creation APIs are included
* in the kernel.
*
* @note The default is @p TRUE.
* @note Requires @p CH_CFG_USE_WAITEXIT.
* @note Requires @p CH_CFG_USE_HEAP and/or @p CH_CFG_USE_MEMPOOLS.
*/
#define CH_CFG_USE_DYNAMIC TRUE
/** @} */
/*===========================================================================*/
/**
* @name Debug options
* @{
*/
/*===========================================================================*/
/**
* @brief Debug option, kernel statistics.
*
* @note The default is @p FALSE.
*/
#define CH_DBG_STATISTICS FALSE
/**
* @brief Debug option, system state check.
* @details If enabled the correct call protocol for system APIs is checked
* at runtime.
*
* @note The default is @p FALSE.
*/
#define CH_DBG_SYSTEM_STATE_CHECK TRUE
/**
* @brief Debug option, parameters checks.
* @details If enabled then the checks on the API functions input
* parameters are activated.
*
* @note The default is @p FALSE.
*/
#define CH_DBG_ENABLE_CHECKS FALSE
/**
* @brief Debug option, consistency checks.
* @details If enabled then all the assertions in the kernel code are
* activated. This includes consistency checks inside the kernel,
* runtime anomalies and port-defined checks.
*
* @note The default is @p FALSE.
*/
#define CH_DBG_ENABLE_ASSERTS FALSE
/**
* @brief Debug option, trace buffer.
* @details If enabled then the trace buffer is activated.
*
* @note The default is @p CH_DBG_TRACE_MASK_DISABLED.
*/
#define CH_DBG_TRACE_MASK CH_DBG_TRACE_MASK_DISABLED
/**
* @brief Trace buffer entries.
* @note The trace buffer is only allocated if @p CH_DBG_TRACE_MASK is
* different from @p CH_DBG_TRACE_MASK_DISABLED.
*/
#define CH_DBG_TRACE_BUFFER_SIZE 128
/**
* @brief Debug option, stack checks.
* @details If enabled then a runtime stack check is performed.
*
* @note The default is @p FALSE.
* @note The stack check is performed in a architecture/port dependent way.
* It may not be implemented or some ports.
* @note The default failure mode is to halt the system with the global
* @p panic_msg variable set to @p NULL.
*/
#define CH_DBG_ENABLE_STACK_CHECK FALSE
/**
* @brief Debug option, stacks initialization.
* @details If enabled then the threads working area is filled with a byte
* value when a thread is created. This can be useful for the
* runtime measurement of the used stack.
*
* @note The default is @p FALSE.
*/
#define CH_DBG_FILL_THREADS FALSE
/**
* @brief Debug option, threads profiling.
* @details If enabled then a field is added to the @p thread_t structure that
* counts the system ticks occurred while executing the thread.
*
* @note The default is @p FALSE.
* @note This debug option is not currently compatible with the
* tickless mode.
*/
#define CH_DBG_THREADS_PROFILING FALSE
/** @} */
/*===========================================================================*/
/**
* @name Kernel hooks
* @{
*/
/*===========================================================================*/
/**
* @brief Threads descriptor structure extension.
* @details User fields added to the end of the @p thread_t structure.
*/
#define CH_CFG_THREAD_EXTRA_FIELDS \
/* Add threads custom fields here.*/
/**
* @brief Threads initialization hook.
* @details User initialization code added to the @p chThdInit() API.
*
* @note It is invoked from within @p chThdInit() and implicitly from all
* the threads creation APIs.
*/
#define CH_CFG_THREAD_INIT_HOOK(tp) { \
/* Add threads initialization code here.*/ \
}
/**
* @brief Threads finalization hook.
* @details User finalization code added to the @p chThdExit() API.
*/
#define CH_CFG_THREAD_EXIT_HOOK(tp) { \
/* Add threads finalization code here.*/ \
}
/**
* @brief Context switch hook.
* @details This hook is invoked just before switching between threads.
*/
#define CH_CFG_CONTEXT_SWITCH_HOOK(ntp, otp) { \
/* Context switch code here.*/ \
}
/**
* @brief ISR enter hook.
*/
#define CH_CFG_IRQ_PROLOGUE_HOOK() { \
/* IRQ prologue code here.*/ \
}
/**
* @brief ISR exit hook.
*/
#define CH_CFG_IRQ_EPILOGUE_HOOK() { \
/* IRQ epilogue code here.*/ \
}
/**
* @brief Idle thread enter hook.
* @note This hook is invoked within a critical zone, no OS functions
* should be invoked from here.
* @note This macro can be used to activate a power saving mode.
*/
#define CH_CFG_IDLE_ENTER_HOOK() { \
/* Idle-enter code here.*/ \
}
/**
* @brief Idle thread leave hook.
* @note This hook is invoked within a critical zone, no OS functions
* should be invoked from here.
* @note This macro can be used to deactivate a power saving mode.
*/
#define CH_CFG_IDLE_LEAVE_HOOK() { \
/* Idle-leave code here.*/ \
}
/**
* @brief Idle Loop hook.
* @details This hook is continuously invoked by the idle thread loop.
*/
#define CH_CFG_IDLE_LOOP_HOOK() { \
/* Idle loop code here.*/ \
}
/**
* @brief System tick event hook.
* @details This hook is invoked in the system tick handler immediately
* after processing the virtual timers queue.
*/
#define CH_CFG_SYSTEM_TICK_HOOK() { \
/* System tick event code here.*/ \
}
/**
* @brief System halt hook.
* @details This hook is invoked in case to a system halting error before
* the system is halted.
*/
#define CH_CFG_SYSTEM_HALT_HOOK(reason) { \
/* System halt code here.*/ \
}
/**
* @brief Trace hook.
* @details This hook is invoked each time a new record is written in the
* trace buffer.
*/
#define CH_CFG_TRACE_HOOK(tep) { \
/* Trace code here.*/ \
}
/** @} */
/*===========================================================================*/
/* Port-specific settings (override port settings defaulted in chcore.h). */
/*===========================================================================*/
#define CORTEX_VTOR_INIT 0x00200000U
#ifndef __ASSEMBLER__
void chDbgPanic3(const char *msg, const char * file, int line);
#endif
/**
* declared as a macro so that this code does not use stack
* so that it would not crash the error handler in case of stack issues
*/
#if CH_DBG_SYSTEM_STATE_CHECK
#define hasFatalError() (ch.dbg.panic_msg != NULL)
#else
#define hasFatalError() (FALSE)
#endif
#define chDbgAssert(c, remark) do { \
if (CH_DBG_ENABLE_ASSERTS != FALSE) { \
if (!(c)) { \
/*lint -restore*/ \
chSysHalt(remark); \
} \
} \
} while (false)
#endif /* CHCONF_H */
/** @} */

View File

@ -3,265 +3,81 @@
*
* @brief In this header we can configure which firmware modules are used.
*
* STM32F7 config is inherited from STM32F4. This file contains only differences between F4 and F7.
* This is more consistent way to maintain these config 'branches' and add new features.
*
* @date Aug 29, 2013
* @author Andrey Belomutskiy, (c) 2012-2017
*/
#include "../stm32f4ems/efifeatures.h"
#ifndef EFIFEATURES_H_
#define EFIFEATURES_H_
#ifndef EFIFEATURES_STM32F7_H_
#define EFIFEATURES_STM32F7_H_
#define EFI_GPIO_HARDWARE TRUE
// Warning! This is a test config!
#define EFI_FSIO TRUE
#define EFI_PWM_TESTER FALSE
#define HAL_USE_USB_MSD FALSE
#define EFI_USE_CCM TRUE
/**
* if you have a 60-2 trigger, or if you just want better performance, you
* probably want EFI_ENABLE_ASSERTS to be FALSE. Also you would probably want to FALSE
* CH_DBG_ENABLE_CHECKS
* CH_DBG_ENABLE_ASSERTS
* CH_DBG_ENABLE_TRACE
* in chconf.h
*
*/
#if !defined(EFI_ENABLE_ASSERTS) || defined(__DOXYGEN__)
#define EFI_ENABLE_ASSERTS TRUE
#endif /* EFI_ENABLE_ASSERTS */
#if !defined(EFI_ENABLE_MOCK_ADC) || defined(__DOXYGEN__)
#define EFI_ENABLE_MOCK_ADC TRUE
#endif /* EFI_ENABLE_MOCK_ADC */
//#define EFI_UART_ECHO_TEST_MODE TRUE
// todo: reconfigure RAM sections for STM32F7
#undef EFI_USE_CCM
#define EFI_USE_CCM FALSE
// todo: no actual selection pin configured for Nucleo
#undef EFI_USE_UART_FOR_CONSOLE
#define EFI_USE_UART_FOR_CONSOLE FALSE
/**
* Build-in logic analyzer support. Logic analyzer viewer is one of the java console panes.
*/
#define EFI_WAVE_ANALYZER TRUE
#undef EFI_POTENTIOMETER
#define EFI_POTENTIOMETER FALSE
/**
* TunerStudio support.
*/
#define EFI_TUNER_STUDIO TRUE
/**
* Bluetooth UART setup support.
*/
#define EFI_BLUETOOTH_SETUP FALSE
/**
* TunerStudio debug output
*/
#define EFI_TUNER_STUDIO_VERBOSE TRUE
#define EFI_DEFAILED_LOGGING FALSE
/**
* Dev console support.
*/
#define EFI_CLI_SUPPORT TRUE
#define EFI_RTC TRUE
#define EFI_ALTERNATOR_CONTROL TRUE
#define EFI_AUX_PID TRUE
#define EFI_SIGNAL_EXECUTOR_SLEEP FALSE
#define EFI_SIGNAL_EXECUTOR_ONE_TIMER TRUE
#define EFI_SIGNAL_EXECUTOR_HW_TIMER FALSE
#define FUEL_MATH_EXTREME_LOGGING FALSE
#define SPARK_EXTREME_LOGGING FALSE
#define TRIGGER_EXTREME_LOGGING FALSE
#define EFI_INTERNAL_FLASH TRUE
/**
* Usually you need shaft position input, but maybe you do not need it?
*/
#define EFI_SHAFT_POSITION_INPUT TRUE
/**
* Maybe we are just sniffing what's going on?
*/
#define EFI_ENGINE_CONTROL TRUE
#define EFI_SPEED_DENSITY TRUE
/**
* MCP42010 digital potentiometer support. This could be useful if you are stimulating some
* stock ECU
*/
//#define EFI_POTENTIOMETER FALSE
#define EFI_POTENTIOMETER TRUE
#define EFI_ANALOG_SENSORS TRUE
#define EFI_MAX_31855 TRUE
#undef EFI_MAX_31855
#define EFI_MAX_31855 FALSE
#undef EFI_MCP_3208
#define EFI_MCP_3208 FALSE
#define EFI_HIP_9011 TRUE
#undef EFI_HIP_9011
#define EFI_HIP_9011 FALSE
#define EFI_CJ125 TRUE
#define EFI_INTERNAL_ADC TRUE
#undef EFI_CJ125
#define EFI_CJ125 FALSE
#undef EFI_DENSO_ADC
#define EFI_DENSO_ADC FALSE
#define EFI_CAN_SUPPORT TRUE
#undef EFI_MEMS
#define EFI_MEMS FALSE
#define EFI_HD44780_LCD TRUE
#undef EFI_CAN_SUPPORT
#define EFI_CAN_SUPPORT FALSE
#define EFI_IDLE_CONTROL TRUE
#define EFI_IDLE_INCREMENTAL_PID_CIC FALSE
/**
* Control the main power relay based on measured ignition voltage (Vbatt)
*/
#define EFI_MAIN_RELAY_CONTROL FALSE
#define EFI_PWM TRUE
#define EFI_VEHICLE_SPEED TRUE
#define EFI_FUEL_PUMP TRUE
#define EFI_ENGINE_EMULATOR TRUE
#define EFI_EMULATE_POSITION_SENSORS TRUE
/**
* This macros is used to hide pieces of the code from unit tests, so it only makes sense in folders exposed to the tests project.
* This macros is NOT about taking out logging in general.
*/
#define EFI_PROD_CODE TRUE
#undef EFI_HD44780_LCD
#define EFI_HD44780_LCD FALSE
/**
* Do we need file logging (like SD card) logic?
*/
#define EFI_FILE_LOGGING TRUE
#undef EFI_FILE_LOGGING
#define EFI_FILE_LOGGING FALSE
#ifndef EFI_USB_SERIAL
#undef EFI_USB_SERIAL
#define EFI_USB_SERIAL TRUE
#endif
/**
* While we embed multiple PnP configurations into the same firmware binary, these marcoses give us control
* over which configurations go into the binary
*/
#define EFI_SUPPORT_DODGE_NEON TRUE
#define EFI_SUPPORT_FORD_ASPIRE TRUE
#define EFI_SUPPORT_FORD_FIESTA TRUE
#define EFI_SUPPORT_NISSAN_PRIMERA TRUE
#define EFI_SUPPORT_1995_FORD_INLINE_6 TRUE
#define EFI_ENGINE_SNIFFER TRUE
#define EFI_HISTOGRAMS FALSE
#define EFI_SENSOR_CHART TRUE
#if defined __GNUC__
#define EFI_PERF_METRICS FALSE
#define DL_OUTPUT_BUFFER 6500
#else
#define EFI_PERF_METRICS FALSE
#define DL_OUTPUT_BUFFER 8000
#endif
/**
* Do we need GPS logic?
*/
#define EFI_UART_GPS TRUE
//#define EFI_UART_GPS FALSE
#define EFI_ELECTRONIC_THROTTLE_BODY TRUE
//#define EFI_ELECTRONIC_THROTTLE_BODY FALSE
/**
* Do we need Malfunction Indicator blinking logic?
*/
#define EFI_MALFUNCTION_INDICATOR TRUE
//#define EFI_MALFUNCTION_INDICATOR FALSE
#define CONSOLE_MAX_ACTIONS 180
#define EFI_MAP_AVERAGING TRUE
//#define EFI_MAP_AVERAGING FALSE
// todo: most of this should become configurable
// todo: switch to continues ADC conversion for slow ADC?
#define EFI_INTERNAL_SLOW_ADC_PWM &PWMD8
// todo: switch to continues ADC conversion for fast ADC?
#define EFI_INTERNAL_FAST_ADC_PWM &PWMD4
#define EFI_SPI1_AF 5
#define EFI_SPI2_AF 5
/**
* This section is for right-side center SPI
*/
#define EFI_SPI3_AF 6
#define EFI_I2C_SCL_BRAIN_PIN GPIOB_6
#define EFI_I2C_SDA_BRAIN_PIN GPIOB_7
#define EFI_I2C_AF 4
/**
* Patched version of ChibiOS/RT support extra details in the system error messages
*/
#define EFI_CUSTOM_PANIC_METHOD TRUE
#define ADC_CHANNEL_VREF ADC_CHANNEL_IN14
/**
* currently ChibiOS uses only first and second channels of each timer for input capture
*
* So, our options are:
*
* TIM2_CH1
* PA5
*
* TIM4_CH1
* PB6
* PD12
*
* TIM9_CH1
* PE5
*/
#undef EFI_UART_GPS
#define EFI_UART_GPS FALSE
// todo: start using consoleUartDevice? Not sure
#ifndef EFI_CONSOLE_UART_DEVICE
#undef EFI_CONSOLE_UART_DEVICE
#define EFI_CONSOLE_UART_DEVICE (&SD3)
#endif
/**
* Use 'HAL_USE_UART' DMA-mode driver instead of 'HAL_USE_SERIAL'
*
* See also
* STM32_SERIAL_USE_USARTx
* STM32_UART_USE_USARTx
* in mcuconf.h
*/
// todo: our "DMA-half" ChibiOS patch not implemented for USARTv2/STM32F7
#undef TS_UART_DMA_MODE
#define TS_UART_DMA_MODE FALSE
#undef TS_DMA_UART_DEVICE
#define TS_DMA_UART_DEVICE (&UARTD3)
#undef TS_SERIAL_UART_DEVICE
#define TS_SERIAL_UART_DEVICE (&SD3)
// todo: add DMA-mode for Console?
@ -270,48 +86,28 @@
#endif
// todo: start using consoleSerialTxPin? Not sure
#ifndef EFI_CONSOLE_TX_PORT
#define EFI_CONSOLE_TX_PORT GPIOC
#endif
#ifndef EFI_CONSOLE_TX_PIN
#define EFI_CONSOLE_TX_PIN 10
#endif
#undef EFI_CONSOLE_TX_PORT
#define EFI_CONSOLE_TX_PORT GPIOD
#undef EFI_CONSOLE_TX_PIN
#define EFI_CONSOLE_TX_PIN 8
// todo: start using consoleSerialRxPin? Not sure
#ifndef EFI_CONSOLE_RX_PORT
#define EFI_CONSOLE_RX_PORT GPIOC
#endif
#ifndef EFI_CONSOLE_RX_PIN
#define EFI_CONSOLE_RX_PIN 11
#endif
// todo: this should be detected automatically based on pin selection
#define EFI_CONSOLE_AF 7
// todo: this should be detected automatically based on pin selection
#define TS_SERIAL_AF 7
#undef EFI_CONSOLE_RX_PORT
#define EFI_CONSOLE_RX_PORT GPIOD
#undef EFI_CONSOLE_RX_PIN
#define EFI_CONSOLE_RX_PIN 9
#undef LED_WARNING_BRAIN_PIN
#define LED_WARNING_BRAIN_PIN GPIOD_13
// LED_ERROR_BRAIN_PIN should match LED_ERROR_PORT/LED_ERROR_PIN
#define LED_ERROR_BRAIN_PIN GPIOD_14
#define LED_ERROR_PORT GPIOD
#undef LED_ERROR_BRAIN_PIN
#define LED_ERROR_BRAIN_PIN GPIOB_14
#undef LED_ERROR_PORT
#define LED_ERROR_PORT GPIOB
#undef LED_ERROR_PIN
#define LED_ERROR_PIN 14
#define EFI_WARNING_LED TRUE
// todo: temporary ignore errors, this is a test config
#define EFI_PRINT_ERRORS_AS_WARNINGS TRUE
// USART1 -> check defined STM32_SERIAL_USE_USART1
// For GPS we have USART1. We can start with PB7 USART1_RX and PB6 USART1_TX
#define GPS_SERIAL_DEVICE &SD1
#define GPS_SERIAL_SPEED 38400
#define CONSOLE_MODE_SWITCH_PORT GPIOB
#define CONSOLE_MODE_SWITCH_PIN 1
#define CONFIG_RESET_SWITCH_PORT GPIOD
#define CONFIG_RESET_SWITCH_PIN 6
/**
* This is the size of the MemoryStream used by chvprintf
*/
#define INTERMEDIATE_LOGGING_BUFFER_SIZE 2000
#endif /* EFIFEATURES_H_ */
#endif /* EFIFEATURES_STM32F7_H_ */

View File

@ -0,0 +1,398 @@
/*
ChibiOS - Copyright (C) 2006..2016 Giovanni Di Sirio
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
/**
* @file templates/halconf.h
* @brief HAL configuration header.
* @details HAL configuration file, this file allows to enable or disable the
* various device drivers from your application. You may also use
* this file in order to override the device drivers default settings.
*
* @addtogroup HAL_CONF
* @{
*/
#ifndef HALCONF_H
#define HALCONF_H
#include "mcuconf.h"
/**
* @brief Enables the PAL subsystem.
*/
#if !defined(HAL_USE_PAL) || defined(__DOXYGEN__)
#define HAL_USE_PAL TRUE
#endif
/**
* @brief Enables the ADC subsystem.
*/
#if !defined(HAL_USE_ADC) || defined(__DOXYGEN__)
#define HAL_USE_ADC TRUE
#endif
/**
* @brief Enables the CAN subsystem.
*/
#if !defined(HAL_USE_CAN) || defined(__DOXYGEN__)
#define HAL_USE_CAN TRUE
#endif
/**
* @brief Enables the DAC subsystem.
*/
#if !defined(HAL_USE_DAC) || defined(__DOXYGEN__)
#define HAL_USE_DAC FALSE
#endif
/**
* @brief Enables the EXT subsystem.
*/
#if !defined(HAL_USE_EXT) || defined(__DOXYGEN__)
#define HAL_USE_EXT TRUE
#endif
/**
* @brief Enables the GPT subsystem.
*/
#if !defined(HAL_USE_GPT) || defined(__DOXYGEN__)
#define HAL_USE_GPT TRUE
#endif
/**
* @brief Enables the I2C subsystem.
*/
#if !defined(HAL_USE_I2C) || defined(__DOXYGEN__)
#define HAL_USE_I2C TRUE
#endif
/**
* @brief Enables the I2S subsystem.
*/
#if !defined(HAL_USE_I2S) || defined(__DOXYGEN__)
#define HAL_USE_I2S FALSE
#endif
/**
* @brief Enables the ICU subsystem.
*/
#if !defined(HAL_USE_ICU) || defined(__DOXYGEN__)
#define HAL_USE_ICU TRUE
#endif
/**
* @brief Enables the MAC subsystem.
*/
#if !defined(HAL_USE_MAC) || defined(__DOXYGEN__)
#define HAL_USE_MAC FALSE
#endif
/**
* @brief Enables the MMC_SPI subsystem.
*/
#if !defined(HAL_USE_MMC_SPI) || defined(__DOXYGEN__)
#define HAL_USE_MMC_SPI TRUE
#endif
/**
* @brief Enables the PWM subsystem.
*/
#if !defined(HAL_USE_PWM) || defined(__DOXYGEN__)
#define HAL_USE_PWM TRUE
#endif
/**
* @brief Enables the QSPI subsystem.
*/
#if !defined(HAL_USE_QSPI) || defined(__DOXYGEN__)
#define HAL_USE_QSPI FALSE
#endif
/**
* @brief Enables the RTC subsystem.
*/
#if !defined(HAL_USE_RTC) || defined(__DOXYGEN__)
#define HAL_USE_RTC TRUE
#endif
/**
* @brief Enables the SDC subsystem.
*/
#if !defined(HAL_USE_SDC) || defined(__DOXYGEN__)
#define HAL_USE_SDC FALSE
#endif
/**
* @brief Enables the SERIAL subsystem.
*/
#if !defined(HAL_USE_SERIAL) || defined(__DOXYGEN__)
#define HAL_USE_SERIAL TRUE
#endif
/**
* @brief Enables the SERIAL over USB subsystem.
*/
#if !defined(HAL_USE_SERIAL_USB) || defined(__DOXYGEN__)
#define HAL_USE_SERIAL_USB TRUE
#endif
/**
* @brief Enables the SPI subsystem.
*/
#if !defined(HAL_USE_SPI) || defined(__DOXYGEN__)
#define HAL_USE_SPI TRUE
#endif
/**
* @brief Enables the UART subsystem.
*/
#if !defined(HAL_USE_UART) || defined(__DOXYGEN__)
/* Configured in efifeatures.h */
#if TS_UART_DMA_MODE
#define HAL_USE_UART TRUE
#else
#define HAL_USE_UART FALSE
#endif
#endif
/**
* @brief Enables the USB subsystem.
*/
#if !defined(HAL_USE_USB) || defined(__DOXYGEN__)
#define HAL_USE_USB TRUE
#endif
/**
* @brief Enables the WDG subsystem.
*/
#if !defined(HAL_USE_WDG) || defined(__DOXYGEN__)
#define HAL_USE_WDG FALSE
#endif
/*===========================================================================*/
/* ADC driver related settings. */
/*===========================================================================*/
/**
* @brief Enables synchronous APIs.
* @note Disabling this option saves both code and data space.
*/
#if !defined(ADC_USE_WAIT) || defined(__DOXYGEN__)
#define ADC_USE_WAIT TRUE
#endif
/**
* @brief Enables the @p adcAcquireBus() and @p adcReleaseBus() APIs.
* @note Disabling this option saves both code and data space.
*/
#if !defined(ADC_USE_MUTUAL_EXCLUSION) || defined(__DOXYGEN__)
#define ADC_USE_MUTUAL_EXCLUSION TRUE
#endif
/*===========================================================================*/
/* CAN driver related settings. */
/*===========================================================================*/
/**
* @brief Sleep mode related APIs inclusion switch.
*/
#if !defined(CAN_USE_SLEEP_MODE) || defined(__DOXYGEN__)
#define CAN_USE_SLEEP_MODE TRUE
#endif
/*===========================================================================*/
/* I2C driver related settings. */
/*===========================================================================*/
/**
* @brief Enables the mutual exclusion APIs on the I2C bus.
*/
#if !defined(I2C_USE_MUTUAL_EXCLUSION) || defined(__DOXYGEN__)
#define I2C_USE_MUTUAL_EXCLUSION TRUE
#endif
/*===========================================================================*/
/* MAC driver related settings. */
/*===========================================================================*/
/**
* @brief Enables an event sources for incoming packets.
*/
#if !defined(MAC_USE_ZERO_COPY) || defined(__DOXYGEN__)
#define MAC_USE_ZERO_COPY FALSE
#endif
/**
* @brief Enables an event sources for incoming packets.
*/
#if !defined(MAC_USE_EVENTS) || defined(__DOXYGEN__)
#define MAC_USE_EVENTS TRUE
#endif
/*===========================================================================*/
/* MMC_SPI driver related settings. */
/*===========================================================================*/
/**
* @brief Delays insertions.
* @details If enabled this options inserts delays into the MMC waiting
* routines releasing some extra CPU time for the threads with
* lower priority, this may slow down the driver a bit however.
* This option is recommended also if the SPI driver does not
* use a DMA channel and heavily loads the CPU.
*/
#if !defined(MMC_NICE_WAITING) || defined(__DOXYGEN__)
#define MMC_NICE_WAITING TRUE
#endif
/*===========================================================================*/
/* SDC driver related settings. */
/*===========================================================================*/
/**
* @brief Number of initialization attempts before rejecting the card.
* @note Attempts are performed at 10mS intervals.
*/
#if !defined(SDC_INIT_RETRY) || defined(__DOXYGEN__)
#define SDC_INIT_RETRY 100
#endif
/**
* @brief Include support for MMC cards.
* @note MMC support is not yet implemented so this option must be kept
* at @p FALSE.
*/
#if !defined(SDC_MMC_SUPPORT) || defined(__DOXYGEN__)
#define SDC_MMC_SUPPORT FALSE
#endif
/**
* @brief Delays insertions.
* @details If enabled this options inserts delays into the MMC waiting
* routines releasing some extra CPU time for the threads with
* lower priority, this may slow down the driver a bit however.
*/
#if !defined(SDC_NICE_WAITING) || defined(__DOXYGEN__)
#define SDC_NICE_WAITING TRUE
#endif
/*===========================================================================*/
/* SERIAL driver related settings. */
/*===========================================================================*/
/**
* @brief Default bit rate.
* @details Configuration parameter, this is the baud rate selected for the
* default configuration.
*/
#if !defined(SERIAL_DEFAULT_BITRATE) || defined(__DOXYGEN__)
#define SERIAL_DEFAULT_BITRATE 38400
#endif
/**
* @brief Serial buffers size.
* @details Configuration parameter, you can change the depth of the queue
* buffers depending on the requirements of your application.
* @note The default is 16 bytes for both the transmission and receive
* buffers.
*/
#if !defined(SERIAL_BUFFERS_SIZE) || defined(__DOXYGEN__)
#define SERIAL_BUFFERS_SIZE 16
#endif
/*===========================================================================*/
/* SERIAL_USB driver related setting. */
/*===========================================================================*/
/**
* @brief Serial over USB buffers size.
* @details Configuration parameter, the buffer size must be a multiple of
* the USB data endpoint maximum packet size.
* @note The default is 256 bytes for both the transmission and receive
* buffers.
*/
#if !defined(SERIAL_USB_BUFFERS_SIZE) || defined(__DOXYGEN__)
#define SERIAL_USB_BUFFERS_SIZE 256
#endif
/**
* @brief Serial over USB number of buffers.
* @note The default is 2 buffers.
*/
#if !defined(SERIAL_USB_BUFFERS_NUMBER) || defined(__DOXYGEN__)
#define SERIAL_USB_BUFFERS_NUMBER 2
#endif
/*===========================================================================*/
/* SPI driver related settings. */
/*===========================================================================*/
/**
* @brief Enables synchronous APIs.
* @note Disabling this option saves both code and data space.
*/
#if !defined(SPI_USE_WAIT) || defined(__DOXYGEN__)
#define SPI_USE_WAIT TRUE
#endif
/**
* @brief Enables the @p spiAcquireBus() and @p spiReleaseBus() APIs.
* @note Disabling this option saves both code and data space.
*/
#if !defined(SPI_USE_MUTUAL_EXCLUSION) || defined(__DOXYGEN__)
#define SPI_USE_MUTUAL_EXCLUSION TRUE
#endif
/*===========================================================================*/
/* UART driver related settings. */
/*===========================================================================*/
/**
* @brief Enables synchronous APIs.
* @note Disabling this option saves both code and data space.
*/
#if !defined(UART_USE_WAIT) || defined(__DOXYGEN__)
/* Configured in efifeatures.h */
#if TS_UART_DMA_MODE
#define UART_USE_WAIT TRUE
#else
#define UART_USE_WAIT FALSE
#endif
#endif
/**
* @brief Enables the @p uartAcquireBus() and @p uartReleaseBus() APIs.
* @note Disabling this option saves both code and data space.
*/
#if !defined(UART_USE_MUTUAL_EXCLUSION) || defined(__DOXYGEN__)
#define UART_USE_MUTUAL_EXCLUSION FALSE
#endif
/*===========================================================================*/
/* USB driver related settings. */
/*===========================================================================*/
/**
* @brief Enables synchronous APIs.
* @note Disabling this option saves both code and data space.
*/
#if !defined(USB_USE_WAIT) || defined(__DOXYGEN__)
#define USB_USE_WAIT FALSE
#endif
#endif /* HALCONF_H */
/** @} */

View File

@ -0,0 +1,418 @@
/*
ChibiOS - Copyright (C) 2006..2016 Giovanni Di Sirio
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
#ifndef MCUCONF_H
#define MCUCONF_H
#include "efifeatures.h"
#include "rusefi_enums.h"
/**
* This is about SingleTimerExecutor - rusEfi 1MHz precise scheduling timer
* this is not about ChibiOS virtual timer which rusEfi uses for
* periodicFastCallback and periodicSlowCallback
* See STM32_ST_IRQ_PRIORITY
*
* http://www.chibios.org/dokuwiki/doku.php?id=chibios:kb:priority
*/
#define PRECISE_SCHEDULING_TIMER_PRIORITY 4
/**
* Input Capture Unit is how we capture shaft position sensors output
*/
#define ICU_PRIORITY 3
/**
* UART DMA-mode byte capture (low latency)
*/
#define UART_DMA_IRQ_PRIORITY (PRECISE_SCHEDULING_TIMER_PRIORITY + 2)
/*
* STM32F7xx drivers configuration.
* The following settings override the default settings present in
* the various device driver implementation headers.
* Note that the settings for each driver only have effect if the whole
* driver is enabled in halconf.h.
*
* IRQ priorities:
* 15...0 Lowest...Highest.
*
* DMA priorities:
* 0...3 Lowest...Highest.
*/
#define STM32F7xx_MCUCONF
/*
* HAL driver system settings.
*/
#define STM32_NO_INIT FALSE
#define STM32_PVD_ENABLE FALSE
#define STM32_PLS STM32_PLS_LEV0
#define STM32_BKPRAM_ENABLE FALSE
#define STM32_HSI_ENABLED TRUE
#define STM32_LSI_ENABLED TRUE
#define STM32_HSE_ENABLED TRUE
#define STM32_LSE_ENABLED FALSE
#define STM32_CLOCK48_REQUIRED TRUE
#define STM32_SW STM32_SW_PLL
#define STM32_PLLSRC STM32_PLLSRC_HSE
#define STM32_PLLM_VALUE 8
#define STM32_PLLN_VALUE 336
#define STM32_PLLP_VALUE 2
#define STM32_PLLQ_VALUE 7
#define STM32_HPRE STM32_HPRE_DIV1
#define STM32_PPRE1 STM32_PPRE1_DIV4
#define STM32_PPRE2 STM32_PPRE2_DIV2
#if STM32_LSE_ENABLED
#define STM32_RTCSEL STM32_RTCSEL_LSE
#else
#define STM32_RTCSEL STM32_RTCSEL_LSI
#endif
#define STM32_RTCPRE_VALUE 8
#define STM32_MCO1SEL STM32_MCO1SEL_HSI
#define STM32_MCO1PRE STM32_MCO1PRE_DIV1
#define STM32_MCO2SEL STM32_MCO2SEL_SYSCLK
#define STM32_MCO2PRE STM32_MCO2PRE_DIV5
#define STM32_I2SSRC STM32_I2SSRC_CKIN
#define STM32_PLLI2SN_VALUE 192
#define STM32_PLLI2SP_VALUE 4
#define STM32_PLLI2SQ_VALUE 4
#define STM32_PLLI2SR_VALUE 4
#define STM32_PLLI2SDIVQ_VALUE 2
#define STM32_PLLSAIN_VALUE 192
#define STM32_PLLSAIP_VALUE 4
#define STM32_PLLSAIQ_VALUE 4
#define STM32_PLLSAIR_VALUE 4
#define STM32_PLLSAIDIVQ_VALUE 2
#define STM32_PLLSAIDIVR_VALUE 2
#define STM32_SAI1SEL STM32_SAI1SEL_OFF
#define STM32_SAI2SEL STM32_SAI2SEL_OFF
#define STM32_LCDTFT_REQUIRED FALSE
#define STM32_USART1SEL STM32_USART1SEL_PCLK2
#define STM32_USART2SEL STM32_USART2SEL_PCLK1
#define STM32_USART3SEL STM32_USART3SEL_PCLK1
#define STM32_UART4SEL STM32_UART4SEL_PCLK1
#define STM32_UART5SEL STM32_UART5SEL_PCLK1
#define STM32_USART6SEL STM32_USART6SEL_PCLK2
#define STM32_UART7SEL STM32_UART7SEL_PCLK1
#define STM32_UART8SEL STM32_UART8SEL_PCLK1
#define STM32_I2C1SEL STM32_I2C1SEL_PCLK1
#define STM32_I2C2SEL STM32_I2C2SEL_PCLK1
#define STM32_I2C3SEL STM32_I2C3SEL_PCLK1
#define STM32_I2C4SEL STM32_I2C4SEL_PCLK1
#define STM32_LPTIM1SEL STM32_LPTIM1SEL_PCLK1
#define STM32_CECSEL STM32_CECSEL_LSE
#define STM32_CK48MSEL STM32_CK48MSEL_PLL
#define STM32_SDMMCSEL STM32_SDMMCSEL_PLL48CLK
#define STM32_SRAM2_NOCACHE FALSE
/*
* ADC driver system settings.
*/
#define STM32_ADC_ADCPRE ADC_CCR_ADCPRE_DIV4
#define STM32_ADC_USE_ADC1 TRUE
#define STM32_ADC_USE_ADC2 TRUE
#define STM32_ADC_USE_ADC3 FALSE
#define STM32_ADC_ADC1_DMA_STREAM STM32_DMA_STREAM_ID(2, 4)
#define STM32_ADC_ADC2_DMA_STREAM STM32_DMA_STREAM_ID(2, 2)
#define STM32_ADC_ADC3_DMA_STREAM STM32_DMA_STREAM_ID(2, 1)
#define STM32_ADC_ADC1_DMA_PRIORITY 2
#define STM32_ADC_ADC2_DMA_PRIORITY 2
#define STM32_ADC_ADC3_DMA_PRIORITY 2
#define STM32_ADC_IRQ_PRIORITY PRECISE_SCHEDULING_TIMER_PRIORITY + 2
#define STM32_ADC_ADC1_DMA_IRQ_PRIORITY PRECISE_SCHEDULING_TIMER_PRIORITY + 2
#define STM32_ADC_ADC2_DMA_IRQ_PRIORITY PRECISE_SCHEDULING_TIMER_PRIORITY + 2
#define STM32_ADC_ADC3_DMA_IRQ_PRIORITY PRECISE_SCHEDULING_TIMER_PRIORITY + 2
/*
* CAN driver system settings.
*/
#define STM32_CAN_USE_CAN1 TRUE
#define STM32_CAN_USE_CAN2 TRUE
#define STM32_CAN_USE_CAN3 FALSE
#define STM32_CAN_CAN1_IRQ_PRIORITY PRECISE_SCHEDULING_TIMER_PRIORITY + 7
#define STM32_CAN_CAN2_IRQ_PRIORITY PRECISE_SCHEDULING_TIMER_PRIORITY + 7
#define STM32_CAN_CAN3_IRQ_PRIORITY PRECISE_SCHEDULING_TIMER_PRIORITY + 7
/*
* DAC driver system settings.
*/
#define STM32_DAC_DUAL_MODE FALSE
#define STM32_DAC_USE_DAC1_CH1 FALSE
#define STM32_DAC_USE_DAC1_CH2 FALSE
#define STM32_DAC_DAC1_CH1_IRQ_PRIORITY 10
#define STM32_DAC_DAC1_CH2_IRQ_PRIORITY 10
#define STM32_DAC_DAC1_CH1_DMA_PRIORITY 2
#define STM32_DAC_DAC1_CH2_DMA_PRIORITY 2
#define STM32_DAC_DAC1_CH1_DMA_STREAM STM32_DMA_STREAM_ID(1, 5)
#define STM32_DAC_DAC1_CH2_DMA_STREAM STM32_DMA_STREAM_ID(1, 6)
/*
* EXT driver system settings.
*/
#define STM32_EXT_EXTI0_IRQ_PRIORITY PRECISE_SCHEDULING_TIMER_PRIORITY + 2
#define STM32_EXT_EXTI1_IRQ_PRIORITY PRECISE_SCHEDULING_TIMER_PRIORITY + 2
#define STM32_EXT_EXTI2_IRQ_PRIORITY PRECISE_SCHEDULING_TIMER_PRIORITY + 2
#define STM32_EXT_EXTI3_IRQ_PRIORITY PRECISE_SCHEDULING_TIMER_PRIORITY + 2
#define STM32_EXT_EXTI4_IRQ_PRIORITY PRECISE_SCHEDULING_TIMER_PRIORITY + 2
#define STM32_EXT_EXTI5_9_IRQ_PRIORITY PRECISE_SCHEDULING_TIMER_PRIORITY + 2
#define STM32_EXT_EXTI10_15_IRQ_PRIORITY PRECISE_SCHEDULING_TIMER_PRIORITY + 2
#define STM32_EXT_EXTI16_IRQ_PRIORITY PRECISE_SCHEDULING_TIMER_PRIORITY + 2
#define STM32_EXT_EXTI17_IRQ_PRIORITY 15
#define STM32_EXT_EXTI18_IRQ_PRIORITY PRECISE_SCHEDULING_TIMER_PRIORITY + 2
#define STM32_EXT_EXTI19_IRQ_PRIORITY PRECISE_SCHEDULING_TIMER_PRIORITY + 2
#define STM32_EXT_EXTI20_IRQ_PRIORITY PRECISE_SCHEDULING_TIMER_PRIORITY + 2
#define STM32_EXT_EXTI21_IRQ_PRIORITY 15
#define STM32_EXT_EXTI22_IRQ_PRIORITY 15
/*
* GPT driver system settings.
*/
#define STM32_GPT_USE_TIM1 FALSE
#define STM32_GPT_USE_TIM2 FALSE
#define STM32_GPT_USE_TIM3 FALSE
#define STM32_GPT_USE_TIM4 FALSE
#define STM32_GPT_USE_TIM5 TRUE
#define STM32_GPT_USE_TIM6 FALSE
#define STM32_GPT_USE_TIM7 FALSE
#define STM32_GPT_USE_TIM8 FALSE
#define STM32_GPT_USE_TIM9 FALSE
#define STM32_GPT_USE_TIM11 FALSE
#define STM32_GPT_USE_TIM12 FALSE
#define STM32_GPT_USE_TIM14 FALSE
#define STM32_GPT_TIM1_IRQ_PRIORITY 7
#define STM32_GPT_TIM2_IRQ_PRIORITY 7
#define STM32_GPT_TIM3_IRQ_PRIORITY 7
#define STM32_GPT_TIM4_IRQ_PRIORITY 7
#define STM32_GPT_TIM5_IRQ_PRIORITY PRECISE_SCHEDULING_TIMER_PRIORITY
#define STM32_GPT_TIM6_IRQ_PRIORITY 7
#define STM32_GPT_TIM7_IRQ_PRIORITY 7
#define STM32_GPT_TIM8_IRQ_PRIORITY 7
#define STM32_GPT_TIM9_IRQ_PRIORITY 7
#define STM32_GPT_TIM11_IRQ_PRIORITY 7
#define STM32_GPT_TIM12_IRQ_PRIORITY 7
#define STM32_GPT_TIM14_IRQ_PRIORITY 7
/*
* I2C driver system settings.
*/
#define STM32_I2C_USE_I2C1 TRUE
#define STM32_I2C_USE_I2C2 FALSE
#define STM32_I2C_USE_I2C3 FALSE
#define STM32_I2C_USE_I2C4 FALSE
#define STM32_I2C_BUSY_TIMEOUT 50
#define STM32_I2C_I2C1_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 0)
#define STM32_I2C_I2C1_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 6)
#define STM32_I2C_I2C2_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 2)
#define STM32_I2C_I2C2_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 7)
#define STM32_I2C_I2C3_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 2)
#define STM32_I2C_I2C3_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 4)
#define STM32_I2C_I2C4_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 2)
#define STM32_I2C_I2C4_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 5)
#define STM32_I2C_I2C1_IRQ_PRIORITY 5
#define STM32_I2C_I2C2_IRQ_PRIORITY 5
#define STM32_I2C_I2C3_IRQ_PRIORITY 5
#define STM32_I2C_I2C4_IRQ_PRIORITY 5
#define STM32_I2C_I2C1_DMA_PRIORITY 3
#define STM32_I2C_I2C2_DMA_PRIORITY 3
#define STM32_I2C_I2C3_DMA_PRIORITY 3
#define STM32_I2C_I2C4_DMA_PRIORITY 3
#define STM32_I2C_DMA_ERROR_HOOK(i2cp) osalSysHalt("DMA failure")
/*
* ICU driver system settings.
*/
#define STM32_ICU_USE_TIM1 TRUE
#define STM32_ICU_USE_TIM2 FALSE // ???
#define STM32_ICU_USE_TIM3 TRUE
#define STM32_ICU_USE_TIM4 FALSE
#define STM32_ICU_USE_TIM5 FALSE
#define STM32_ICU_USE_TIM8 FALSE
#define STM32_ICU_USE_TIM9 TRUE
#define STM32_ICU_TIM1_IRQ_PRIORITY ICU_PRIORITY
#define STM32_ICU_TIM2_IRQ_PRIORITY ICU_PRIORITY
#define STM32_ICU_TIM3_IRQ_PRIORITY ICU_PRIORITY
#define STM32_ICU_TIM4_IRQ_PRIORITY ICU_PRIORITY
#define STM32_ICU_TIM5_IRQ_PRIORITY ICU_PRIORITY
#define STM32_ICU_TIM8_IRQ_PRIORITY ICU_PRIORITY
#define STM32_ICU_TIM9_IRQ_PRIORITY ICU_PRIORITY
/*
* MAC driver system settings.
*/
#define STM32_MAC_TRANSMIT_BUFFERS 2
#define STM32_MAC_RECEIVE_BUFFERS 4
#define STM32_MAC_BUFFERS_SIZE 1522
#define STM32_MAC_PHY_TIMEOUT 100
#define STM32_MAC_ETH1_CHANGE_PHY_STATE TRUE
#define STM32_MAC_ETH1_IRQ_PRIORITY 13
#define STM32_MAC_IP_CHECKSUM_OFFLOAD 0
/*
* PWM driver system settings.
*/
#define STM32_PWM_USE_ADVANCED FALSE
#define STM32_PWM_USE_TIM1 FALSE
#define STM32_PWM_USE_TIM2 FALSE
#define STM32_PWM_USE_TIM3 FALSE
#define STM32_PWM_USE_TIM4 TRUE
#define STM32_PWM_USE_TIM5 FALSE
#define STM32_PWM_USE_TIM8 TRUE
#define STM32_PWM_USE_TIM9 FALSE
#define STM32_PWM_TIM1_IRQ_PRIORITY 7
#define STM32_PWM_TIM2_IRQ_PRIORITY 7
#define STM32_PWM_TIM3_IRQ_PRIORITY 7
#define STM32_PWM_TIM4_IRQ_PRIORITY 7
#define STM32_PWM_TIM5_IRQ_PRIORITY 7
#define STM32_PWM_TIM8_IRQ_PRIORITY 7
#define STM32_PWM_TIM9_IRQ_PRIORITY 7
/*
* SDC driver system settings.
*/
#define STM32_SDC_USE_SDMMC1 FALSE
#define STM32_SDC_SDMMC_UNALIGNED_SUPPORT TRUE
#define STM32_SDC_SDMMC_WRITE_TIMEOUT 1000
#define STM32_SDC_SDMMC_READ_TIMEOUT 1000
#define STM32_SDC_SDMMC_CLOCK_DELAY 10
#define STM32_SDC_SDMMC1_DMA_STREAM STM32_DMA_STREAM_ID(2, 3)
#define STM32_SDC_SDMMC1_DMA_PRIORITY 3
#define STM32_SDC_SDMMC1_IRQ_PRIORITY 9
/*
* SERIAL driver system settings.
*/
#define STM32_SERIAL_USE_USART1 TRUE
#define STM32_SERIAL_USE_USART2 TRUE
#define STM32_SERIAL_USE_USART3 TRUE
#define STM32_SERIAL_USE_UART4 FALSE
#define STM32_SERIAL_USE_UART5 FALSE
#define STM32_SERIAL_USE_USART6 FALSE
#define STM32_SERIAL_USE_UART7 FALSE
#define STM32_SERIAL_USE_UART8 FALSE
#define STM32_SERIAL_USART1_PRIORITY (PRECISE_SCHEDULING_TIMER_PRIORITY + 2)
#define STM32_SERIAL_USART2_PRIORITY (PRECISE_SCHEDULING_TIMER_PRIORITY + 2)
#define STM32_SERIAL_USART3_PRIORITY (PRECISE_SCHEDULING_TIMER_PRIORITY + 2)
#define STM32_SERIAL_UART4_PRIORITY (PRECISE_SCHEDULING_TIMER_PRIORITY + 2)
#define STM32_SERIAL_UART5_PRIORITY (PRECISE_SCHEDULING_TIMER_PRIORITY + 2)
#define STM32_SERIAL_USART6_PRIORITY (PRECISE_SCHEDULING_TIMER_PRIORITY + 2)
#define STM32_SERIAL_UART7_PRIORITY (PRECISE_SCHEDULING_TIMER_PRIORITY + 2)
#define STM32_SERIAL_UART8_PRIORITY (PRECISE_SCHEDULING_TIMER_PRIORITY + 2)
/*
* SPI driver system settings.
*/
#define STM32_SPI_USE_SPI1 TRUE
#define STM32_SPI_USE_SPI2 TRUE
#define STM32_SPI_USE_SPI3 TRUE
#define STM32_SPI_USE_SPI4 FALSE
#define STM32_SPI_USE_SPI5 FALSE
#define STM32_SPI_USE_SPI6 FALSE
#define STM32_SPI_SPI1_RX_DMA_STREAM STM32_DMA_STREAM_ID(2, 0)
#define STM32_SPI_SPI1_TX_DMA_STREAM STM32_DMA_STREAM_ID(2, 3)
#define STM32_SPI_SPI2_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 3)
#define STM32_SPI_SPI2_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 4)
#define STM32_SPI_SPI3_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 0)
#define STM32_SPI_SPI3_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 7)
#define STM32_SPI_SPI4_RX_DMA_STREAM STM32_DMA_STREAM_ID(2, 0)
#define STM32_SPI_SPI4_TX_DMA_STREAM STM32_DMA_STREAM_ID(2, 1)
#define STM32_SPI_SPI5_RX_DMA_STREAM STM32_DMA_STREAM_ID(2, 3)
#define STM32_SPI_SPI5_TX_DMA_STREAM STM32_DMA_STREAM_ID(2, 4)
#define STM32_SPI_SPI6_RX_DMA_STREAM STM32_DMA_STREAM_ID(2, 6)
#define STM32_SPI_SPI6_TX_DMA_STREAM STM32_DMA_STREAM_ID(2, 5)
#define STM32_SPI_SPI1_DMA_PRIORITY 1
#define STM32_SPI_SPI2_DMA_PRIORITY 1
#define STM32_SPI_SPI3_DMA_PRIORITY 1
#define STM32_SPI_SPI4_DMA_PRIORITY 1
#define STM32_SPI_SPI5_DMA_PRIORITY 1
#define STM32_SPI_SPI6_DMA_PRIORITY 1
#define STM32_SPI_SPI1_IRQ_PRIORITY 10
#define STM32_SPI_SPI2_IRQ_PRIORITY 10
#define STM32_SPI_SPI3_IRQ_PRIORITY 10
#define STM32_SPI_SPI4_IRQ_PRIORITY 10
#define STM32_SPI_SPI5_IRQ_PRIORITY 10
#define STM32_SPI_SPI6_IRQ_PRIORITY 10
#define STM32_SPI_DMA_ERROR_HOOK(spip) osalSysHalt("DMA failure")
/*
* ST driver system settings.
*/
#define STM32_ST_IRQ_PRIORITY 8
#define STM32_ST_USE_TIMER 2
/*
* UART driver system settings.
*/
#define STM32_UART_USE_USART1 FALSE
#define STM32_UART_USE_USART2 FALSE
#define STM32_UART_USE_USART3 TRUE
#define STM32_UART_USE_UART4 FALSE
#define STM32_UART_USE_UART5 FALSE
#define STM32_UART_USE_USART6 FALSE
#define STM32_UART_USE_UART7 FALSE
#define STM32_UART_USE_UART8 FALSE
#define STM32_UART_USART1_RX_DMA_STREAM STM32_DMA_STREAM_ID(2, 5)
#define STM32_UART_USART1_TX_DMA_STREAM STM32_DMA_STREAM_ID(2, 7)
#define STM32_UART_USART2_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 5)
#define STM32_UART_USART2_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 6)
#define STM32_UART_USART3_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 1)
#define STM32_UART_USART3_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 3)
#define STM32_UART_UART4_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 2)
#define STM32_UART_UART4_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 4)
#define STM32_UART_UART5_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 0)
#define STM32_UART_UART5_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 7)
#define STM32_UART_USART6_RX_DMA_STREAM STM32_DMA_STREAM_ID(2, 2)
#define STM32_UART_USART6_TX_DMA_STREAM STM32_DMA_STREAM_ID(2, 7)
#define STM32_UART_UART7_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 3)
#define STM32_UART_UART7_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 1)
#define STM32_UART_UART8_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 6)
#define STM32_UART_UART8_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 0)
#define STM32_UART_USART1_IRQ_PRIORITY UART_DMA_IRQ_PRIORITY
#define STM32_UART_USART2_IRQ_PRIORITY UART_DMA_IRQ_PRIORITY
#define STM32_UART_USART3_IRQ_PRIORITY UART_DMA_IRQ_PRIORITY
#define STM32_UART_UART4_IRQ_PRIORITY UART_DMA_IRQ_PRIORITY
#define STM32_UART_UART5_IRQ_PRIORITY UART_DMA_IRQ_PRIORITY
#define STM32_UART_USART6_IRQ_PRIORITY UART_DMA_IRQ_PRIORITY
#define STM32_UART_USART1_DMA_PRIORITY 0
#define STM32_UART_USART2_DMA_PRIORITY 0
#define STM32_UART_USART3_DMA_PRIORITY 0
#define STM32_UART_UART4_DMA_PRIORITY 0
#define STM32_UART_UART5_DMA_PRIORITY 0
#define STM32_UART_USART6_DMA_PRIORITY 0
#define STM32_UART_UART7_DMA_PRIORITY 0
#define STM32_UART_UART8_DMA_PRIORITY 0
#define STM32_UART_DMA_ERROR_HOOK(uartp) osalSysHalt("DMA failure")
/*
* USB driver system settings.
*/
#define STM32_USB_USE_OTG1 TRUE
#define STM32_USB_USE_OTG2 FALSE
#define STM32_USB_OTG1_IRQ_PRIORITY 14
#define STM32_USB_OTG2_IRQ_PRIORITY 14
#define STM32_USB_OTG1_RX_FIFO_SIZE 512
#define STM32_USB_OTG2_RX_FIFO_SIZE 1024
#define STM32_USB_OTG_THREAD_PRIO LOWPRIO
#define STM32_USB_OTG_THREAD_STACK_SIZE 1024
#define STM32_USB_OTGFIFO_FILL_BASEPRI 0
/*
* WDG driver system settings.
*/
#define STM32_WDG_USE_IWDG FALSE
#endif /* MCUCONF_H */

View File

@ -151,7 +151,9 @@ void runConsoleLoop(ts_channel_s *console) {
if (boardConfiguration->startConsoleInBinaryMode) {
// switch to binary protocol
consoleInBinaryMode = true;
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
runBinaryProtocolLoop(console, true);
#endif /* EFI_TUNER_STUDIO */
}
while (true) {
@ -171,7 +173,9 @@ void runConsoleLoop(ts_channel_s *console) {
logMsg("Switching to binary mode\r\n");
#endif
// switch to binary protocol
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
runBinaryProtocolLoop(console, true);
#endif /* EFI_TUNER_STUDIO */
}
}
}

View File

@ -93,10 +93,10 @@ int warningEnabled = true;
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
extern TunerStudioOutputChannels tsOutputChannels;
extern tunerstudio_counters_s tsState;
#endif
extern bool hasFirmwareErrorFlag;
extern tunerstudio_counters_s tsState;
extern int maxTriggerReentraint;
extern uint32_t maxLockedDuration;
#define FULL_LOGGING_KEY "fl"

View File

@ -26,10 +26,10 @@
#include "engine_state.h"
#include "engine_math.h"
#include "signal_executor.h"
#if !EFI_UNIT_TEST || defined(__DOXYGEN__)
#include "tunerstudio_configuration.h"
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
extern TunerStudioOutputChannels tsOutputChannels;
#endif /* EFI_UNIT_TEST */
#endif /* EFI_TUNER_STUDIO */
EXTERN_ENGINE
;
@ -130,15 +130,14 @@ floatms_t AccelEnrichmemnt::getTpsEnrichment(DECLARE_ENGINE_PARAMETER_SIGNATURE)
extraFuel = 0;
}
#if !EFI_UNIT_TEST || defined(__DOXYGEN__)
if (engineConfiguration->debugMode == DBG_TPS_ACCEL) {
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
tsOutputChannels.debugFloatField1 = tpsFrom;
tsOutputChannels.debugFloatField2 = tpsTo;
tsOutputChannels.debugFloatField3 = valueFromTable;
tsOutputChannels.debugFloatField4 = extraFuel;
#endif /* EFI_TUNER_STUDIO */
}
#endif
return extraFuel;
}
@ -164,14 +163,13 @@ float AccelEnrichmemnt::getEngineLoadEnrichment(DECLARE_ENGINE_PARAMETER_SIGNATU
result = d * engineConfiguration->engineLoadAccelEnrichmentMultiplier;
}
#if ! EFI_UNIT_TEST || defined(__DOXYGEN__)
if (engineConfiguration->debugMode == DBG_EL_ACCEL) {
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
tsOutputChannels.debugIntField1 = distance;
tsOutputChannels.debugFloatField1 = result;
tsOutputChannels.debugFloatField2 = taper;
#endif /* EFI_TUNER_STUDIO */
}
#endif
return result;
}

View File

@ -27,9 +27,9 @@
EXTERN_ENGINE;
#if !EFI_UNIT_TEST || defined(__DOXYGEN__)
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
extern TunerStudioOutputChannels tsOutputChannels;
#endif
#endif /* EFI_TUNER_STUDIO */
static ign_Map3D_t advanceMap("advance");
// This coeff in ctor parameter is sufficient for int16<->float conversion!
@ -112,11 +112,11 @@ static angle_t getAdvanceCorrections(int rpm DECLARE_ENGINE_PARAMETER_SUFFIX) {
iatCorrection = iatAdvanceCorrectionMap.getValue((float) rpm, engine->sensors.iat);
}
if (engineConfiguration->debugMode == DBG_IGNITION_TIMING) {
#if !EFI_UNIT_TEST || defined(__DOXYGEN__)
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
tsOutputChannels.debugFloatField1 = iatCorrection;
tsOutputChannels.debugFloatField2 = engine->engineState.cltTimingCorrection;
tsOutputChannels.debugFloatField3 = engine->fsioTimingAdjustment;
#endif
#endif /* EFI_TUNER_STUDIO */
}
return iatCorrection

View File

@ -26,7 +26,9 @@ extern fsio8_Map3D_f32t fsioTable1;
// todo: this is to some extent a copy-paste of alternatorController. maybe same loop
// for all PIDs?
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
extern TunerStudioOutputChannels tsOutputChannels;
#endif /* EFI_TUNER_STUDIO */
static THD_WORKING_AREA(auxPidThreadStack, UTILITY_THREAD_STACK_SIZE);
@ -89,8 +91,10 @@ static msg_t auxPidThread(int param) {
if (engineConfiguration->debugMode == DBG_AUX_PID_1) {
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
auxPid.postState(&tsOutputChannels);
tsOutputChannels.debugIntField3 = (int)(10 * targetValue);
#endif /* EFI_TUNER_STUDIO */
}
auxPidPwm[0].setSimplePwmDutyCycle(pwm / 100);

View File

@ -38,9 +38,9 @@ extern afr_Map3D_t afrMap;
EXTERN_ENGINE
;
#if ! EFI_UNIT_TEST || defined(__DOXYGEN__)
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
extern TunerStudioOutputChannels tsOutputChannels;
#endif
#endif /* EFI_TUNER_STUDIO */
MockAdcState::MockAdcState() {
memset(hasMockAdc, 0, sizeof(hasMockAdc));
@ -249,13 +249,12 @@ void EngineState::periodicFastCallback(DECLARE_ENGINE_PARAMETER_SIGNATURE) {
} else {
cltFuelCorrection = warmupAfrPid.getValue(warmupTargetAfr, engine->sensors.currentAfr, 1);
}
#if ! EFI_UNIT_TEST || defined(__DOXYGEN__)
if (engineConfiguration->debugMode == DBG_WARMUP_ENRICH) {
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
tsOutputChannels.debugFloatField1 = warmupTargetAfr;
warmupAfrPid.postState(&tsOutputChannels);
#endif /* EFI_TUNER_STUDIO */
}
#endif
} else {
cltFuelCorrection = getCltFuelCorrection(PASS_ENGINE_PARAMETER_SIGNATURE);
}

View File

@ -32,9 +32,9 @@ static THD_WORKING_AREA(alternatorControlThreadStack, UTILITY_THREAD_STACK_SIZE)
static percent_t currentAltDuty;
#if ! EFI_UNIT_TEST || defined(__DOXYGEN__)
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
extern TunerStudioOutputChannels tsOutputChannels;
#endif
#endif /* EFI_TUNER_STUDIO */
static bool currentPlainOnOffState = false;
static bool shouldResetPid = false;
@ -56,15 +56,13 @@ static msg_t AltCtrlThread(int param) {
altPid.sleep();
#if ! EFI_UNIT_TEST || defined(__DOXYGEN__)
if (engineConfiguration->debugMode == DBG_ALTERNATOR_PID) {
// this block could be executed even in on/off alternator control mode
// but at least we would reflect latest state
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
altPid.postState(&tsOutputChannels);
#endif /* EFI_TUNER_STUDIO */
}
#endif /* !EFI_UNIT_TEST */
// todo: migrate this to FSIO
bool alternatorShouldBeEnabledAtCurrentRpm = GET_RPM() > engineConfiguration->cranking.rpm;
@ -85,8 +83,9 @@ static msg_t AltCtrlThread(int param) {
enginePins.alternatorPin.setValue(newState);
currentPlainOnOffState = newState;
if (engineConfiguration->debugMode == DBG_ALTERNATOR_PID) {
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
tsOutputChannels.debugIntField1 = newState;
#endif /* EFI_TUNER_STUDIO */
}
continue;

View File

@ -61,7 +61,9 @@
#include "pin_repository.h"
#include "pwm_generator.h"
#include "pid_auto_tune.h"
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
extern TunerStudioOutputChannels tsOutputChannels;
#endif /* EFI_TUNER_STUDIO */
static bool shouldResetPid = false;
static PID_AutoTune autoTune;
@ -94,9 +96,13 @@ static msg_t etbThread(void *arg) {
UNUSED(arg);
while (true) {
if (engineConfiguration->debugMode == DBG_ELECTRONIC_THROTTLE_PID) {
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
pid.postState(&tsOutputChannels);
#endif /* EFI_TUNER_STUDIO */
} else if (engineConfiguration->debugMode == DBG_ELECTRONIC_THROTTLE_EXTRA) {
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
tsOutputChannels.debugFloatField1 = valueOverride;
#endif /* EFI_TUNER_STUDIO */
}
if (shouldResetPid) {

View File

@ -39,7 +39,9 @@
static THD_WORKING_AREA(ivThreadStack, UTILITY_THREAD_STACK_SIZE);
static Logging *logger;
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
extern TunerStudioOutputChannels tsOutputChannels;
#endif /* EFI_TUNER_STUDIO */
EXTERN_ENGINE
;
@ -355,15 +357,17 @@ static msg_t ivThread(int param) {
if (engineConfiguration->debugMode == DBG_IDLE_CONTROL) {
#if ! EFI_UNIT_TEST || defined(__DOXYGEN__)
if (engineConfiguration->idleMode == IM_AUTO) {
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
// see also tsOutputChannels->idlePosition
idlePid.postState(&tsOutputChannels, 1000000);
#endif /* EFI_TUNER_STUDIO */
} else {
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
tsOutputChannels.debugFloatField1 = iacPosition;
tsOutputChannels.debugIntField1 = iacMotor.getTargetPosition();
#endif /* EFI_TUNER_STUDIO */
}
#endif
}
// The threshold is dependent on IAC type (see initIdleHardware())

View File

@ -215,10 +215,12 @@ static void applyMapMinBufferLength() {
}
void postMapState(TunerStudioOutputChannels *tsOutputChannels) {
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
tsOutputChannels->debugFloatField1 = v_averagedMapValue;
tsOutputChannels->debugFloatField2 = engine->engineState.mapAveragingDuration;
tsOutputChannels->debugFloatField3 = currentPressure;
tsOutputChannels->debugIntField1 = mapMeasurementsCounter;
#endif /* EFI_TUNER_STUDIO */
}
void refreshMapAveragingPreCalc(DECLARE_ENGINE_PARAMETER_SIGNATURE) {

View File

@ -106,15 +106,17 @@ void Pid::setErrorAmplification(float coef) {
errorAmplificationCoef = coef;
}
#if EFI_PROD_CODE || EFI_SIMULATOR
void Pid::postState(TunerStudioOutputChannels *tsOutputChannels) {
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
postState(tsOutputChannels, 1);
#endif /* EFI_TUNER_STUDIO */
}
/**
* see https://rusefi.com/wiki/index.php?title=Manual:Debug_fields
*/
void Pid::postState(TunerStudioOutputChannels *tsOutputChannels, int pMult) {
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
tsOutputChannels->debugFloatField1 = prevResult;
tsOutputChannels->debugFloatField2 = iTerm;
tsOutputChannels->debugFloatField3 = getPrevError();
@ -127,8 +129,8 @@ void Pid::postState(TunerStudioOutputChannels *tsOutputChannels, int pMult) {
tsOutputChannels->debugIntField2 = getOffset();
tsOutputChannels->debugIntField3 = resetCounter;
tsOutputChannels->debugIntField4 = pid->period;
#endif /* EFI_TUNER_STUDIO */
}
#endif
void Pid::sleep() {
#if !EFI_UNIT_TEST || defined(__DOXYGEN__)

View File

@ -131,7 +131,10 @@ floatms_t getSpeedDensityFuel(DECLARE_ENGINE_PARAMETER_SIGNATURE) {
efiAssert(CUSTOM_ERR_ASSERT, !cisnan(adjustedMap), "NaN adjustedMap", 0);
float airMass = getCylinderAirMass(engineConfiguration, ENGINE(engineState.currentVE), adjustedMap, tChargeK);
efiAssert(CUSTOM_ERR_ASSERT, !cisnan(airMass), "NaN airMass", 0);
if (cisnan(airMass)) {
warning(CUSTOM_ERR_6685, "NaN airMass");
return 0;
}
#if EFI_PRINTF_FUEL_DETAILS || defined(__DOXYGEN__)
printf("map=%.2f adjustedMap=%.2f airMass=%.2f\t\n",
map, adjustedMap, engine->engineState.airMass);

View File

@ -192,6 +192,7 @@ static void handleDtcRequest(int numCodes, int *dtcCode) {
}
}
#if HAL_USE_CAN || defined(__DOXYGEN__)
void obdOnCanPacketRx(CANRxFrame *rx) {
if (rx->SID != OBD_TEST_REQUEST) {
return;
@ -210,5 +211,6 @@ void obdOnCanPacketRx(CANRxFrame *rx) {
scheduleMsg(&logger, "Got unhandled OBD message");
}
}
#endif /* HAL_USE_CAN */
#endif /* EFI_CAN_SUPPORT */

View File

@ -37,6 +37,8 @@
#define PID_SUPPORTED_PIDS_REQUEST_41_60 0x40
#define PID_FUEL_RATE 0x5E
#if HAL_USE_CAN || defined(__DOXYGEN__)
void obdOnCanPacketRx(CANRxFrame *rx);
#endif /* HAL_USE_CAN */
#endif /* CONTROLLERS_OBD2_H_ */

View File

@ -877,7 +877,9 @@ static void enableOrDisable(const char *param, bool isEnabled) {
boardConfiguration->enabledStep1Limiter = isEnabled;
#if EFI_PROD_CODE || defined(__DOXYGEN__)
} else if (strEqualCaseInsensitive(param, "auto_idle")) {
#if EFI_IDLE_CONTROL || defined(__DOXYGEN__)
setIdleMode(isEnabled ? IM_MANUAL : IM_AUTO);
#endif /* EFI_IDLE_CONTROL */
#endif /* EFI_PROD_CODE */
} else if (strEqualCaseInsensitive(param, "serial")) {
boardConfiguration->useSerialPort = isEnabled;
@ -1155,7 +1157,10 @@ command_f_s commandsF[] = {{"mock_iat_voltage", setMockIatVoltage},
{"engine_decel_multiplier", setDecelMult},
{"flat_injector_lag", setFlatInjectorLag},
#if EFI_PROD_CODE || defined(__DOXYGEN__)
#if EFI_VEHICLE_SPEED || defined(__DOXYGEN__)
{"mock_vehicle_speed", setMockVehicleSpeed},
#endif /* EFI_VEHICLE_SPEED */
#if EFI_IDLE_CONTROL || defined(__DOXYGEN__)
{"idle_offset", setIdleOffset},
{"idle_p", setIdlePFactor},
{"idle_i", setIdleIFactor},
@ -1163,6 +1168,7 @@ command_f_s commandsF[] = {{"mock_iat_voltage", setMockIatVoltage},
{"etb_p", setEtbPFactor},
{"etb_i", setEtbIFactor},
{"etb_d", setEtbDFactor},
#endif /* EFI_IDLE_CONTROL */
#endif /* EFI_PROD_CODE */
// {"", },
@ -1208,10 +1214,14 @@ command_i_s commandsI[] = {{"ignition_mode", setIgnitionMode},
{"engine_load_accel_len", setEngineLoadAccelLen},
#if EFI_PROD_CODE || defined(__DOXYGEN__)
{"bor", setBor},
#if EFI_CAN_SUPPORT || defined(__DOXYGEN__)
{"can_mode", setCanType},
#endif /* EFI_CAN_SUPPORT */
#if EFI_IDLE_CONTROL || defined(__DOXYGEN__)
{"idle_position", setIdleValvePosition},
{"idle_rpm", setTargetIdleRpm},
{"idle_dt", setIdleDT},
#endif /* EFI_IDLE_CONTROL */
#endif /* EFI_PROD_CODE */
// {"", },
// {"", },

View File

@ -170,16 +170,20 @@ void initSignalExecutorImpl(void) {
initMicrosecondTimer();
}
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
extern TunerStudioOutputChannels tsOutputChannels;
#endif /* EFI_TUNER_STUDIO */
#include "engine.h"
EXTERN_ENGINE;
void executorStatistics() {
if (engineConfiguration->debugMode == DBG_EXECUTOR) {
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
tsOutputChannels.debugIntField1 = instance.timerCallbackCounter;
tsOutputChannels.debugIntField2 = instance.doExecuteCounter;
tsOutputChannels.debugIntField3 = instance.scheduleCounter;
#endif /* EFI_TUNER_STUDIO */
}
}

View File

@ -443,7 +443,7 @@ const char *portname(ioportid_t GPIOx) {
return "PC";
if (GPIOx == GPIOD)
return "PD";
#if defined(STM32F4XX)
#if defined(STM32F4XX) || defined(STM32F7XX)
if (GPIOx == GPIOE)
return "PE";
if (GPIOx == GPIOH)

View File

@ -74,7 +74,9 @@ static Logging *logger;
#if ! EFI_UNIT_TEST
static pid_s *fuelPidS = &persistentState.persistentConfiguration.engineConfiguration.fuelClosedLoopPid;
static Pid fuelPid(fuelPidS);
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
extern TunerStudioOutputChannels tsOutputChannels;
#endif /* EFI_TUNER_STUDIO */
#endif
// todo: figure out if this even helps?
@ -360,8 +362,10 @@ static void fuelClosedLoopCorrection(DECLARE_ENGINE_PARAMETER_SIGNATURE) {
engine->engineState.fuelPidCorrection = fuelPid.getValue(ENGINE(engineState.targetAFR), ENGINE(sensors.currentAfr), 1);
if (engineConfiguration->debugMode == DBG_FUEL_PID_CORRECTION) {
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
tsOutputChannels.debugFloatField1 = engine->engineState.fuelPidCorrection;
fuelPid.postState(&tsOutputChannels);
#endif /* EFI_TUNER_STUDIO */
}
#endif

View File

@ -29,7 +29,9 @@
#include "rfiutil.h"
#include "pin_repository.h"
#include "tunerstudio.h"
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
extern TunerStudioOutputChannels tsOutputChannels;
#endif /* EFI_TUNER_STUDIO */
#endif /* EFI_PROD_CODE */
#if EFI_ENGINE_SNIFFER || defined(__DOXYGEN__)
@ -122,11 +124,11 @@ void hwHandleVvtCamSignal(trigger_value_e front) {
if (engineConfiguration->isPrintTriggerSynchDetails) {
scheduleMsg(logger, "looks good: vvt ratio %.2f", ratio);
}
#if EFI_PROD_CODE || defined(__DOXYGEN__)
if (engineConfiguration->debugMode == DBG_VVT) {
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
tsOutputChannels.debugIntField1++;
#endif /* EFI_TUNER_STUDIO */
}
#endif /* EFI_PROD_CODE */
}
@ -149,22 +151,22 @@ void hwHandleVvtCamSignal(trigger_value_e front) {
* virtual crank-based trigger
*/
tc->triggerState.incrementTotalEventCounter();
#if EFI_PROD_CODE || defined(__DOXYGEN__)
if (engineConfiguration->debugMode == DBG_VVT) {
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
tsOutputChannels.debugIntField1++;
#endif /* EFI_TUNER_STUDIO */
}
#endif /* EFI_PROD_CODE */
}
} else if (engineConfiguration->vvtMode == VVT_SECOND_HALF) {
bool isEven = tc->triggerState.isEvenRevolution();
if (isEven) {
// see above comment
#if EFI_PROD_CODE || defined(__DOXYGEN__)
tc->triggerState.incrementTotalEventCounter();
if (engineConfiguration->debugMode == DBG_VVT) {
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
tsOutputChannels.debugIntField1++;
#endif /* EFI_TUNER_STUDIO */
}
#endif /* EFI_PROD_CODE */
}
} else if (engineConfiguration->vvtMode == MIATA_NB2) {
@ -623,7 +625,9 @@ void triggerInfo(void) {
scheduleMsg(logger, "maxEventCallbackDuration=%d", maxEventCallbackDuration);
#if EFI_HIP_9011 || defined(__DOXYGEN__)
scheduleMsg(logger, "hipLastExecutionCount=%d", hipLastExecutionCount);
#endif /* EFI_HIP_9011 */
scheduleMsg(logger, "hwSetTimerDuration=%d", hwSetTimerDuration);
scheduleMsg(logger, "totalTriggerHandlerMaxTime=%d", triggerMaxDuration);

View File

@ -64,9 +64,9 @@ bool printTriggerDebug = false;
float actualSynchGap;
#endif /* ! EFI_PROD_CODE */
#if ! EFI_UNIT_TEST || defined(__DOXYGEN__)
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
extern TunerStudioOutputChannels tsOutputChannels;
#endif /* EFI_UNIT_TEST */
#endif /* EFI_TUNER_STUDIO */
static Logging * logger;
@ -254,11 +254,11 @@ void TriggerState::decodeTriggerEvent(trigger_event_e const signal, efitime_t no
// this is getting a little out of hand, any ideas?
if (CONFIG(debugMode) == DBG_TRIGGER_SYNC) {
#if ! EFI_UNIT_TEST || defined(__DOXYGEN__)
float currentGap = 1.0 * toothDurations[0] / toothDurations[1];
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
tsOutputChannels.debugFloatField1 = currentGap;
tsOutputChannels.debugFloatField2 = currentCycle.current_index;
#endif /* EFI_UNIT_TEST */
#endif /* EFI_TUNER_STUDIO */
}
bool isGapCondition[GAP_TRACKING_LENGTH];
@ -364,12 +364,11 @@ void TriggerState::decodeTriggerEvent(trigger_event_e const signal, efitime_t no
enginePins.triggerDecoderErrorPin.setValue(isDecodingError);
if (isDecodingError && !isInitializingTrigger) {
if (engineConfiguration->debugMode == DBG_TRIGGER_SYNC) {
#if ! EFI_UNIT_TEST || defined(__DOXYGEN__)
#if EFI_TUNER_STUDIO || defined(__DOXYGEN__)
tsOutputChannels.debugIntField1 = currentCycle.eventCount[0];
tsOutputChannels.debugIntField2 = currentCycle.eventCount[1];
tsOutputChannels.debugIntField3 = currentCycle.eventCount[2];
#endif /* EFI_UNIT_TEST */
#endif /* EFI_TUNER_STUDIO */
}
warning(CUSTOM_SYNC_COUNT_MISMATCH, "trigger not happy current %d/%d/%d expected %d/%d/%d",

View File

@ -99,7 +99,9 @@ void initEngineEmulator(Logging *sharedLogger, Engine *engine) {
return;
#if EFI_POTENTIOMETER
#if HAL_USE_SPI || defined(__DOXYGEN__)
initPotentiometers(sharedLogger, &engine->engineConfiguration->bc);
#endif /* HAL_USE_SPI */
#endif /* EFI_POTENTIOMETER */
//initECUstimulator();

View File

@ -14,6 +14,8 @@
#include "hardware.h"
#include "mpu_util.h"
#if HAL_USE_SPI || defined(__DOXYGEN__)
/**
* MCP42010 digital potentiometer driver
*
@ -38,7 +40,12 @@
*/
/* Low speed SPI configuration (281.250kHz, CPHA=0, CPOL=0, MSb first).*/
#if defined(STM32F7XX)
#define SPI_POT_CONFIG SPI_CR1_BR_2 | SPI_CR1_BR_1 | SPI_CR1_CRCL
#else /* defined(STM32F4XX) */
#define SPI_POT_CONFIG SPI_CR1_BR_2 | SPI_CR1_BR_1 | SPI_CR1_DFF
#endif /* defined(STM32F4XX) */
static Logging * logger;
@ -112,3 +119,5 @@ void initPotentiometers(Logging *sharedLogger, board_configuration_s *boardConfi
print("digiPot logic disabled\r\n");
#endif
}
#endif /* HAL_USE_SPI */

View File

@ -74,13 +74,23 @@ typedef unsigned int time_t;
*
* Please note that DMA does not work with CCM memory
*/
#if EFI_USE_CCM && defined __GNUC__
#define CCM_OPTIONAL __attribute__((section(".ram4")))
#elif defined __GNUC__
#define CCM_OPTIONAL
#else
#define CCM_OPTIONAL @ ".ram4"
#if defined(STM32F7XX)
#undef EFI_USE_CCM
// todo: DTCM == CCM on STM32F7?
//#define CCM_RAM ".ram3"
#else /* defined(STM32F4XX) */
#define CCM_RAM ".ram4"
#endif /* defined(STM32F4XX) */
#if EFI_USE_CCM
#if defined __GNUC__
#define CCM_OPTIONAL __attribute__((section(CCM_RAM)))
#else // non-gcc
#define CCM_OPTIONAL @ CCM_RAM
#endif
#else /* !EFI_USE_CCM */
#define CCM_OPTIONAL
#endif /* EFI_USE_CCM */
#if EFI_PROD_CODE || defined(__DOXYGEN__)

View File

@ -17,13 +17,14 @@
*/
#include "accelerometer.h"
#include "lis302dl.h"
#include "hardware.h"
#include "mpu_util.h"
EXTERN_ENGINE;
#if EFI_MEMS || defined(__DOXYGEN__)
#include "lis302dl.h"
static SPIDriver *driver;
/*
@ -77,6 +78,7 @@ void initAccelerometer(DECLARE_ENGINE_PARAMETER_SIGNATURE) {
if (!boardConfiguration->is_enabled_spi_1)
return; // temporary
#if HAL_USE_SPI || defined(__DOXYGEN__)
driver = getSpiDevice(engineConfiguration->accelerometerSpiDevice);
turnOnSpi(engineConfiguration->accelerometerSpiDevice);
@ -94,6 +96,7 @@ void initAccelerometer(DECLARE_ENGINE_PARAMETER_SIGNATURE) {
lis302dlWriteRegister(driver, LIS302DL_CTRL_REG3, 0x00);
chThdCreateStatic(ivThreadStack, sizeof(ivThreadStack), NORMALPRIO, (tfunc_t) ivThread, NULL);
#endif /* HAL_USE_SPI */
}
#endif /* EFI_MEMS */

View File

@ -197,6 +197,7 @@ void doSlowAdc(void) {
#endif /* EFI_INTERNAL_ADC */
}
#if HAL_USE_PWM || defined(__DOXYGEN__)
static void pwmpcb_slow(PWMDriver *pwmp) {
(void) pwmp;
doSlowAdc();
@ -229,6 +230,7 @@ static void pwmpcb_fast(PWMDriver *pwmp) {
fastAdc.conversionCount++;
#endif /* EFI_INTERNAL_ADC */
}
#endif /* HAL_USE_PWM */
float getMCUInternalTemperature(void) {
float TemperatureValue = adcToVolts(slowAdc.getAdcValueByHwChannel(ADC_CHANNEL_SENSOR));
@ -265,6 +267,7 @@ int getInternalAdcValue(const char *msg, adc_channel_e hwChannel) {
return slowAdc.getAdcValueByHwChannel(hwChannel);
}
#if HAL_USE_PWM || defined(__DOXYGEN__)
static PWMConfig pwmcfg_slow = { PWM_FREQ_SLOW, PWM_PERIOD_SLOW, pwmpcb_slow, { {
PWM_OUTPUT_DISABLED, NULL }, { PWM_OUTPUT_DISABLED, NULL }, {
PWM_OUTPUT_DISABLED, NULL }, { PWM_OUTPUT_DISABLED, NULL } },
@ -276,6 +279,7 @@ PWM_OUTPUT_DISABLED, NULL }, { PWM_OUTPUT_DISABLED, NULL }, {
PWM_OUTPUT_DISABLED, NULL }, { PWM_OUTPUT_DISABLED, NULL } },
/* HW dependent part.*/
0, 0 };
#endif /* HAL_USE_PWM */
static void initAdcPin(brain_pin_e pin, const char *msg) {
// todo: migrate to scheduleMsg if we want this back print("adc %s\r\n", msg);
@ -671,16 +675,20 @@ void initAdcInputs(bool boardTestMode) {
slowAdc.enableChannel((adc_channel_e)ADC_CHANNEL_SENSOR);
slowAdc.init();
#if HAL_USE_PWM || defined(__DOXYGEN__)
pwmStart(EFI_INTERNAL_SLOW_ADC_PWM, &pwmcfg_slow);
pwmEnablePeriodicNotification(EFI_INTERNAL_SLOW_ADC_PWM);
#endif /* HAL_USE_PWM */
if (boardConfiguration->isFastAdcEnabled) {
fastAdc.init();
/*
* Initializes the PWM driver.
*/
#if HAL_USE_PWM || defined(__DOXYGEN__)
pwmStart(EFI_INTERNAL_FAST_ADC_PWM, &pwmcfg_fast);
pwmEnablePeriodicNotification(EFI_INTERNAL_FAST_ADC_PWM);
#endif /* HAL_USE_PWM */
}
// ADC_CHANNEL_IN0 // PA0

View File

@ -8,6 +8,7 @@
uint32_t backupRamLoad(backup_ram_e idx) {
switch (idx) {
#if HAL_USE_RTC || defined(__DOXYGEN__)
case BACKUP_STEPPER_POS:
return RTCD1.rtc->BKP0R & 0xffff;
case BACKUP_IGNITION_SWITCH_COUNTER:
@ -16,6 +17,7 @@ uint32_t backupRamLoad(backup_ram_e idx) {
return RTCD1.rtc->BKP1R & 0xffff;
case BACKUP_CJ125_CALIBRATION_HEATER:
return (RTCD1.rtc->BKP1R >> 16) & 0xffff;
#endif /* HAL_USE_RTC */
default:
//scheduleMsg(logger, "Invalid backup ram idx %d", idx);
return 0;
@ -24,6 +26,7 @@ uint32_t backupRamLoad(backup_ram_e idx) {
void backupRamSave(backup_ram_e idx, uint32_t value) {
switch (idx) {
#if HAL_USE_RTC || defined(__DOXYGEN__)
case BACKUP_STEPPER_POS:
RTCD1.rtc->BKP0R = (RTCD1.rtc->BKP0R & ~0x0000ffff) | (value & 0xffff);
break;
@ -36,6 +39,7 @@ void backupRamSave(backup_ram_e idx, uint32_t value) {
case BACKUP_CJ125_CALIBRATION_HEATER:
RTCD1.rtc->BKP1R = (RTCD1.rtc->BKP1R & ~0xffff0000) | ((value & 0xffff) << 16);
break;
#endif /* HAL_USE_RTC */
default:
//scheduleMsg(logger, "Invalid backup ram idx %d, value 0x08x", idx, value);
break;

View File

@ -39,7 +39,7 @@ extern "C" {
* 11 to program 64 bits per step
*/
// Warning, flashdata_t must be unsigned!!!
#if defined(STM32F4XX) || defined(__DOXYGEN__)
#if defined(STM32F4XX) || defined(STM32F7XX) || defined(__DOXYGEN__)
#define FLASH_CR_PSIZE_MASK FLASH_CR_PSIZE_0 | FLASH_CR_PSIZE_1
#if ((STM32_VDD >= 270) && (STM32_VDD <= 360)) || defined(__DOXYGEN__)
#define FLASH_CR_PSIZE_VALUE FLASH_CR_PSIZE_1

View File

@ -131,7 +131,13 @@ SPIDriver * getSpiDevice(spi_device_e spiDevice) {
#endif
#if HAL_USE_I2C || defined(__DOXYGEN__)
#if defined(STM32F7XX)
// values calculated with STM32CubeMX tool, 100kHz I2C clock for Nucleo-767 @168 MHz, PCK1=42MHz
#define HAL_I2C_F7_100_TIMINGR 0x00A0A3F7
static I2CConfig i2cfg = { HAL_I2C_F7_100_TIMINGR, 0, 0 }; // todo: does it work?
#else /* defined(STM32F4XX) */
static I2CConfig i2cfg = { OPMODE_I2C, 100000, STD_DUTY_CYCLE, };
#endif /* defined(STM32F4XX) */
void initI2Cmodule(void) {
print("Starting I2C module\r\n");
@ -229,12 +235,14 @@ static void unregisterPin(brain_pin_e currentPin, brain_pin_e prevPin) {
}
void stopSpi(spi_device_e device) {
#if HAL_USE_SPI || defined(__DOXYGEN__)
if (!isSpiInitialized[device])
return; // not turned on
isSpiInitialized[device] = false;
unmarkPin(getSckPin(device));
unmarkPin(getMisoPin(device));
unmarkPin(getMosiPin(device));
#endif /* HAL_USE_SPI */
}
void applyNewHardwareSettings(void) {
@ -246,12 +254,18 @@ void applyNewHardwareSettings(void) {
enginePins.stopInjectionPins();
enginePins.stopIgnitionPins();
#if EFI_CAN_SUPPORT || defined(__DOXYGEN__)
stopCanPins();
#endif /* EFI_CAN_SUPPORT */
#if EFI_ELECTRONIC_THROTTLE_BODY || defined(__DOXYGEN__)
bool etbRestartNeeded = isETBRestartNeeded();
if (etbRestartNeeded) {
stopETBPins();
}
#endif /* EFI_ELECTRONIC_THROTTLE_BODY */
#if EFI_VEHICLE_SPEED || defined(__DOXYGEN__)
stopVSSPins();
#endif /* EFI_VEHICLE_SPEED */
stopAuxPins();
if (engineConfiguration->bc.is_enabled_spi_1 != activeConfiguration.bc.is_enabled_spi_1)
@ -279,11 +293,17 @@ void applyNewHardwareSettings(void) {
enginePins.startInjectionPins();
enginePins.startIgnitionPins();
#if EFI_CAN_SUPPORT || defined(__DOXYGEN__)
startCanPins();
#endif /* EFI_CAN_SUPPORT */
#if EFI_ELECTRONIC_THROTTLE_BODY || defined(__DOXYGEN__)
if (etbRestartNeeded) {
startETBPins();
}
#endif /* EFI_ELECTRONIC_THROTTLE_BODY */
#if EFI_VEHICLE_SPEED || defined(__DOXYGEN__)
startVSSPins();
#endif /* EFI_VEHICLE_SPEED */
startAuxPins();
adcConfigListener(engine);

View File

@ -6,9 +6,7 @@ HW_LAYER_EGT_CPP = $(PROJECT_DIR)/hw_layer/can_hw.cpp \
HW_LAYER_EMS = $(HW_LAYER_EGT) \
$(PROJECT_DIR)/hw_layer/mcp3208.c \
$(PROJECT_DIR)/hw_layer/flash.c \
$(PROJECT_DIR)/hw_layer/stm32f4/stm32f4xx_hal_flash.c \
$(PROJECT_DIR)/hw_layer/stm32f4/stm32f4xx_hal_flash_ex.c
$(PROJECT_DIR)/hw_layer/flash.c
HW_LAYER_EMS_CPP = $(HW_LAYER_EGT_CPP) \
$(PROJECT_DIR)/hw_layer/accelerometer.cpp \
@ -29,7 +27,16 @@ HW_LAYER_EMS_CPP = $(HW_LAYER_EGT_CPP) \
$(PROJECT_DIR)/hw_layer/stepper.cpp \
$(PROJECT_DIR)/hw_layer/servo.cpp \
$(PROJECT_DIR)/hw_layer/io_pins.cpp \
$(PROJECT_DIR)/hw_layer/stm32f4/mpu_util.cpp \
$(PROJECT_DIR)/hw_layer/rtc_helper.cpp \
$(PROJECT_DIR)/hw_layer/backup_ram.cpp
ifeq ($(PROJECT_CPU),ST_STM32F7)
HW_LAYER_EMS += $(PROJECT_DIR)/hw_layer/stm32f7/stm32f7xx_hal_flash.c \
$(PROJECT_DIR)/hw_layer/stm32f7/stm32f7xx_hal_flash_ex.c
HW_LAYER_EMS_CPP += $(PROJECT_DIR)/hw_layer/stm32f7/mpu_util.cpp
else
HW_LAYER_EMS += $(PROJECT_DIR)/hw_layer/stm32f4/stm32f4xx_hal_flash.c \
$(PROJECT_DIR)/hw_layer/stm32f4/stm32f4xx_hal_flash_ex.c
HW_LAYER_EMS_CPP += $(PROJECT_DIR)/hw_layer/stm32f4/mpu_util.cpp
endif

View File

@ -27,7 +27,7 @@ static LoggingWithStorage logger("io_pins");
extern EnginePins enginePins;
#if defined(STM32F4XX)
#if defined(STM32F4XX) || defined(STM32F7XX)
static ioportid_t PORTS[] = { GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH };
#else
static ioportid_t PORTS[] = { GPIOA, GPIOB, GPIOC, GPIOD, GPIOF};

View File

@ -11,7 +11,10 @@
#include "global.h"
#include "engine_configuration.h"
#if HAL_USE_SPI || defined(__DOXYGEN__)
void initMax31855(Logging *sharedLogger, SPIDriver *drv, egt_cs_array_t max31855_cs);
#endif /* HAL_USE_SPI */
uint16_t getEgtValue(int egtChannel);
#endif /* MAX31855_H_ */

View File

@ -45,13 +45,13 @@ static int getPortIndex(ioportid_t port) {
return 2;
if (port == GPIOD)
return 3;
#if defined(STM32F4XX)
#if defined(STM32F4XX) || defined(STM32F7XX)
if (port == GPIOE)
return 4;
#endif /* defined(STM32F4XX) */
if (port == GPIOF)
return 5;
#if defined(STM32F4XX)
#if defined(STM32F4XX) || defined(STM32F7XX)
if (port == GPIOH)
return 6;
#endif /* defined(STM32F4XX) */

View File

@ -14,6 +14,9 @@
#include "usbcfg.h"
#include "efifeatures.h"
static bool isUsbSerialInitialized = false;
void usb_serial_start(void) {
/*
* Initializes a serial-over-USB CDC driver.
@ -37,10 +40,12 @@ void usb_serial_start(void) {
*/
sdStart(&SD2, NULL);
#endif
isUsbSerialInitialized = true;
}
bool is_usb_serial_ready(void) {
return SDU1.config->usbp->state == USB_ACTIVE;
return isUsbSerialInitialized && SDU1.config->usbp->state == USB_ACTIVE;
}
#else

View File

@ -0,0 +1,4 @@
HW_STM32_SRC_CPP = $(PROJECT_DIR)/hw_layer/stm32f7/mpu_util.cpp

View File

@ -0,0 +1,413 @@
/**
* @file mpu_util.cpp
*
* @date Jul 27, 2014
* @author Andrey Belomutskiy, (c) 2012-2018
*/
#include "global.h"
#include "mpu_util.h"
#include "error_handling.h"
#include "engine.h"
#include "pin_repository.h"
#include "stm32f7xx_hal_flash.h"
#include "rfiutil.h"
EXTERN_ENGINE;
extern "C" {
void prvGetRegistersFromStack(uint32_t *pulFaultStackAddress);
}
extern uint32_t __main_stack_base__;
#define GET_CFSR() (*((volatile uint32_t *) (0xE000ED28)))
#if defined __GNUC__
// GCC version
typedef struct port_intctx intctx_t;
int getRemainingStack(thread_t *otp) {
#if CH_DBG_ENABLE_STACK_CHECK
// this would dismiss coverity warning - see http://rusefi.com/forum/viewtopic.php?f=5&t=655
// coverity[uninit_use]
register intctx_t *r13 asm ("r13");
otp->activeStack = r13;
int remainingStack;
if (ch.dbg.isr_cnt > 0) {
remainingStack = 9999;
// ISR context
// todo remainingStack = (int)(r13 - 1) - (int)&__main_stack_base__;
} else {
remainingStack = 9999;
// todo remainingStack = (int)(r13 - 1) - (int)otp->p_stklimit;
}
otp->remainingStack = remainingStack;
return remainingStack;
#else
return 99999;
#endif /* CH_DBG_ENABLE_STACK_CHECK */
}
#else /* __GNUC__ */
extern uint32_t CSTACK$$Base; /* symbol created by the IAR linker */
extern uint32_t IRQSTACK$$Base; /* symbol created by the IAR linker */
int getRemainingStack(thread_t *otp) {
#if CH_DBG_ENABLE_STACK_CHECK || defined(__DOXYGEN__)
int remainingStack;
if (ch.dbg.isr_cnt > 0) {
remainingStack = (__get_SP() - sizeof(port_intctx)) - (int)&IRQSTACK$$Base;
} else {
remainingStack = (__get_SP() - sizeof(port_intctx)) - (int)otp->p_stklimit;
}
otp->remainingStack = remainingStack;
return remainingStack;
#else
return 999999;
#endif
}
// IAR version
#endif /* GNU / IAR */
void baseHardwareInit(void) {
// looks like this holds a random value on start? Let's set a nice clean zero
DWT->CYCCNT = 0;
BOR_Set(BOR_Level_1); // one step above default value
}
void _unhandled_exception(void) {
/*lint -restore*/
chDbgPanic3("_unhandled_exception", __FILE__, __LINE__);
while (true) {
}
}
void DebugMonitorVector(void) {
chDbgPanic3("DebugMonitorVector", __FILE__, __LINE__);
while (TRUE)
;
}
void UsageFaultVector(void) {
chDbgPanic3("UsageFaultVector", __FILE__, __LINE__);
while (TRUE)
;
}
void BusFaultVector(void) {
chDbgPanic3("BusFaultVector", __FILE__, __LINE__);
while (TRUE) {
}
}
/**
+ * @brief Register values for postmortem debugging.
+ */
volatile uint32_t postmortem_r0;
volatile uint32_t postmortem_r1;
volatile uint32_t postmortem_r2;
volatile uint32_t postmortem_r3;
volatile uint32_t postmortem_r12;
volatile uint32_t postmortem_lr; /* Link register. */
volatile uint32_t postmortem_pc; /* Program counter. */
volatile uint32_t postmortem_psr;/* Program status register. */
volatile uint32_t postmortem_CFSR;
volatile uint32_t postmortem_HFSR;
volatile uint32_t postmortem_DFSR;
volatile uint32_t postmortem_AFSR;
volatile uint32_t postmortem_BFAR;
volatile uint32_t postmortem_MMAR;
volatile uint32_t postmortem_SCB_SHCSR;
/**
* @brief Evaluates to TRUE if system runs under debugger control.
* @note This bit resets only by power reset.
*/
#define is_under_debugger() (((CoreDebug)->DHCSR) & \
CoreDebug_DHCSR_C_DEBUGEN_Msk)
/**
*
*/
void prvGetRegistersFromStack(uint32_t *pulFaultStackAddress) {
postmortem_r0 = pulFaultStackAddress[0];
postmortem_r1 = pulFaultStackAddress[1];
postmortem_r2 = pulFaultStackAddress[2];
postmortem_r3 = pulFaultStackAddress[3];
postmortem_r12 = pulFaultStackAddress[4];
postmortem_lr = pulFaultStackAddress[5];
postmortem_pc = pulFaultStackAddress[6];
postmortem_psr = pulFaultStackAddress[7];
/* Configurable Fault Status Register. Consists of MMSR, BFSR and UFSR */
postmortem_CFSR = GET_CFSR();
/* Hard Fault Status Register */
postmortem_HFSR = (*((volatile uint32_t *) (0xE000ED2C)));
/* Debug Fault Status Register */
postmortem_DFSR = (*((volatile uint32_t *) (0xE000ED30)));
/* Auxiliary Fault Status Register */
postmortem_AFSR = (*((volatile uint32_t *) (0xE000ED3C)));
/* Read the Fault Address Registers. These may not contain valid values.
Check BFARVALID/MMARVALID to see if they are valid values
MemManage Fault Address Register */
postmortem_MMAR = (*((volatile uint32_t *) (0xE000ED34)));
/* Bus Fault Address Register */
postmortem_BFAR = (*((volatile uint32_t *) (0xE000ED38)));
postmortem_SCB_SHCSR = SCB->SHCSR;
if (is_under_debugger()) {
__asm("BKPT #0\n");
// Break into the debugger
}
/* harmless infinite loop */
while (1) {
;
}
}
void HardFaultVector(void) {
#if 0 && defined __GNUC__
__asm volatile (
" tst lr, #4 \n"
" ite eq \n"
" mrseq r0, msp \n"
" mrsne r0, psp \n"
" ldr r1, [r0, #24] \n"
" ldr r2, handler2_address_const \n"
" bx r2 \n"
" handler2_address_const: .word prvGetRegistersFromStack \n"
);
#else
#endif /* 0 && defined __GNUC__ */
int cfsr = GET_CFSR();
if (cfsr & 0x1) {
chDbgPanic3("H IACCVIOL", __FILE__, __LINE__);
} else if (cfsr & 0x100) {
chDbgPanic3("H IBUSERR", __FILE__, __LINE__);
} else if (cfsr & 0x20000) {
chDbgPanic3("H INVSTATE", __FILE__, __LINE__);
} else {
chDbgPanic3("HardFaultVector", __FILE__, __LINE__);
}
while (TRUE) {
}
}
#if HAL_USE_SPI || defined(__DOXYGEN__)
bool isSpiInitialized[5] = { false, false, false, false, false };
static int getSpiAf(SPIDriver *driver) {
#if STM32_SPI_USE_SPI1
if (driver == &SPID1) {
return EFI_SPI1_AF;
}
#endif
#if STM32_SPI_USE_SPI2
if (driver == &SPID2) {
return EFI_SPI2_AF;
}
#endif
#if STM32_SPI_USE_SPI3
if (driver == &SPID3) {
return EFI_SPI3_AF;
}
#endif
return -1;
}
brain_pin_e getMisoPin(spi_device_e device) {
switch(device) {
case SPI_DEVICE_1:
return boardConfiguration->spi1misoPin;
case SPI_DEVICE_2:
return boardConfiguration->spi2misoPin;
case SPI_DEVICE_3:
return boardConfiguration->spi3misoPin;
default:
break;
}
return GPIO_UNASSIGNED;
}
brain_pin_e getMosiPin(spi_device_e device) {
switch(device) {
case SPI_DEVICE_1:
return boardConfiguration->spi1mosiPin;
case SPI_DEVICE_2:
return boardConfiguration->spi2mosiPin;
case SPI_DEVICE_3:
return boardConfiguration->spi3mosiPin;
default:
break;
}
return GPIO_UNASSIGNED;
}
brain_pin_e getSckPin(spi_device_e device) {
switch(device) {
case SPI_DEVICE_1:
return boardConfiguration->spi1sckPin;
case SPI_DEVICE_2:
return boardConfiguration->spi2sckPin;
case SPI_DEVICE_3:
return boardConfiguration->spi3sckPin;
default:
break;
}
return GPIO_UNASSIGNED;
}
void turnOnSpi(spi_device_e device) {
if (isSpiInitialized[device])
return; // already initialized
isSpiInitialized[device] = true;
if (device == SPI_DEVICE_1) {
// todo: introduce a nice structure with all fields for same SPI
#if STM32_SPI_USE_SPI1
// scheduleMsg(&logging, "Turning on SPI1 pins");
initSpiModule(&SPID1, getSckPin(device),
getMisoPin(device),
getMosiPin(device),
engineConfiguration->spi1SckMode,
engineConfiguration->spi1MosiMode,
engineConfiguration->spi1MisoMode);
#endif /* STM32_SPI_USE_SPI1 */
}
if (device == SPI_DEVICE_2) {
#if STM32_SPI_USE_SPI2
// scheduleMsg(&logging, "Turning on SPI2 pins");
initSpiModule(&SPID2, getSckPin(device),
getMisoPin(device),
getMosiPin(device),
engineConfiguration->spi2SckMode,
engineConfiguration->spi2MosiMode,
engineConfiguration->spi2MisoMode);
#endif /* STM32_SPI_USE_SPI2 */
}
if (device == SPI_DEVICE_3) {
#if STM32_SPI_USE_SPI3
// scheduleMsg(&logging, "Turning on SPI3 pins");
initSpiModule(&SPID3, getSckPin(device),
getMisoPin(device),
getMosiPin(device),
engineConfiguration->spi3SckMode,
engineConfiguration->spi3MosiMode,
engineConfiguration->spi3MisoMode);
#endif /* STM32_SPI_USE_SPI3 */
}
}
void initSpiModule(SPIDriver *driver, brain_pin_e sck, brain_pin_e miso,
brain_pin_e mosi,
int sckMode,
int mosiMode,
int misoMode) {
efiSetPadMode("SPI clock", sck, PAL_MODE_ALTERNATE(getSpiAf(driver)) + sckMode);
efiSetPadMode("SPI master out", mosi, PAL_MODE_ALTERNATE(getSpiAf(driver)) + mosiMode);
efiSetPadMode("SPI master in ", miso, PAL_MODE_ALTERNATE(getSpiAf(driver)) + misoMode);
}
void initSpiCs(SPIConfig *spiConfig, brain_pin_e csPin) {
spiConfig->end_cb = NULL;
ioportid_t port = getHwPort("spi", csPin);
ioportmask_t pin = getHwPin("spi", csPin);
spiConfig->ssport = port;
spiConfig->sspad = pin;
efiSetPadMode("chip select", csPin, PAL_STM32_MODE_OUTPUT);
}
#endif /* HAL_USE_SPI */
BOR_Level_t BOR_Get(void) {
FLASH_OBProgramInitTypeDef FLASH_Handle;
/* Read option bytes */
HAL_FLASHEx_OBGetConfig(&FLASH_Handle);
/* Return BOR value */
return (BOR_Level_t) FLASH_Handle.BORLevel;
}
BOR_Result_t BOR_Set(BOR_Level_t BORValue) {
if (BOR_Get() == BORValue) {
return BOR_Result_Ok;
}
FLASH_OBProgramInitTypeDef FLASH_Handle;
FLASH_Handle.BORLevel = (uint32_t)BORValue;
FLASH_Handle.OptionType = OPTIONBYTE_BOR;
HAL_FLASH_OB_Unlock();
HAL_FLASHEx_OBProgram(&FLASH_Handle);
HAL_StatusTypeDef status = HAL_FLASH_OB_Launch();
HAL_FLASH_OB_Lock();
if (status != HAL_OK) {
return BOR_Result_Error;
}
return BOR_Result_Ok;
}
#if EFI_CAN_SUPPORT || defined(__DOXYGEN__)
static bool isValidCan1RxPin(brain_pin_e pin) {
return pin == GPIOA_11 || pin == GPIOB_8 || pin == GPIOD_0;
}
static bool isValidCan1TxPin(brain_pin_e pin) {
return pin == GPIOA_12 || pin == GPIOB_9 || pin == GPIOD_1;
}
static bool isValidCan2RxPin(brain_pin_e pin) {
return pin == GPIOB_5 || pin == GPIOB_12;
}
static bool isValidCan2TxPin(brain_pin_e pin) {
return pin == GPIOB_6 || pin == GPIOB_13;
}
bool isValidCanTxPin(brain_pin_e pin) {
return isValidCan1TxPin(pin) || isValidCan2TxPin(pin);
}
bool isValidCanRxPin(brain_pin_e pin) {
return isValidCan1RxPin(pin) || isValidCan2RxPin(pin);
}
CANDriver * detectCanDevice(brain_pin_e pinRx, brain_pin_e pinTx) {
if (isValidCan1RxPin(pinRx) && isValidCan1TxPin(pinTx))
return &CAND1;
if (isValidCan2RxPin(pinRx) && isValidCan2TxPin(pinTx))
return &CAND2;
return NULL;
}
#endif /* EFI_CAN_SUPPORT */

View File

@ -0,0 +1,105 @@
/**
* @file mpu_util.h
*
* @date Jul 27, 2014
* @author Andrey Belomutskiy, (c) 2012-2017
*/
#ifndef MPU_UTIL_H_
#define MPU_UTIL_H_
#include "stm32f7xx_hal_flash_ex.h"
// we are lucky - all CAN pins use the same AF
#define EFI_CAN_RX_AF 9
#define EFI_CAN_TX_AF 9
// burnout or 'Burn Out'
typedef enum {
BOR_Level_None = OB_BOR_OFF, // 0x0C=12 Supply voltage ranges from 1.62 to 2.10 V
BOR_Level_1 = OB_BOR_LEVEL1, // 0x08 Supply voltage ranges from 2.10 to 2.40 V
BOR_Level_2 = OB_BOR_LEVEL2, // 0x04 Supply voltage ranges from 2.40 to 2.70 V
BOR_Level_3 = OB_BOR_LEVEL3 // 0x00 Supply voltage ranges from 2.70 to 3.60 V
} BOR_Level_t;
typedef enum {
BOR_Result_Ok = 0x00,
BOR_Result_Error
} BOR_Result_t;
BOR_Level_t BOR_Get(void);
BOR_Result_t BOR_Set(BOR_Level_t BORValue);
#ifndef GPIO_AF_TIM1
#define GPIO_AF_TIM1 1
#endif
#ifndef GPIO_AF_TIM2
#define GPIO_AF_TIM2 1
#endif
#ifndef GPIO_AF_TIM3
#define GPIO_AF_TIM3 2
#endif
#ifndef GPIO_AF_TIM4
#define GPIO_AF_TIM4 2
#endif
#ifndef GPIO_AF_TIM5
#define GPIO_AF_TIM5 2
#endif
#ifndef GPIO_AF_TIM9
#define GPIO_AF_TIM9 3
#endif
#ifndef ADC_TwoSamplingDelay_5Cycles
#define ADC_TwoSamplingDelay_5Cycles ((uint32_t)0x00000000)
#endif
#ifndef ADC_TwoSamplingDelay_20Cycles
#define ADC_TwoSamplingDelay_20Cycles ((uint32_t)0x00000F00)
#endif
#ifndef ADC_CR2_SWSTART
#define ADC_CR2_SWSTART ((uint32_t)0x40000000)
#endif
void baseHardwareInit(void);
void turnOnSpi(spi_device_e device);
#ifdef __cplusplus
extern "C"
{
#endif /* __cplusplus */
// these need to be declared C style for the linker magic to work
void DebugMonitorVector(void);
void UsageFaultVector(void);
void BusFaultVector(void);
void HardFaultVector(void);
#ifdef __cplusplus
}
#endif /* __cplusplus */
#endif /* MPU_UTIL_H_ */
#if HAL_USE_SPI || defined(__DOXYGEN__)
void initSpiModule(SPIDriver *driver, brain_pin_e sck, brain_pin_e miso,
brain_pin_e mosi,
int sckMode,
int mosiMode,
int misoMode);
/**
* @see getSpiDevice
*/
void initSpiCs(SPIConfig *spiConfig, brain_pin_e csPin);
#endif /* HAL_USE_SPI */
#if HAL_USE_CAN || defined(__DOXYGEN__)
bool isValidCanTxPin(brain_pin_e pin);
bool isValidCanRxPin(brain_pin_e pin);
CANDriver * detectCanDevice(brain_pin_e pinRx, brain_pin_e pinTx);
#endif /* HAL_USE_CAN */

View File

@ -0,0 +1,213 @@
/**
******************************************************************************
* @file stm32f7xx_hal_def.h
* @author MCD Application Team
* @version V1.2.0
* @date 30-December-2016
* @brief This file contains HAL common defines, enumeration, macros and
* structures definitions.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F7xx_HAL_DEF
#define __STM32F7xx_HAL_DEF
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f7xx.h"
//#include "Legacy/stm32_hal_legacy.h"
#include <stdio.h>
/* Exported types ------------------------------------------------------------*/
/**
* @brief HAL Status structures definition
*/
typedef enum
{
HAL_OK = 0x00U,
HAL_ERROR = 0x01U,
HAL_BUSY = 0x02U,
HAL_TIMEOUT = 0x03U
} HAL_StatusTypeDef;
/**
* @brief HAL Lock structures definition
*/
typedef enum
{
HAL_UNLOCKED = 0x00,
HAL_LOCKED = 0x01
} HAL_LockTypeDef;
/* Exported macro ------------------------------------------------------------*/
#define HAL_MAX_DELAY 0xFFFFFFFFU
#define HAL_IS_BIT_SET(REG, BIT) (((REG) & (BIT)) != RESET)
#define HAL_IS_BIT_CLR(REG, BIT) (((REG) & (BIT)) == RESET)
#define __HAL_LINKDMA(__HANDLE__, __PPP_DMA_FIELD__, __DMA_HANDLE__) \
do{ \
(__HANDLE__)->__PPP_DMA_FIELD__ = &(__DMA_HANDLE__); \
(__DMA_HANDLE__).Parent = (__HANDLE__); \
} while(0)
//#define UNUSED(x) ((void)(x))
/** @brief Reset the Handle's State field.
* @param __HANDLE__: specifies the Peripheral Handle.
* @note This macro can be used for the following purpose:
* - When the Handle is declared as local variable; before passing it as parameter
* to HAL_PPP_Init() for the first time, it is mandatory to use this macro
* to set to 0 the Handle's "State" field.
* Otherwise, "State" field may have any random value and the first time the function
* HAL_PPP_Init() is called, the low level hardware initialization will be missed
* (i.e. HAL_PPP_MspInit() will not be executed).
* - When there is a need to reconfigure the low level hardware: instead of calling
* HAL_PPP_DeInit() then HAL_PPP_Init(), user can make a call to this macro then HAL_PPP_Init().
* In this later function, when the Handle's "State" field is set to 0, it will execute the function
* HAL_PPP_MspInit() which will reconfigure the low level hardware.
* @retval None
*/
#define __HAL_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = 0U)
#if (USE_RTOS == 1)
/* Reserved for future use */
#error "USE_RTOS should be 0 in the current HAL release"
#else
#define __HAL_LOCK(__HANDLE__) \
do{ \
if((__HANDLE__)->Lock == HAL_LOCKED) \
{ \
return HAL_BUSY; \
} \
else \
{ \
(__HANDLE__)->Lock = HAL_LOCKED; \
} \
}while (0)
#define __HAL_UNLOCK(__HANDLE__) \
do{ \
(__HANDLE__)->Lock = HAL_UNLOCKED; \
}while (0)
#endif /* USE_RTOS */
#if defined ( __GNUC__ )
#ifndef __weak
#define __weak __attribute__((weak))
#endif /* __weak */
#ifndef __packed
#define __packed __attribute__((__packed__))
#endif /* __packed */
#endif /* __GNUC__ */
/* Macro to get variable aligned on 4-bytes, for __ICCARM__ the directive "#pragma data_alignment=4" must be used instead */
#if defined (__GNUC__) /* GNU Compiler */
#ifndef __ALIGN_END
#define __ALIGN_END __attribute__ ((aligned (4)))
#endif /* __ALIGN_END */
#ifndef __ALIGN_BEGIN
#define __ALIGN_BEGIN
#endif /* __ALIGN_BEGIN */
#else
#ifndef __ALIGN_END
#define __ALIGN_END
#endif /* __ALIGN_END */
#ifndef __ALIGN_BEGIN
#if defined (__CC_ARM) /* ARM Compiler */
#define __ALIGN_BEGIN __align(4)
#elif defined (__ICCARM__) /* IAR Compiler */
#define __ALIGN_BEGIN
#endif /* __CC_ARM */
#endif /* __ALIGN_BEGIN */
#endif /* __GNUC__ */
/**
* @brief __RAM_FUNC definition
*/
#if defined ( __CC_ARM )
/* ARM Compiler
------------
RAM functions are defined using the toolchain options.
Functions that are executed in RAM should reside in a separate source module.
Using the 'Options for File' dialog you can simply change the 'Code / Const'
area of a module to a memory space in physical RAM.
Available memory areas are declared in the 'Target' tab of the 'Options for Target'
dialog.
*/
#define __RAM_FUNC HAL_StatusTypeDef
#elif defined ( __ICCARM__ )
/* ICCARM Compiler
---------------
RAM functions are defined using a specific toolchain keyword "__ramfunc".
*/
#define __RAM_FUNC __ramfunc HAL_StatusTypeDef
#elif defined ( __GNUC__ )
/* GNU Compiler
------------
RAM functions are defined using a specific toolchain attribute
"__attribute__((section(".RamFunc")))".
*/
#define __RAM_FUNC HAL_StatusTypeDef __attribute__((section(".RamFunc")))
#endif
/**
* @brief __NOINLINE definition
*/
#if defined ( __CC_ARM ) || defined ( __GNUC__ )
/* ARM & GNUCompiler
----------------
*/
#define __NOINLINE __attribute__ ( (noinline) )
#elif defined ( __ICCARM__ )
/* ICCARM Compiler
---------------
*/
#define __NOINLINE _Pragma("optimize = no_inline")
#endif
#ifdef __cplusplus
}
#endif
#endif /* ___STM32F7xx_HAL_DEF */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,839 @@
/**
******************************************************************************
* @file stm32f7xx_hal_flash.c
* @author MCD Application Team
* @version V1.2.0
* @date 30-December-2016
* @brief FLASH HAL module driver.
* This file provides firmware functions to manage the following
* functionalities of the internal FLASH memory:
* + Program operations functions
* + Memory Control functions
* + Peripheral Errors functions
*
@verbatim
==============================================================================
##### FLASH peripheral features #####
==============================================================================
[..] The Flash memory interface manages CPU AHB I-Code and D-Code accesses
to the Flash memory. It implements the erase and program Flash memory operations
and the read and write protection mechanisms.
[..] The Flash memory interface accelerates code execution with a system of instruction
prefetch and cache lines.
[..] The FLASH main features are:
(+) Flash memory read operations
(+) Flash memory program/erase operations
(+) Read / write protections
(+) Prefetch on I-Code
(+) 64 cache lines of 128 bits on I-Code
(+) 8 cache lines of 128 bits on D-Code
##### How to use this driver #####
==============================================================================
[..]
This driver provides functions and macros to configure and program the FLASH
memory of all STM32F7xx devices.
(#) FLASH Memory IO Programming functions:
(++) Lock and Unlock the FLASH interface using HAL_FLASH_Unlock() and
HAL_FLASH_Lock() functions
(++) Program functions: byte, half word, word and double word
(++) There Two modes of programming :
(+++) Polling mode using HAL_FLASH_Program() function
(+++) Interrupt mode using HAL_FLASH_Program_IT() function
(#) Interrupts and flags management functions :
(++) Handle FLASH interrupts by calling HAL_FLASH_IRQHandler()
(++) Wait for last FLASH operation according to its status
(++) Get error flag status by calling HAL_SetErrorCode()
[..]
In addition to these functions, this driver includes a set of macros allowing
to handle the following operations:
(+) Set the latency
(+) Enable/Disable the prefetch buffer
(+) Enable/Disable the Instruction cache and the Data cache
(+) Reset the Instruction cache and the Data cache
(+) Enable/Disable the FLASH interrupts
(+) Monitor the FLASH flags status
[..]
(@) For any Flash memory program operation (erase or program), the CPU clock frequency
(HCLK) must be at least 1MHz.
(@) The contents of the Flash memory are not guaranteed if a device reset occurs during
a Flash memory operation.
(@) Any attempt to read the Flash memory while it is being written or erased, causes the
bus to stall. Read operations are processed correctly once the program operation has
completed. This means that code or data fetches cannot be performed while a write/erase
operation is ongoing.
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
//#include "stm32f7xx_hal.h"
#include "stm32f7xx_hal_flash_ex.h"
#include "stm32f7xx_hal_flash.h"
#define assert_param(expr) ((void)0)
/** @addtogroup STM32F7xx_HAL_Driver
* @{
*/
/** @defgroup FLASH FLASH
* @brief FLASH HAL module driver
* @{
*/
#define HAL_FLASH_MODULE_ENABLED
#ifdef HAL_FLASH_MODULE_ENABLED
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/** @addtogroup FLASH_Private_Constants
* @{
*/
#define SECTOR_MASK ((uint32_t)0xFFFFFF07U)
#define FLASH_TIMEOUT_VALUE ((uint32_t)50000U)/* 50 s */
/**
* @}
*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/** @addtogroup FLASH_Private_Variables
* @{
*/
/* Variable used for Erase sectors under interruption */
FLASH_ProcessTypeDef pFlash;
/**
* @}
*/
/* Private function prototypes -----------------------------------------------*/
/** @addtogroup FLASH_Private_Functions
* @{
*/
/* Program operations */
static void FLASH_Program_DoubleWord(uint32_t Address, uint64_t Data);
static void FLASH_Program_Word(uint32_t Address, uint32_t Data);
static void FLASH_Program_HalfWord(uint32_t Address, uint16_t Data);
static void FLASH_Program_Byte(uint32_t Address, uint8_t Data);
static void FLASH_SetErrorCode(void);
HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout);
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/** @defgroup FLASH_Exported_Functions FLASH Exported Functions
* @{
*/
/** @defgroup FLASH_Exported_Functions_Group1 Programming operation functions
* @brief Programming operation functions
*
@verbatim
===============================================================================
##### Programming operation functions #####
===============================================================================
[..]
This subsection provides a set of functions allowing to manage the FLASH
program operations.
@endverbatim
* @{
*/
/**
* @brief Program byte, halfword, word or double word at a specified address
* @param TypeProgram: Indicate the way to program at a specified address.
* This parameter can be a value of @ref FLASH_Type_Program
* @param Address: specifies the address to be programmed.
* @param Data: specifies the data to be programmed
*
* @retval HAL_StatusTypeDef HAL Status
*/
HAL_StatusTypeDef HAL_FLASH_Program(uint32_t TypeProgram, uint32_t Address, uint64_t Data)
{
HAL_StatusTypeDef status = HAL_ERROR;
/* Process Locked */
__HAL_LOCK(&pFlash);
/* Check the parameters */
assert_param(IS_FLASH_TYPEPROGRAM(TypeProgram));
/* Wait for last operation to be completed */
status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE);
if(status == HAL_OK)
{
switch(TypeProgram)
{
case FLASH_TYPEPROGRAM_BYTE :
{
/*Program byte (8-bit) at a specified address.*/
FLASH_Program_Byte(Address, (uint8_t) Data);
break;
}
case FLASH_TYPEPROGRAM_HALFWORD :
{
/*Program halfword (16-bit) at a specified address.*/
FLASH_Program_HalfWord(Address, (uint16_t) Data);
break;
}
case FLASH_TYPEPROGRAM_WORD :
{
/*Program word (32-bit) at a specified address.*/
FLASH_Program_Word(Address, (uint32_t) Data);
break;
}
case FLASH_TYPEPROGRAM_DOUBLEWORD :
{
/*Program double word (64-bit) at a specified address.*/
FLASH_Program_DoubleWord(Address, Data);
break;
}
default :
break;
}
/* Wait for last operation to be completed */
status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE);
/* If the program operation is completed, disable the PG Bit */
FLASH->CR &= (~FLASH_CR_PG);
}
/* Process Unlocked */
__HAL_UNLOCK(&pFlash);
return status;
}
/**
* @brief Program byte, halfword, word or double word at a specified address with interrupt enabled.
* @param TypeProgram: Indicate the way to program at a specified address.
* This parameter can be a value of @ref FLASH_Type_Program
* @param Address: specifies the address to be programmed.
* @param Data: specifies the data to be programmed
*
* @retval HAL Status
*/
HAL_StatusTypeDef HAL_FLASH_Program_IT(uint32_t TypeProgram, uint32_t Address, uint64_t Data)
{
HAL_StatusTypeDef status = HAL_OK;
/* Process Locked */
__HAL_LOCK(&pFlash);
/* Check the parameters */
assert_param(IS_FLASH_TYPEPROGRAM(TypeProgram));
/* Enable End of FLASH Operation interrupt */
__HAL_FLASH_ENABLE_IT(FLASH_IT_EOP);
/* Enable Error source interrupt */
__HAL_FLASH_ENABLE_IT(FLASH_IT_ERR);
/* Clear pending flags (if any) */
__HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR |\
FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR| FLASH_FLAG_ERSERR);
pFlash.ProcedureOnGoing = FLASH_PROC_PROGRAM;
pFlash.Address = Address;
switch(TypeProgram)
{
case FLASH_TYPEPROGRAM_BYTE :
{
/*Program byte (8-bit) at a specified address.*/
FLASH_Program_Byte(Address, (uint8_t) Data);
break;
}
case FLASH_TYPEPROGRAM_HALFWORD :
{
/*Program halfword (16-bit) at a specified address.*/
FLASH_Program_HalfWord(Address, (uint16_t) Data);
break;
}
case FLASH_TYPEPROGRAM_WORD :
{
/*Program word (32-bit) at a specified address.*/
FLASH_Program_Word(Address, (uint32_t) Data);
break;
}
case FLASH_TYPEPROGRAM_DOUBLEWORD :
{
/*Program double word (64-bit) at a specified address.*/
FLASH_Program_DoubleWord(Address, Data);
break;
}
default :
break;
}
return status;
}
/**
* @brief This function handles FLASH interrupt request.
* @retval None
*/
void HAL_FLASH_IRQHandler(void)
{
uint32_t temp = 0;
/* If the program operation is completed, disable the PG Bit */
FLASH->CR &= (~FLASH_CR_PG);
/* If the erase operation is completed, disable the SER Bit */
FLASH->CR &= (~FLASH_CR_SER);
FLASH->CR &= SECTOR_MASK;
/* if the erase operation is completed, disable the MER Bit */
FLASH->CR &= (~FLASH_MER_BIT);
/* Check FLASH End of Operation flag */
if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_EOP) != RESET)
{
/* Clear FLASH End of Operation pending bit */
__HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP);
switch (pFlash.ProcedureOnGoing)
{
case FLASH_PROC_SECTERASE :
{
/* Nb of sector to erased can be decreased */
pFlash.NbSectorsToErase--;
/* Check if there are still sectors to erase */
if(pFlash.NbSectorsToErase != 0)
{
temp = pFlash.Sector;
/* Indicate user which sector has been erased */
HAL_FLASH_EndOfOperationCallback(temp);
/* Increment sector number */
temp = ++pFlash.Sector;
FLASH_Erase_Sector(temp, pFlash.VoltageForErase);
}
else
{
/* No more sectors to Erase, user callback can be called.*/
/* Reset Sector and stop Erase sectors procedure */
pFlash.Sector = temp = 0xFFFFFFFFU;
/* FLASH EOP interrupt user callback */
HAL_FLASH_EndOfOperationCallback(temp);
/* Sector Erase procedure is completed */
pFlash.ProcedureOnGoing = FLASH_PROC_NONE;
}
break;
}
case FLASH_PROC_MASSERASE :
{
/* MassErase ended. Return the selected bank : in this product we don't have Banks */
/* FLASH EOP interrupt user callback */
HAL_FLASH_EndOfOperationCallback(0);
/* MAss Erase procedure is completed */
pFlash.ProcedureOnGoing = FLASH_PROC_NONE;
break;
}
case FLASH_PROC_PROGRAM :
{
/*Program ended. Return the selected address*/
/* FLASH EOP interrupt user callback */
HAL_FLASH_EndOfOperationCallback(pFlash.Address);
/* Programming procedure is completed */
pFlash.ProcedureOnGoing = FLASH_PROC_NONE;
break;
}
default :
break;
}
}
/* Check FLASH operation error flags */
if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_ALL_ERRORS) != RESET)
{
switch (pFlash.ProcedureOnGoing)
{
case FLASH_PROC_SECTERASE :
{
/* return the faulty sector */
temp = pFlash.Sector;
pFlash.Sector = 0xFFFFFFFFU;
break;
}
case FLASH_PROC_MASSERASE :
{
/* No return in case of Mass Erase */
temp = 0;
break;
}
case FLASH_PROC_PROGRAM :
{
/*return the faulty address*/
temp = pFlash.Address;
break;
}
default :
break;
}
/*Save the Error code*/
FLASH_SetErrorCode();
/* FLASH error interrupt user callback */
HAL_FLASH_OperationErrorCallback(temp);
/*Stop the procedure ongoing */
pFlash.ProcedureOnGoing = FLASH_PROC_NONE;
}
if(pFlash.ProcedureOnGoing == FLASH_PROC_NONE)
{
/* Disable End of FLASH Operation interrupt */
__HAL_FLASH_DISABLE_IT(FLASH_IT_EOP);
/* Disable Error source interrupt */
__HAL_FLASH_DISABLE_IT(FLASH_IT_ERR);
/* Process Unlocked */
__HAL_UNLOCK(&pFlash);
}
}
/**
* @brief FLASH end of operation interrupt callback
* @param ReturnValue: The value saved in this parameter depends on the ongoing procedure
* - Sectors Erase: Sector which has been erased (if 0xFFFFFFFF, it means that
* all the selected sectors have been erased)
* - Program : Address which was selected for data program
* - Mass Erase : No return value expected
* @retval None
*/
__weak void HAL_FLASH_EndOfOperationCallback(uint32_t ReturnValue)
{
/* Prevent unused argument(s) compilation warning */
//UNUSED(ReturnValue);
/* NOTE : This function Should not be modified, when the callback is needed,
the HAL_FLASH_EndOfOperationCallback could be implemented in the user file
*/
}
/**
* @brief FLASH operation error interrupt callback
* @param ReturnValue: The value saved in this parameter depends on the ongoing procedure
* - Sectors Erase: Sector which has been erased (if 0xFFFFFFFF, it means that
* all the selected sectors have been erased)
* - Program : Address which was selected for data program
* - Mass Erase : No return value expected
* @retval None
*/
__weak void HAL_FLASH_OperationErrorCallback(uint32_t ReturnValue)
{
/* Prevent unused argument(s) compilation warning */
//UNUSED(ReturnValue);
/* NOTE : This function Should not be modified, when the callback is needed,
the HAL_FLASH_OperationErrorCallback could be implemented in the user file
*/
}
/**
* @}
*/
/** @defgroup FLASH_Exported_Functions_Group2 Peripheral Control functions
* @brief management functions
*
@verbatim
===============================================================================
##### Peripheral Control functions #####
===============================================================================
[..]
This subsection provides a set of functions allowing to control the FLASH
memory operations.
@endverbatim
* @{
*/
/**
* @brief Unlock the FLASH control register access
* @retval HAL Status
*/
HAL_StatusTypeDef HAL_FLASH_Unlock(void)
{
if((FLASH->CR & FLASH_CR_LOCK) != RESET)
{
/* Authorize the FLASH Registers access */
FLASH->KEYR = FLASH_KEY1;
FLASH->KEYR = FLASH_KEY2;
}
else
{
return HAL_ERROR;
}
return HAL_OK;
}
/**
* @brief Locks the FLASH control register access
* @retval HAL Status
*/
HAL_StatusTypeDef HAL_FLASH_Lock(void)
{
/* Set the LOCK Bit to lock the FLASH Registers access */
FLASH->CR |= FLASH_CR_LOCK;
return HAL_OK;
}
/**
* @brief Unlock the FLASH Option Control Registers access.
* @retval HAL Status
*/
HAL_StatusTypeDef HAL_FLASH_OB_Unlock(void)
{
if((FLASH->OPTCR & FLASH_OPTCR_OPTLOCK) != RESET)
{
/* Authorizes the Option Byte register programming */
FLASH->OPTKEYR = FLASH_OPT_KEY1;
FLASH->OPTKEYR = FLASH_OPT_KEY2;
}
else
{
return HAL_ERROR;
}
return HAL_OK;
}
/**
* @brief Lock the FLASH Option Control Registers access.
* @retval HAL Status
*/
HAL_StatusTypeDef HAL_FLASH_OB_Lock(void)
{
/* Set the OPTLOCK Bit to lock the FLASH Option Byte Registers access */
FLASH->OPTCR |= FLASH_OPTCR_OPTLOCK;
return HAL_OK;
}
/**
* @brief Launch the option byte loading.
* @retval HAL Status
*/
HAL_StatusTypeDef HAL_FLASH_OB_Launch(void)
{
/* Set the OPTSTRT bit in OPTCR register */
FLASH->OPTCR |= FLASH_OPTCR_OPTSTRT;
/* Wait for last operation to be completed */
return(FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE));
}
/**
* @}
*/
/** @defgroup FLASH_Exported_Functions_Group3 Peripheral State and Errors functions
* @brief Peripheral Errors functions
*
@verbatim
===============================================================================
##### Peripheral Errors functions #####
===============================================================================
[..]
This subsection permits to get in run-time Errors of the FLASH peripheral.
@endverbatim
* @{
*/
/**
* @brief Get the specific FLASH error flag.
* @retval FLASH_ErrorCode: The returned value can be:
* @arg FLASH_ERROR_ERS: FLASH Erasing Sequence error flag
* @arg FLASH_ERROR_PGP: FLASH Programming Parallelism error flag
* @arg FLASH_ERROR_PGA: FLASH Programming Alignment error flag
* @arg FLASH_ERROR_WRP: FLASH Write protected error flag
* @arg FLASH_ERROR_OPERATION: FLASH operation Error flag
*/
uint32_t HAL_FLASH_GetError(void)
{
return pFlash.ErrorCode;
}
/**
* @}
*/
/**
* @brief Wait for a FLASH operation to complete.
* @param Timeout: maximum flash operationtimeout
* @retval HAL Status
*/
HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout)
{
uint32_t tickstart = 0;
/* Clear Error Code */
pFlash.ErrorCode = HAL_FLASH_ERROR_NONE;
/* Wait for the FLASH operation to complete by polling on BUSY flag to be reset.
Even if the FLASH operation fails, the BUSY flag will be reset and an error
flag will be set */
/* Get tick */
// todo: implement rusEfi own timeout
//tickstart = HAL_GetTick();
while(__HAL_FLASH_GET_FLAG(FLASH_FLAG_BSY) != RESET)
{
/*
// todo: implement rusEfi own timeout
if(Timeout != HAL_MAX_DELAY)
{
if((Timeout == 0)||((HAL_GetTick() - tickstart ) > Timeout))
{
return HAL_TIMEOUT;
}
}
*/
}
if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_ALL_ERRORS) != RESET)
{
/*Save the error code*/
FLASH_SetErrorCode();
return HAL_ERROR;
}
/* Check FLASH End of Operation flag */
if (__HAL_FLASH_GET_FLAG(FLASH_FLAG_EOP) != RESET)
{
/* Clear FLASH End of Operation pending bit */
__HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP);
}
/* If there is an error flag set */
return HAL_OK;
}
/**
* @brief Program a double word (64-bit) at a specified address.
* @note This function must be used when the device voltage range is from
* 2.7V to 3.6V and an External Vpp is present.
*
* @note If an erase and a program operations are requested simultaneously,
* the erase operation is performed before the program one.
*
* @param Address: specifies the address to be programmed.
* @param Data: specifies the data to be programmed.
* @retval None
*/
static void FLASH_Program_DoubleWord(uint32_t Address, uint64_t Data)
{
/* Check the parameters */
assert_param(IS_FLASH_ADDRESS(Address));
/* If the previous operation is completed, proceed to program the new data */
FLASH->CR &= CR_PSIZE_MASK;
FLASH->CR |= FLASH_PSIZE_DOUBLE_WORD;
FLASH->CR |= FLASH_CR_PG;
*(__IO uint64_t*)Address = Data;
/* Data synchronous Barrier (DSB) Just after the write operation
This will force the CPU to respect the sequence of instruction (no optimization).*/
__DSB();
}
/**
* @brief Program word (32-bit) at a specified address.
* @note This function must be used when the device voltage range is from
* 2.7V to 3.6V.
*
* @note If an erase and a program operations are requested simultaneously,
* the erase operation is performed before the program one.
*
* @param Address: specifies the address to be programmed.
* @param Data: specifies the data to be programmed.
* @retval None
*/
static void FLASH_Program_Word(uint32_t Address, uint32_t Data)
{
/* Check the parameters */
assert_param(IS_FLASH_ADDRESS(Address));
/* If the previous operation is completed, proceed to program the new data */
FLASH->CR &= CR_PSIZE_MASK;
FLASH->CR |= FLASH_PSIZE_WORD;
FLASH->CR |= FLASH_CR_PG;
*(__IO uint32_t*)Address = Data;
/* Data synchronous Barrier (DSB) Just after the write operation
This will force the CPU to respect the sequence of instruction (no optimization).*/
__DSB();
}
/**
* @brief Program a half-word (16-bit) at a specified address.
* @note This function must be used when the device voltage range is from
* 2.7V to 3.6V.
*
* @note If an erase and a program operations are requested simultaneously,
* the erase operation is performed before the program one.
*
* @param Address: specifies the address to be programmed.
* @param Data: specifies the data to be programmed.
* @retval None
*/
static void FLASH_Program_HalfWord(uint32_t Address, uint16_t Data)
{
/* Check the parameters */
assert_param(IS_FLASH_ADDRESS(Address));
/* If the previous operation is completed, proceed to program the new data */
FLASH->CR &= CR_PSIZE_MASK;
FLASH->CR |= FLASH_PSIZE_HALF_WORD;
FLASH->CR |= FLASH_CR_PG;
*(__IO uint16_t*)Address = Data;
/* Data synchronous Barrier (DSB) Just after the write operation
This will force the CPU to respect the sequence of instruction (no optimization).*/
__DSB();
}
/**
* @brief Program byte (8-bit) at a specified address.
* @note This function must be used when the device voltage range is from
* 2.7V to 3.6V.
*
* @note If an erase and a program operations are requested simultaneously,
* the erase operation is performed before the program one.
*
* @param Address: specifies the address to be programmed.
* @param Data: specifies the data to be programmed.
* @retval None
*/
static void FLASH_Program_Byte(uint32_t Address, uint8_t Data)
{
/* Check the parameters */
assert_param(IS_FLASH_ADDRESS(Address));
/* If the previous operation is completed, proceed to program the new data */
FLASH->CR &= CR_PSIZE_MASK;
FLASH->CR |= FLASH_PSIZE_BYTE;
FLASH->CR |= FLASH_CR_PG;
*(__IO uint8_t*)Address = Data;
/* Data synchronous Barrier (DSB) Just after the write operation
This will force the CPU to respect the sequence of instruction (no optimization).*/
__DSB();
}
/**
* @brief Set the specific FLASH error flag.
* @retval None
*/
static void FLASH_SetErrorCode(void)
{
if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_OPERR) != RESET)
{
pFlash.ErrorCode |= HAL_FLASH_ERROR_OPERATION;
}
if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_WRPERR) != RESET)
{
pFlash.ErrorCode |= HAL_FLASH_ERROR_WRP;
}
if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_PGAERR) != RESET)
{
pFlash.ErrorCode |= HAL_FLASH_ERROR_PGA;
}
if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_PGPERR) != RESET)
{
pFlash.ErrorCode |= HAL_FLASH_ERROR_PGP;
}
if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_ERSERR) != RESET)
{
pFlash.ErrorCode |= HAL_FLASH_ERROR_ERS;
}
#if defined (FLASH_OPTCR2_PCROP)
if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_RDERR) != RESET)
{
pFlash.ErrorCode |= HAL_FLASH_ERROR_RD;
}
#endif /* FLASH_OPTCR2_PCROP */
/* Clear error programming flags */
__HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_ALL_ERRORS);
}
/**
* @}
*/
#endif /* HAL_FLASH_MODULE_ENABLED */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,426 @@
/**
******************************************************************************
* @file stm32f7xx_hal_flash.h
* @author MCD Application Team
* @version V1.2.0
* @date 30-December-2016
* @brief Header file of FLASH HAL module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F7xx_HAL_FLASH_H
#define __STM32F7xx_HAL_FLASH_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f7xx_hal_def.h"
/** @addtogroup STM32F7xx_HAL_Driver
* @{
*/
/** @addtogroup FLASH
* @{
*/
/* Exported types ------------------------------------------------------------*/
/** @defgroup FLASH_Exported_Types FLASH Exported Types
* @{
*/
/**
* @brief FLASH Procedure structure definition
*/
typedef enum
{
FLASH_PROC_NONE = 0U,
FLASH_PROC_SECTERASE,
FLASH_PROC_MASSERASE,
FLASH_PROC_PROGRAM
} FLASH_ProcedureTypeDef;
/**
* @brief FLASH handle Structure definition
*/
typedef struct
{
__IO FLASH_ProcedureTypeDef ProcedureOnGoing; /* Internal variable to indicate which procedure is ongoing or not in IT context */
__IO uint32_t NbSectorsToErase; /* Internal variable to save the remaining sectors to erase in IT context */
__IO uint8_t VoltageForErase; /* Internal variable to provide voltage range selected by user in IT context */
__IO uint32_t Sector; /* Internal variable to define the current sector which is erasing */
__IO uint32_t Address; /* Internal variable to save address selected for program */
HAL_LockTypeDef Lock; /* FLASH locking object */
__IO uint32_t ErrorCode; /* FLASH error code */
}FLASH_ProcessTypeDef;
/**
* @}
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup FLASH_Exported_Constants FLASH Exported Constants
* @{
*/
/** @defgroup FLASH_Error_Code FLASH Error Code
* @brief FLASH Error Code
* @{
*/
#define HAL_FLASH_ERROR_NONE ((uint32_t)0x00000000U) /*!< No error */
#define HAL_FLASH_ERROR_ERS ((uint32_t)0x00000002U) /*!< Programming Sequence error */
#define HAL_FLASH_ERROR_PGP ((uint32_t)0x00000004U) /*!< Programming Parallelism error */
#define HAL_FLASH_ERROR_PGA ((uint32_t)0x00000008U) /*!< Programming Alignment error */
#define HAL_FLASH_ERROR_WRP ((uint32_t)0x00000010U) /*!< Write protection error */
#define HAL_FLASH_ERROR_OPERATION ((uint32_t)0x00000020U) /*!< Operation Error */
#define HAL_FLASH_ERROR_RD ((uint32_t)0x00000040U) /*!< Read Protection Error */
/**
* @}
*/
/** @defgroup FLASH_Type_Program FLASH Type Program
* @{
*/
#define FLASH_TYPEPROGRAM_BYTE ((uint32_t)0x00U) /*!< Program byte (8-bit) at a specified address */
#define FLASH_TYPEPROGRAM_HALFWORD ((uint32_t)0x01U) /*!< Program a half-word (16-bit) at a specified address */
#define FLASH_TYPEPROGRAM_WORD ((uint32_t)0x02U) /*!< Program a word (32-bit) at a specified address */
#define FLASH_TYPEPROGRAM_DOUBLEWORD ((uint32_t)0x03U) /*!< Program a double word (64-bit) at a specified address */
/**
* @}
*/
/** @defgroup FLASH_Flag_definition FLASH Flag definition
* @brief Flag definition
* @{
*/
#define FLASH_FLAG_EOP FLASH_SR_EOP /*!< FLASH End of Operation flag */
#define FLASH_FLAG_OPERR FLASH_SR_OPERR /*!< FLASH operation Error flag */
#define FLASH_FLAG_WRPERR FLASH_SR_WRPERR /*!< FLASH Write protected error flag */
#define FLASH_FLAG_PGAERR FLASH_SR_PGAERR /*!< FLASH Programming Alignment error flag */
#define FLASH_FLAG_PGPERR FLASH_SR_PGPERR /*!< FLASH Programming Parallelism error flag */
#define FLASH_FLAG_ERSERR FLASH_SR_ERSERR /*!< FLASH Erasing Sequence error flag */
#define FLASH_FLAG_BSY FLASH_SR_BSY /*!< FLASH Busy flag */
#if defined (FLASH_OPTCR2_PCROP)
#define FLASH_FLAG_RDERR FLASH_SR_RDERR /*!< FLASH Read protection error flag */
#define FLASH_FLAG_ALL_ERRORS (FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | \
FLASH_FLAG_PGPERR | FLASH_FLAG_ERSERR | FLASH_FLAG_RDERR)
#else
#define FLASH_FLAG_ALL_ERRORS (FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | \
FLASH_FLAG_PGPERR | FLASH_FLAG_ERSERR)
#endif /* FLASH_OPTCR2_PCROP */
/**
* @}
*/
/** @defgroup FLASH_Interrupt_definition FLASH Interrupt definition
* @brief FLASH Interrupt definition
* @{
*/
#define FLASH_IT_EOP FLASH_CR_EOPIE /*!< End of FLASH Operation Interrupt source */
#define FLASH_IT_ERR ((uint32_t)0x02000000U) /*!< Error Interrupt source */
/**
* @}
*/
/** @defgroup FLASH_Program_Parallelism FLASH Program Parallelism
* @{
*/
#define FLASH_PSIZE_BYTE ((uint32_t)0x00000000U)
#define FLASH_PSIZE_HALF_WORD ((uint32_t)FLASH_CR_PSIZE_0)
#define FLASH_PSIZE_WORD ((uint32_t)FLASH_CR_PSIZE_1)
#define FLASH_PSIZE_DOUBLE_WORD ((uint32_t)FLASH_CR_PSIZE)
#define CR_PSIZE_MASK ((uint32_t)0xFFFFFCFFU)
/**
* @}
*/
/** @defgroup FLASH_Keys FLASH Keys
* @{
*/
#define FLASH_KEY1 ((uint32_t)0x45670123U)
#define FLASH_KEY2 ((uint32_t)0xCDEF89ABU)
#define FLASH_OPT_KEY1 ((uint32_t)0x08192A3BU)
#define FLASH_OPT_KEY2 ((uint32_t)0x4C5D6E7FU)
/**
* @}
*/
/** @defgroup FLASH_Sectors FLASH Sectors
* @{
*/
#define FLASH_SECTOR_0 ((uint32_t)0U) /*!< Sector Number 0 */
#define FLASH_SECTOR_1 ((uint32_t)1U) /*!< Sector Number 1 */
#define FLASH_SECTOR_2 ((uint32_t)2U) /*!< Sector Number 2 */
#define FLASH_SECTOR_3 ((uint32_t)3U) /*!< Sector Number 3 */
#define FLASH_SECTOR_4 ((uint32_t)4U) /*!< Sector Number 4 */
#define FLASH_SECTOR_5 ((uint32_t)5U) /*!< Sector Number 5 */
#define FLASH_SECTOR_6 ((uint32_t)6U) /*!< Sector Number 6 */
#define FLASH_SECTOR_7 ((uint32_t)7U) /*!< Sector Number 7 */
/**
* @}
*/
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @defgroup FLASH_Exported_Macros FLASH Exported Macros
* @{
*/
/**
* @brief Set the FLASH Latency.
* @param __LATENCY__: FLASH Latency
* The value of this parameter depend on device used within the same series
* @retval none
*/
#define __HAL_FLASH_SET_LATENCY(__LATENCY__) \
MODIFY_REG(FLASH->ACR, FLASH_ACR_LATENCY, (uint32_t)(__LATENCY__))
/**
* @brief Get the FLASH Latency.
* @retval FLASH Latency
* The value of this parameter depend on device used within the same series
*/
#define __HAL_FLASH_GET_LATENCY() (READ_BIT((FLASH->ACR), FLASH_ACR_LATENCY))
/**
* @brief Enable the FLASH prefetch buffer.
* @retval none
*/
#define __HAL_FLASH_PREFETCH_BUFFER_ENABLE() (FLASH->ACR |= FLASH_ACR_PRFTEN)
/**
* @brief Disable the FLASH prefetch buffer.
* @retval none
*/
#define __HAL_FLASH_PREFETCH_BUFFER_DISABLE() (FLASH->ACR &= (~FLASH_ACR_PRFTEN))
/**
* @brief Enable the FLASH Adaptive Real-Time memory accelerator.
* @note The ART accelerator is available only for flash access on ITCM interface.
* @retval none
*/
#define __HAL_FLASH_ART_ENABLE() SET_BIT(FLASH->ACR, FLASH_ACR_ARTEN)
/**
* @brief Disable the FLASH Adaptive Real-Time memory accelerator.
* @retval none
*/
#define __HAL_FLASH_ART_DISABLE() CLEAR_BIT(FLASH->ACR, FLASH_ACR_ARTEN)
/**
* @brief Resets the FLASH Adaptive Real-Time memory accelerator.
* @note This function must be used only when the Adaptive Real-Time memory accelerator
* is disabled.
* @retval None
*/
#define __HAL_FLASH_ART_RESET() (FLASH->ACR |= FLASH_ACR_ARTRST)
/**
* @brief Enable the specified FLASH interrupt.
* @param __INTERRUPT__ : FLASH interrupt
* This parameter can be any combination of the following values:
* @arg FLASH_IT_EOP: End of FLASH Operation Interrupt
* @arg FLASH_IT_ERR: Error Interrupt
* @retval none
*/
#define __HAL_FLASH_ENABLE_IT(__INTERRUPT__) (FLASH->CR |= (__INTERRUPT__))
/**
* @brief Disable the specified FLASH interrupt.
* @param __INTERRUPT__ : FLASH interrupt
* This parameter can be any combination of the following values:
* @arg FLASH_IT_EOP: End of FLASH Operation Interrupt
* @arg FLASH_IT_ERR: Error Interrupt
* @retval none
*/
#define __HAL_FLASH_DISABLE_IT(__INTERRUPT__) (FLASH->CR &= ~(uint32_t)(__INTERRUPT__))
/**
* @brief Get the specified FLASH flag status.
* @param __FLAG__: specifies the FLASH flag to check.
* This parameter can be one of the following values:
* @arg FLASH_FLAG_EOP : FLASH End of Operation flag
* @arg FLASH_FLAG_OPERR : FLASH operation Error flag
* @arg FLASH_FLAG_WRPERR: FLASH Write protected error flag
* @arg FLASH_FLAG_PGAERR: FLASH Programming Alignment error flag
* @arg FLASH_FLAG_PGPERR: FLASH Programming Parallelism error flag
* @arg FLASH_FLAG_ERSERR : FLASH Erasing Sequence error flag
* @arg FLASH_FLAG_BSY : FLASH Busy flag
* @retval The new state of __FLAG__ (SET or RESET).
*/
#define __HAL_FLASH_GET_FLAG(__FLAG__) ((FLASH->SR & (__FLAG__)))
/**
* @brief Clear the specified FLASH flag.
* @param __FLAG__: specifies the FLASH flags to clear.
* This parameter can be any combination of the following values:
* @arg FLASH_FLAG_EOP : FLASH End of Operation flag
* @arg FLASH_FLAG_OPERR : FLASH operation Error flag
* @arg FLASH_FLAG_WRPERR: FLASH Write protected error flag
* @arg FLASH_FLAG_PGAERR: FLASH Programming Alignment error flag
* @arg FLASH_FLAG_PGPERR: FLASH Programming Parallelism error flag
* @arg FLASH_FLAG_ERSERR : FLASH Erasing Sequence error flag
* @retval none
*/
#define __HAL_FLASH_CLEAR_FLAG(__FLAG__) (FLASH->SR = (__FLAG__))
/**
* @}
*/
/* Include FLASH HAL Extension module */
#include "stm32f7xx_hal_flash_ex.h"
/* Exported functions --------------------------------------------------------*/
/** @addtogroup FLASH_Exported_Functions
* @{
*/
/** @addtogroup FLASH_Exported_Functions_Group1
* @{
*/
/* Program operation functions ***********************************************/
HAL_StatusTypeDef HAL_FLASH_Program(uint32_t TypeProgram, uint32_t Address, uint64_t Data);
HAL_StatusTypeDef HAL_FLASH_Program_IT(uint32_t TypeProgram, uint32_t Address, uint64_t Data);
/* FLASH IRQ handler method */
void HAL_FLASH_IRQHandler(void);
/* Callbacks in non blocking modes */
void HAL_FLASH_EndOfOperationCallback(uint32_t ReturnValue);
void HAL_FLASH_OperationErrorCallback(uint32_t ReturnValue);
/**
* @}
*/
/** @addtogroup FLASH_Exported_Functions_Group2
* @{
*/
/* Peripheral Control functions **********************************************/
HAL_StatusTypeDef HAL_FLASH_Unlock(void);
HAL_StatusTypeDef HAL_FLASH_Lock(void);
HAL_StatusTypeDef HAL_FLASH_OB_Unlock(void);
HAL_StatusTypeDef HAL_FLASH_OB_Lock(void);
/* Option bytes control */
HAL_StatusTypeDef HAL_FLASH_OB_Launch(void);
/**
* @}
*/
/** @addtogroup FLASH_Exported_Functions_Group3
* @{
*/
/* Peripheral State functions ************************************************/
uint32_t HAL_FLASH_GetError(void);
HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout);
/**
* @}
*/
/**
* @}
*/
/* Private types -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/** @defgroup FLASH_Private_Variables FLASH Private Variables
* @{
*/
/**
* @}
*/
/* Private constants ---------------------------------------------------------*/
/** @defgroup FLASH_Private_Constants FLASH Private Constants
* @{
*/
/**
* @brief OPTCR register byte 1 (Bits[15:8]) base address
*/
#define OPTCR_BYTE1_ADDRESS ((uint32_t)0x40023C15)
/**
* @}
*/
/* Private macros ------------------------------------------------------------*/
/** @defgroup FLASH_Private_Macros FLASH Private Macros
* @{
*/
/** @defgroup FLASH_IS_FLASH_Definitions FLASH Private macros to check input parameters
* @{
*/
#define IS_FLASH_TYPEPROGRAM(VALUE)(((VALUE) == FLASH_TYPEPROGRAM_BYTE) || \
((VALUE) == FLASH_TYPEPROGRAM_HALFWORD) || \
((VALUE) == FLASH_TYPEPROGRAM_WORD) || \
((VALUE) == FLASH_TYPEPROGRAM_DOUBLEWORD))
/**
* @}
*/
/**
* @}
*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup FLASH_Private_Functions FLASH Private Functions
* @{
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32F7xx_HAL_FLASH_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,667 @@
/**
******************************************************************************
* @file stm32f7xx_hal_flash_ex.h
* @author MCD Application Team
* @version V1.2.0
* @date 30-December-2016
* @brief Header file of FLASH HAL Extension module.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F7xx_HAL_FLASH_EX_H
#define __STM32F7xx_HAL_FLASH_EX_H
#ifdef __cplusplus
extern "C" {
#endif
#define FLASH_OTP_BASE 0x1FF0F000U /*!< Base address of : (up to 1024 Bytes) embedded FLASH OTP Area */
#define FLASH_OTP_END 0x1FF0F41FU /*!< End address of : (up to 1024 Bytes) embedded FLASH OTP Area */
/* Includes ------------------------------------------------------------------*/
#include "stm32f7xx_hal_def.h"
/** @addtogroup STM32F7xx_HAL_Driver
* @{
*/
/** @addtogroup FLASHEx
* @{
*/
/* Exported types ------------------------------------------------------------*/
/** @defgroup FLASHEx_Exported_Types FLASH Exported Types
* @{
*/
/**
* @brief FLASH Erase structure definition
*/
typedef struct
{
uint32_t TypeErase; /*!< Mass erase or sector Erase.
This parameter can be a value of @ref FLASHEx_Type_Erase */
#if defined (FLASH_OPTCR_nDBANK)
uint32_t Banks; /*!< Select banks to erase when Mass erase is enabled.
This parameter must be a value of @ref FLASHEx_Banks */
#endif /* FLASH_OPTCR_nDBANK */
uint32_t Sector; /*!< Initial FLASH sector to erase when Mass erase is disabled
This parameter must be a value of @ref FLASHEx_Sectors */
uint32_t NbSectors; /*!< Number of sectors to be erased.
This parameter must be a value between 1 and (max number of sectors - value of Initial sector)*/
uint32_t VoltageRange;/*!< The device voltage range which defines the erase parallelism
This parameter must be a value of @ref FLASHEx_Voltage_Range */
} FLASH_EraseInitTypeDef;
/**
* @brief FLASH Option Bytes Program structure definition
*/
typedef struct
{
uint32_t OptionType; /*!< Option byte to be configured.
This parameter can be a value of @ref FLASHEx_Option_Type */
uint32_t WRPState; /*!< Write protection activation or deactivation.
This parameter can be a value of @ref FLASHEx_WRP_State */
uint32_t WRPSector; /*!< Specifies the sector(s) to be write protected.
The value of this parameter depend on device used within the same series */
uint32_t RDPLevel; /*!< Set the read protection level.
This parameter can be a value of @ref FLASHEx_Option_Bytes_Read_Protection */
uint32_t BORLevel; /*!< Set the BOR Level.
This parameter can be a value of @ref FLASHEx_BOR_Reset_Level */
uint32_t USERConfig; /*!< Program the FLASH User Option Byte: WWDG_SW / IWDG_SW / RST_STOP / RST_STDBY /
IWDG_FREEZE_STOP / IWDG_FREEZE_SANDBY / nDBANK / nDBOOT.
nDBANK / nDBOOT are only available for STM32F76xxx/STM32F77xxx devices */
uint32_t BootAddr0; /*!< Boot base address when Boot pin = 0.
This parameter can be a value of @ref FLASHEx_Boot_Address */
uint32_t BootAddr1; /*!< Boot base address when Boot pin = 1.
This parameter can be a value of @ref FLASHEx_Boot_Address */
#if defined (FLASH_OPTCR2_PCROP)
uint32_t PCROPSector; /*!< Set the PCROP sector.
This parameter can be a value of @ref FLASHEx_Option_Bytes_PCROP_Sectors */
uint32_t PCROPRdp; /*!< Set the PCROP_RDP option.
This parameter can be a value of @ref FLASHEx_Option_Bytes_PCROP_RDP */
#endif /* FLASH_OPTCR2_PCROP */
} FLASH_OBProgramInitTypeDef;
/**
* @}
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup FLASHEx_Exported_Constants FLASH Exported Constants
* @{
*/
/** @defgroup FLASHEx_Type_Erase FLASH Type Erase
* @{
*/
#define FLASH_TYPEERASE_SECTORS ((uint32_t)0x00U) /*!< Sectors erase only */
#define FLASH_TYPEERASE_MASSERASE ((uint32_t)0x01U) /*!< Flash Mass erase activation */
/**
* @}
*/
/** @defgroup FLASHEx_Voltage_Range FLASH Voltage Range
* @{
*/
#define FLASH_VOLTAGE_RANGE_1 ((uint32_t)0x00U) /*!< Device operating range: 1.8V to 2.1V */
#define FLASH_VOLTAGE_RANGE_2 ((uint32_t)0x01U) /*!< Device operating range: 2.1V to 2.7V */
#define FLASH_VOLTAGE_RANGE_3 ((uint32_t)0x02U) /*!< Device operating range: 2.7V to 3.6V */
#define FLASH_VOLTAGE_RANGE_4 ((uint32_t)0x03U) /*!< Device operating range: 2.7V to 3.6V + External Vpp */
/**
* @}
*/
/** @defgroup FLASHEx_WRP_State FLASH WRP State
* @{
*/
#define OB_WRPSTATE_DISABLE ((uint32_t)0x00U) /*!< Disable the write protection of the desired bank 1 sectors */
#define OB_WRPSTATE_ENABLE ((uint32_t)0x01U) /*!< Enable the write protection of the desired bank 1 sectors */
/**
* @}
*/
/** @defgroup FLASHEx_Option_Type FLASH Option Type
* @{
*/
#define OPTIONBYTE_WRP ((uint32_t)0x01U) /*!< WRP option byte configuration */
#define OPTIONBYTE_RDP ((uint32_t)0x02U) /*!< RDP option byte configuration */
#define OPTIONBYTE_USER ((uint32_t)0x04U) /*!< USER option byte configuration */
#define OPTIONBYTE_BOR ((uint32_t)0x08U) /*!< BOR option byte configuration */
#define OPTIONBYTE_BOOTADDR_0 ((uint32_t)0x10U) /*!< Boot 0 Address configuration */
#define OPTIONBYTE_BOOTADDR_1 ((uint32_t)0x20U) /*!< Boot 1 Address configuration */
#if defined (FLASH_OPTCR2_PCROP)
#define OPTIONBYTE_PCROP ((uint32_t)0x40U) /*!< PCROP configuration */
#define OPTIONBYTE_PCROP_RDP ((uint32_t)0x80U) /*!< PCROP_RDP configuration */
#endif /* FLASH_OPTCR2_PCROP */
/**
* @}
*/
/** @defgroup FLASHEx_Option_Bytes_Read_Protection FLASH Option Bytes Read Protection
* @{
*/
#define OB_RDP_LEVEL_0 ((uint8_t)0xAAU)
#define OB_RDP_LEVEL_1 ((uint8_t)0x55U)
#define OB_RDP_LEVEL_2 ((uint8_t)0xCCU) /*!< Warning: When enabling read protection level 2
it s no more possible to go back to level 1 or 0 */
/**
* @}
*/
/** @defgroup FLASHEx_Option_Bytes_WWatchdog FLASH Option Bytes WWatchdog
* @{
*/
#define OB_WWDG_SW ((uint32_t)0x10U) /*!< Software WWDG selected */
#define OB_WWDG_HW ((uint32_t)0x00U) /*!< Hardware WWDG selected */
/**
* @}
*/
/** @defgroup FLASHEx_Option_Bytes_IWatchdog FLASH Option Bytes IWatchdog
* @{
*/
#define OB_IWDG_SW ((uint32_t)0x20U) /*!< Software IWDG selected */
#define OB_IWDG_HW ((uint32_t)0x00U) /*!< Hardware IWDG selected */
/**
* @}
*/
/** @defgroup FLASHEx_Option_Bytes_nRST_STOP FLASH Option Bytes nRST_STOP
* @{
*/
#define OB_STOP_NO_RST ((uint32_t)0x40U) /*!< No reset generated when entering in STOP */
#define OB_STOP_RST ((uint32_t)0x00U) /*!< Reset generated when entering in STOP */
/**
* @}
*/
/** @defgroup FLASHEx_Option_Bytes_nRST_STDBY FLASH Option Bytes nRST_STDBY
* @{
*/
#define OB_STDBY_NO_RST ((uint32_t)0x80U) /*!< No reset generated when entering in STANDBY */
#define OB_STDBY_RST ((uint32_t)0x00U) /*!< Reset generated when entering in STANDBY */
/**
* @}
*/
/** @defgroup FLASHEx_Option_Bytes_IWDG_FREEZE_STOP FLASH IWDG Counter Freeze in STOP
* @{
*/
#define OB_IWDG_STOP_FREEZE ((uint32_t)0x00000000U) /*!< Freeze IWDG counter in STOP mode */
#define OB_IWDG_STOP_ACTIVE ((uint32_t)0x80000000U) /*!< IWDG counter active in STOP mode */
/**
* @}
*/
/** @defgroup FLASHEx_Option_Bytes_IWDG_FREEZE_SANDBY FLASH IWDG Counter Freeze in STANDBY
* @{
*/
#define OB_IWDG_STDBY_FREEZE ((uint32_t)0x00000000U) /*!< Freeze IWDG counter in STANDBY mode */
#define OB_IWDG_STDBY_ACTIVE ((uint32_t)0x40000000U) /*!< IWDG counter active in STANDBY mode */
/**
* @}
*/
/** @defgroup FLASHEx_BOR_Reset_Level FLASH BOR Reset Level
* @{
*/
#define OB_BOR_LEVEL3 ((uint32_t)0x00U) /*!< Supply voltage ranges from 2.70 to 3.60 V */
#define OB_BOR_LEVEL2 ((uint32_t)0x04U) /*!< Supply voltage ranges from 2.40 to 2.70 V */
#define OB_BOR_LEVEL1 ((uint32_t)0x08U) /*!< Supply voltage ranges from 2.10 to 2.40 V */
#define OB_BOR_OFF ((uint32_t)0x0CU) /*!< Supply voltage ranges from 1.62 to 2.10 V */
/**
* @}
*/
#if defined (FLASH_OPTCR_nDBOOT)
/** @defgroup FLASHEx_Option_Bytes_nDBOOT FLASH Option Bytes nDBOOT
* @{
*/
#define OB_DUAL_BOOT_DISABLE ((uint32_t)0x10000000U) /* !< Dual Boot disable. Boot according to boot address option */
#define OB_DUAL_BOOT_ENABLE ((uint32_t)0x00000000U) /* !< Dual Boot enable. Boot always from system memory if boot address in flash
(Dual bank Boot mode), or RAM if Boot address option in RAM */
/**
* @}
*/
#endif /* FLASH_OPTCR_nDBOOT */
#if defined (FLASH_OPTCR_nDBANK)
/** @defgroup FLASHEx_Option_Bytes_nDBank FLASH Single Bank or Dual Bank
* @{
*/
#define OB_NDBANK_SINGLE_BANK ((uint32_t)0x20000000U) /*!< NDBANK bit is set : Single Bank mode */
#define OB_NDBANK_DUAL_BANK ((uint32_t)0x00000000U) /*!< NDBANK bit is reset : Dual Bank mode */
/**
* @}
*/
#endif /* FLASH_OPTCR_nDBANK */
/** @defgroup FLASHEx_Boot_Address FLASH Boot Address
* @{
*/
#define OB_BOOTADDR_ITCM_RAM ((uint32_t)0x0000U) /*!< Boot from ITCM RAM (0x00000000) */
#define OB_BOOTADDR_SYSTEM ((uint32_t)0x0040U) /*!< Boot from System memory bootloader (0x00100000) */
#define OB_BOOTADDR_ITCM_FLASH ((uint32_t)0x0080U) /*!< Boot from Flash on ITCM interface (0x00200000) */
#define OB_BOOTADDR_AXIM_FLASH ((uint32_t)0x2000U) /*!< Boot from Flash on AXIM interface (0x08000000) */
#define OB_BOOTADDR_DTCM_RAM ((uint32_t)0x8000U) /*!< Boot from DTCM RAM (0x20000000) */
#define OB_BOOTADDR_SRAM1 ((uint32_t)0x8004U) /*!< Boot from SRAM1 (0x20010000) */
#if (SRAM2_BASE == 0x2003C000U)
#define OB_BOOTADDR_SRAM2 ((uint32_t)0x800FU) /*!< Boot from SRAM2 (0x2003C000) */
#else
#define OB_BOOTADDR_SRAM2 ((uint32_t)0x8013U) /*!< Boot from SRAM2 (0x2004C000) */
#endif /* SRAM2_BASE == 0x2003C000U */
/**
* @}
*/
/** @defgroup FLASH_Latency FLASH Latency
* @{
*/
#define FLASH_LATENCY_0 FLASH_ACR_LATENCY_0WS /*!< FLASH Zero Latency cycle */
#define FLASH_LATENCY_1 FLASH_ACR_LATENCY_1WS /*!< FLASH One Latency cycle */
#define FLASH_LATENCY_2 FLASH_ACR_LATENCY_2WS /*!< FLASH Two Latency cycles */
#define FLASH_LATENCY_3 FLASH_ACR_LATENCY_3WS /*!< FLASH Three Latency cycles */
#define FLASH_LATENCY_4 FLASH_ACR_LATENCY_4WS /*!< FLASH Four Latency cycles */
#define FLASH_LATENCY_5 FLASH_ACR_LATENCY_5WS /*!< FLASH Five Latency cycles */
#define FLASH_LATENCY_6 FLASH_ACR_LATENCY_6WS /*!< FLASH Six Latency cycles */
#define FLASH_LATENCY_7 FLASH_ACR_LATENCY_7WS /*!< FLASH Seven Latency cycles */
#define FLASH_LATENCY_8 FLASH_ACR_LATENCY_8WS /*!< FLASH Eight Latency cycles */
#define FLASH_LATENCY_9 FLASH_ACR_LATENCY_9WS /*!< FLASH Nine Latency cycles */
#define FLASH_LATENCY_10 FLASH_ACR_LATENCY_10WS /*!< FLASH Ten Latency cycles */
#define FLASH_LATENCY_11 FLASH_ACR_LATENCY_11WS /*!< FLASH Eleven Latency cycles */
#define FLASH_LATENCY_12 FLASH_ACR_LATENCY_12WS /*!< FLASH Twelve Latency cycles */
#define FLASH_LATENCY_13 FLASH_ACR_LATENCY_13WS /*!< FLASH Thirteen Latency cycles */
#define FLASH_LATENCY_14 FLASH_ACR_LATENCY_14WS /*!< FLASH Fourteen Latency cycles */
#define FLASH_LATENCY_15 FLASH_ACR_LATENCY_15WS /*!< FLASH Fifteen Latency cycles */
/**
* @}
*/
#if defined (FLASH_OPTCR_nDBANK)
/** @defgroup FLASHEx_Banks FLASH Banks
* @{
*/
#define FLASH_BANK_1 ((uint32_t)0x01U) /*!< Bank 1 */
#define FLASH_BANK_2 ((uint32_t)0x02U) /*!< Bank 2 */
#define FLASH_BANK_BOTH ((uint32_t)(FLASH_BANK_1 | FLASH_BANK_2)) /*!< Bank1 and Bank2 */
/**
* @}
*/
#endif /* FLASH_OPTCR_nDBANK */
/** @defgroup FLASHEx_MassErase_bit FLASH Mass Erase bit
* @{
*/
#if defined (FLASH_OPTCR_nDBANK)
#define FLASH_MER_BIT (FLASH_CR_MER1 | FLASH_CR_MER2) /*!< 2 MER bits */
#else
#define FLASH_MER_BIT (FLASH_CR_MER) /*!< only 1 MER bit */
#endif /* FLASH_OPTCR_nDBANK */
/**
* @}
*/
/** @defgroup FLASHEx_Sectors FLASH Sectors
* @{
*/
#if (FLASH_SECTOR_TOTAL == 24)
#define FLASH_SECTOR_8 ((uint32_t)8U) /*!< Sector Number 8 */
#define FLASH_SECTOR_9 ((uint32_t)9U) /*!< Sector Number 9 */
#define FLASH_SECTOR_10 ((uint32_t)10U) /*!< Sector Number 10 */
#define FLASH_SECTOR_11 ((uint32_t)11U) /*!< Sector Number 11 */
#define FLASH_SECTOR_12 ((uint32_t)12U) /*!< Sector Number 12 */
#define FLASH_SECTOR_13 ((uint32_t)13U) /*!< Sector Number 13 */
#define FLASH_SECTOR_14 ((uint32_t)14U) /*!< Sector Number 14 */
#define FLASH_SECTOR_15 ((uint32_t)15U) /*!< Sector Number 15 */
#define FLASH_SECTOR_16 ((uint32_t)16U) /*!< Sector Number 16 */
#define FLASH_SECTOR_17 ((uint32_t)17U) /*!< Sector Number 17 */
#define FLASH_SECTOR_18 ((uint32_t)18U) /*!< Sector Number 18 */
#define FLASH_SECTOR_19 ((uint32_t)19U) /*!< Sector Number 19 */
#define FLASH_SECTOR_20 ((uint32_t)20U) /*!< Sector Number 20 */
#define FLASH_SECTOR_21 ((uint32_t)21U) /*!< Sector Number 21 */
#define FLASH_SECTOR_22 ((uint32_t)22U) /*!< Sector Number 22 */
#define FLASH_SECTOR_23 ((uint32_t)23U) /*!< Sector Number 23 */
#endif /* FLASH_SECTOR_TOTAL == 24 */
/**
* @}
*/
#if (FLASH_SECTOR_TOTAL == 24)
/** @defgroup FLASHEx_Option_Bytes_Write_Protection FLASH Option Bytes Write Protection
* @note For Single Bank mode, use OB_WRP_SECTOR_x defines: In fact, in FLASH_OPTCR register,
* nWRP[11:0] bits contain the value of the write-protection option bytes for sectors 0 to 11.
* For Dual Bank mode, use OB_WRP_DB_SECTOR_x defines: In fact, in FLASH_OPTCR register,
* nWRP[11:0] bits are divided on two groups, one group dedicated for bank 1 and
* a second one dedicated for bank 2 (nWRP[i] activates Write protection on sector 2*i and 2*i+1).
* This behavior is applicable only for STM32F76xxx / STM32F77xxx devices.
* @{
*/
/* Single Bank Sectors */
#define OB_WRP_SECTOR_0 ((uint32_t)0x00010000U) /*!< Write protection of Single Bank Sector0 */
#define OB_WRP_SECTOR_1 ((uint32_t)0x00020000U) /*!< Write protection of Single Bank Sector1 */
#define OB_WRP_SECTOR_2 ((uint32_t)0x00040000U) /*!< Write protection of Single Bank Sector2 */
#define OB_WRP_SECTOR_3 ((uint32_t)0x00080000U) /*!< Write protection of Single Bank Sector3 */
#define OB_WRP_SECTOR_4 ((uint32_t)0x00100000U) /*!< Write protection of Single Bank Sector4 */
#define OB_WRP_SECTOR_5 ((uint32_t)0x00200000U) /*!< Write protection of Single Bank Sector5 */
#define OB_WRP_SECTOR_6 ((uint32_t)0x00400000U) /*!< Write protection of Single Bank Sector6 */
#define OB_WRP_SECTOR_7 ((uint32_t)0x00800000U) /*!< Write protection of Single Bank Sector7 */
#define OB_WRP_SECTOR_8 ((uint32_t)0x01000000U) /*!< Write protection of Single Bank Sector8 */
#define OB_WRP_SECTOR_9 ((uint32_t)0x02000000U) /*!< Write protection of Single Bank Sector9 */
#define OB_WRP_SECTOR_10 ((uint32_t)0x04000000U) /*!< Write protection of Single Bank Sector10 */
#define OB_WRP_SECTOR_11 ((uint32_t)0x08000000U) /*!< Write protection of Single Bank Sector11 */
#define OB_WRP_SECTOR_All ((uint32_t)0x0FFF0000U) /*!< Write protection of all Sectors for Single Bank Flash */
/* Dual Bank Sectors */
#define OB_WRP_DB_SECTOR_0 ((uint32_t)0x00010000U) /*!< Write protection of Dual Bank Sector0 */
#define OB_WRP_DB_SECTOR_1 ((uint32_t)0x00010000U) /*!< Write protection of Dual Bank Sector1 */
#define OB_WRP_DB_SECTOR_2 ((uint32_t)0x00020000U) /*!< Write protection of Dual Bank Sector2 */
#define OB_WRP_DB_SECTOR_3 ((uint32_t)0x00020000U) /*!< Write protection of Dual Bank Sector3 */
#define OB_WRP_DB_SECTOR_4 ((uint32_t)0x00040000U) /*!< Write protection of Dual Bank Sector4 */
#define OB_WRP_DB_SECTOR_5 ((uint32_t)0x00040000U) /*!< Write protection of Dual Bank Sector5 */
#define OB_WRP_DB_SECTOR_6 ((uint32_t)0x00080000U) /*!< Write protection of Dual Bank Sector6 */
#define OB_WRP_DB_SECTOR_7 ((uint32_t)0x00080000U) /*!< Write protection of Dual Bank Sector7 */
#define OB_WRP_DB_SECTOR_8 ((uint32_t)0x00100000U) /*!< Write protection of Dual Bank Sector8 */
#define OB_WRP_DB_SECTOR_9 ((uint32_t)0x00100000U) /*!< Write protection of Dual Bank Sector9 */
#define OB_WRP_DB_SECTOR_10 ((uint32_t)0x00200000U) /*!< Write protection of Dual Bank Sector10 */
#define OB_WRP_DB_SECTOR_11 ((uint32_t)0x00200000U) /*!< Write protection of Dual Bank Sector11 */
#define OB_WRP_DB_SECTOR_12 ((uint32_t)0x00400000U) /*!< Write protection of Dual Bank Sector12 */
#define OB_WRP_DB_SECTOR_13 ((uint32_t)0x00400000U) /*!< Write protection of Dual Bank Sector13 */
#define OB_WRP_DB_SECTOR_14 ((uint32_t)0x00800000U) /*!< Write protection of Dual Bank Sector14 */
#define OB_WRP_DB_SECTOR_15 ((uint32_t)0x00800000U) /*!< Write protection of Dual Bank Sector15 */
#define OB_WRP_DB_SECTOR_16 ((uint32_t)0x01000000U) /*!< Write protection of Dual Bank Sector16 */
#define OB_WRP_DB_SECTOR_17 ((uint32_t)0x01000000U) /*!< Write protection of Dual Bank Sector17 */
#define OB_WRP_DB_SECTOR_18 ((uint32_t)0x02000000U) /*!< Write protection of Dual Bank Sector18 */
#define OB_WRP_DB_SECTOR_19 ((uint32_t)0x02000000U) /*!< Write protection of Dual Bank Sector19 */
#define OB_WRP_DB_SECTOR_20 ((uint32_t)0x04000000U) /*!< Write protection of Dual Bank Sector20 */
#define OB_WRP_DB_SECTOR_21 ((uint32_t)0x04000000U) /*!< Write protection of Dual Bank Sector21 */
#define OB_WRP_DB_SECTOR_22 ((uint32_t)0x08000000U) /*!< Write protection of Dual Bank Sector22 */
#define OB_WRP_DB_SECTOR_23 ((uint32_t)0x08000000U) /*!< Write protection of Dual Bank Sector23 */
#define OB_WRP_DB_SECTOR_All ((uint32_t)0x0FFF0000U) /*!< Write protection of all Sectors for Dual Bank Flash */
/**
* @}
*/
#endif /* FLASH_SECTOR_TOTAL == 24 */
#if (FLASH_SECTOR_TOTAL == 8)
/** @defgroup FLASHEx_Option_Bytes_Write_Protection FLASH Option Bytes Write Protection
* @{
*/
#define OB_WRP_SECTOR_0 ((uint32_t)0x00010000U) /*!< Write protection of Sector0 */
#define OB_WRP_SECTOR_1 ((uint32_t)0x00020000U) /*!< Write protection of Sector1 */
#define OB_WRP_SECTOR_2 ((uint32_t)0x00040000U) /*!< Write protection of Sector2 */
#define OB_WRP_SECTOR_3 ((uint32_t)0x00080000U) /*!< Write protection of Sector3 */
#define OB_WRP_SECTOR_4 ((uint32_t)0x00100000U) /*!< Write protection of Sector4 */
#define OB_WRP_SECTOR_5 ((uint32_t)0x00200000U) /*!< Write protection of Sector5 */
#define OB_WRP_SECTOR_6 ((uint32_t)0x00400000U) /*!< Write protection of Sector6 */
#define OB_WRP_SECTOR_7 ((uint32_t)0x00800000U) /*!< Write protection of Sector7 */
#define OB_WRP_SECTOR_All ((uint32_t)0x00FF0000U) /*!< Write protection of all Sectors */
/**
* @}
*/
#endif /* FLASH_SECTOR_TOTAL == 8 */
#if defined (FLASH_OPTCR2_PCROP)
/** @defgroup FLASHEx_Option_Bytes_PCROP_Sectors FLASH Option Bytes PCROP Sectors
* @{
*/
#define OB_PCROP_SECTOR_0 ((uint32_t)0x00000001U) /*!< PC Readout protection of Sector0 */
#define OB_PCROP_SECTOR_1 ((uint32_t)0x00000002U) /*!< PC Readout protection of Sector1 */
#define OB_PCROP_SECTOR_2 ((uint32_t)0x00000004U) /*!< PC Readout protection of Sector2 */
#define OB_PCROP_SECTOR_3 ((uint32_t)0x00000008U) /*!< PC Readout protection of Sector3 */
#define OB_PCROP_SECTOR_4 ((uint32_t)0x00000010U) /*!< PC Readout protection of Sector4 */
#define OB_PCROP_SECTOR_5 ((uint32_t)0x00000020U) /*!< PC Readout protection of Sector5 */
#define OB_PCROP_SECTOR_6 ((uint32_t)0x00000040U) /*!< PC Readout protection of Sector6 */
#define OB_PCROP_SECTOR_7 ((uint32_t)0x00000080U) /*!< PC Readout protection of Sector7 */
#define OB_PCROP_SECTOR_All ((uint32_t)0x000000FFU) /*!< PC Readout protection of all Sectors */
/**
* @}
*/
/** @defgroup FLASHEx_Option_Bytes_PCROP_RDP FLASH Option Bytes PCROP_RDP Bit
* @{
*/
#define OB_PCROP_RDP_ENABLE ((uint32_t)0x80000000U) /*!< PCROP_RDP Enable */
#define OB_PCROP_RDP_DISABLE ((uint32_t)0x00000000U) /*!< PCROP_RDP Disable */
/**
* @}
*/
#endif /* FLASH_OPTCR2_PCROP */
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/** @defgroup FLASH_Exported_Macros FLASH Exported Macros
* @{
*/
/**
* @brief Calculate the FLASH Boot Base Adress (BOOT_ADD0 or BOOT_ADD1)
* @note Returned value BOOT_ADDx[15:0] corresponds to boot address [29:14].
* @param __ADDRESS__: FLASH Boot Address (in the range 0x0000 0000 to 0x2004 FFFF with a granularity of 16KB)
* @retval The FLASH Boot Base Adress
*/
#define __HAL_FLASH_CALC_BOOT_BASE_ADR(__ADDRESS__) ((__ADDRESS__) >> 14)
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/** @addtogroup FLASHEx_Exported_Functions
* @{
*/
/** @addtogroup FLASHEx_Exported_Functions_Group1
* @{
*/
/* Extension Program operation functions *************************************/
HAL_StatusTypeDef HAL_FLASHEx_Erase(FLASH_EraseInitTypeDef *pEraseInit, uint32_t *SectorError);
HAL_StatusTypeDef HAL_FLASHEx_Erase_IT(FLASH_EraseInitTypeDef *pEraseInit);
HAL_StatusTypeDef HAL_FLASHEx_OBProgram(FLASH_OBProgramInitTypeDef *pOBInit);
void HAL_FLASHEx_OBGetConfig(FLASH_OBProgramInitTypeDef *pOBInit);
/**
* @}
*/
/**
* @}
*/
/* Private types -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private constants ---------------------------------------------------------*/
/* Private macros ------------------------------------------------------------*/
/** @defgroup FLASHEx_Private_Macros FLASH Private Macros
* @{
*/
/** @defgroup FLASHEx_IS_FLASH_Definitions FLASH Private macros to check input parameters
* @{
*/
#define IS_FLASH_TYPEERASE(VALUE)(((VALUE) == FLASH_TYPEERASE_SECTORS) || \
((VALUE) == FLASH_TYPEERASE_MASSERASE))
#define IS_VOLTAGERANGE(RANGE)(((RANGE) == FLASH_VOLTAGE_RANGE_1) || \
((RANGE) == FLASH_VOLTAGE_RANGE_2) || \
((RANGE) == FLASH_VOLTAGE_RANGE_3) || \
((RANGE) == FLASH_VOLTAGE_RANGE_4))
#define IS_WRPSTATE(VALUE)(((VALUE) == OB_WRPSTATE_DISABLE) || \
((VALUE) == OB_WRPSTATE_ENABLE))
#if defined (FLASH_OPTCR2_PCROP)
#define IS_OPTIONBYTE(VALUE)(((VALUE) <= (OPTIONBYTE_WRP | OPTIONBYTE_RDP | OPTIONBYTE_USER |\
OPTIONBYTE_BOR | OPTIONBYTE_BOOTADDR_0 | OPTIONBYTE_BOOTADDR_1 |\
OPTIONBYTE_PCROP | OPTIONBYTE_PCROP_RDP)))
#else
#define IS_OPTIONBYTE(VALUE)(((VALUE) <= (OPTIONBYTE_WRP | OPTIONBYTE_RDP | OPTIONBYTE_USER |\
OPTIONBYTE_BOR | OPTIONBYTE_BOOTADDR_0 | OPTIONBYTE_BOOTADDR_1)))
#endif /* FLASH_OPTCR2_PCROP */
#define IS_OB_BOOT_ADDRESS(ADDRESS) ((ADDRESS) <= 0x8013)
#define IS_OB_RDP_LEVEL(LEVEL) (((LEVEL) == OB_RDP_LEVEL_0) ||\
((LEVEL) == OB_RDP_LEVEL_1) ||\
((LEVEL) == OB_RDP_LEVEL_2))
#define IS_OB_WWDG_SOURCE(SOURCE) (((SOURCE) == OB_WWDG_SW) || ((SOURCE) == OB_WWDG_HW))
#define IS_OB_IWDG_SOURCE(SOURCE) (((SOURCE) == OB_IWDG_SW) || ((SOURCE) == OB_IWDG_HW))
#define IS_OB_STOP_SOURCE(SOURCE) (((SOURCE) == OB_STOP_NO_RST) || ((SOURCE) == OB_STOP_RST))
#define IS_OB_STDBY_SOURCE(SOURCE) (((SOURCE) == OB_STDBY_NO_RST) || ((SOURCE) == OB_STDBY_RST))
#define IS_OB_IWDG_STOP_FREEZE(FREEZE) (((FREEZE) == OB_IWDG_STOP_FREEZE) || ((FREEZE) == OB_IWDG_STOP_ACTIVE))
#define IS_OB_IWDG_STDBY_FREEZE(FREEZE) (((FREEZE) == OB_IWDG_STDBY_FREEZE) || ((FREEZE) == OB_IWDG_STDBY_ACTIVE))
#define IS_OB_BOR_LEVEL(LEVEL) (((LEVEL) == OB_BOR_LEVEL1) || ((LEVEL) == OB_BOR_LEVEL2) ||\
((LEVEL) == OB_BOR_LEVEL3) || ((LEVEL) == OB_BOR_OFF))
#define IS_FLASH_LATENCY(LATENCY) (((LATENCY) == FLASH_LATENCY_0) || \
((LATENCY) == FLASH_LATENCY_1) || \
((LATENCY) == FLASH_LATENCY_2) || \
((LATENCY) == FLASH_LATENCY_3) || \
((LATENCY) == FLASH_LATENCY_4) || \
((LATENCY) == FLASH_LATENCY_5) || \
((LATENCY) == FLASH_LATENCY_6) || \
((LATENCY) == FLASH_LATENCY_7) || \
((LATENCY) == FLASH_LATENCY_8) || \
((LATENCY) == FLASH_LATENCY_9) || \
((LATENCY) == FLASH_LATENCY_10) || \
((LATENCY) == FLASH_LATENCY_11) || \
((LATENCY) == FLASH_LATENCY_12) || \
((LATENCY) == FLASH_LATENCY_13) || \
((LATENCY) == FLASH_LATENCY_14) || \
((LATENCY) == FLASH_LATENCY_15))
#define IS_FLASH_ADDRESS(ADDRESS) ((((ADDRESS) >= FLASH_BASE) && ((ADDRESS) <= FLASH_END)) || \
(((ADDRESS) >= FLASH_OTP_BASE) && ((ADDRESS) <= FLASH_OTP_END)))
#define IS_FLASH_NBSECTORS(NBSECTORS) (((NBSECTORS) != 0U) && ((NBSECTORS) <= FLASH_SECTOR_TOTAL))
#if (FLASH_SECTOR_TOTAL == 8)
#define IS_FLASH_SECTOR(SECTOR) (((SECTOR) == FLASH_SECTOR_0) || ((SECTOR) == FLASH_SECTOR_1) ||\
((SECTOR) == FLASH_SECTOR_2) || ((SECTOR) == FLASH_SECTOR_3) ||\
((SECTOR) == FLASH_SECTOR_4) || ((SECTOR) == FLASH_SECTOR_5) ||\
((SECTOR) == FLASH_SECTOR_6) || ((SECTOR) == FLASH_SECTOR_7))
#define IS_OB_WRP_SECTOR(SECTOR) ((((SECTOR) & 0xFF00FFFFU) == 0x00000000U) && ((SECTOR) != 0x00000000U))
#endif /* FLASH_SECTOR_TOTAL == 8 */
#if (FLASH_SECTOR_TOTAL == 24)
#define IS_FLASH_SECTOR(SECTOR) (((SECTOR) == FLASH_SECTOR_0) || ((SECTOR) == FLASH_SECTOR_1) ||\
((SECTOR) == FLASH_SECTOR_2) || ((SECTOR) == FLASH_SECTOR_3) ||\
((SECTOR) == FLASH_SECTOR_4) || ((SECTOR) == FLASH_SECTOR_5) ||\
((SECTOR) == FLASH_SECTOR_6) || ((SECTOR) == FLASH_SECTOR_7) ||\
((SECTOR) == FLASH_SECTOR_8) || ((SECTOR) == FLASH_SECTOR_9) ||\
((SECTOR) == FLASH_SECTOR_10) || ((SECTOR) == FLASH_SECTOR_11) ||\
((SECTOR) == FLASH_SECTOR_12) || ((SECTOR) == FLASH_SECTOR_13) ||\
((SECTOR) == FLASH_SECTOR_14) || ((SECTOR) == FLASH_SECTOR_15) ||\
((SECTOR) == FLASH_SECTOR_16) || ((SECTOR) == FLASH_SECTOR_17) ||\
((SECTOR) == FLASH_SECTOR_18) || ((SECTOR) == FLASH_SECTOR_19) ||\
((SECTOR) == FLASH_SECTOR_20) || ((SECTOR) == FLASH_SECTOR_21) ||\
((SECTOR) == FLASH_SECTOR_22) || ((SECTOR) == FLASH_SECTOR_23))
#define IS_OB_WRP_SECTOR(SECTOR) ((((SECTOR) & 0xF000FFFFU) == 0x00000000U) && ((SECTOR) != 0x00000000U))
#endif /* FLASH_SECTOR_TOTAL == 24 */
#if defined (FLASH_OPTCR_nDBANK)
#define IS_OB_NDBANK(VALUE) (((VALUE) == OB_NDBANK_SINGLE_BANK) || \
((VALUE) == OB_NDBANK_DUAL_BANK))
#define IS_FLASH_BANK(BANK) (((BANK) == FLASH_BANK_1) || \
((BANK) == FLASH_BANK_2) || \
((BANK) == FLASH_BANK_BOTH))
#endif /* FLASH_OPTCR_nDBANK */
#if defined (FLASH_OPTCR_nDBOOT)
#define IS_OB_NDBOOT(VALUE) (((VALUE) == OB_DUAL_BOOT_DISABLE) || \
((VALUE) == OB_DUAL_BOOT_ENABLE))
#endif /* FLASH_OPTCR_nDBOOT */
#if defined (FLASH_OPTCR2_PCROP)
#define IS_OB_PCROP_SECTOR(SECTOR) (((SECTOR) & (uint32_t)0xFFFFFF00U) == 0x00000000U)
#define IS_OB_PCROP_RDP_VALUE(VALUE) (((VALUE) == OB_PCROP_RDP_DISABLE) || \
((VALUE) == OB_PCROP_RDP_ENABLE))
#endif /* FLASH_OPTCR2_PCROP */
/**
* @}
*/
/**
* @}
*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup FLASHEx_Private_Functions FLASH Private Functions
* @{
*/
void FLASH_Erase_Sector(uint32_t Sector, uint8_t VoltageRange);
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __STM32F7xx_HAL_FLASH_EX_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -63,7 +63,7 @@ enable2ndByteCanID = false
; see PAGE_0_SIZE in C source code
; CONFIG_DEFINITION_START
; this section was generated automatically by ConfigDefinition.jar based on rusefi_config.txt Tue Oct 30 04:58:47 EDT 2018
; this section was generated automatically by ConfigDefinition.jar based on rusefi_config.txt Sat Nov 10 20:59:11 EST 2018
pageSize = 20000
page = 1
@ -2383,6 +2383,7 @@ cmd_stop_engine = "w\x00\x99\x00\x00"
field = "SPI3 SCK", spi3sckPin, {is_enabled_spi_3 == 1}
field = "hip9011CsPin", hip9011CsPin
field = "LIS302DLCsPin", LIS302DLCsPin
field = "Malfunction Indicator", malfunctionIndicatorPin
dialog = allPins1_2, "", xAxis

View File

@ -1534,6 +1534,7 @@ cmd_stop_engine = "w\x00\x99\x00\x00"
field = "SPI3 SCK", spi3sckPin, {is_enabled_spi_3 == 1}
field = "hip9011CsPin", hip9011CsPin
field = "LIS302DLCsPin", LIS302DLCsPin
field = "Malfunction Indicator", malfunctionIndicatorPin
dialog = allPins1_2, "", xAxis

Binary file not shown.

After

Width:  |  Height:  |  Size: 945 KiB

Binary file not shown.