periph_cpu.h File Reference

Shared CPU specific definitions for the STM32 family. More...

Detailed Description

Shared CPU specific definitions for the STM32 family.

Author
Hauke Petersen hauke.nosp@m..pet.nosp@m.ersen.nosp@m.@fu-.nosp@m.berli.nosp@m.n.de
Vincent Dupont vince.nosp@m.nt@o.nosp@m.takey.nosp@m.s.co.nosp@m.m

Definition in file periph_cpu.h.

#include <limits.h>
#include "cpu.h"
#include "macros/units.h"
+ Include dependency graph for periph_cpu.h:
+ This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Data Structures

struct  dma_conf_t
 DMA configuration. More...
 
struct  adc_conf_t
 ADC device configuration. More...
 
struct  dac_conf_t
 DAC line configuration data. More...
 
struct  timer_conf_t
 Timer configuration. More...
 
struct  pwm_chan_t
 PWM channel. More...
 
struct  pwm_conf_t
 PWM device configuration. More...
 
struct  qdec_chan_t
 QDEC channel. More...
 
struct  qdec_conf_t
 QDEC configuration. More...
 
struct  uart_conf_t
 UART device configuration. More...
 
struct  spi_conf_t
 SPI configuration structure type. More...
 
struct  i2c_conf_t
 I2C configuration options. More...
 
struct  stm32_usb_otg_fshs_config_t
 stm32 USB OTG configuration More...
 
struct  eth_conf_t
 Ethernet Peripheral configuration. More...
 
struct  eth_dma_desc
 Layout of enhanced RX/TX DMA descriptor. More...
 

Macros

#define PM_EWUP_CONFIG   (0U)
 Wake-up pins configuration (CSR register)
 
#define GPIO_UNDEF   (0xffffffff)
 Definition of a fitting UNDEF value.
 
#define GPIO_PIN(x, y)   ((GPIOA_BASE + (x << 10)) | y)
 Define a CPU specific GPIO pin generator macro.
 
#define SPI_HWCS_MASK   (0xffffff00)
 Define a magic number that tells us to use hardware chip select. More...
 
#define SPI_HWCS(x)   (SPI_HWCS_MASK | x)
 Override the default SPI hardware chip select access macro. More...
 
#define GPIO_MODE(io, pr, ot)   ((io << 0) | (pr << 2) | (ot << 4))
 Generate GPIO mode bitfields. More...
 
#define DMA_CHAN_CONFIG_UNSUPPORTED   (UINT8_MAX)
 DMA channel/trigger configuration for DMA peripherals without channel/trigger filtering such as the stm32f1 and stm32f3.
 
#define UART_TXBUF_SIZE   (64)
 Size of the UART TX buffer for non-blocking mode.
 

Typedefs

typedef unsigned dma_t
 DMA type.
 
typedef struct eth_dma_desc edma_desc_t
 Layout of enhanced RX/TX DMA descriptor. More...
 

Enumerations

enum  bus_t { APB1, APB2 }
 Available peripheral buses. More...
 
enum  
 Available GPIO ports.
 
enum  gpio_af_t {
  GPIO_AF0 = 0, GPIO_AF1, GPIO_AF2, GPIO_AF3,
  GPIO_AF4, GPIO_AF5, GPIO_AF6, GPIO_AF7,
  GPIO_AF8, GPIO_AF9, GPIO_AF10, GPIO_AF11,
  GPIO_AF12, GPIO_AF13, GPIO_AF14, GPIO_AF15,
  GPIO_AF0 = 0, GPIO_AF1, GPIO_AF2, GPIO_AF3,
  GPIO_AF4, GPIO_AF5, GPIO_AF6, GPIO_AF7,
  GPIO_AF8, GPIO_AF9, GPIO_AF10, GPIO_AF11,
  GPIO_AF12, GPIO_AF13, GPIO_AF14, GPIO_AF15
}
 Available MUX values for configuring a pin's alternate function. More...
 
enum  dma_mode_t { DMA_PERIPH_TO_MEM = 0, DMA_MEM_TO_PERIPH = 1, DMA_MEM_TO_MEM = 2 }
 DMA modes. More...
 
enum  uart_type_t { KINETIS_UART, KINETIS_LPUART, STM32_USART, STM32_LPUART }
 UART hardware module types. More...
 
enum  stm32_usb_otg_fshs_type_t { STM32_USB_OTG_FS = 0, STM32_USB_OTG_HS = 1 }
 USB OTG peripheral type. More...
 
enum  stm32_usb_otg_fshs_phy_t { STM32_USB_OTG_PHY_BUILTIN, STM32_USB_OTG_PHY_ULPI }
 Type of USB OTG peripheral phy. More...
 
enum  eth_mode_t { MII = 18, RMII = 9, SMI = 2 }
 STM32 Ethernet configuration mode. More...
 

Functions

uint32_t periph_apb_clk (uint8_t bus)
 Get the actual bus clock frequency for the APB buses. More...
 
uint32_t periph_timer_clk (uint8_t bus)
 Get the actual timer clock frequency. More...
 
void periph_clk_en (bus_t bus, uint32_t mask)
 Enable the given peripheral clock. More...
 
void periph_lpclk_dis (bus_t bus, uint32_t mask)
 Disable the given peripheral clock. More...
 
void periph_lpclk_en (bus_t bus, uint32_t mask)
 Enable the given peripheral clock in low power mode. More...
 
void periph_clk_dis (bus_t bus, uint32_t mask)
 Disable the given peripheral clock in low power mode. More...
 
void gpio_init_af (gpio_t pin, gpio_af_t af)
 Configure the alternate function for the given pin. More...
 
void gpio_init_analog (gpio_t pin)
 Configure the given pin to be used as ADC input. More...
 
#define CPUID_LEN   (12U)
 CPU specific LSI clock speed. More...
 
#define CPUID_ADDR   (UID_BASE)
 Starting address of the CPU ID.
 
#define PROVIDES_PM_LAYERED_OFF
 We provide our own pm_off() function for all STM32-based CPUs.
 
#define TIMER_CHANNEL_NUMOF   (4U)
 All STM timers have 4 capture-compare channels.
 
#define TIM_CHAN(tim, chan)   *(&dev(tim)->CCR1 + chan)
 Define a macro for accessing a timer channel.
 
#define QDEC_CHAN   (2U)
 All STM QDEC timers have 2 capture channels.
 
#define PERIPH_SPI_NEEDS_TRANSFER_BYTE
 Use the shared SPI functions.
 
#define PERIPH_SPI_NEEDS_TRANSFER_REG
 
#define PERIPH_SPI_NEEDS_TRANSFER_REGS
 

PM definitions

#define PM_NUM_MODES   (2U)
 Number of usable low power modes.
 

Power modes

#define STM32_PM_STOP   (1U)
 
#define STM32_PM_STANDBY   (0U)
 

WDT upper and lower bound times in ms

#define NWDT_TIME_LOWER_LIMIT   (1U)
 
#define NWDT_TIME_UPPER_LIMIT
 
#define WDT_HAS_STOP   (0U)
 
#define WDT_HAS_INIT   (0U)
 

Use the shared I2C functions

#define PERIPH_I2C_NEED_READ_REG
 Use read reg function from periph common.
 
#define PERIPH_I2C_NEED_WRITE_REG
 Use write reg function from periph common.
 
#define PERIPH_I2C_NEED_READ_REGS
 

DMA Increment modes

#define DMA_INC_SRC_ADDR   (0x04)
 
#define DMA_INC_DST_ADDR   (0x08)
 
#define DMA_INC_BOTH_ADDR   (DMA_INC_SRC_ADDR | DMA_INC_DST_ADDR)
 

DMA data width

#define DMA_DATA_WIDTH_BYTE   (0x00)
 
#define DMA_DATA_WIDTH_HALF_WORD   (0x01)
 
#define DMA_DATA_WIDTH_WORD   (0x02)
 
#define DMA_DATA_WIDTH_MASK   (0x03)
 
#define DMA_DATA_WIDTH_SHIFT   (0)
 
#define HAVE_SPI_CLK_T
 Override SPI clock speed values.
 
enum  {
  SPI_CLK_100KHZ = KHZ(100), SPI_CLK_400KHZ = KHZ(400), SPI_CLK_1MHZ = MHZ(1), SPI_CLK_5MHZ = MHZ(5),
  SPI_CLK_10MHZ = MHZ(10)
}
 
typedef uint32_t spi_clk_t
 SPI clock type.
 

Flags in the status word of the Ethernet enhanced RX DMA descriptor

#define RX_DESC_STAT_LS   (BIT8)
 If set, descriptor is the last of a frame.
 
#define RX_DESC_STAT_FS   (BIT9)
 If set, descriptor is the first of a frame.
 
#define RX_DESC_STAT_FL   (0x3FFF0000) /* bits 16-29 */
 Frame length. More...
 
#define RX_DESC_STAT_DE   (BIT14)
 If set, a frame too large to fit buffers given by descriptors was received.
 
#define RX_DESC_STAT_ES   (BIT14)
 If set, an error occurred during RX.
 
#define RX_DESC_STAT_OWN   (BIT31)
 If set, descriptor is owned by DMA, otherwise by CPU.
 

Flags in the control word of the Ethernet enhanced RX DMA descriptor

#define RX_DESC_CTRL_RCH   (BIT14)
 Indicates if RDES3 points to the next DMA descriptor (1), or to a second buffer (0) More...
 

Flags in the status word of the Ethernet enhanced TX DMA descriptor

#define TX_DESC_STAT_UF   (BIT1)
 If set, an underflow occurred while sending.
 
#define TX_DESC_STAT_EC   (BIT8)
 If set, TX was aborted due to excessive collisions (half-duplex only)
 
#define TX_DESC_STAT_NC   (BIT10)
 If set, no carrier was detected (TX aborted)
 
#define TX_DESC_STAT_ES   (BIT15)
 If set, one or more error occurred.
 
#define TX_DESC_STAT_TTSS   (BIT17)
 If set, the descriptor contains a valid PTP timestamp.
 
#define TX_DESC_STAT_TCH   (BIT20)
 Indicates if TDES3 points to the next DMA descriptor (1), or to a second buffer (0) More...
 
#define TX_DESC_STAT_TER   (BIT21)
 If set, DMA will return to first descriptor in ring afterwards.
 
#define TX_DESC_STAT_CIC   (BIT22 | BIT23)
 Checksum insertion control. More...
 
#define TX_DESC_STAT_TTSE   (BIT25)
 If set, an PTP timestamp is added to the descriptor after TX completed.
 
#define TX_DESC_STAT_FS   (BIT28)
 If set, buffer contains first segment of frame to transmit.
 
#define TX_DESC_STAT_LS   (BIT29)
 If set, buffer contains last segment of frame to transmit.
 
#define TX_DESC_STAT_IC   (BIT30)
 If set, trigger IRQ on completion.
 
#define TX_DESC_STAT_OWN   (BIT31)
 If set, descriptor is owned by DMA, otherwise by CPU.
 

Macro Definition Documentation

◆ CPUID_LEN

#define CPUID_LEN   (12U)

CPU specific LSI clock speed.

Length of the CPU_ID in octets

This is the same for all members of the stm32 family

Definition at line 92 of file periph_cpu.h.

◆ GPIO_MODE

#define GPIO_MODE (   io,
  pr,
  ot 
)    ((io << 0) | (pr << 2) | (ot << 4))

Generate GPIO mode bitfields.

We use 5 bit to encode the mode:

  • bit 0+1: pin mode (input / output)
  • bit 2+3: pull resistor configuration
  • bit 4: output type (0: push-pull, 1: open-drain)

Definition at line 383 of file periph_cpu.h.

◆ NWDT_TIME_UPPER_LIMIT

#define NWDT_TIME_UPPER_LIMIT
Value:
(4U * US_PER_MS * 4096U * (1 << 6U) \
/ CLOCK_LSI)

Definition at line 161 of file periph_cpu.h.

◆ RX_DESC_CTRL_RCH

#define RX_DESC_CTRL_RCH   (BIT14)

Indicates if RDES3 points to the next DMA descriptor (1), or to a second buffer (0)

If the bit is set, RDES3 (edma_desc_t::desc_next) will point to the next DMA descriptor rather than to a second frame-segment buffer. This is always set by the driver

Definition at line 1120 of file periph_cpu.h.

◆ RX_DESC_STAT_FL

#define RX_DESC_STAT_FL   (0x3FFF0000) /* bits 16-29 */

Frame length.

The length of the frame in host memory order including CRC. Only valid if RX_DESC_STAT_LS is set and RX_DESC_STAT_DE is not set.

Definition at line 1104 of file periph_cpu.h.

◆ SPI_HWCS

#define SPI_HWCS (   x)    (SPI_HWCS_MASK | x)

Override the default SPI hardware chip select access macro.

Since the CPU does only support one single hardware chip select line, we can detect the usage of non-valid lines by comparing to SPI_HWCS_VALID.

Definition at line 285 of file periph_cpu.h.

◆ SPI_HWCS_MASK

#define SPI_HWCS_MASK   (0xffffff00)

Define a magic number that tells us to use hardware chip select.

We use a random value here, that does clearly differentiate from any possible GPIO_PIN(x) value.

Definition at line 277 of file periph_cpu.h.

◆ TX_DESC_STAT_CIC

#define TX_DESC_STAT_CIC   (BIT22 | BIT23)

Checksum insertion control.

Value Meaning
0b00 Checksum insertion disabled
0b01 Calculate and insert checksum in IPv4 header
0b10 Calculate and insert IPv4 checksum, insert pre-calculated payload checksum
`0b11 Calculated and insert both IPv4 and payload checksum

Definition at line 1150 of file periph_cpu.h.

◆ TX_DESC_STAT_TCH

#define TX_DESC_STAT_TCH   (BIT20)

Indicates if TDES3 points to the next DMA descriptor (1), or to a second buffer (0)

If the bit is set, TDES3 (edma_desc_t::desc_next) will point to the next DMA descriptor rather than to a second frame-segment buffer. This is always set by the driver

Definition at line 1138 of file periph_cpu.h.

Typedef Documentation

◆ edma_desc_t

typedef struct eth_dma_desc edma_desc_t

Layout of enhanced RX/TX DMA descriptor.

Note
Don't confuse this with the normal RX/TX descriptor format.
Warning
The content of the status and control bits is different for RX and TX DMA descriptors

Enumeration Type Documentation

◆ anonymous enum

anonymous enum
Enumerator
SPI_CLK_100KHZ 

drive the SPI bus with 100KHz

SPI_CLK_400KHZ 

drive the SPI bus with 400KHz

SPI_CLK_1MHZ 

drive the SPI bus with 1MHz

SPI_CLK_5MHZ 

drive the SPI bus with 5MHz

SPI_CLK_10MHZ 

drive the SPI bus with 10MHz

Definition at line 651 of file periph_cpu.h.

◆ bus_t

enum bus_t

Available peripheral buses.

Enumerator
APB1 

APB1 bus.

APB2 

APB2 bus.

Definition at line 175 of file periph_cpu.h.

◆ dma_mode_t

enum dma_mode_t

DMA modes.

Enumerator
DMA_PERIPH_TO_MEM 

Peripheral to memory.

DMA_MEM_TO_PERIPH 

Memory to peripheral.

DMA_MEM_TO_MEM 

Memory to memory.

Definition at line 454 of file periph_cpu.h.

◆ eth_mode_t

enum eth_mode_t

STM32 Ethernet configuration mode.

Enumerator
MII 

Configuration for MII.

RMII 

Configuration for RMII.

SMI 

Configuration for SMI.

Definition at line 1041 of file periph_cpu.h.

◆ gpio_af_t

enum gpio_af_t

Available MUX values for configuring a pin's alternate function.

Enumerator
GPIO_AF0 

use alternate function 0

GPIO_AF1 

use alternate function 1

GPIO_AF2 

use alternate function 2

GPIO_AF3 

use alternate function 3

GPIO_AF4 

use alternate function 4

GPIO_AF5 

use alternate function 5

GPIO_AF6 

use alternate function 6

GPIO_AF7 

use alternate function 7

GPIO_AF8 

use alternate function 8

GPIO_AF9 

use alternate function 9

GPIO_AF10 

use alternate function 10

GPIO_AF11 

use alternate function 11

GPIO_AF12 

use alternate function 12

GPIO_AF13 

use alternate function 13

GPIO_AF14 

use alternate function 14

GPIO_AF15 

use alternate function 15

GPIO_AF0 

use alternate function 0

GPIO_AF1 

use alternate function 1

GPIO_AF2 

use alternate function 2

GPIO_AF3 

use alternate function 3

GPIO_AF4 

use alternate function 4

GPIO_AF5 

use alternate function 5

GPIO_AF6 

use alternate function 6

GPIO_AF7 

use alternate function 7

GPIO_AF8 

use alternate function 8

GPIO_AF9 

use alternate function 9

GPIO_AF10 

use alternate function 10

GPIO_AF11 

use alternate function 11

GPIO_AF12 

use alternate function 12

GPIO_AF13 

use alternate function 13

GPIO_AF14 

use alternate function 14

GPIO_AF15 

use alternate function 15

Definition at line 306 of file periph_cpu.h.

◆ stm32_usb_otg_fshs_phy_t

Type of USB OTG peripheral phy.

The FS type only supports the built-in type, the HS phy can have either the FS built-in phy enabled or the HS ULPI interface enabled.

Definition at line 819 of file periph_cpu.h.

◆ stm32_usb_otg_fshs_type_t

USB OTG peripheral type.

High speed peripheral is assumed to have DMA support available.

Warning
Only one of each type is supported at the moment, it is not supported to have two FS type or two HS type peripherals enabled on a single MCU.
Enumerator
STM32_USB_OTG_FS 

Full speed peripheral.

STM32_USB_OTG_HS 

High speed peripheral.

Definition at line 808 of file periph_cpu.h.

◆ uart_type_t

UART hardware module types.

Enumerator
KINETIS_UART 

Kinetis UART module type.

KINETIS_LPUART 

Kinetis Low-power UART (LPUART) module type.

STM32_USART 

STM32 USART module type.

STM32_LPUART 

STM32 Low-power UART (LPUART) module type.

Definition at line 582 of file periph_cpu.h.

Function Documentation

◆ gpio_init_af()

void gpio_init_af ( gpio_t  pin,
gpio_af_t  af 
)

Configure the alternate function for the given pin.

Parameters
[in]pinpin to configure
[in]afalternate function to use

◆ gpio_init_analog()

void gpio_init_analog ( gpio_t  pin)

Configure the given pin to be used as ADC input.

Parameters
[in]pinpin to configure

◆ periph_apb_clk()

uint32_t periph_apb_clk ( uint8_t  bus)

Get the actual bus clock frequency for the APB buses.

Parameters
[in]bustarget APBx bus
Returns
bus clock frequency in Hz

◆ periph_clk_dis()

void periph_clk_dis ( bus_t  bus,
uint32_t  mask 
)

Disable the given peripheral clock in low power mode.

Parameters
[in]busbus the peripheral is connected to
[in]maskbit in the RCC enable register

◆ periph_clk_en()

void periph_clk_en ( bus_t  bus,
uint32_t  mask 
)

Enable the given peripheral clock.

Parameters
[in]busbus the peripheral is connected to
[in]maskbit in the RCC enable register

◆ periph_lpclk_dis()

void periph_lpclk_dis ( bus_t  bus,
uint32_t  mask 
)

Disable the given peripheral clock.

Parameters
[in]busbus the peripheral is connected to
[in]maskbit in the RCC enable register

◆ periph_lpclk_en()

void periph_lpclk_en ( bus_t  bus,
uint32_t  mask 
)

Enable the given peripheral clock in low power mode.

Parameters
[in]busbus the peripheral is connected to
[in]maskbit in the RCC enable register

◆ periph_timer_clk()

uint32_t periph_timer_clk ( uint8_t  bus)

Get the actual timer clock frequency.

Parameters
[in]buscorresponding APBx bus
Returns
timer clock frequency in Hz
US_PER_MS
#define US_PER_MS
The number of microseconds per millisecond.
Definition: timex.h:54