stm32l4: add initial soc support for stm32l4

Add the initial SoC support for the STM32L4XX family. The code was
tested on STM32L476RG, but should work on any STM32L4XX currently
available.

This implementation was inspired by the stm32f1x implementation.

Change-Id: Id6670bce0c423617284e8467a9c461531f948e0f
Signed-off-by: Fabien Parent <fparent@baylibre.com>
Signed-off-by: Kumar Gala <kumar.gala@linaro.org>
Signed-off-by: Erwan Gouriou <erwan.gouriou@linaro.org>
This commit is contained in:
Neil Armstrong 2016-10-03 15:51:32 +02:00 committed by Kumar Gala
commit 8833e44f6d
15 changed files with 794 additions and 0 deletions

View file

@ -0,0 +1,30 @@
# Kconfig - ST Microelectronics STM32L4 MCU line
#
# Copyright (c) 2016 Open-RnD Sp. z o.o.
# Copyright (c) 2016 BayLibre, SAS
#
# 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.
#
if SOC_SERIES_STM32L4X
source "arch/arm/soc/st_stm32/stm32l4/Kconfig.defconfig.stm32l4*"
config SOC_SERIES
default stm32l4
config NUM_IRQ_PRIO_BITS
int
default 4
endif # SOC_SERIES_STM32L4X

View file

@ -0,0 +1,36 @@
# Kconfig - ST Microelectronics STM32L476RG MCU
#
# Copyright (c) 2016 Open-RnD Sp. z o.o.
# Copyright (c) 2016 BayLibre, SAS
#
# 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.
#
if SOC_STM32L476XX
config SOC
string
default stm32l476xx
config SRAM_SIZE
default 96
config FLASH_SIZE
default 1024
config NUM_IRQS
int
default 82
endif # SOC_STM32L476XX

View file

@ -0,0 +1,27 @@
# Kconfig - ST Microelectronics STM32L4 MCU series
#
# Copyright (c) 2016 Open-RnD Sp. z o.o.
# Copyright (c) 2016 BayLibre, SAS
#
# 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.
#
config SOC_SERIES_STM32L4X
bool "STM32L4x Series MCU"
select CPU_CORTEX_M
select CPU_CORTEX_M4
select SOC_FAMILY_STM32
select SYS_POWER_LOW_POWER_STATE_SUPPORTED
select CPU_HAS_SYSTICK
help
Enable support for STM32L4 MCU series

View file

@ -0,0 +1,27 @@
# Kconfig - ST Microelectronics STM32L4 MCU line
#
# Copyright (c) 2016 Open-RnD Sp. z o.o.
# Copyright (c) 2016 BayLibre, SAS
#
# 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.
#
choice
prompt "STM32L4x MCU Selection"
depends on SOC_SERIES_STM32L4X
config SOC_STM32L476XX
bool "STM32L476XX"
select HAS_STM32CUBE
endchoice

View file

@ -0,0 +1,4 @@
obj-y += soc.o
obj-$(CONFIG_GPIO) += soc_gpio.o
obj-$(CONFIG_PINMUX) += soc_pinmux.o

View file

@ -0,0 +1,19 @@
/* linker.ld - Linker command/script file */
/*
* Copyright (c) 2014-2016 Wind River Systems, Inc.
*
* 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.
*/
#include <arch/arm/cortex_m/scripts/linker.ld>

View file

@ -0,0 +1,70 @@
/*
* Copyright (c) 2016 Open-RnD Sp. z o.o.
* Copyright (c) 2016 BayLibre, SAS
*
* 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
* @brief System/hardware module for STM32L4 processor
*/
#include <nanokernel.h>
#include <device.h>
#include <init.h>
#include <soc.h>
#include <arch/cpu.h>
/**
* @brief Perform basic hardware initialization at boot.
*
* This needs to be run from the very beginning.
* So the init priority has to be 0 (zero).
*
* @return 0
*/
static int stm32l4_init(struct device *arg)
{
uint32_t key;
ARG_UNUSED(arg);
key = irq_lock();
/* Setup the vector table offset register (VTOR),
* which is located at the beginning of flash area.
*/
_scs_relocate_vector_table((void *)CONFIG_FLASH_BASE_ADDRESS);
/* Clear all faults */
_ScbMemFaultAllFaultsReset();
_ScbBusFaultAllFaultsReset();
_ScbUsageFaultAllFaultsReset();
_ScbHardFaultAllFaultsReset();
/* Install default handler that simply resets the CPU
* if configured in the kernel, NOP otherwise
*/
NMI_INIT();
irq_unlock(key);
/* Update CMSIS SystemCoreClock variable (HCLK) */
SystemCoreClock = CONFIG_SYS_CLOCK_HW_CYCLES_PER_SEC;
return 0;
}
SYS_INIT(stm32l4_init, PRE_KERNEL_1, 0);

View file

@ -0,0 +1,50 @@
/*
* Copyright (c) 2016 Open-RnD Sp. z o.o.
* Copyright (c) 2016 BayLibre, SAS
*
* 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 SoC configuration macros for the STM32F103 family processors.
*
* Based on reference manual:
* STM32L4x1, STM32L4x2, STM32L431xx STM32L443xx STM32L433xx, STM32L4x5,
* STM32l4x6 advanced ARM ® -based 32-bit MCUs
*
* Chapter 2.2.2: Memory map and register boundary addresses
*/
#ifndef _STM32L4X_SOC_H_
#define _STM32L4X_SOC_H_
#ifndef _ASMLANGUAGE
#include <autoconf.h>
#include <device.h>
#include <stm32l4xx.h>
#define GPIO_REG_SIZE 0x400
/* base address for where GPIO registers start */
#define GPIO_PORTS_BASE (GPIOA_BASE)
#include "soc_irq.h"
#ifdef CONFIG_SERIAL_HAS_DRIVER
#include <stm32l4xx_ll_usart.h>
#endif
#endif /* !_ASMLANGUAGE */
#endif /* _STM32L4X_SOC_H_ */

View file

@ -0,0 +1,246 @@
/*
* Copyright (c) 2016 Open-RnD Sp. z o.o.
* Copyright (c) 2016 BayLibre, SAS
*
* 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.
*/
/**
* @brief
*
* Based on reference manual:
* STM32L4x1, STM32L4x2, STM32L431xx STM32L443xx STM32L433xx, STM32L4x5,
* STM32l4x6 advanced ARM ® -based 32-bit MCUs
*
* General-purpose I/Os (GPIOs)
*/
#include <errno.h>
#include <device.h>
#include "soc.h"
#include "soc_registers.h"
#include "soc_pinmux.h"
#include <gpio.h>
#include <gpio/gpio_stm32.h>
enum {
STM32L4X_MODER_INPUT_MODE = 0x0,
STM32L4X_MODER_OUTPUT_MODE = 0x1,
STM32L4X_MODER_ALT_MODE = 0x2,
STM32L4X_MODER_ANALOG_MODE = 0x3,
STM32L4X_MODER_MASK = 0x3,
};
enum {
STM32L4X_OTYPER_PUSH_PULL = 0x0,
STM32L4X_OTYPER_OPEN_DRAIN = 0x1,
STM32L4X_OTYPER_MASK = 0x1,
};
enum {
STM32L4X_PUPDR_NO_PULL = 0x0,
STM32L4X_PUPDR_PULL_UP = 0x1,
STM32L4X_PUPDR_PULL_DOWN = 0x2,
STM32L4X_PUPDR_MASK = 0x3,
};
enum {
STM32L4X_PIN3 = 3,
STM32L4X_PIN7 = 7,
STM32L4X_PIN11 = 11,
STM32L4X_PIN15 = 15,
};
#define STM32L4X_IDR_PIN_MASK 0x1
#define STM32L4X_AFR_MASK 0xf
/* GPIO registers - each GPIO port controls 16 pins */
struct stm32l4x_gpio {
uint32_t moder;
uint32_t otyper;
uint32_t ospeedr;
uint32_t pupdr;
uint32_t idr;
uint32_t odr;
uint32_t bsrr;
uint32_t lckr;
uint32_t afr[2];
uint32_t brr;
uint32_t ascr; /* Only present on STM32L4x1, STM32L4x5, STM32L4x6 */
};
/**
* @brief map pin function to MODE register value
*/
static uint32_t func_to_mode(int conf, unsigned int afnum)
{
/* If an alternate function is specified */
if (afnum) {
return STM32L4X_MODER_ALT_MODE;
}
switch (conf) {
case STM32L4X_PIN_CONFIG_BIAS_HIGH_IMPEDANCE:
case STM32L4X_PIN_CONFIG_BIAS_PULL_UP:
case STM32L4X_PIN_CONFIG_BIAS_PULL_DOWN:
return STM32L4X_MODER_INPUT_MODE;
case STM32L4X_PIN_CONFIG_ANALOG:
return STM32L4X_MODER_ANALOG_MODE;
default:
return STM32L4X_MODER_OUTPUT_MODE;
}
return STM32L4X_MODER_INPUT_MODE;
}
static uint32_t func_to_otype(int conf)
{
switch (conf) {
case STM32L4X_PIN_CONFIG_OPEN_DRAIN:
case STM32L4X_PIN_CONFIG_OPEN_DRAIN_PULL_UP:
case STM32L4X_PIN_CONFIG_OPEN_DRAIN_PULL_DOWN:
return STM32L4X_OTYPER_OPEN_DRAIN;
default:
return STM32L4X_OTYPER_PUSH_PULL;
}
return STM32L4X_OTYPER_PUSH_PULL;
}
static uint32_t func_to_pupd(int conf)
{
switch (conf) {
case STM32L4X_PIN_CONFIG_ANALOG:
case STM32L4X_PIN_CONFIG_BIAS_HIGH_IMPEDANCE:
case STM32L4X_PIN_CONFIG_PUSH_PULL:
case STM32L4X_PIN_CONFIG_OPEN_DRAIN:
return STM32L4X_PUPDR_NO_PULL;
case STM32L4X_PIN_CONFIG_BIAS_PULL_UP:
case STM32L4X_PIN_CONFIG_PUSH_PULL_PULL_UP:
case STM32L4X_PIN_CONFIG_OPEN_DRAIN_PULL_UP:
return STM32L4X_PUPDR_PULL_UP;
case STM32L4X_PIN_CONFIG_BIAS_PULL_DOWN:
case STM32L4X_PIN_CONFIG_PUSH_PULL_PULL_DOWN:
case STM32L4X_PIN_CONFIG_OPEN_DRAIN_PULL_DOWN:
return STM32L4X_PUPDR_PULL_DOWN;
}
return STM32L4X_PUPDR_NO_PULL;
}
int stm32_gpio_flags_to_conf(int flags, int *pincfg)
{
int direction = flags & GPIO_DIR_MASK;
if (!pincfg) {
return -EINVAL;
}
if (direction == GPIO_DIR_OUT) {
*pincfg = STM32L4X_PIN_CONFIG_PUSH_PULL;
} else if (direction == GPIO_DIR_IN) {
int pud = flags & GPIO_PUD_MASK;
/* pull-{up,down} maybe? */
if (pud == GPIO_PUD_PULL_UP) {
*pincfg = STM32L4X_PIN_CONFIG_BIAS_PULL_UP;
} else if (pud == GPIO_PUD_PULL_DOWN) {
*pincfg = STM32L4X_PIN_CONFIG_BIAS_PULL_DOWN;
} else {
/* floating */
*pincfg = STM32L4X_PIN_CONFIG_BIAS_HIGH_IMPEDANCE;
}
} else {
return -ENOTSUP;
}
return 0;
}
int stm32_gpio_configure(uint32_t *base_addr, int pin, int pinconf, int afnum)
{
volatile struct stm32l4x_gpio *gpio =
(struct stm32l4x_gpio *)(base_addr);
unsigned int mode, otype, pupd;
unsigned int pin_shift = pin << 1;
unsigned int afr_bank = pin / 8;
unsigned int afr_shift = (pin % 8) << 2;
uint32_t scratch;
mode = func_to_mode(pinconf, afnum);
otype = func_to_otype(pinconf);
pupd = func_to_pupd(pinconf);
scratch = gpio->moder & ~(STM32L4X_MODER_MASK << pin_shift);
gpio->moder = scratch | (mode << pin_shift);
scratch = gpio->otyper & ~(STM32L4X_OTYPER_MASK << pin);
gpio->otyper = scratch | (otype << pin);
scratch = gpio->pupdr & ~(STM32L4X_PUPDR_MASK << pin_shift);
gpio->pupdr = scratch | (pupd << pin_shift);
scratch = gpio->afr[afr_bank] & ~(STM32L4X_AFR_MASK << afr_shift);
gpio->afr[afr_bank] = scratch | (afnum << afr_shift);
return 0;
}
int stm32_gpio_set(uint32_t *base, int pin, int value)
{
struct stm32l4x_gpio *gpio = (struct stm32l4x_gpio *)base;
int pval = 1 << (pin & 0xf);
if (value) {
gpio->odr |= pval;
} else {
gpio->odr &= ~pval;
}
return 0;
}
int stm32_gpio_get(uint32_t *base, int pin)
{
struct stm32l4x_gpio *gpio = (struct stm32l4x_gpio *)base;
return (gpio->idr >> pin) & STM32L4X_IDR_PIN_MASK;
}
int stm32_gpio_enable_int(int port, int pin)
{
struct stm32l4x_syscfg *syscfg = (struct stm32l4x_syscfg *)SYSCFG_BASE;
struct device *clk = device_get_binding(STM32_CLOCK_CONTROL_NAME);
uint32_t *reg;
clock_control_on(clk, (clock_control_subsys_t *)
STM32L4X_CLOCK_SUBSYS_SYSCFG);
if (pin <= STM32L4X_PIN3) {
reg = &syscfg->exticr1;
} else if (pin <= STM32L4X_PIN7) {
reg = &syscfg->exticr2;
} else if (pin <= STM32L4X_PIN11) {
reg = &syscfg->exticr3;
} else if (pin <= STM32L4X_PIN15) {
reg = &syscfg->exticr4;
} else {
return -EINVAL;
}
*reg &= STM32L4X_SYSCFG_EXTICR_PIN_MASK << ((pin % 4) * 4);
*reg |= port << ((pin % 4) * 4);
return 0; /* Nothing to do here for STM32L4s */
}

View file

@ -0,0 +1,111 @@
/*
* Copyright (c) 2016 Open-RnD Sp. z o.o.
* Copyright (c) 2016 BayLibre, SAS
*
* 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 _STM32L4_SOC_IRQ_H_
#define _STM32L4_SOC_IRQ_H_
/*
* We cannot use the enum present in the ST headers for the IRQs because
* of the IRQ_CONNECT macro. The macro exepects a number or a symbol that can
* be processed by the preprocessor.
*/
#define STM32L4_IRQ_WWDG 0
#define STM32L4_IRQ_PVD 1
#define STM32L4_IRQ_TAMPER 2
#define STM32L4_IRQ_RTC 3
#define STM32L4_IRQ_FLASH 4
#define STM32L4_IRQ_RCC 5
#define STM32L4_IRQ_EXTI0 6
#define STM32L4_IRQ_EXTI1 7
#define STM32L4_IRQ_EXTI2 8
#define STM32L4_IRQ_EXTI3 9
#define STM32L4_IRQ_EXTI4 10
#define STM32L4_IRQ_DMA1_CH1 11
#define STM32L4_IRQ_DMA1_CH2 12
#define STM32L4_IRQ_DMA1_CH3 13
#define STM32L4_IRQ_DMA1_CH4 14
#define STM32L4_IRQ_DMA1_CH5 15
#define STM32L4_IRQ_DMA1_CH6 16
#define STM32L4_IRQ_DMA1_CH7 17
#define STM32L4_IRQ_ADC1_2 18
#define STM32L4_IRQ_CAN_TX 19
#define STM32L4_IRQ_CAN_RX0 20
#define STM32L4_IRQ_CAN_RX1 21
#define STM32L4_IRQ_CAN_SCE 22
#define STM32L4_IRQ_EXTI9_5 23
#define STM32L4_IRQ_TIM1_BRK 24
#define STM32L4_IRQ_TIM1_UP 25
#define STM32L4_IRQ_TIM1_TRG_COM 26
#define STM32L4_IRQ_TIM1_CC 27
#define STM32L4_IRQ_TIM2 28
#define STM32L4_IRQ_TIM3 29
#define STM32L4_IRQ_TIM4 30
#define STM32L4_IRQ_I2C1_EV 31
#define STM32L4_IRQ_I2C1_ER 32
#define STM32L4_IRQ_I2C2_EV 33
#define STM32L4_IRQ_I2C2_ER 34
#define STM32L4_IRQ_SPI1 35
#define STM32L4_IRQ_SPI2 36
#define STM32L4_IRQ_USART1 37
#define STM32L4_IRQ_USART2 38
#define STM32L4_IRQ_USART3 39
#define STM32L4_IRQ_EXTI15_10 40
#define STM32L4_IRQ_RTC_ALARM 41
#define STM32L4_IRQ_DFSDM1_FLT3 42
#define STM32L4_IRQ_TIM8_BRK 43
#define STM32L4_IRQ_TIM8_UP 44
#define STM32L4_IRQ_TIM8_TRG_COM 45
#define STM32L4_IRQ_TIM8_CC 46
#define STM32L4_IRQ_ADC3 47
#define STM32L4_IRQ_FSMC 48
#define STM32L4_IRQ_SDIO 49
#define STM32L4_IRQ_TIM5 50
#define STM32L4_IRQ_SPI3 51
#define STM32L4_IRQ_UART4 52
#define STM32L4_IRQ_UART5 53
#define STM32L4_IRQ_TIM6 54
#define STM32L4_IRQ_TIM7 55
#define STM32L4_IRQ_DMA2_CH1 56
#define STM32L4_IRQ_DMA2_CH2 57
#define STM32L4_IRQ_DMA2_CH3 58
#define STM32L4_IRQ_DMA2_CH4 59
#define STM32L4_IRQ_DMA2_CH5 60
#define STM32L4_IRQ_DFSDM1_FLT0 61
#define STM32L4_IRQ_DFSDM1_FLT1 62
#define STM32L4_IRQ_DFSDM1_FLT2 63
#define STM32L4_IRQ_COMP 64
#define STM32L4_IRQ_LPTIM1 65
#define STM32L4_IRQ_LPTIM2 66
#define STM32L4_IRQ_OTG_FS 67
#define STM32L4_IRQ_DMA2_CH6 68
#define STM32L4_IRQ_DMA2_CH7 69
#define STM32L4_IRQ_LPUART1 70
#define STM32L4_IRQ_QUADSPI 71
#define STM32L4_IRQ_I2C3_EV 72
#define STM32L4_IRQ_I2C3_ER 73
#define STM32L4_IRQ_SAI1 74
#define STM32L4_IRQ_SAI2 75
#define STM32L4_IRQ_SWPMI1 76
#define STM32L4_IRQ_TSC 77
#define STM32L4_IRQ_LCD 78
#define STM32L4_IRQ_AES 79
#define STM32L4_IRQ_RNG 80
#define STM32L4_IRQ_FPU 81
#define STM32L4_IRQ_CRS 82
#endif /* _STM32L4_SOC_IRQ_H_ */

View file

@ -0,0 +1,77 @@
/*
* Copyright (c) 2016 Open-RnD Sp. z o.o.
* Copyright (c) 2016 BayLibre, SAS
*
* 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.
*/
#include <errno.h>
#include "soc.h"
#include "soc_pinmux.h"
#include <device.h>
#include <misc/util.h>
#include <pinmux/stm32/pinmux_stm32.h>
#include <drivers/clock_control/stm32_clock_control.h>
/**
* @brief pin configuration
*/
static const struct stm32_pinmux_conf pins[] = {
};
int stm32_get_pin_config(int pin, int func)
{
/* GPIO function is always available, to save space it is not
* listed in alternate functions array
*/
if (func == STM32_PINMUX_FUNC_GPIO) {
return STM32L4X_PIN_CONFIG_BIAS_HIGH_IMPEDANCE;
}
/* analog function is another 'known' setting */
if (func == STM32_PINMUX_FUNC_ANALOG) {
return STM32L4X_PIN_CONFIG_ANALOG;
}
for (int i = 0; i < ARRAY_SIZE(pins); i++) {
if (pins[i].pin == pin) {
if ((func - 1) >= pins[i].nfuncs) {
return -EINVAL;
}
return pins[i].funcs[func - 1];
}
}
return -EINVAL;
}
clock_control_subsys_t stm32_get_port_clock(int port)
{
const clock_control_subsys_t ports_to_clock[STM32_PORTS_MAX] = {
UINT_TO_POINTER(STM32L4X_CLOCK_SUBSYS_GPIOA),
UINT_TO_POINTER(STM32L4X_CLOCK_SUBSYS_GPIOB),
UINT_TO_POINTER(STM32L4X_CLOCK_SUBSYS_GPIOC),
UINT_TO_POINTER(STM32L4X_CLOCK_SUBSYS_GPIOD),
UINT_TO_POINTER(STM32L4X_CLOCK_SUBSYS_GPIOE),
UINT_TO_POINTER(STM32L4X_CLOCK_SUBSYS_GPIOF),
UINT_TO_POINTER(STM32L4X_CLOCK_SUBSYS_GPIOG),
UINT_TO_POINTER(STM32L4X_CLOCK_SUBSYS_GPIOH),
};
if (port > STM32_PORTH) {
return NULL;
}
return ports_to_clock[port];
}

View file

@ -0,0 +1,35 @@
/*
* Copyright (c) 2016 Open-RnD Sp. z o.o.
* Copyright (c) 2016 BayLibre, SAS
*
* 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 _STM32L4X_SOC_PINMUX_H_
#define _STM32L4X_SOC_PINMUX_H_
/* IO pin functions */
enum stm32l4x_pin_config_mode {
STM32L4X_PIN_CONFIG_BIAS_HIGH_IMPEDANCE = 0,
STM32L4X_PIN_CONFIG_BIAS_PULL_UP,
STM32L4X_PIN_CONFIG_BIAS_PULL_DOWN,
STM32L4X_PIN_CONFIG_ANALOG,
STM32L4X_PIN_CONFIG_OPEN_DRAIN,
STM32L4X_PIN_CONFIG_OPEN_DRAIN_PULL_UP,
STM32L4X_PIN_CONFIG_OPEN_DRAIN_PULL_DOWN,
STM32L4X_PIN_CONFIG_PUSH_PULL,
STM32L4X_PIN_CONFIG_PUSH_PULL_PULL_UP,
STM32L4X_PIN_CONFIG_PUSH_PULL_PULL_DOWN,
};
#endif /* _STM32L4X_SOC_PINMUX_H_ */

View file

@ -0,0 +1,24 @@
/*
* Copyright (c) 2016 Open-RnD Sp. z o.o.
* Copyright (c) 2016 BayLibre, SAS
*
* 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 _STM32L4X_SOC_REGISTERS_H_
#define _STM32L4X_SOC_REGISTERS_H_
/* include register mapping headers */
#include "syscfg_registers.h"
#endif /* _STM32L4X_SOC_REGISTERS_H_ */

View file

@ -0,0 +1,36 @@
/*
* Copyright (c) 2016 BayLibre, SAS
*
* 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 _STM32L4X_SYSCFG_REGISTERS_H_
#define _STM32L4X_SYSCFG_REGISTERS_H_
#define STM32L4X_SYSCFG_EXTICR_PIN_MASK 7
/* SYSCFG registers */
struct stm32l4x_syscfg {
uint32_t memrmp;
uint32_t cfgr1;
uint32_t exticr1;
uint32_t exticr2;
uint32_t exticr3;
uint32_t exticr4;
uint32_t scsr;
uint32_t cfgr2;
uint32_t swpr;
uint32_t skr;
};
#endif /* _STM32L4X_SYSCFG_REGISTERS_H_ */

View file

@ -26,6 +26,8 @@ endif
ifdef CONFIG_SOC_SERIES_STM32L4X ifdef CONFIG_SOC_SERIES_STM32L4X
obj-y += stm32l4xx/drivers/src/stm32l4xx_hal.o obj-y += stm32l4xx/drivers/src/stm32l4xx_hal.o
obj-y += stm32l4xx/drivers/src/stm32l4xx_hal_rcc.o
obj-$(CONFIG_SERIAL_HAS_DRIVER) += stm32l4xx/drivers/src/stm32l4xx_hal_uart.o
obj-y += stm32l4xx/soc/system_stm32l4xx.o obj-y += stm32l4xx/soc/system_stm32l4xx.o
endif endif