Add software

This commit is contained in:
RocketGod
2022-09-22 09:26:57 -07:00
parent fee0ab05fd
commit 957ea3d712
4511 changed files with 1943182 additions and 0 deletions

View File

@ -0,0 +1,48 @@
##
## 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
PREFIX ?= arm-none-eabi
CC = $(PREFIX)-gcc
AR = $(PREFIX)-ar
CFLAGS = -Os -g \
-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
# ARFLAGS = rcsv
ARFLAGS = rcs
OBJS = gpio.o rcc.o
OBJS += crc_common_all.o dac_common_all.o dma_common_f24.o \
gpio_common_all.o gpio_common_f0234.o i2c_common_all.o \
iwdg_common_all.o rtc_common_l1f024.o spi_common_all.o \
spi_common_f124.o timer_common_all.o timer_common_f234.o \
timer_common_f24.o usart_common_all.o usart_common_f124.o \
flash_common_f234.o flash_common_f24.o hash_common_f24.o \
crypto_common_f24.o exti_common_all.o
VPATH += ../../usb:../:../../cm3:../common
include ../../Makefile.include

View File

@ -0,0 +1,34 @@
/** @defgroup crc_file CRC
@ingroup STM32F2xx
@brief <b>libopencm3 STM32F2xx CRC</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/crc.h>
#include <libopencm3/stm32/common/crc_common_all.h>

View File

@ -0,0 +1,33 @@
/** @defgroup dac_file DAC
@ingroup STM32F2xx
@brief <b>libopencm3 STM32F2xx DAC</b>
@version 1.0.0
@date 18 August 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/dac.h>
#include <libopencm3/stm32/common/dac_common_all.h>

View File

@ -0,0 +1,33 @@
/** @defgroup dma_file DMA
@ingroup STM32F2xx
@brief <b>libopencm3 STM32F2xx DMA</b>
@version 1.0.0
@date 30 November 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/dma.h>
#include <libopencm3/stm32/common/dma_common_f24.h>

View File

@ -0,0 +1,31 @@
/** @defgroup gpio_file GPIO
@ingroup STM32F2xx
@brief <b>libopencm3 STM32F2xx General Purpose I/O</b>
@version 1.0.0
@date 18 August 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/gpio.h>

View File

@ -0,0 +1,33 @@
/** @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>
#include <libopencm3/stm32/common/spi_common_all.h>

View File

@ -0,0 +1,33 @@
/** @defgroup iwdg_file IWDG
@ingroup STM32F2xx
@brief <b>libopencm3 STM32F2xx Independent Watchdog Timer</b>
@version 1.0.0
@date 18 August 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/iwdg.h>
#include <libopencm3/stm32/common/iwdg_common_all.h>

View File

@ -0,0 +1,106 @@
/*
* 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/>.
*/
/* Generic linker script for STM32 targets using libopencm3. */
/* Memory regions must be defined in the ld script which includes this one. */
/* Enforce emmition of the vector table. */
EXTERN (vector_table)
/* Define the entry point of the output file. */
ENTRY(reset_handler)
/* Define sections. */
SECTIONS
{
.text : {
*(.vectors) /* Vector table */
*(.text*) /* Program code */
. = ALIGN(4);
*(.rodata*) /* Read-only data */
. = ALIGN(4);
} >rom
/* C++ Static constructors/destructors, also used for __attribute__
* ((constructor)) and the likes */
.preinit_array : {
. = ALIGN(4);
__preinit_array_start = .;
KEEP (*(.preinit_array))
__preinit_array_end = .;
} >rom
.init_array : {
. = ALIGN(4);
__init_array_start = .;
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array))
__init_array_end = .;
} >rom
.fini_array : {
. = ALIGN(4);
__fini_array_start = .;
KEEP (*(.fini_array))
KEEP (*(SORT(.fini_array.*)))
__fini_array_end = .;
} >rom
/*
* Another section used by C++ stuff, appears when using newlib with
* 64bit (long long) printf support
*/
.ARM.extab : {
*(.ARM.extab*)
} >rom
.ARM.exidx : {
__exidx_start = .;
*(.ARM.exidx*)
__exidx_end = .;
} >rom
. = ALIGN(4);
_etext = .;
.data : {
_data = .;
*(.data*) /* Read-write initialized data */
. = ALIGN(4);
_edata = .;
} >ram AT >rom
_data_loadaddr = LOADADDR(.data);
.bss : {
*(.bss*) /* Read-write zero initialized data */
*(COMMON)
. = ALIGN(4);
_ebss = .;
} >ram
/*
* The .eh_frame section appears to be used for C++ exception handling.
* You may need to fix this if you're using C++.
*/
/DISCARD/ : { *(.eh_frame) }
. = ALIGN(4);
end = .;
}
PROVIDE(_stack = ORIGIN(ram) + LENGTH(ram));

View File

@ -0,0 +1,415 @@
/*
* 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/f2/rcc.h>
#include <libopencm3/stm32/f2/flash.h>
/* Set the default ppre1 and ppre2 peripheral clock frequencies after reset. */
uint32_t rcc_ppre1_frequency = 16000000;
uint32_t rcc_ppre2_frequency = 16000000;
const clock_scale_t hse_8mhz_3v3[CLOCK_3V3_END] = {
{ /* 120MHz */
.pllm = 8,
.plln = 240,
.pllp = 2,
.pllq = 5,
.hpre = RCC_CFGR_HPRE_DIV_NONE,
.ppre1 = RCC_CFGR_PPRE_DIV_4,
.ppre2 = RCC_CFGR_PPRE_DIV_2,
.flash_config = FLASH_ACR_ICE | FLASH_ACR_DCE |
FLASH_ACR_LATENCY_3WS,
.apb1_frequency = 30000000,
.apb2_frequency = 60000000,
},
};
void rcc_osc_ready_int_clear(osc_t osc)
{
switch (osc) {
case PLL:
RCC_CIR |= RCC_CIR_PLLRDYC;
break;
case HSE:
RCC_CIR |= RCC_CIR_HSERDYC;
break;
case HSI:
RCC_CIR |= RCC_CIR_HSIRDYC;
break;
case LSE:
RCC_CIR |= RCC_CIR_LSERDYC;
break;
case LSI:
RCC_CIR |= RCC_CIR_LSIRDYC;
break;
}
}
void rcc_osc_ready_int_enable(osc_t osc)
{
switch (osc) {
case PLL:
RCC_CIR |= RCC_CIR_PLLRDYIE;
break;
case HSE:
RCC_CIR |= RCC_CIR_HSERDYIE;
break;
case HSI:
RCC_CIR |= RCC_CIR_HSIRDYIE;
break;
case LSE:
RCC_CIR |= RCC_CIR_LSERDYIE;
break;
case LSI:
RCC_CIR |= RCC_CIR_LSIRDYIE;
break;
}
}
void rcc_osc_ready_int_disable(osc_t osc)
{
switch (osc) {
case PLL:
RCC_CIR &= ~RCC_CIR_PLLRDYIE;
break;
case HSE:
RCC_CIR &= ~RCC_CIR_HSERDYIE;
break;
case HSI:
RCC_CIR &= ~RCC_CIR_HSIRDYIE;
break;
case LSE:
RCC_CIR &= ~RCC_CIR_LSERDYIE;
break;
case LSI:
RCC_CIR &= ~RCC_CIR_LSIRDYIE;
break;
}
}
int rcc_osc_ready_int_flag(osc_t osc)
{
switch (osc) {
case PLL:
return ((RCC_CIR & RCC_CIR_PLLRDYF) != 0);
break;
case HSE:
return ((RCC_CIR & RCC_CIR_HSERDYF) != 0);
break;
case HSI:
return ((RCC_CIR & RCC_CIR_HSIRDYF) != 0);
break;
case LSE:
return ((RCC_CIR & RCC_CIR_LSERDYF) != 0);
break;
case 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);
}
void rcc_wait_for_osc_ready(osc_t osc)
{
switch (osc) {
case PLL:
while ((RCC_CR & RCC_CR_PLLRDY) == 0);
break;
case HSE:
while ((RCC_CR & RCC_CR_HSERDY) == 0);
break;
case HSI:
while ((RCC_CR & RCC_CR_HSIRDY) == 0);
break;
case LSE:
while ((RCC_BDCR & RCC_BDCR_LSERDY) == 0);
break;
case LSI:
while ((RCC_CSR & RCC_CSR_LSIRDY) == 0);
break;
}
}
void rcc_wait_for_sysclk_status(osc_t osc)
{
switch (osc) {
case PLL:
while ((RCC_CFGR & ((1 << 1) | (1 << 0))) != RCC_CFGR_SWS_PLL);
break;
case HSE:
while ((RCC_CFGR & ((1 << 1) | (1 << 0))) != RCC_CFGR_SWS_HSE);
break;
case HSI:
while ((RCC_CFGR & ((1 << 1) | (1 << 0))) != RCC_CFGR_SWS_HSI);
break;
default:
/* Shouldn't be reached. */
break;
}
}
void rcc_osc_on(osc_t osc)
{
switch (osc) {
case PLL:
RCC_CR |= RCC_CR_PLLON;
break;
case HSE:
RCC_CR |= RCC_CR_HSEON;
break;
case HSI:
RCC_CR |= RCC_CR_HSION;
break;
case LSE:
RCC_BDCR |= RCC_BDCR_LSEON;
break;
case LSI:
RCC_CSR |= RCC_CSR_LSION;
break;
}
}
void rcc_osc_off(osc_t osc)
{
switch (osc) {
case PLL:
RCC_CR &= ~RCC_CR_PLLON;
break;
case HSE:
RCC_CR &= ~RCC_CR_HSEON;
break;
case HSI:
RCC_CR &= ~RCC_CR_HSION;
break;
case LSE:
RCC_BDCR &= ~RCC_BDCR_LSEON;
break;
case 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_osc_bypass_enable(osc_t osc)
{
switch (osc) {
case HSE:
RCC_CR |= RCC_CR_HSEBYP;
break;
case LSE:
RCC_BDCR |= RCC_BDCR_LSEBYP;
break;
case PLL:
case HSI:
case LSI:
/* Do nothing, only HSE/LSE allowed here. */
break;
}
}
void rcc_osc_bypass_disable(osc_t osc)
{
switch (osc) {
case HSE:
RCC_CR &= ~RCC_CR_HSEBYP;
break;
case LSE:
RCC_BDCR &= ~RCC_BDCR_LSEBYP;
break;
case PLL:
case HSI:
case LSI:
/* Do nothing, only HSE/LSE allowed here. */
break;
}
}
void rcc_peripheral_enable_clock(volatile uint32_t *reg, uint32_t en)
{
*reg |= en;
}
void rcc_peripheral_disable_clock(volatile uint32_t *reg, uint32_t en)
{
*reg &= ~en;
}
void rcc_peripheral_reset(volatile uint32_t *reg, uint32_t reset)
{
*reg |= reset;
}
void rcc_peripheral_clear_reset(volatile uint32_t *reg, uint32_t clear_reset)
{
*reg &= ~clear_reset;
}
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 clock_scale_t *clock)
{
/* Enable internal high-speed oscillator. */
rcc_osc_on(HSI);
rcc_wait_for_osc_ready(HSI);
/* Select HSI as SYSCLK source. */
rcc_set_sysclk_source(RCC_CFGR_SW_HSI);
/* Enable external high-speed oscillator 8MHz. */
rcc_osc_on(HSE);
rcc_wait_for_osc_ready(HSE);
/*
* Set prescalers for AHB, ADC, ABP1, ABP2.
* Do this before touching the PLL (TODO: why?).
*/
rcc_set_hpre(clock->hpre);
rcc_set_ppre1(clock->ppre1);
rcc_set_ppre2(clock->ppre2);
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(PLL);
rcc_wait_for_osc_ready(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(PLL);
/* Set the peripheral clock frequencies used. */
rcc_ppre1_frequency = clock->apb1_frequency;
rcc_ppre2_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;
}

View File

@ -0,0 +1,32 @@
/** @defgroup rtc_file RTC
*
* @ingroup STM32F2xx
*
* @brief <b>libopencm3 STM32F2xx RTC</b>
*
* @version 1.0.0
*
* @date 4 March 2013
*
* 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/rtc.h>
#include <libopencm3/stm32/common/rtc_common_l1f024.h>

View File

@ -0,0 +1,33 @@
/** @defgroup spi_file SPI
@ingroup STM32F2xx
@brief <b>libopencm3 STM32F2xx SPI</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/spi.h>
#include <libopencm3/stm32/common/spi_common_f24.h>

View File

@ -0,0 +1,40 @@
/* 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 timer_file Timers
@ingroup STM32F2xx
@brief <b>libopencm3 STM32F2xx Timers</b>
@version 1.0.0
@date 18 August 2012
*/
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Edward Cheeseman <evbuilder@users.sourceforge.org>
* Copyright (C) 2011 Stephen Caudle <scaudle@doceme.com>
*
* 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/timer.h>
#include <libopencm3/stm32/common/timer_common_f24.h>

View File

@ -0,0 +1,33 @@
/** @defgroup usart_file USART
@ingroup STM32F2xx
@brief <b>libopencm3 STM32F2xx USART</b>
@version 1.0.0
@date 30 August 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/usart.h>
#include <libopencm3/stm32/common/usart_common_all.h>