diff options
author | Damien George <damien.p.george@gmail.com> | 2017-08-13 21:33:40 +1000 |
---|---|---|
committer | Damien George <damien.p.george@gmail.com> | 2017-08-13 21:33:40 +1000 |
commit | e52758da223e57b6cd9458f039f8ccc50ee76ddb (patch) | |
tree | 2d5218ad0e1f30c686f51f5807b5676fe0007fe5 /stmhal/boards | |
parent | be2387885bf251fb44b6b64aeadff147a4ae7266 (diff) | |
parent | 9b39263b118a4be65c58bf9c396203fa535bebe1 (diff) | |
download | micropython-e52758da223e57b6cd9458f039f8ccc50ee76ddb.tar.gz micropython-e52758da223e57b6cd9458f039f8ccc50ee76ddb.zip |
Merge tag 'v1.8.1' into parse-bytecode
Many ESP8266 improvements, enhanced WebREPL, and support for STM32L4 MCUs
This release brings general improvements and bug fixes, and some new
features. There is now a uerror module for consistent errno handling
across ports, as well as textual names of OS errors that are printed when
an OSError is raised. There is support for frozen packages, via both
frozen scripts and frozen bytecode. WebREPL on the ESP8266 is greatly
improved with many bug fixes and now supports an unlimited (or very large)
number of reconnects. The os module on the ESP8266 now has rename, chdir,
getcwd and stat. The unix port now includes the ussl module by default.
The stmhal port has support for STM32L4 MCUs including the STM32L476
Discovery board and the LimiFrog board.
README:
- add explicit note that subdirs contain more READMEs
- add "make deplibs" to quick build section
- "quick build": Use "make axtls" after all
CODECONVENTIONS.md:
- describe git commit messages conventions
py core:
- obj: add warning note about get_array return value and GC blocks
- objstr: binary type of str/bytes for buffer protocol is 'B'
- runtime: properly handle passing user mappings to ** keyword args
- repl: if there're no better alternatives, try to complete "import"
- mpz: fix bug with overflowing C-shift in division routine
- mpz: do Python style division/modulo within bignum divmod routine
- mpz: fix mpn_div so that it doesn't modify memory of denominator
- vstr: vstr_null_terminated_str(): Extend string by at most one byte
- vstr: change allocation policy, +16 to requested size, instead of *2
- add mperrno.h file with uPy defined errno constants
- add uerrno module, with errno constants and dict
- parse: add uerrno to list of modules to look for constants in
- mperrno: add EAFNOSUPPORT definition
- repl: fix handling of backslash in quotes when checking continuation
- gc: gc_dump_alloc_table(): Show byte/str and (byte)array objects
- gc: make (byte)array type dumping conditional on these types being enabled
- gc: use '=' char for tail blocks when dumping heap
- mperrno: add some more MP_Exxx constants, related to networking
- moduerrno: add more constants to the errno module
- add mp_errno_to_str() and use it to provide nicer OSError msgs
- objfloat, py/modmath: ensure M_PI and M_E defined
- emitglue: fix build on AArch64 (ARMv8, etc.) related to loading .mpy files
- objexcept: don't convert errno to str in constructor, do it in print
- moduerrno: add EACCES, pretty common error on Unix
- gc: gc_dump_alloc_table(): dump heap offset instead of actual address
- objstr: make dedicated splitlines function, supporting diff newlines
- objstringio: add TODO comment about avoiding copying on .getvalue()
- modstruct: raise ValueError on unsupported format char
- stream: support both "exact size" and "one underlying call" operations
- declare constant data as properly constant
- stream: add mp_stream_close() helper function
- mphal.h: provide default prototypes for mp_hal_delay_us/mp_hal_ticks_us
- rework frozen modules support to support packages
- objstr: implement str.center()
- allow to stat and import frozen mpy files using new frozen "VFS"
- makeqstrdata.py: allow to have double-quote characters in qstrs
- objnamedtuple: allow passing field names as a tuple
- moduerrno: add EEXIST, EISDIR, ECONNREFUSED
- modstruct: allow to have "0s" in struct format
extmod:
- modlwip: convert errno's to use MP_Exxx symbols
- modlwip: rework how Python accept callback is called
- when including extmod headers, prefix path with extmod/
- modwebsocket: add close() method
- modwebrepl: add close() method
- moduos_dupterm: dumpterm subsystem is responsible for closing stream
- modussl: make more compatible with non-default obj representations
- machine_i2c: redo mp_hal_pin macros to use open_drain and od_low
- virtpin: initial implementation of open-ended C-level Pin interface
- vfs_fat: replace text error messages by POSIX error numbers
- vfs_fat: add chdir() method
- vfs_fat: add getcwd() method
- vfs_fat: add vfs.stat() method
- add machine time_pulse_us function (at C and Python level)
- machine: add MICROPY_PY_MACHINE_PULSE config for time_pulse_us
lib:
- timeutils/timeutils: timeutils_mktime may accept negative time values
drivers:
- cc3000: rename timeval to cc3000_timeval, to avoid clash
- add C-level function to read DHT11 and DHT22 devices
- display/ssd1306: update SSD1306_SPI to work with new API
tools:
- make-frozen.py: properly escape hex chars when making C strings
- make-frozen.py: quick fix to support package-modules
- mpy-tool.py: add checks for critical configuration vars
- make-frozen.py: update for latest changes in frozen modules support
- mpy-tool.py: include .py extension in frozen filename
- mpy-tool.py: don't strip directories from the frozen source name
- upgrade upip to 0.7: SSL cert warning, use uerrno, better usage message
tests:
- run-tests: factor out list of supported external boards
- disable memoryview tests that overflow int conversion
- basics/string_splitlines: reinstate feature test for splitlines
- struct1: add testcase for an unknown type char
- add testcase for str.center()
- extmod/vfs_fat_ramdisk: add testcases for chdir(), getcwd()
- misc/recursive_iternext.py: increase depth N from 1000 to 2000
- misc/recursive_iternext.py: provide more fine-grained selection of N
- pyb/rtc: make RTC test on pyboard more reliable by calling init()
mpy-cross:
- add -s option to specify the embedded source filename
unix port:
- mphalport: add mp_hal_delay_us() for consistency with other ports
- enable uerrno module
- add ability to include frozen bytecode in the build
- mpconfigport_coverage.h: add dedicated config file for coverage build
- unix_mphal: implement mp_hal_ticks_us()
- support frozen packages
- Makefile: nanbox build is not compatible with modussl, disable
- enable "ussl" module
- mpconfigport.mk: document MICROPY_STANDALONE make-level option
- Makefile: "make axtls": automatically fetch submodules if missing
windows port:
- enable multi-processor compilation for msvc
stmhal port:
- l4: adapt DMA to be able to support STM32L4 MCU series
- l4: adapt startup code, clock configuration and interrupts
- l4: make CCM/DTCM RAM start-up conditional on MCU type
- l4: add support for machine.sleep on STM32L4 MCUs
- dma: make DAC DMA descriptors conditional on having a DAC
- add board files for LIMIFROG board
- for LIMIFROG board, add early-init function to get to DFU mode
- dma: fix builds for boards with an F4 or F7 but no DAC
- sdcard: fix initialisation of DMA TX so that writes work
- can: allow to get existing CAN obj if constructed without args
- fix clock configuration for STM32L476-discovery; also add I2C2
- convert to use internal errno symbols; enable uerrno module
- for network drivers, convert to use MP_Exxx errno symbols
- led: allow LEDs to be in PWM mode with TIM1 and channels 1-4
- i2c: expose I2CHandle3 for use by custom C code
- sdcard: allow to do unaligned read-from/write-to SD card
- support frozen packages using .mpy files
- moduos: getcwd(): use mp_obj_new_exception_arg1()
- dac: add DAC deinit() method
- uart: fix wrong baudrate calculation for stm32l4 series
esp8266 port:
- scripts/: remove use of pin.PULL_NONE
- scripts/inisetup: don't start WebREPL on boot in master branch
- scripts/: add fill() to NeoPixel
- scripts/webrepl: add optional password argument to webrepl.start()
- scripts/webrepl: add start_foreground() method
- main: bump heap size to 28K
- mpconfigport: reduce various parser-related allocation params
- help: add "sta_if.active(True)" command
- convert to use new MP_Exxx errno symbols
- enable uerrno module, weak linked also as errno
- change to use internal errno's
- moduos.c: addition of the rename method to module uos
- scripts/port_diag: add network diagnostic output
- scripts/webrepl_setup: show password placeholder char
- scripts/webrepl_setup: add max password length check
- README: add a very first start section
- add APA102 serial individually controllable LEDs support
- enable collections.OrderedDict
- main: update _boot module loading for recent frozen modules refactors
- scripts/port_diag: dump network interface IP settings
- esp_mphal: fix NLR buffer leak in call_dupterm_read()
- esp_mphal: handle Ctrl+C from dupterm (e.g. WebREPL)
- esp_mphal: mp_uos_dupterm_deactivate() may raise exception
- add mp_hal_pin_input() and mp_hal_pin_output() functions
- modpybspi: configure pins when initialising an SPI object
- xtirq: add xtirq.h for controlling xtensa irqs
- ets_alt_task: don't run ets_loop_iter if irqs are disabled
- modmachine: add disable_irq and enable_irq functions
- enable DHT C-level driver
- add dht.py script for high-level control of DHT11/DHT22 sensor
- Makefile: document "disable" value for UART_OS
- modnetwork: scan() is only supported by STA when it's enabled
- modnetwork: protect scan() callback against memory errors
- modnetwork: allow to press ctrl-C while scan() is running
- uart: properly initialise UART0 RXD pin in uart_config
- moduos: add chdir() and getcwd() functions
- scripts/ntptime: allow to override NTP server
- modmachine: add machine.time_pulse_us function
- enable MICROPY_PY_IO_FILEIO to get compliant text/binary streams
- moduos.c: add stat() to the module uos of esp8266
- rtc: set RTC user memory length to 0 on first boot
- provide a dedicated variable to disable ets_loop_iter
- modpybrtc: handle RTC overflow
docs:
- machine.UART: filter out unimplemented UART methods from esp8266 docs
- esp8266/quickref: new way to get MAC address
- esp8266/quickstart: remove i2c examples with stop=False
- ustruct: describe supported type codes
- ussl: add basic description of axTLS-based modussl
- esp8266: Include ussl module in the docs
- machine: make disable_irq and enable_irq docs available for all
- library/machine: add documentation for machine.time_pulse_us
- math, cmath: add port availability information
- library/index: add intro paragraph regarding availability of modules
- README: add some hints for PDF docs generation
- wipy/tutorial: add note about screen key bindings on OS X
- esp8266/quickref: update WebREPL section for 1.8.1 release
- esp8266: fix ESP8266 Network tutorial
- esp8266/quickref: use local image of Adafruit Huzzah board
- esp8266/general: add note about RTC overflow
travis:
- install gcc-arm-none-eabi with --force-yes for now
Diffstat (limited to 'stmhal/boards')
-rw-r--r-- | stmhal/boards/LIMIFROG/board_init.c | 154 | ||||
-rw-r--r-- | stmhal/boards/LIMIFROG/mpconfigboard.h | 71 | ||||
-rw-r--r-- | stmhal/boards/LIMIFROG/mpconfigboard.mk | 4 | ||||
-rw-r--r-- | stmhal/boards/LIMIFROG/pins.csv | 114 | ||||
-rw-r--r-- | stmhal/boards/LIMIFROG/stm32l4xx_hal_conf.h | 373 | ||||
-rw-r--r-- | stmhal/boards/PYBLITEV10/mpconfigboard.h | 4 | ||||
-rw-r--r-- | stmhal/boards/PYBV10/mpconfigboard.h | 4 | ||||
-rw-r--r-- | stmhal/boards/PYBV11/mpconfigboard.h | 4 | ||||
-rw-r--r-- | stmhal/boards/PYBV3/mpconfigboard.h | 3 | ||||
-rw-r--r-- | stmhal/boards/PYBV4/mpconfigboard.h | 4 | ||||
-rw-r--r-- | stmhal/boards/STM32L476DISC/mpconfigboard.h | 8 | ||||
-rw-r--r-- | stmhal/boards/stm32l476xe.ld | 134 |
12 files changed, 866 insertions, 11 deletions
diff --git a/stmhal/boards/LIMIFROG/board_init.c b/stmhal/boards/LIMIFROG/board_init.c new file mode 100644 index 0000000000..72f9208424 --- /dev/null +++ b/stmhal/boards/LIMIFROG/board_init.c @@ -0,0 +1,154 @@ +// The code is this file allows the user to enter DFU mode when the board +// starts up, by connecting POS10 on the external connector to GND. +// The code itself is taken from the LimiFrog software repository found at +// https://github.com/LimiFrog/LimiFrog-SW, and the original license header +// is copied below. + +#include STM32_HAL_H + +static void LBF_DFU_If_Needed(void); + +void LIMIFROG_board_early_init(void) { + LBF_DFU_If_Needed(); +} + +/******************************************************************************* + * LBF_DFU_If_Needed.c + * + * (c)2015 LimiFrog / CYMEYA + * This program is licensed under the terms of the MIT License. + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND. + * Please refer to the License File LICENSE.txt located at the root of this + * project for full licensing conditions, + * or visit https://opensource.org/licenses/MIT. + ******************************************************************************/ + +#define __LIMIFROG_02 + +/* ==== BTLE (excl UART) ======================================== */ +// PC9 = BT_RST (active high) + +#define BT_RST_PIN GPIO_PIN_9 +#define BT_RST_PORT GPIOC + +// Position 10 +#ifdef __LIMIFROG_01 + #define CONN_POS10_PIN GPIO_PIN_9 + #define CONN_POS10_PORT GPIOB +#else + #define CONN_POS10_PIN GPIO_PIN_8 + #define CONN_POS10_PORT GPIOB +#endif + +static inline void GPIO_HIGH(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + GPIOx->BSRR = (uint32_t)GPIO_Pin; +} + +static inline int IS_GPIO_RESET(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + GPIO_PinState bitstatus; + if((GPIOx->IDR & GPIO_Pin) != (uint32_t)GPIO_PIN_RESET) + { + bitstatus = GPIO_PIN_SET; + } + else + { + bitstatus = GPIO_PIN_RESET; + } + return (bitstatus==GPIO_PIN_RESET); +} + +/************************************************************** + RATIONALE FOR THIS FUNCTION : + + - The STM32 embeds in ROM a bootloader that allows to + obtain code and boot from a number of different interfaces, + including USB in a mode called "DFU" (Device Frimware Update) + [see AN3606 from ST for full details] + This bootloader code is executed instead of the regular + application code when pin BOOT0 is pulled-up (which on + LimiFrog0.2 is achieved by pressing the general-purpose + pushbutton switch on the side. + - The bootloader monitors a number of IOs of the STM32 to decide + from which interface it should boot. + - Problem in LimiFrog (up to versions 0.2a at least): upon + power-up the BLE modules generates some activity on UART3, + which is part of the pins monitored by the STM32. + This misleads the bootloader in trying to boot from UART3 + and, as a result, not continuing with booting from USB. + + - This code implements an alternative solution to launch the + bootloader while making sure UART3 remains stable. + - The idea it to start application code with a check, prior to any + other applicative code, of whether USB bootload is required (as + flagged by a GPIO pulled low at reset, in the same way as BOOT0). + The hadware reset pin of BLE is asserted (so that now it won't + generate any acitivity on UART3), and if USB bootload is required : + bootload ROM is remapped at address 0x0, stack pointer is + updated and the code is branched to the start of the bootloader. + - This code is run prior to any applicative configuration of clocks, + IRQs etc. -- the STM32 is therefore still running from MSI + + THIS FUNCTION MAY BE SUPPRESSED IF YOU NEVER NEED TO BOOT DFU MODE + + ********************************************************************/ + +static void LBF_DFU_If_Needed(void) +{ + + + GPIO_InitTypeDef GPIO_InitStruct; + + + // Initialize and assert pin BTLE_RST + // (hw reset to BLE module, so it won't drive UART3) + + __GPIOC_CLK_ENABLE(); + GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_LOW; + GPIO_InitStruct.Pin = BT_RST_PIN; + HAL_GPIO_Init(BT_RST_PORT, &GPIO_InitStruct); + + GPIO_HIGH(BT_RST_PORT, BT_RST_PIN); // assert BTLE reset + + + /* -- Bootloader will be called if position 10 on the extension port + is actively pulled low -- */ + // Note - this is an arbitrary choice, code could be modified to + // monitor another GPIO of the STM32 and/or decide that active level + // is high rather than low + + + // Initialize Extension Port Position 10 = PB8 (bears I2C1_SCL) + // Use weak pull-up to detect if pin is externally pulled low + + __GPIOB_CLK_ENABLE(); + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Pin = CONN_POS10_PIN; + HAL_GPIO_Init(CONN_POS10_PORT, &GPIO_InitStruct); + + // If selection pin pulled low... + if ( IS_GPIO_RESET(CONN_POS10_PORT, CONN_POS10_PIN )) + + { + // Remap bootloader ROM (ie System Flash) to address 0x0 + SYSCFG->MEMRMP = 0x00000001; + + // Init stack pointer with value residing at ROM base + asm ( + "LDR R0, =0x00000000\n\t" // load ROM base address" + "LDR SP,[R0, #0]\n\t" // assign main stack pointer" + ); + + // Jump to address pointed by 0x00000004 -- */ + + asm ( + "LDR R0,[R0, #4]\n\t" // load bootloader address + "BX R0\n\t" + ); + + } +} diff --git a/stmhal/boards/LIMIFROG/mpconfigboard.h b/stmhal/boards/LIMIFROG/mpconfigboard.h new file mode 100644 index 0000000000..782c9c90f8 --- /dev/null +++ b/stmhal/boards/LIMIFROG/mpconfigboard.h @@ -0,0 +1,71 @@ +#include STM32_HAL_H + +#define MICROPY_HW_BOARD_NAME "LIMIFROG" +#define MICROPY_HW_MCU_NAME "STM32L476" + +#define MICROPY_HW_HAS_SWITCH (1) +#define MICROPY_HW_HAS_FLASH (1) +#define MICROPY_HW_HAS_SDCARD (0) +#define MICROPY_HW_HAS_MMA7660 (0) +#define MICROPY_HW_HAS_LIS3DSH (0) +#define MICROPY_HW_HAS_LCD (0) +#define MICROPY_HW_ENABLE_RNG (1) +#define MICROPY_HW_ENABLE_RTC (1) +#define MICROPY_HW_ENABLE_TIMER (1) +#define MICROPY_HW_ENABLE_SERVO (0) +#define MICROPY_HW_ENABLE_DAC (0) +#define MICROPY_HW_ENABLE_CAN (0) + +#define MICROPY_BOARD_EARLY_INIT LIMIFROG_board_early_init +void LIMIFROG_board_early_init(void); + +// MSI is used and is 4MHz +#define MICROPY_HW_CLK_PLLM (1) +#define MICROPY_HW_CLK_PLLN (40) +#define MICROPY_HW_CLK_PLLP (RCC_PLLP_DIV7) +#define MICROPY_HW_CLK_PLLR (RCC_PLLR_DIV2) +#define MICROPY_HW_CLK_PLLQ (RCC_PLLQ_DIV2) + +#define MICROPY_HW_FLASH_LATENCY FLASH_LATENCY_4 + +// USART config +#define MICROPY_HW_UART3_PORT (GPIOC) +#define MICROPY_HW_UART3_PINS (GPIO_PIN_10 | GPIO_PIN_11) + +// I2C busses +#define MICROPY_HW_I2C1_SCL (pin_B8) +#define MICROPY_HW_I2C1_SDA (pin_B9) +#define MICROPY_HW_I2C2_SCL (pin_B10) +#define MICROPY_HW_I2C2_SDA (pin_B11) +// We use an array of baudrates and corresponding TIMINGR values. +// +// The value 0x90112626 was obtained from the DISCOVERY_I2C1_TIMING constant +// defined in the STM32L4Cube file Drivers/BSP/STM32L476G-Discovery/stm32l476g_discovery.h +#define MICROPY_HW_I2C_BAUDRATE_TIMING {{100000, 0x90112626}} +#define MICROPY_HW_I2C_BAUDRATE_DEFAULT 100000 +#define MICROPY_HW_I2C_BAUDRATE_MAX 100000 + +// SPI busses +#define MICROPY_HW_SPI1_NSS (pin_A4) +#define MICROPY_HW_SPI1_SCK (pin_A5) +#define MICROPY_HW_SPI1_MISO (pin_A6) +#define MICROPY_HW_SPI1_MOSI (pin_A7) + +#define MICROPY_HW_SPI3_NSS (pin_A15) +#define MICROPY_HW_SPI3_SCK (pin_B3) +#define MICROPY_HW_SPI3_MISO (pin_B4) +#define MICROPY_HW_SPI3_MOSI (pin_B5) + +#define MICROPY_HW_USRSW_PIN (pin_A15) +#define MICROPY_HW_USRSW_PULL (GPIO_NOPULL) +#define MICROPY_HW_USRSW_EXTI_MODE (GPIO_MODE_IT_RISING) +#define MICROPY_HW_USRSW_PRESSED (1) + +// LEDs +#define MICROPY_HW_LED1 (pin_C3) // red +#define MICROPY_HW_LED_OTYPE (GPIO_MODE_OUTPUT_PP) +#define MICROPY_HW_LED_ON(pin) (pin->gpio->BSRR = pin->pin_mask) +#define MICROPY_HW_LED_OFF(pin) (pin->gpio->BSRR = pin->pin_mask<<16) + +// USB config +// #define MICROPY_HW_USB_OTG_ID_PIN (pin_C12) // This is not the official ID Pin which should be PA10 diff --git a/stmhal/boards/LIMIFROG/mpconfigboard.mk b/stmhal/boards/LIMIFROG/mpconfigboard.mk new file mode 100644 index 0000000000..cb89e25f5b --- /dev/null +++ b/stmhal/boards/LIMIFROG/mpconfigboard.mk @@ -0,0 +1,4 @@ +MCU_SERIES = l4 +CMSIS_MCU = STM32L476xx +AF_FILE = boards/stm32l476_af.csv +LD_FILE = boards/stm32l476xe.ld diff --git a/stmhal/boards/LIMIFROG/pins.csv b/stmhal/boards/LIMIFROG/pins.csv new file mode 100644 index 0000000000..52f96b669c --- /dev/null +++ b/stmhal/boards/LIMIFROG/pins.csv @@ -0,0 +1,114 @@ +PA0,PA0 +PA1,PA1 +PA2,PA2 +PA3,PA3 +PA4,PA4 +PA5,PA5 +PA6,PA6 +PA7,PA7 +PA8,PA8 +PA9,PA9 +PA10,PA10 +PA11,PA11 +PA12,PA12 +PA13,PA13 +PA14,PA14 +PA15,PA15 +PB0,PB0 +PB1,PB1 +PB2,PB2 +PB3,PB3 +PB4,PB4 +PB5,PB5 +PB6,PB6 +PB7,PB7 +PB8,PB8 +PB9,PB9 +PB10,PB10 +PB11,PB11 +PB12,PB12 +PB13,PB13 +PB14,PB14 +PB15,PB15 +PC0,PC0 +PC1,PC1 +PC2,PC2 +PC3,PC3 +PC4,PC4 +PC5,PC5 +PC6,PC6 +PC7,PC7 +PC8,PC8 +PC9,PC9 +PC10,PC10 +PC11,PC11 +PC12,PC12 +PC13,PC13 +PC14,PC14 +PC15,PC15 +PD0,PD0 +PD1,PD1 +PD2,PD2 +PD3,PD3 +PD4,PD4 +PD5,PD5 +PD6,PD6 +PD7,PD7 +PD8,PD8 +PD9,PD9 +PD10,PD10 +PD11,PD11 +PD12,PD12 +PD13,PD13 +PD14,PD14 +PD15,PD15 +PE0,PE0 +PE1,PE1 +PE2,PE2 +PE3,PE3 +PE4,PE4 +PE5,PE5 +PE6,PE6 +PE7,PE7 +PE8,PE8 +PE9,PE9 +PE10,PE10 +PE11,PE11 +PE12,PE12 +PE13,PE13 +PE14,PE14 +PE15,PE15 +PF0,PF0 +PF1,PF1 +PF2,PF2 +PF3,PF3 +PF4,PF4 +PF5,PF5 +PF6,PF6 +PF7,PF7 +PF8,PF8 +PF9,PF9 +PF10,PF10 +PF11,PF11 +PF12,PF12 +PF13,PF13 +PF14,PF14 +PF15,PF15 +PG0,PG0 +PG1,PG1 +PG2,PG2 +PG3,PG3 +PG4,PG4 +PG5,PG5 +PG6,PG6 +PG7,PG7 +PG8,PG8 +PG9,PG9 +PG10,PG10 +PG11,PG11 +PG12,PG12 +PG13,PG13 +PG14,PG14 +PG15,PG15 +PH0,PH0 +PH1,PH1 diff --git a/stmhal/boards/LIMIFROG/stm32l4xx_hal_conf.h b/stmhal/boards/LIMIFROG/stm32l4xx_hal_conf.h new file mode 100644 index 0000000000..9348e06790 --- /dev/null +++ b/stmhal/boards/LIMIFROG/stm32l4xx_hal_conf.h @@ -0,0 +1,373 @@ +/** + ****************************************************************************** + * @file stm32l4xx_hal_conf.h + * @author MCD Application Team + * @version V1.2.0 + * @date 25-November-2015 + * @brief HAL configuration template file. + * This file should be copied to the application folder and renamed + * to stm32l4xx_hal_conf.h. + ****************************************************************************** + * @attention + * + * <h2><center>© COPYRIGHT(c) 2015 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 __STM32L4xx_HAL_CONF_H +#define __STM32L4xx_HAL_CONF_H + +#ifdef __cplusplus + extern "C" { +#endif + +#define USE_USB_FS +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/* ########################## Module Selection ############################## */ +/** + * @brief This is the list of modules to be used in the HAL driver + */ +#define HAL_MODULE_ENABLED +#define HAL_ADC_MODULE_ENABLED +#define HAL_CAN_MODULE_ENABLED +/* #define HAL_COMP_MODULE_ENABLED */ +#define HAL_CORTEX_MODULE_ENABLED +/* #define HAL_CRC_MODULE_ENABLED */ +/* #define HAL_CRYP_MODULE_ENABLED */ +#define HAL_DAC_MODULE_ENABLED +/* #define HAL_DFSDM_MODULE_ENABLED */ +#define HAL_DMA_MODULE_ENABLED +/* #define HAL_FIREWALL_MODULE_ENABLED */ +#define HAL_FLASH_MODULE_ENABLED +/* #define HAL_HCD_MODULE_ENABLED */ +/* #define HAL_NAND_MODULE_ENABLED */ +/* #define HAL_NOR_MODULE_ENABLED */ +/* #define HAL_SRAM_MODULE_ENABLED */ +#define HAL_GPIO_MODULE_ENABLED +#define HAL_I2C_MODULE_ENABLED +/* #define HAL_IRDA_MODULE_ENABLED */ +/* #define HAL_IWDG_MODULE_ENABLED */ +/* #define HAL_LCD_MODULE_ENABLED */ +/* #define HAL_LPTIM_MODULE_ENABLED */ +/* #define HAL_OPAMP_MODULE_ENABLED */ +#define HAL_PCD_MODULE_ENABLED +#define HAL_PWR_MODULE_ENABLED +/* #define HAL_QSPI_MODULE_ENABLED */ +#define HAL_RCC_MODULE_ENABLED +#define HAL_RNG_MODULE_ENABLED +#define HAL_RTC_MODULE_ENABLED +/* #define HAL_SAI_MODULE_ENABLED */ +#define HAL_SD_MODULE_ENABLED +/* #define HAL_SMARTCARD_MODULE_ENABLED */ +/* #define HAL_SMBUS_MODULE_ENABLED */ +#define HAL_SPI_MODULE_ENABLED +/* #define HAL_SWPMI_MODULE_ENABLED */ +#define HAL_TIM_MODULE_ENABLED +/* #define HAL_TSC_MODULE_ENABLED */ +#define HAL_UART_MODULE_ENABLED +/* #define HAL_USART_MODULE_ENABLED */ +/* #define HAL_WWDG_MODULE_ENABLED */ + + +/* ########################## Oscillator Values adaptation ####################*/ +/** + * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSE is used as system clock source, directly or through the PLL). + */ +#if !defined (HSE_VALUE) + #define HSE_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +#if !defined (HSE_STARTUP_TIMEOUT) + #define HSE_STARTUP_TIMEOUT ((uint32_t)100) /*!< Time out for HSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + +/** + * @brief Internal Multiple Speed oscillator (MSI) default value. + * This value is the default MSI range value after Reset. + */ +#if !defined (MSI_VALUE) + #define MSI_VALUE ((uint32_t)4000000) /*!< Value of the Internal oscillator in Hz*/ +#endif /* MSI_VALUE */ + +/** + * @brief Internal High Speed oscillator (HSI) value. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSI is used as system clock source, directly or through the PLL). + */ +#if !defined (HSI_VALUE) + #define HSI_VALUE ((uint32_t)16000000) /*!< Value of the Internal oscillator in Hz*/ +#endif /* HSI_VALUE */ + +/** + * @brief Internal Low Speed oscillator (LSI) value. + */ +#if !defined (LSI_VALUE) + #define LSI_VALUE ((uint32_t)32000) /*!< LSI Typical Value in Hz*/ +#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz + The real value may vary depending on the variations + in voltage and temperature. */ +/** + * @brief External Low Speed oscillator (LSE) value. + * This value is used by the UART, RTC HAL module to compute the system frequency + */ +#if !defined (LSE_VALUE) + #define LSE_VALUE ((uint32_t)32768) /*!< Value of the External oscillator in Hz*/ +#endif /* LSE_VALUE */ + +#if !defined (LSE_STARTUP_TIMEOUT) + #define LSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for LSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + +/** + * @brief External clock source for SAI1 peripheral + * This value is used by the RCC HAL module to compute the SAI1 & SAI2 clock source + * frequency. + */ +#if !defined (EXTERNAL_SAI1_CLOCK_VALUE) + #define EXTERNAL_SAI1_CLOCK_VALUE ((uint32_t)48000) /*!< Value of the SAI1 External clock source in Hz*/ +#endif /* EXTERNAL_SAI1_CLOCK_VALUE */ + +/** + * @brief External clock source for SAI2 peripheral + * This value is used by the RCC HAL module to compute the SAI1 & SAI2 clock source + * frequency. + */ +#if !defined (EXTERNAL_SAI2_CLOCK_VALUE) + #define EXTERNAL_SAI2_CLOCK_VALUE ((uint32_t)48000) /*!< Value of the SAI2 External clock source in Hz*/ +#endif /* EXTERNAL_SAI2_CLOCK_VALUE */ + +/* Tip: To avoid modifying this file each time you need to use different HSE, + === you can define the HSE value in your toolchain compiler preprocessor. */ + +/* ########################### System Configuration ######################### */ +/** + * @brief This is the HAL system configuration section + */ +#define VDD_VALUE ((uint32_t)3300) /*!< Value of VDD in mv */ +#define TICK_INT_PRIORITY ((uint32_t)0x00) /*!< tick interrupt priority */ +#define USE_RTOS 0 +#define PREFETCH_ENABLE 1 +#define INSTRUCTION_CACHE_ENABLE 1 +#define DATA_CACHE_ENABLE 1 + +/* ########################## Assert Selection ############################## */ +/** + * @brief Uncomment the line below to expanse the "assert_param" macro in the + * HAL drivers code + */ +/* #define USE_FULL_ASSERT 1 */ + +/* Includes ------------------------------------------------------------------*/ +/** + * @brief Include module's header file + */ + +#ifdef HAL_RCC_MODULE_ENABLED + #include "stm32l4xx_hal_rcc.h" +#endif /* HAL_RCC_MODULE_ENABLED */ + +#ifdef HAL_GPIO_MODULE_ENABLED + #include "stm32l4xx_hal_gpio.h" +#endif /* HAL_GPIO_MODULE_ENABLED */ + +#ifdef HAL_DMA_MODULE_ENABLED + #include "stm32l4xx_hal_dma.h" +#endif /* HAL_DMA_MODULE_ENABLED */ + +#ifdef HAL_DFSDM_MODULE_ENABLED + #include "stm32l4xx_hal_dfsdm.h" +#endif /* HAL_DFSDM_MODULE_ENABLED */ + +#ifdef HAL_CORTEX_MODULE_ENABLED + #include "stm32l4xx_hal_cortex.h" +#endif /* HAL_CORTEX_MODULE_ENABLED */ + +#ifdef HAL_ADC_MODULE_ENABLED + #include "stm32l4xx_hal_adc.h" +#endif /* HAL_ADC_MODULE_ENABLED */ + +#ifdef HAL_CAN_MODULE_ENABLED + #include "stm32l4xx_hal_can.h" +#endif /* HAL_CAN_MODULE_ENABLED */ + +#ifdef HAL_COMP_MODULE_ENABLED + #include "stm32l4xx_hal_comp.h" +#endif /* HAL_COMP_MODULE_ENABLED */ + +#ifdef HAL_CRC_MODULE_ENABLED + #include "stm32l4xx_hal_crc.h" +#endif /* HAL_CRC_MODULE_ENABLED */ + +#ifdef HAL_CRYP_MODULE_ENABLED + #include "stm32l4xx_hal_cryp.h" +#endif /* HAL_CRYP_MODULE_ENABLED */ + +#ifdef HAL_DAC_MODULE_ENABLED + #include "stm32l4xx_hal_dac.h" +#endif /* HAL_DAC_MODULE_ENABLED */ + +#ifdef HAL_FIREWALL_MODULE_ENABLED + #include "stm32l4xx_hal_firewall.h" +#endif /* HAL_FIREWALL_MODULE_ENABLED */ + +#ifdef HAL_FLASH_MODULE_ENABLED + #include "stm32l4xx_hal_flash.h" +#endif /* HAL_FLASH_MODULE_ENABLED */ + +#ifdef HAL_SRAM_MODULE_ENABLED + #include "stm32l4xx_hal_sram.h" +#endif /* HAL_SRAM_MODULE_ENABLED */ + +#ifdef HAL_NOR_MODULE_ENABLED + #include "stm32l4xx_hal_nor.h" +#endif /* HAL_NOR_MODULE_ENABLED */ + +#ifdef HAL_NAND_MODULE_ENABLED + #include "stm32l4xx_hal_nand.h" +#endif /* HAL_NAND_MODULE_ENABLED */ + +#ifdef HAL_I2C_MODULE_ENABLED + #include "stm32l4xx_hal_i2c.h" +#endif /* HAL_I2C_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED + #include "stm32l4xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_LCD_MODULE_ENABLED + #include "stm32l4xx_hal_lcd.h" +#endif /* HAL_LCD_MODULE_ENABLED */ + +#ifdef HAL_LPTIM_MODULE_ENABLED +#include "stm32l4xx_hal_lptim.h" +#endif /* HAL_LPTIM_MODULE_ENABLED */ + +#ifdef HAL_OPAMP_MODULE_ENABLED +#include "stm32l4xx_hal_opamp.h" +#endif /* HAL_OPAMP_MODULE_ENABLED */ + +#ifdef HAL_PWR_MODULE_ENABLED + #include "stm32l4xx_hal_pwr.h" +#endif /* HAL_PWR_MODULE_ENABLED */ + +#ifdef HAL_QSPI_MODULE_ENABLED + #include "stm32l4xx_hal_qspi.h" +#endif /* HAL_QSPI_MODULE_ENABLED */ + +#ifdef HAL_RNG_MODULE_ENABLED + #include "stm32l4xx_hal_rng.h" +#endif /* HAL_RNG_MODULE_ENABLED */ + +#ifdef HAL_RTC_MODULE_ENABLED + #include "stm32l4xx_hal_rtc.h" +#endif /* HAL_RTC_MODULE_ENABLED */ + +#ifdef HAL_SAI_MODULE_ENABLED + #include "stm32l4xx_hal_sai.h" +#endif /* HAL_SAI_MODULE_ENABLED */ + +#ifdef HAL_SD_MODULE_ENABLED + #include "stm32l4xx_hal_sd.h" +#endif /* HAL_SD_MODULE_ENABLED */ + +#ifdef HAL_SMBUS_MODULE_ENABLED + #include "stm32l4xx_hal_smbus.h" +#endif /* HAL_SMBUS_MODULE_ENABLED */ + +#ifdef HAL_SPI_MODULE_ENABLED + #include "stm32l4xx_hal_spi.h" +#endif /* HAL_SPI_MODULE_ENABLED */ + +#ifdef HAL_SWPMI_MODULE_ENABLED + #include "stm32l4xx_hal_swpmi.h" +#endif /* HAL_SWPMI_MODULE_ENABLED */ + +#ifdef HAL_TIM_MODULE_ENABLED + #include "stm32l4xx_hal_tim.h" +#endif /* HAL_TIM_MODULE_ENABLED */ + +#ifdef HAL_TSC_MODULE_ENABLED + #include "stm32l4xx_hal_tsc.h" +#endif /* HAL_TSC_MODULE_ENABLED */ + +#ifdef HAL_UART_MODULE_ENABLED + #include "stm32l4xx_hal_uart.h" +#endif /* HAL_UART_MODULE_ENABLED */ + +#ifdef HAL_USART_MODULE_ENABLED + #include "stm32l4xx_hal_usart.h" +#endif /* HAL_USART_MODULE_ENABLED */ + +#ifdef HAL_IRDA_MODULE_ENABLED + #include "stm32l4xx_hal_irda.h" +#endif /* HAL_IRDA_MODULE_ENABLED */ + +#ifdef HAL_SMARTCARD_MODULE_ENABLED + #include "stm32l4xx_hal_smartcard.h" +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ + +#ifdef HAL_WWDG_MODULE_ENABLED + #include "stm32l4xx_hal_wwdg.h" +#endif /* HAL_WWDG_MODULE_ENABLED */ + +#ifdef HAL_PCD_MODULE_ENABLED + #include "stm32l4xx_hal_pcd.h" +#endif /* HAL_PCD_MODULE_ENABLED */ + +#ifdef HAL_HCD_MODULE_ENABLED + #include "stm32l4xx_hal_hcd.h" +#endif /* HAL_HCD_MODULE_ENABLED */ + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr: If expr is false, it calls assert_failed function + * which reports the name of the source file and the source + * line number of the call that failed. + * If expr is true, it returns no value. + * @retval None + */ + #define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__)) +/* Exported functions ------------------------------------------------------- */ + void assert_failed(uint8_t* file, uint32_t line); +#else + #define assert_param(expr) ((void)0) +#endif /* USE_FULL_ASSERT */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32L4xx_HAL_CONF_H */ + + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/stmhal/boards/PYBLITEV10/mpconfigboard.h b/stmhal/boards/PYBLITEV10/mpconfigboard.h index 97c972095a..83dcb938b3 100644 --- a/stmhal/boards/PYBLITEV10/mpconfigboard.h +++ b/stmhal/boards/PYBLITEV10/mpconfigboard.h @@ -71,8 +71,8 @@ #define MICROPY_HW_LED2 (pin_A14) // green #define MICROPY_HW_LED3 (pin_A15) // yellow #define MICROPY_HW_LED4 (pin_B4) // blue -#define MICROPY_HW_LED3_PWM { TIM2, 2, GPIO_AF1_TIM2 } -#define MICROPY_HW_LED4_PWM { TIM3, 3, GPIO_AF2_TIM3 } +#define MICROPY_HW_LED3_PWM { TIM2, 2, TIM_CHANNEL_1, GPIO_AF1_TIM2 } +#define MICROPY_HW_LED4_PWM { TIM3, 3, TIM_CHANNEL_1, GPIO_AF2_TIM3 } #define MICROPY_HW_LED_OTYPE (GPIO_MODE_OUTPUT_PP) #define MICROPY_HW_LED_ON(pin) (pin->gpio->BSRRL = pin->pin_mask) #define MICROPY_HW_LED_OFF(pin) (pin->gpio->BSRRH = pin->pin_mask) diff --git a/stmhal/boards/PYBV10/mpconfigboard.h b/stmhal/boards/PYBV10/mpconfigboard.h index bc1d848b77..c654ec9a70 100644 --- a/stmhal/boards/PYBV10/mpconfigboard.h +++ b/stmhal/boards/PYBV10/mpconfigboard.h @@ -82,8 +82,8 @@ #define MICROPY_HW_LED2 (pin_A14) // green #define MICROPY_HW_LED3 (pin_A15) // yellow #define MICROPY_HW_LED4 (pin_B4) // blue -#define MICROPY_HW_LED3_PWM { TIM2, 2, GPIO_AF1_TIM2 } -#define MICROPY_HW_LED4_PWM { TIM3, 3, GPIO_AF2_TIM3 } +#define MICROPY_HW_LED3_PWM { TIM2, 2, TIM_CHANNEL_1, GPIO_AF1_TIM2 } +#define MICROPY_HW_LED4_PWM { TIM3, 3, TIM_CHANNEL_1, GPIO_AF2_TIM3 } #define MICROPY_HW_LED_OTYPE (GPIO_MODE_OUTPUT_PP) #define MICROPY_HW_LED_ON(pin) (pin->gpio->BSRRL = pin->pin_mask) #define MICROPY_HW_LED_OFF(pin) (pin->gpio->BSRRH = pin->pin_mask) diff --git a/stmhal/boards/PYBV11/mpconfigboard.h b/stmhal/boards/PYBV11/mpconfigboard.h index b3c0983e34..9b5b7de27b 100644 --- a/stmhal/boards/PYBV11/mpconfigboard.h +++ b/stmhal/boards/PYBV11/mpconfigboard.h @@ -82,8 +82,8 @@ #define MICROPY_HW_LED2 (pin_A14) // green #define MICROPY_HW_LED3 (pin_A15) // yellow #define MICROPY_HW_LED4 (pin_B4) // blue -#define MICROPY_HW_LED3_PWM { TIM2, 2, GPIO_AF1_TIM2 } -#define MICROPY_HW_LED4_PWM { TIM3, 3, GPIO_AF2_TIM3 } +#define MICROPY_HW_LED3_PWM { TIM2, 2, TIM_CHANNEL_1, GPIO_AF1_TIM2 } +#define MICROPY_HW_LED4_PWM { TIM3, 3, TIM_CHANNEL_1, GPIO_AF2_TIM3 } #define MICROPY_HW_LED_OTYPE (GPIO_MODE_OUTPUT_PP) #define MICROPY_HW_LED_ON(pin) (pin->gpio->BSRRL = pin->pin_mask) #define MICROPY_HW_LED_OFF(pin) (pin->gpio->BSRRH = pin->pin_mask) diff --git a/stmhal/boards/PYBV3/mpconfigboard.h b/stmhal/boards/PYBV3/mpconfigboard.h index 67877fd0b2..44fb221610 100644 --- a/stmhal/boards/PYBV3/mpconfigboard.h +++ b/stmhal/boards/PYBV3/mpconfigboard.h @@ -66,10 +66,13 @@ #define MICROPY_HW_USRSW_PRESSED (0) // LEDs +#define MICROPY_HW_LED_INVERTED (1) // LEDs are on when pin is driven low #define MICROPY_HW_LED1 (pin_A8) // R1 - red #define MICROPY_HW_LED2 (pin_A10) // R2 - red #define MICROPY_HW_LED3 (pin_C4) // G1 - green #define MICROPY_HW_LED4 (pin_C5) // G2 - green +#define MICROPY_HW_LED1_PWM { TIM1, 1, TIM_CHANNEL_1, GPIO_AF1_TIM1 } +#define MICROPY_HW_LED2_PWM { TIM1, 1, TIM_CHANNEL_3, GPIO_AF1_TIM1 } #define MICROPY_HW_LED_OTYPE (GPIO_MODE_OUTPUT_PP) #define MICROPY_HW_LED_ON(pin) (pin->gpio->BSRRH = pin->pin_mask) #define MICROPY_HW_LED_OFF(pin) (pin->gpio->BSRRL = pin->pin_mask) diff --git a/stmhal/boards/PYBV4/mpconfigboard.h b/stmhal/boards/PYBV4/mpconfigboard.h index 7c75508ed4..cc931fb6bf 100644 --- a/stmhal/boards/PYBV4/mpconfigboard.h +++ b/stmhal/boards/PYBV4/mpconfigboard.h @@ -79,8 +79,8 @@ #define MICROPY_HW_LED2 (pin_A14) // green #define MICROPY_HW_LED3 (pin_A15) // yellow #define MICROPY_HW_LED4 (pin_B4) // blue -#define MICROPY_HW_LED3_PWM { TIM2, 2, GPIO_AF1_TIM2 } -#define MICROPY_HW_LED4_PWM { TIM3, 3, GPIO_AF2_TIM3 } +#define MICROPY_HW_LED3_PWM { TIM2, 2, TIM_CHANNEL_1, GPIO_AF1_TIM2 } +#define MICROPY_HW_LED4_PWM { TIM3, 3, TIM_CHANNEL_1, GPIO_AF2_TIM3 } #define MICROPY_HW_LED_OTYPE (GPIO_MODE_OUTPUT_PP) #define MICROPY_HW_LED_ON(pin) (pin->gpio->BSRRL = pin->pin_mask) #define MICROPY_HW_LED_OFF(pin) (pin->gpio->BSRRH = pin->pin_mask) diff --git a/stmhal/boards/STM32L476DISC/mpconfigboard.h b/stmhal/boards/STM32L476DISC/mpconfigboard.h index f4617e67df..79857ccc26 100644 --- a/stmhal/boards/STM32L476DISC/mpconfigboard.h +++ b/stmhal/boards/STM32L476DISC/mpconfigboard.h @@ -16,11 +16,11 @@ #define MICROPY_HW_ENABLE_DAC (0) #define MICROPY_HW_ENABLE_CAN (0) -// HSE is 8MHz -#define MICROPY_HW_CLK_PLLM (2) +// MSI is used and is 4MHz +#define MICROPY_HW_CLK_PLLM (1) #define MICROPY_HW_CLK_PLLN (40) #define MICROPY_HW_CLK_PLLP (RCC_PLLP_DIV7) -#define MICROPY_HW_CLK_PLLR (RCC_PLLP_DIV7) +#define MICROPY_HW_CLK_PLLR (RCC_PLLR_DIV2) #define MICROPY_HW_CLK_PLLQ (RCC_PLLQ_DIV2) #define MICROPY_HW_FLASH_LATENCY FLASH_LATENCY_4 @@ -32,6 +32,8 @@ // I2C busses #define MICROPY_HW_I2C1_SCL (pin_B6) #define MICROPY_HW_I2C1_SDA (pin_B7) +#define MICROPY_HW_I2C2_SCL (pin_B10) +#define MICROPY_HW_I2C2_SDA (pin_B11) // We use an array of baudrates and corresponding TIMINGR values. // // The value 0x90112626 was obtained from the DISCOVERY_I2C1_TIMING constant diff --git a/stmhal/boards/stm32l476xe.ld b/stmhal/boards/stm32l476xe.ld new file mode 100644 index 0000000000..a4b1ce0974 --- /dev/null +++ b/stmhal/boards/stm32l476xe.ld @@ -0,0 +1,134 @@ +/* + GNU linker script for STM32L476XE +*/ + +/* Specify the memory areas */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 512K + FLASH_ISR (rx) : ORIGIN = 0x08000000, LENGTH = 0x0000800 /* sector 0, 2 KiB */ + FLASH_FS (r) : ORIGIN = 0x08000800, LENGTH = 0x001F800 /* sectors 1-63 (2K each = 126 KiB) */ + FLASH_TEXT (rx) : ORIGIN = 0x08020000, LENGTH = 0x0060000 /* Sector starting @ 64 */ + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 96K + SRAM2 (xrw) : ORIGIN = 0x10000000, LENGTH = 32K +} + +ENTRY(Reset_Handler) + +/* produce a link error if there is not this amount of RAM for these sections */ +_minimum_stack_size = 2K; +_minimum_heap_size = 16K; + +/* Define the top end of the stack. The stack is full descending so begins just + above last byte of RAM. Note that EABI requires the stack to be 8-byte + aligned for a call. */ +_estack = ORIGIN(RAM) + LENGTH(RAM); + +/* RAM extents for the garbage collector */ +_ram_end = ORIGIN(RAM) + LENGTH(RAM); +_heap_end = 0x20014000; /* tunable */ + + +/* define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + + . = ALIGN(4); + } >FLASH_ISR + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + /* *(.glue_7) */ /* glue arm to thumb code */ + /* *(.glue_7t) */ /* glue thumb to arm code */ + + . = ALIGN(4); + _etext = .; /* define a global symbol at end of code */ + } >FLASH_TEXT + + /* + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) + } >FLASH + + .ARM : + { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + */ + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* This is the initialized data section + The program executes knowing that the data is in the RAM + but the loader puts the initial values in the FLASH (inidata). + It is one task of the startup to copy the initial values from FLASH to RAM. */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start; used by startup code in order to initialise the .data section in RAM */ + _ram_start = .; /* create a global symbol at ram start for garbage collector */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end; used by startup code in order to initialise the .data section in RAM */ + } >RAM AT> FLASH_TEXT + + /* Uninitialized data section */ + .bss : + { + . = ALIGN(4); + _sbss = .; /* define a global symbol at bss start; used by startup code */ + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end; used by startup code and GC */ + } >RAM + + /* this is to define the start of the heap, and make sure we have a minimum size */ + .heap : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + _heap_start = .; /* define a global symbol at heap start */ + . = . + _minimum_heap_size; + } >RAM + + /* this just checks there is enough RAM for the stack */ + .stack : + { + . = ALIGN(4); + . = . + _minimum_stack_size; + . = ALIGN(4); + } >RAM + + /* Remove information from the standard libraries */ + /* + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + */ + + .ARM.attributes 0 : { *(.ARM.attributes) } +} |