subrepo:
  subdir:   "libopencm3"
  merged:   "f5813a54"
upstream:
  origin:   "https://github.com/libopencm3/libopencm3"
  branch:   "master"
  commit:   "f5813a54"
git-subrepo:
  version:  "0.4.3"
  origin:   "???"
  commit:   "???"
This commit is contained in:
2021-09-30 16:34:10 +03:00
parent 1a441e5806
commit 244fdbc35c
1125 changed files with 185440 additions and 0 deletions

View File

@@ -0,0 +1,62 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
LIBNAME = libopencm3_stm32f2
SRCLIBDIR ?= ../..
CC = $(PREFIX)gcc
AR = $(PREFIX)ar
TGT_CFLAGS = -Os \
-Wall -Wextra -Wimplicit-function-declaration \
-Wredundant-decls -Wmissing-prototypes -Wstrict-prototypes \
-Wundef -Wshadow \
-I../../../include -fno-common \
-mcpu=cortex-m3 -mthumb $(FP_FLAGS) -Wstrict-prototypes \
-ffunction-sections -fdata-sections -MD -DSTM32F2
TGT_CFLAGS += $(DEBUG_FLAGS)
TGT_CFLAGS += $(STANDARD_FLAGS)
# ARFLAGS = rcsv
ARFLAGS = rcs
OBJS += crc_common_all.o
OBJS += crypto_common_f24.o
OBJS += dac_common_all.o dac_common_v1.o
OBJS += desig_common_all.o desig_common_v1.o
OBJS += dma_common_f24.o
OBJS += exti_common_all.o
OBJS += flash.o flash_common_all.o flash_common_f.o flash_common_f24.o flash_common_idcache.o
OBJS += gpio_common_all.o gpio_common_f0234.o
OBJS += hash_common_f24.o
OBJS += i2c_common_v1.o
OBJS += iwdg_common_all.o
OBJS += rcc.o rcc_common_all.o
OBJS += rng_common_v1.o
OBJS += rtc_common_l1f024.o
OBJS += spi_common_all.o spi_common_v1.o spi_common_v1_frf.o
OBJS += timer_common_all.o timer_common_f0234.o timer_common_f24.o
OBJS += usart_common_all.o usart_common_f124.o
OBJS += usb.o usb_standard.o usb_control.o usb_msc.o
OBJS += usb_hid.o
OBJS += usb_audio.o usb_cdc.o usb_midi.o
OBJS += usb_dwc_common.o usb_f107.o usb_f207.o
VPATH += ../../usb:../:../../cm3:../common
include ../../Makefile.include

View File

@@ -0,0 +1,31 @@
/** @defgroup crypto_file CRYPTO
*
* @ingroup STM32F2xx
*
* @brief <b>libopencm3 STM32F2xx Cryptographic controller</b>
*
* @version 1.0.0
*
* @date 14 January 2014
*
* LGPL License Terms @ref lgpl_license
*/
/*
* This file is part of the libopencm3 project.
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/crypto.h>

View File

@@ -0,0 +1,83 @@
/** @defgroup flash_file FLASH peripheral API
*
* @ingroup peripheral_apis
*
* @brief <b>libopencm3 STM32F2xx FLASH</b>
*
* @version 1.0.0
*
* @author @htmlonly &copy; @endhtmlonly 2010
* Thomas Otto <tommi@viadmin.org>
* @author @htmlonly &copy; @endhtmlonly 2010
* Mark Butler <mbutler@physics.otago.ac.nz>
*
* @date 14 January 2014
*
* This library supports the FLASH memory controller in the STM32F2
* series of ARM Cortex Microcontrollers by ST Microelectronics.
*
* For the STM32F2xx, accessing FLASH memory is described briefly in
* section 2.3.3 of the STM32F2xx Reference Manual.
* For detailed programming information see:
* PM0059 programming manual: STM32F10xxx Flash programming
* June 2013, Doc ID DocID15687 Rev 5
*
* LGPL License Terms @ref lgpl_license
*/
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
* Copyright (C) 2010 Mark Butler <mbutler@physics.otago.ac.nz>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
/**@{*/
#include <libopencm3/stm32/flash.h>
void flash_wait_for_last_operation(void)
{
while ((FLASH_SR & FLASH_SR_BSY) == FLASH_SR_BSY);
}
/*---------------------------------------------------------------------------*/
/** @brief Clear the Programming Sequence Error Flag
This flag is set when incorrect programming configuration has been made.
*/
void flash_clear_pgserr_flag(void)
{
FLASH_SR |= FLASH_SR_PGSERR;
}
/*---------------------------------------------------------------------------*/
/** @brief Clear All Status Flags
Program error, end of operation, write protect error, busy.
*/
void flash_clear_status_flags(void)
{
flash_clear_pgserr_flag();
flash_clear_pgaerr_flag();
flash_clear_wrperr_flag();
flash_clear_pgperr_flag();
flash_clear_eop_flag();
}
/**@}*/

View File

@@ -0,0 +1,32 @@
/** @defgroup i2c_file I2C
*
* @ingroup STM32F2xx
*
* @brief <b>libopencm3 STM32F2xx I2C</b>
*
* @version 1.0.0
*
* @date 15 October 2012
*
* LGPL License Terms @ref lgpl_license
*/
/*
* This file is part of the libopencm3 project.
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/i2c.h>

View File

@@ -0,0 +1,444 @@
/** @defgroup rcc_file RCC peripheral API
*
* @ingroup peripheral_apis
*
* @section rcc_f2_api_ex Reset and Clock Control API.
*
* @brief <b>libopencm3 STM32F2xx Reset and Clock Control</b>
*
* @author @htmlonly &copy; @endhtmlonly 2013 Frantisek Burian <BuFran at seznam.cz>
*
* @date 18 Jun 2013
*
* This library supports the Reset and Clock Control System in the STM32 series
* of ARM Cortex Microcontrollers by ST Microelectronics.
*
* LGPL License Terms @ref lgpl_license
*/
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2009 Federico Ruiz-Ugalde <memeruiz at gmail dot com>
* Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
* Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/cm3/assert.h>
#include <libopencm3/stm32/rcc.h>
#include <libopencm3/stm32/flash.h>
/**@{*/
/* Set the default clock frequencies after reset. */
uint32_t rcc_ahb_frequency = 16000000;
uint32_t rcc_apb1_frequency = 16000000;
uint32_t rcc_apb2_frequency = 16000000;
const struct rcc_clock_scale rcc_hse_8mhz_3v3[RCC_CLOCK_3V3_END] = {
{ /* 120MHz */
.pllm = 8,
.plln = 240,
.pllp = 2,
.pllq = 5,
.hpre = RCC_CFGR_HPRE_NODIV,
.ppre1 = RCC_CFGR_PPRE_DIV4,
.ppre2 = RCC_CFGR_PPRE_DIV2,
.flash_config = FLASH_ACR_DCEN | FLASH_ACR_ICEN |
FLASH_ACR_LATENCY_3WS,
.apb1_frequency = 30000000,
.apb2_frequency = 60000000,
},
};
void rcc_osc_ready_int_clear(enum rcc_osc osc)
{
switch (osc) {
case RCC_PLL:
RCC_CIR |= RCC_CIR_PLLRDYC;
break;
case RCC_HSE:
RCC_CIR |= RCC_CIR_HSERDYC;
break;
case RCC_HSI:
RCC_CIR |= RCC_CIR_HSIRDYC;
break;
case RCC_LSE:
RCC_CIR |= RCC_CIR_LSERDYC;
break;
case RCC_LSI:
RCC_CIR |= RCC_CIR_LSIRDYC;
break;
}
}
void rcc_osc_ready_int_enable(enum rcc_osc osc)
{
switch (osc) {
case RCC_PLL:
RCC_CIR |= RCC_CIR_PLLRDYIE;
break;
case RCC_HSE:
RCC_CIR |= RCC_CIR_HSERDYIE;
break;
case RCC_HSI:
RCC_CIR |= RCC_CIR_HSIRDYIE;
break;
case RCC_LSE:
RCC_CIR |= RCC_CIR_LSERDYIE;
break;
case RCC_LSI:
RCC_CIR |= RCC_CIR_LSIRDYIE;
break;
}
}
void rcc_osc_ready_int_disable(enum rcc_osc osc)
{
switch (osc) {
case RCC_PLL:
RCC_CIR &= ~RCC_CIR_PLLRDYIE;
break;
case RCC_HSE:
RCC_CIR &= ~RCC_CIR_HSERDYIE;
break;
case RCC_HSI:
RCC_CIR &= ~RCC_CIR_HSIRDYIE;
break;
case RCC_LSE:
RCC_CIR &= ~RCC_CIR_LSERDYIE;
break;
case RCC_LSI:
RCC_CIR &= ~RCC_CIR_LSIRDYIE;
break;
}
}
int rcc_osc_ready_int_flag(enum rcc_osc osc)
{
switch (osc) {
case RCC_PLL:
return ((RCC_CIR & RCC_CIR_PLLRDYF) != 0);
break;
case RCC_HSE:
return ((RCC_CIR & RCC_CIR_HSERDYF) != 0);
break;
case RCC_HSI:
return ((RCC_CIR & RCC_CIR_HSIRDYF) != 0);
break;
case RCC_LSE:
return ((RCC_CIR & RCC_CIR_LSERDYF) != 0);
break;
case RCC_LSI:
return ((RCC_CIR & RCC_CIR_LSIRDYF) != 0);
break;
}
cm3_assert_not_reached();
}
void rcc_css_int_clear(void)
{
RCC_CIR |= RCC_CIR_CSSC;
}
int rcc_css_int_flag(void)
{
return ((RCC_CIR & RCC_CIR_CSSF) != 0);
}
bool rcc_is_osc_ready(enum rcc_osc osc)
{
switch (osc) {
case RCC_PLL:
return RCC_CR & RCC_CR_PLLRDY;
case RCC_HSE:
return RCC_CR & RCC_CR_HSERDY;
case RCC_HSI:
return RCC_CR & RCC_CR_HSIRDY;
case RCC_LSE:
return RCC_BDCR & RCC_BDCR_LSERDY;
case RCC_LSI:
return RCC_CSR & RCC_CSR_LSIRDY;
}
return false;
}
void rcc_wait_for_osc_ready(enum rcc_osc osc)
{
while (!rcc_is_osc_ready(osc));
}
void rcc_wait_for_sysclk_status(enum rcc_osc osc)
{
switch (osc) {
case RCC_PLL:
while (((RCC_CFGR >> RCC_CFGR_SWS_SHIFT) & RCC_CFGR_SWS_MASK) !=
RCC_CFGR_SWS_PLL);
break;
case RCC_HSE:
while (((RCC_CFGR >> RCC_CFGR_SWS_SHIFT) & RCC_CFGR_SWS_MASK) !=
RCC_CFGR_SWS_HSE);
break;
case RCC_HSI:
while (((RCC_CFGR >> RCC_CFGR_SWS_SHIFT) & RCC_CFGR_SWS_MASK) !=
RCC_CFGR_SWS_HSI);
break;
default:
/* Shouldn't be reached. */
break;
}
}
void rcc_osc_on(enum rcc_osc osc)
{
switch (osc) {
case RCC_PLL:
RCC_CR |= RCC_CR_PLLON;
break;
case RCC_HSE:
RCC_CR |= RCC_CR_HSEON;
break;
case RCC_HSI:
RCC_CR |= RCC_CR_HSION;
break;
case RCC_LSE:
RCC_BDCR |= RCC_BDCR_LSEON;
break;
case RCC_LSI:
RCC_CSR |= RCC_CSR_LSION;
break;
}
}
void rcc_osc_off(enum rcc_osc osc)
{
switch (osc) {
case RCC_PLL:
RCC_CR &= ~RCC_CR_PLLON;
break;
case RCC_HSE:
RCC_CR &= ~RCC_CR_HSEON;
break;
case RCC_HSI:
RCC_CR &= ~RCC_CR_HSION;
break;
case RCC_LSE:
RCC_BDCR &= ~RCC_BDCR_LSEON;
break;
case RCC_LSI:
RCC_CSR &= ~RCC_CSR_LSION;
break;
}
}
void rcc_css_enable(void)
{
RCC_CR |= RCC_CR_CSSON;
}
void rcc_css_disable(void)
{
RCC_CR &= ~RCC_CR_CSSON;
}
void rcc_set_sysclk_source(uint32_t clk)
{
uint32_t reg32;
reg32 = RCC_CFGR;
reg32 &= ~((1 << 1) | (1 << 0));
RCC_CFGR = (reg32 | clk);
}
void rcc_set_pll_source(uint32_t pllsrc)
{
uint32_t reg32;
reg32 = RCC_PLLCFGR;
reg32 &= ~(1 << 22);
RCC_PLLCFGR = (reg32 | (pllsrc << 22));
}
void rcc_set_ppre2(uint32_t ppre2)
{
uint32_t reg32;
reg32 = RCC_CFGR;
reg32 &= ~((1 << 13) | (1 << 14) | (1 << 15));
RCC_CFGR = (reg32 | (ppre2 << 13));
}
void rcc_set_ppre1(uint32_t ppre1)
{
uint32_t reg32;
reg32 = RCC_CFGR;
reg32 &= ~((1 << 10) | (1 << 11) | (1 << 12));
RCC_CFGR = (reg32 | (ppre1 << 10));
}
void rcc_set_hpre(uint32_t hpre)
{
uint32_t reg32;
reg32 = RCC_CFGR;
reg32 &= ~((1 << 4) | (1 << 5) | (1 << 6) | (1 << 7));
RCC_CFGR = (reg32 | (hpre << 4));
}
void rcc_set_rtcpre(uint32_t rtcpre)
{
uint32_t reg32;
reg32 = RCC_CFGR;
reg32 &= ~((1 << 16) | (1 << 17) | (1 << 18) | (1 << 19) | (1 << 20));
RCC_CFGR = (reg32 | (rtcpre << 16));
}
void rcc_set_main_pll_hsi(uint32_t pllm, uint32_t plln, uint32_t pllp,
uint32_t pllq)
{
RCC_PLLCFGR = (pllm << RCC_PLLCFGR_PLLM_SHIFT) |
(plln << RCC_PLLCFGR_PLLN_SHIFT) |
(((pllp >> 1) - 1) << RCC_PLLCFGR_PLLP_SHIFT) |
(pllq << RCC_PLLCFGR_PLLQ_SHIFT);
}
void rcc_set_main_pll_hse(uint32_t pllm, uint32_t plln, uint32_t pllp,
uint32_t pllq)
{
RCC_PLLCFGR = (pllm << RCC_PLLCFGR_PLLM_SHIFT) |
(plln << RCC_PLLCFGR_PLLN_SHIFT) |
(((pllp >> 1) - 1) << RCC_PLLCFGR_PLLP_SHIFT) |
RCC_PLLCFGR_PLLSRC |
(pllq << RCC_PLLCFGR_PLLQ_SHIFT);
}
uint32_t rcc_system_clock_source(void)
{
/* Return the clock source which is used as system clock. */
return (RCC_CFGR & 0x000c) >> 2;
}
void rcc_clock_setup_hse_3v3(const struct rcc_clock_scale *clock)
{
/* Enable internal high-speed oscillator. */
rcc_osc_on(RCC_HSI);
rcc_wait_for_osc_ready(RCC_HSI);
/* Select HSI as SYSCLK source. */
rcc_set_sysclk_source(RCC_CFGR_SW_HSI);
/* Enable external high-speed oscillator 8MHz. */
rcc_osc_on(RCC_HSE);
rcc_wait_for_osc_ready(RCC_HSE);
/*
* Set prescalers for AHB, ADC, APB1, APB2.
* Do this before touching the PLL (TODO: why?).
*/
rcc_set_hpre(clock->hpre);
rcc_set_ppre1(clock->ppre1);
rcc_set_ppre2(clock->ppre2);
/* Disable PLL oscillator before changing its configuration. */
rcc_osc_off(RCC_PLL);
/* Configure the PLL oscillator. */
rcc_set_main_pll_hse(clock->pllm, clock->plln,
clock->pllp, clock->pllq);
/* Enable PLL oscillator and wait for it to stabilize. */
rcc_osc_on(RCC_PLL);
rcc_wait_for_osc_ready(RCC_PLL);
/* Configure flash settings. */
flash_set_ws(clock->flash_config);
/* Select PLL as SYSCLK source. */
rcc_set_sysclk_source(RCC_CFGR_SW_PLL);
/* Wait for PLL clock to be selected. */
rcc_wait_for_sysclk_status(RCC_PLL);
/* Set the peripheral clock frequencies used. */
rcc_apb1_frequency = clock->apb1_frequency;
rcc_apb2_frequency = clock->apb2_frequency;
}
void rcc_backupdomain_reset(void)
{
/* Set the backup domain software reset. */
RCC_BDCR |= RCC_BDCR_BDRST;
/* Clear the backup domain software reset. */
RCC_BDCR &= ~RCC_BDCR_BDRST;
}
/*---------------------------------------------------------------------------*/
/** @brief Get the peripheral clock speed for the USART at base specified.
* @param usart Base address of USART to get clock frequency for.
*/
uint32_t rcc_get_usart_clk_freq(uint32_t usart)
{
if (usart == USART1_BASE || usart == USART6_BASE) {
return rcc_apb2_frequency;
} else {
return rcc_apb1_frequency;
}
}
/*---------------------------------------------------------------------------*/
/** @brief Get the peripheral clock speed for the Timer at base specified.
* @param timer Base address of TIM to get clock frequency for.
*/
uint32_t rcc_get_timer_clk_freq(uint32_t timer)
{
/* Handle APB1 timer clocks. */
if (timer >= TIM2_BASE && timer <= TIM14_BASE) {
uint8_t ppre1 = (RCC_CFGR >> RCC_CFGR_PPRE1_SHIFT) & RCC_CFGR_PPRE1_MASK;
return (ppre1 == RCC_CFGR_PPRE_DIV_NONE) ? rcc_apb1_frequency
: 2 * rcc_apb1_frequency;
} else {
uint8_t ppre2 = (RCC_CFGR >> RCC_CFGR_PPRE2_SHIFT) & RCC_CFGR_PPRE2_MASK;
return (ppre2 == RCC_CFGR_PPRE_DIV_NONE) ? rcc_apb2_frequency
: 2 * rcc_apb2_frequency;
}
}
/*---------------------------------------------------------------------------*/
/** @brief Get the peripheral clock speed for the I2C device at base specified.
* @param i2c Base address of I2C to get clock frequency for.
*/
uint32_t rcc_get_i2c_clk_freq(uint32_t i2c __attribute__((unused)))
{
return rcc_apb1_frequency;
}
/*---------------------------------------------------------------------------*/
/** @brief Get the peripheral clock speed for the SPI device at base specified.
* @param spi Base address of SPI device to get clock frequency for (e.g. SPI1_BASE).
*/
uint32_t rcc_get_spi_clk_freq(uint32_t spi) {
if (spi == SPI1_BASE) {
return rcc_apb2_frequency;
} else {
return rcc_apb1_frequency;
}
}
/**@}*/

View File

@@ -0,0 +1,31 @@
/* This file is used for documentation purposes. It does not need
to be compiled. All source code is in the common area.
If there is any device specific code required it can be included here,
in which case this file must be added to the compile list. */
/** @defgroup rng_file RNG
@ingroup STM32F2xx
@brief <b>libopencm3 STM32F2xx RNG</b>
*/
/*
* This file is part of the libopencm3 project.
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/rng.h>