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,67 @@
##
## 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_stm32f1
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 $(FP_FLAGS) -mthumb -Wstrict-prototypes \
-ffunction-sections -fdata-sections -MD -DSTM32F1
TGT_CFLAGS += $(DEBUG_FLAGS)
TGT_CFLAGS += $(STANDARD_FLAGS)
# ARFLAGS = rcsv
ARFLAGS = rcs
OBJS += adc.o adc_common_v1.o
OBJS += can.o
OBJS += crc_common_all.o
OBJS += dac_common_all.o dac_common_v1.o
OBJS += desig_common_all.o desig_common_v1.o
OBJS += dma_common_l1f013.o
OBJS += exti_common_all.o
OBJS += flash.o flash_common_all.o flash_common_f.o flash_common_f01.o
OBJS += gpio.o gpio_common_all.o
OBJS += i2c_common_v1.o
OBJS += iwdg_common_all.o
OBJS += pwr_common_v1.o
OBJS += rcc.o rcc_common_all.o
OBJS += rtc.o
OBJS += spi_common_all.o spi_common_v1.o
OBJS += timer.o timer_common_all.o
OBJS += usart_common_all.o usart_common_f124.o
OBJS += mac.o mac_stm32fxx7.o
OBJS += phy.o phy_ksz80x1.o
OBJS += usb.o usb_control.o usb_standard.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
OBJS += st_usbfs_core.o st_usbfs_v1.o
VPATH += ../../usb:../:../../cm3:../common:../../ethernet
include ../../Makefile.include

View File

@@ -0,0 +1,443 @@
/** @addtogroup adc_file ADC peripheral API
@ingroup peripheral_apis
@version 1.0.0
@author @htmlonly &copy; @endhtmlonly 2009
Edward Cheeseman <evbuilder@users.sourceforge.net>
@author @htmlonly &copy; @endhtmlonly 2012
Ken Sarkies <ksarkies@internode.on.net>
@date 18 August 2012
This library supports the A/D Converter Control System in the STM32F1xx series
of ARM Cortex Microcontrollers by ST Microelectronics.
Devices can have up to three A/D converters each with their own set of
registers. However all the A/D converters share a common clock which is
prescaled from the APB2 clock by default by a minimum factor of 2 to a maximum
of 8.
Each A/D converter has up to 18 channels:
@li On ADC1 the analog channels 16 and 17 are internally connected to the
temperature
sensor and V<sub>REFINT</sub>, respectively.
@li On ADC2 the analog channels 16 and 17 are internally connected to
V<sub>SS</sub>.
@li On ADC3 the analog channels 9, 14, 15, 16 and 17 are internally connected
to V<sub>SS</sub>.
The conversions can occur as a one-off conversion whereby the process stops
once conversion is complete. The conversions can also be continuous wherein a
new conversion starts immediately the previous conversion has ended.
Conversion can occur as a single channel conversion or a scan of a group of
channels in either continuous or one-off mode. If more than one channel is
converted in a scan group, DMA must be used to transfer the data as there is
only one result register available. An interrupt can be set to occur at the end
of conversion, which occurs after all channels have been scanned.
A discontinuous mode allows a subgroup of group of a channels to be converted
in bursts of a given length.
Injected conversions allow a second group of channels to be converted
separately from the regular group. An interrupt can be set to occur at the end
of conversion, which occurs after all channels have been scanned.
@section adc_api_ex Basic ADC Handling API.
Example 1: Simple single channel conversion polled. Enable the peripheral clock
and ADC, reset ADC and set the prescaler divider. Set dual mode to independent
(default). Enable triggering for a software trigger.
@code
rcc_periph_clock_enable(RCC_ADC1);
adc_power_off(ADC1);
rcc_periph_reset_pulse(RST_ADC1);
rcc_set_adcpre(RCC_CFGR_ADCPRE_PCLK2_DIV2);
adc_set_dual_mode(ADC_CR1_DUALMOD_IND);
adc_disable_scan_mode(ADC1);
adc_set_single_conversion_mode(ADC1);
adc_set_sample_time(ADC1, ADC_CHANNEL0, ADC_SMPR_SMP_1DOT5CYC);
adc_enable_external_trigger_regular(ADC1, ADC_CR2_EXTSEL_SWSTART);
adc_power_on(ADC1);
adc_reset_calibration(ADC1);
adc_calibrate(ADC1);
adc_start_conversion_regular(ADC1);
while (! adc_eoc(ADC1));
reg16 = adc_read_regular(ADC1);
@endcode
LGPL License Terms @ref lgpl_license
*/
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2009 Edward Cheeseman <evbuilder@users.sourceforge.net>
*
* 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/adc.h>
/*---------------------------------------------------------------------------*/
/** @brief ADC Power On
If the ADC is in power-down mode then it is powered up. The application needs
to wait a time of about 3 microseconds for stabilization before using the ADC.
If the ADC is already on this function call has no effect.
* NOTE Common with F37x
@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
*/
void adc_power_on(uint32_t adc)
{
if (!(ADC_CR2(adc) & ADC_CR2_ADON)) {
ADC_CR2(adc) |= ADC_CR2_ADON;
}
}
/*---------------------------------------------------------------------------*/
/** @brief ADC Start a Conversion Without Trigger
This initiates a conversion by software without a trigger. The ADC needs to be
powered on before this is called, otherwise this function has no effect.
Note that this is not available in other STM32F families. To ensure code
compatibility, enable triggering and use a software trigger source @see
adc_start_conversion_regular.
@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
*/
void adc_start_conversion_direct(uint32_t adc)
{
if (ADC_CR2(adc) & ADC_CR2_ADON) {
ADC_CR2(adc) |= ADC_CR2_ADON;
}
}
/*---------------------------------------------------------------------------*/
/** @brief ADC Set Dual A/D Mode
The dual mode uses ADC1 as master and ADC2 in a slave arrangement. This setting
is applied to ADC1 only. Start of conversion when triggered can cause
simultaneous conversion with ADC2, or alternate conversion. Regular and
injected conversions can be configured, each one being separately simultaneous
or alternate.
Fast interleaved mode starts ADC1 immediately on trigger, and ADC2 seven clock
cycles later.
Slow interleaved mode starts ADC1 immediately on trigger, and ADC2 fourteen
clock cycles later, followed by ADC1 fourteen cycles later again. This can only
be used on a single channel.
Alternate trigger mode must occur on an injected channel group, and alternates
between the ADCs on each trigger.
Note that sampling must not overlap between ADCs on the same channel.
Dual A/D converter modes possible:
@li IND: Independent mode.
@li CRSISM: Combined regular simultaneous + injected simultaneous mode.
@li CRSATM: Combined regular simultaneous + alternate trigger mode.
@li CISFIM: Combined injected simultaneous + fast interleaved mode.
@li CISSIM: Combined injected simultaneous + slow interleaved mode.
@li ISM: Injected simultaneous mode only.
@li RSM: Regular simultaneous mode only.
@li FIM: Fast interleaved mode only.
@li SIM: Slow interleaved mode only.
@li ATM: Alternate trigger mode only.
@param[in] mode Unsigned int32. Dual mode selection from @ref adc_cr1_dualmod
*/
void adc_set_dual_mode(uint32_t mode)
{
ADC1_CR1 |= mode;
}
/*---------------------------------------------------------------------------*/
/** @brief ADC Enable The Temperature Sensor
This enables both the sensor and the reference voltage measurements on channels
16 and 17.
*/
void adc_enable_temperature_sensor()
{
ADC_CR2(ADC1) |= ADC_CR2_TSVREFE;
}
/*---------------------------------------------------------------------------*/
/** @brief ADC Disable The Temperature Sensor
Disabling this will reduce power consumption from the sensor and the reference
voltage measurements.
*/
void adc_disable_temperature_sensor()
{
ADC_CR2(ADC1) &= ~ADC_CR2_TSVREFE;
}
/*---------------------------------------------------------------------------*/
/** @brief ADC Enable an External Trigger for Regular Channels
This enables an external trigger for set of defined regular channels.
For ADC1 and ADC2
@li Timer 1 CC1 event
@li Timer 1 CC2 event
@li Timer 1 CC3 event
@li Timer 2 CC2 event
@li Timer 3 TRGO event
@li Timer 4 CC4 event
@li EXTI (TIM8_TRGO is also possible on some devices, see datasheet)
@li Software Start
For ADC3
@li Timer 3 CC1 event
@li Timer 2 CC3 event
@li Timer 1 CC3 event
@li Timer 8 CC1 event
@li Timer 8 TRGO event
@li Timer 5 CC1 event
@li Timer 5 CC3 event
@li Software Start
@param[in] adc Unsigned int32. ADC block register address base @ref
adc_reg_base.
@param[in] trigger Unsigned int8. Trigger identifier @ref adc_trigger_regular_12
for ADC1 and ADC2, or @ref adc_trigger_regular_3 for ADC3.
*/
void adc_enable_external_trigger_regular(uint32_t adc, uint32_t trigger)
{
uint32_t reg32;
reg32 = (ADC_CR2(adc) & ~(ADC_CR2_EXTSEL_MASK));
reg32 |= (trigger);
ADC_CR2(adc) = reg32;
ADC_CR2(adc) |= ADC_CR2_EXTTRIG;
}
/*---------------------------------------------------------------------------*/
/** @brief ADC Disable an External Trigger for Regular Channels
@param[in] adc Unsigned int32. ADC block register address base @ref
adc_reg_base.
*/
void adc_disable_external_trigger_regular(uint32_t adc)
{
ADC_CR2(adc) &= ~ADC_CR2_EXTTRIG;
}
/*---------------------------------------------------------------------------*/
/** @brief ADC Enable an External Trigger for Injected Channels
This enables an external trigger for set of defined injected channels.
For ADC1 and ADC2
@li Timer 1 TRGO event
@li Timer 1 CC4 event
@li Timer 2 TRGO event
@li Timer 2 CC1 event
@li Timer 3 CC4 event
@li Timer 4 TRGO event
@li EXTI (TIM8 CC4 is also possible on some devices, see datasheet)
@li Software Start
For ADC3
@li Timer 1 TRGO event
@li Timer 1 CC4 event
@li Timer 4 CC3 event
@li Timer 8 CC2 event
@li Timer 8 CC4 event
@li Timer 5 TRGO event
@li Timer 5 CC4 event
@li Software Start
@param[in] adc Unsigned int32. ADC block register address base @ref
adc_reg_base.
@param[in] trigger Unsigned int8. Trigger identifier @ref
adc_trigger_injected_12 for ADC1 and ADC2, or @ref adc_trigger_injected_3 for
ADC3.
*/
void adc_enable_external_trigger_injected(uint32_t adc, uint32_t trigger)
{
uint32_t reg32;
reg32 = (ADC_CR2(adc) & ~(ADC_CR2_JEXTSEL_MASK)); /* Clear bits [12:14]
*/
reg32 |= (trigger);
ADC_CR2(adc) = reg32;
ADC_CR2(adc) |= ADC_CR2_JEXTTRIG;
}
/*---------------------------------------------------------------------------*/
/** @brief ADC Disable an External Trigger for Injected Channels
@param[in] adc Unsigned int32. ADC block register address base @ref
adc_reg_base.
*/
void adc_disable_external_trigger_injected(uint32_t adc)
{
ADC_CR2(adc) &= ~ADC_CR2_JEXTTRIG;
}
/*---------------------------------------------------------------------------*/
/** @brief ADC Initialize Calibration Registers
This resets the calibration registers. It is not clear if this is required to be
done before every calibration operation.
@param[in] adc Unsigned int32. ADC block register address base @ref
adc_reg_base.
*/
void adc_reset_calibration(uint32_t adc)
{
ADC_CR2(adc) |= ADC_CR2_RSTCAL;
while (ADC_CR2(adc) & ADC_CR2_RSTCAL);
}
/*---------------------------------------------------------------------------*/
/** @brief ADC Calibration
@deprecated replaced by adc_calibrate/_async/_is_calibrating
The calibration data for the ADC is recomputed. The hardware clears the
calibration status flag when calibration is complete. This function does not
return until this happens and the ADC is ready for use.
The ADC must have been powered down for at least 2 ADC clock cycles, then
powered on. before calibration starts
@param[in] adc Unsigned int32. ADC block register address base @ref
adc_reg_base.
*/
void adc_calibration(uint32_t adc)
{
ADC_CR2(adc) |= ADC_CR2_CAL;
while (ADC_CR2(adc) & ADC_CR2_CAL);
}
/**
* Start the ADC calibration and immediately return.
* @sa adc_calibrate
* @sa adc_is_calibrate
* @param adc ADC Block register address base @ref adc_reg_base
*/
void adc_calibrate_async(uint32_t adc)
{
ADC_CR2(adc) |= ADC_CR2_CAL;
}
/**
* Is the ADC Calibrating?
* @param adc ADC Block register address base @ref adc_reg_base
* @return true if the adc is currently calibrating
*/
bool adc_is_calibrating(uint32_t adc)
{
return (ADC_CR2(adc) & ADC_CR2_CAL);
}
/**
* Start ADC calibration and wait for it to finish.
* The ADC must have been powered down for at least 2 ADC clock cycles, then
* powered on before calibration starts
* @param adc ADC Block register address base @ref adc_reg_base
*/
void adc_calibrate(uint32_t adc)
{
adc_calibrate_async(adc);
while (adc_is_calibrating(adc));
}
/*---------------------------------------------------------------------------*/
/** @brief ADC Set the Sample Time for a Single Channel
The sampling time can be selected in ADC clock cycles from 1.5 to 239.5.
@param[in] adc Unsigned int32. ADC block register address base @ref
adc_reg_base.
@param[in] channel Unsigned int8. ADC Channel integer 0..18 or from @ref
adc_channel.
@param[in] time Unsigned int8. Sampling time selection from @ref adc_sample_rg.
* * NOTE Common with f2 and f37x and f4
*/
void adc_set_sample_time(uint32_t adc, uint8_t channel, uint8_t time)
{
uint32_t reg32;
if (channel < 10) {
reg32 = ADC_SMPR2(adc);
reg32 &= ~(0x7 << (channel * 3));
reg32 |= (time << (channel * 3));
ADC_SMPR2(adc) = reg32;
} else {
reg32 = ADC_SMPR1(adc);
reg32 &= ~(0x7 << ((channel - 10) * 3));
reg32 |= (time << ((channel - 10) * 3));
ADC_SMPR1(adc) = reg32;
}
}
/*---------------------------------------------------------------------------*/
/** @brief ADC Set the Sample Time for All Channels
The sampling time can be selected in ADC clock cycles from 1.5 to 239.5, same
for all channels.
@param[in] adc Unsigned int32. ADC block register address base @ref
adc_reg_base.
@param[in] time Unsigned int8. Sampling time selection from @ref adc_sample_rg.
* * NOTE Common with f2 and f37x and f4
*/
void adc_set_sample_time_on_all_channels(uint32_t adc, uint8_t time)
{
uint8_t i;
uint32_t reg32 = 0;
for (i = 0; i <= 9; i++) {
reg32 |= (time << (i * 3));
}
ADC_SMPR2(adc) = reg32;
for (i = 10; i <= 17; i++) {
reg32 |= (time << ((i - 10) * 3));
}
ADC_SMPR1(adc) = reg32;
}
/*---------------------------------------------------------------------------*/
/**@}*/

View File

@@ -0,0 +1,303 @@
/** @defgroup flash_file FLASH peripheral API
*
* @ingroup peripheral_apis
*
* @brief <b>libopencm3 STM32F1xx FLASH Memory</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
*
* For the STM32F1xx, accessing FLASH memory is described briefly in
* section 3.3.3 of the STM32F10x Reference Manual.
* For detailed programming information see:
* PM0075 programming manual: STM32F10xxx Flash programming
* August 2010, Doc ID 17863 Rev 1
* https://github.com/libopencm3/libopencm3-archive/blob/master/st_micro/CD00283419.pdf
*
* FLASH memory may be used for data storage as well as code, and may be
* programmatically modified. Note that for firmware upload the STM32F1xx
* provides a built-in bootloader in system memory that can be entered from a
* running program.
*
* FLASH must first be unlocked before programming. In this module a write to
* FLASH is a blocking operation until the end-of-operation flag is asserted.
*
* @note: don't forget to lock it again when all operations are complete.
*
* For the large memory XL series, with two banks of FLASH, the upper bank is
* accessed with a second set of registers. In principle both banks can be
* written simultaneously, or one read while the other is written. This module
* does not support the simultaneous write feature.
*
* 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/desig.h>
#include <libopencm3/stm32/flash.h>
/*---------------------------------------------------------------------------*/
/** @brief Enable the FLASH Half Cycle Mode
This mode is used for power saving during read access. It is disabled by default
on reset.
Note carefully the clock restrictions under which the half cycle mode may be
enabled or disabled. This mode may only be used while the clock is running at
8MHz. See the reference manual for details.
*/
void flash_halfcycle_enable(void)
{
FLASH_ACR |= FLASH_ACR_HLFCYA;
}
/*---------------------------------------------------------------------------*/
/** @brief Disable the FLASH Half Cycle Mode
*/
void flash_halfcycle_disable(void)
{
FLASH_ACR &= ~FLASH_ACR_HLFCYA;
}
/*---------------------------------------------------------------------------*/
/** @brief Unlock the Flash Program and Erase Controller, upper Bank
This enables write access to the upper bank of the Flash memory in XL devices.
It is locked by default on reset.
*/
void flash_unlock_upper(void)
{
if (desig_get_flash_size() > 512) {
/* Clear the unlock state. */
FLASH_CR2 |= FLASH_CR_LOCK;
/* Authorize the FPEC access. */
FLASH_KEYR2 = FLASH_KEYR_KEY1;
FLASH_KEYR2 = FLASH_KEYR_KEY2;
}
}
/*---------------------------------------------------------------------------*/
/** @brief Lock the Flash Program and Erase Controller, upper Bank
Used to prevent spurious writes to FLASH.
*/
void flash_lock_upper(void)
{
FLASH_CR2 |= FLASH_CR_LOCK;
}
/*---------------------------------------------------------------------------*/
/** @brief Clear the Programming Error Status Flag, upper Bank
*/
void flash_clear_pgerr_flag_upper(void)
{
if (desig_get_flash_size() > 512) {
FLASH_SR2 |= FLASH_SR_PGERR;
}
}
/*---------------------------------------------------------------------------*/
/** @brief Clear the End of Operation Status Flag, upper Bank
*/
void flash_clear_eop_flag_upper(void)
{
if (desig_get_flash_size() > 512) {
FLASH_SR2 |= FLASH_SR_EOP;
}
}
/*---------------------------------------------------------------------------*/
/** @brief Clear the Write Protect Error Status Flag, upper Bank
*/
void flash_clear_wrprterr_flag_upper(void)
{
if (desig_get_flash_size() > 512) {
FLASH_SR2 |= FLASH_SR_WRPRTERR;
}
}
/*---------------------------------------------------------------------------*/
/** @brief Clear All Status Flags
Program error, end of operation, write protect error, busy. Both banks cleared.
*/
void flash_clear_status_flags(void)
{
flash_clear_pgerr_flag();
flash_clear_eop_flag();
flash_clear_wrprterr_flag();
if (desig_get_flash_size() > 512) {
flash_clear_pgerr_flag_upper();
flash_clear_eop_flag_upper();
flash_clear_wrprterr_flag_upper();
}
}
/*---------------------------------------------------------------------------*/
/** @brief Read All Status Flags
The programming error, end of operation, write protect error and busy flags
are returned in the order of appearance in the status register.
Flags for the upper bank, where appropriate, are combined with those for
the lower bank using bitwise OR, without distinction.
@returns uint32_t. bit 0: busy, bit 2: programming error, bit 4: write protect
error, bit 5: end of operation.
*/
uint32_t flash_get_status_flags(void)
{
uint32_t flags = (FLASH_SR & (FLASH_SR_PGERR |
FLASH_SR_EOP |
FLASH_SR_WRPRTERR |
FLASH_SR_BSY));
if (desig_get_flash_size() > 512) {
flags |= (FLASH_SR2 & (FLASH_SR_PGERR |
FLASH_SR_EOP |
FLASH_SR_WRPRTERR |
FLASH_SR_BSY));
}
return flags;
}
/*---------------------------------------------------------------------------*/
/** @brief Program a Half Word to FLASH
This performs all operations necessary to program a 16 bit word to FLASH memory.
The program error flag should be checked separately for the event that memory
was not properly erased.
Status bit polling is used to detect end of operation.
@param[in] address Full address of flash half word to be programmed.
@param[in] data half word to write
*/
void flash_program_half_word(uint32_t address, uint16_t data)
{
flash_wait_for_last_operation();
if ((desig_get_flash_size() > 512) && (address >= FLASH_BASE+0x00080000)) {
FLASH_CR2 |= FLASH_CR_PG;
} else {
FLASH_CR |= FLASH_CR_PG;
}
MMIO16(address) = data;
flash_wait_for_last_operation();
if ((desig_get_flash_size() > 512) && (address >= FLASH_BASE+0x00080000)) {
FLASH_CR2 &= ~FLASH_CR_PG;
} else {
FLASH_CR &= ~FLASH_CR_PG;
}
}
/*---------------------------------------------------------------------------*/
/** @brief Erase a Page of FLASH
This performs all operations necessary to erase a page in FLASH memory.
The page should be checked to ensure that it was properly erased. A page must
first be fully erased before attempting to program it.
Note that the page sizes differ between devices. See the reference manual or
the FLASH programming manual for details.
@param[in] page_address Full address of flash page to be erased.
*/
void flash_erase_page(uint32_t page_address)
{
flash_wait_for_last_operation();
if ((desig_get_flash_size() > 512)
&& (page_address >= FLASH_BASE+0x00080000)) {
FLASH_CR2 |= FLASH_CR_PER;
FLASH_AR2 = page_address;
FLASH_CR2 |= FLASH_CR_STRT;
} else {
FLASH_CR |= FLASH_CR_PER;
FLASH_AR = page_address;
FLASH_CR |= FLASH_CR_STRT;
}
flash_wait_for_last_operation();
if ((desig_get_flash_size() > 512)
&& (page_address >= FLASH_BASE+0x00080000)) {
FLASH_CR2 &= ~FLASH_CR_PER;
} else {
FLASH_CR &= ~FLASH_CR_PER;
}
}
/*---------------------------------------------------------------------------*/
/** @brief Erase All FLASH
This performs all operations necessary to erase all user pages in the FLASH
memory. The information block is unaffected.
*/
void flash_erase_all_pages(void)
{
flash_wait_for_last_operation();
FLASH_CR |= FLASH_CR_MER; /* Enable mass erase. */
FLASH_CR |= FLASH_CR_STRT; /* Trigger the erase. */
flash_wait_for_last_operation();
FLASH_CR &= ~FLASH_CR_MER; /* Disable mass erase. */
/* Repeat for bank 2 */
FLASH_CR2 |= FLASH_CR_MER;
FLASH_CR2 |= FLASH_CR_STRT;
flash_wait_for_last_operation();
FLASH_CR2 &= ~FLASH_CR_MER;
}
/**@}*/

View File

@@ -0,0 +1,198 @@
/** @addtogroup gpio_file
@brief <b>libopencm3 STM32F1xx General Purpose I/O</b>
@version 1.0.0
@author @htmlonly &copy; @endhtmlonly 2009
Uwe Hermann <uwe@hermann-uwe.de>
@author @htmlonly &copy; @endhtmlonly 2012
Ken Sarkies <ksarkies@internode.on.net>
@date 18 August 2012
Each I/O port has 16 individually configurable bits. Many I/O pins share GPIO
functionality with a number of alternate functions and must be configured to
the alternate function mode if these are to be accessed. A feature is available
to remap alternative functions to a limited set of alternative pins in the
event of a clash of requirements.
The data registers associated with each port for input and output are 32 bit
with the upper 16 bits unused. The output buffer must be written as a 32 bit
word, but individual bits may be set or reset separately in atomic operations
to avoid race conditions during interrupts. Bits may also be individually
locked to prevent accidental configuration changes. Once locked the
configuration cannot be changed until after the next reset.
Each port bit can be configured as analog or digital input, the latter can be
floating or pulled up or down. As outputs they can be configured as either
push-pull or open drain, digital I/O or alternate function, and with maximum
output speeds of 2MHz, 10MHz, or 50MHz.
On reset all ports are configured as digital floating input.
@section gpio_api_ex Basic GPIO Handling API.
Example 1: Push-pull digital output actions on ports C2 and C9
@code
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO2 | GPIO9);
gpio_set(GPIOC, GPIO2 | GPIO9);
gpio_clear(GPIOC, GPIO2);
gpio_toggle(GPIOC, GPIO2 | GPIO9);
gpio_port_write(GPIOC, 0x204);
@endcode
Example 1: Digital input on port C12
@code
gpio_set_mode(GPIOC, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, GPIO12);
reg16 = gpio_port_read(GPIOC);
@endcode
LGPL License Terms @ref lgpl_license
*/
/*
* 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/>.
*/
#include <libopencm3/stm32/gpio.h>
/**@{*/
/*---------------------------------------------------------------------------*/
/** @brief Set GPIO Pin Mode
Sets the mode (input/output) and configuration (analog/digitial and
open drain/push pull), for a set of GPIO pins on a given GPIO port.
@param[in] gpioport Unsigned int32. Port identifier @ref gpio_port_id
@param[in] mode Unsigned int8. Pin mode @ref gpio_mode
@param[in] cnf Unsigned int8. Pin configuration @ref gpio_cnf
@param[in] gpios Unsigned int16. Pin identifiers @ref gpio_pin_id
If multiple pins are to be set, use bitwise OR '|' to separate
them.
*/
void gpio_set_mode(uint32_t gpioport, uint8_t mode, uint8_t cnf, uint16_t gpios)
{
uint16_t i, offset = 0;
uint32_t crl = 0, crh = 0, tmp32 = 0;
/*
* We want to set the config only for the pins mentioned in gpios,
* but keeping the others, so read out the actual config first.
*/
crl = GPIO_CRL(gpioport);
crh = GPIO_CRH(gpioport);
/* Iterate over all bits, use i as the bitnumber. */
for (i = 0; i < 16; i++) {
/* Only set the config if the bit is set in gpios. */
if (!((1 << i) & gpios)) {
continue;
}
/* Calculate bit offset. */
offset = (i < 8) ? (i * 4) : ((i - 8) * 4);
/* Use tmp32 to either modify crl or crh. */
tmp32 = (i < 8) ? crl : crh;
/* Modify bits are needed. */
tmp32 &= ~(0xf << offset); /* Clear the bits first. */
tmp32 |= (mode << offset) | (cnf << (offset + 2));
/* Write tmp32 into crl or crh, leave the other unchanged. */
crl = (i < 8) ? tmp32 : crl;
crh = (i >= 8) ? tmp32 : crh;
}
GPIO_CRL(gpioport) = crl;
GPIO_CRH(gpioport) = crh;
}
/*---------------------------------------------------------------------------*/
/** @brief Map the EVENTOUT signal
Enable the EVENTOUT signal and select the port and pin to be used.
@param[in] evoutport Unsigned int8. Port for EVENTOUT signal @ref afio_evcr_port
@param[in] evoutpin Unsigned int8. Pin for EVENTOUT signal @ref afio_evcr_pin
*/
void gpio_set_eventout(uint8_t evoutport, uint8_t evoutpin)
{
AFIO_EVCR = AFIO_EVCR_EVOE | evoutport | evoutpin;
}
/*---------------------------------------------------------------------------*/
/** @brief Map Alternate Function Port Bits (Main Set)
A number of alternate function ports can be remapped to defined alternative
port bits to avoid clashes in cases where multiple alternate functions are
present. Refer to the datasheets for the particular mapping desired. This
provides the main set of remap functionality. See @ref gpio_secondary_remap for
a number of lesser used remaps.
The AFIO remapping feature is used only with the STM32F10x series.
@note The Serial Wire JTAG disable controls allow certain GPIO ports to become
available in place of some of the SWJ signals. Full SWJ capability is obtained
by setting this to zero. The value of this must be specified for every call to
this function as its current value cannot be ascertained from the hardware.
@param[in] swjdisable Disable parts of the SWJ capability @ref
afio_swj_disable.
@param[in] maps Bitwise OR of map enable controls you wish to
enable from @ref afio_remap, @ref afio_remap_can1, @ref afio_remap_tim3,
@ref afio_remap_tim2, @ref afio_remap_tim1, @ref afio_remap_usart3. For
connectivity line devices only @ref afio_remap_cld are also available.
*/
void gpio_primary_remap(uint32_t swjdisable, uint32_t maps)
{
/*
* the SWJ_CFG bits are write only. (read is explicitly undefined)
* To be sure we set only the bits we want we must clear them first.
* However, we are still trying to only enable the map bits desired.
*/
uint32_t reg = AFIO_MAPR & ~AFIO_MAPR_SWJ_MASK;
AFIO_MAPR = reg | swjdisable | maps;
}
/*---------------------------------------------------------------------------*/
/** @brief Map Alternate Function Port Bits (Secondary Set)
A number of alternate function ports can be remapped to defined alternative
port bits to avoid clashes in cases where multiple alternate functions are
present. Refer to the datasheets for the particular mapping desired. This
provides the second smaller and less used set of remap functionality. See @ref
gpio_primary_remap for the main set of remaps.
The AFIO remapping feature is used only with the STM32F10x series.
@param[in] maps Unsigned int32. Bitwise OR of map enable controls from @ref
afio_remap2
*/
void gpio_secondary_remap(uint32_t maps)
{
AFIO_MAPR2 |= maps;
}
/**@}*/

View File

@@ -0,0 +1,31 @@
/** @defgroup i2c_file I2C
@ingroup STM32F1xx
@brief <b>libopencm3 STM32F1xx 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>

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,418 @@
/** @defgroup rtc_file RTC peripheral API
*
* @ingroup peripheral_apis
*
* @brief <b>libopencm3 STM32F1xx RTC</b>
*
* @author @htmlonly &copy; @endhtmlonly 2010 Uwe Hermann <uwe@hermann-uwe.de>
* @author @htmlonly &copy; @endhtmlonly 2010 Lord James <lordjames@y7mail.com>
*
* @version 1.0.0
*
* @date 4 March 2013
*
* The Real Time Clock peripheral consists of a set of 16 bit control, status,
* prescaler, counter and alarm registers. Before the latter three can be
* written the RTC must be placed in configuration mode by a call to
* @ref rtc_enter_config_mode(). The functions below handle this implictly.
*
* The RTC is completely reset by performing a Backup Domain reset. Note
* that this can affect unrelated user data contained in the Backup Domain
* registers. Other forms of reset will not affect the RTC registers as they
* are contained within the backup domain.
*
* The RTC clock source to be used is selected by calling
* @ref rcc_set_rtc_clock_source().
*
* The LSE clock source normally comes from a 32.768kHz external crystal
* This clock is in the backup domain and so continues to run when only the
* V_BAT supply is present. A prescaler value of 7FFF will give a 1 second
* count quantum.
*
* The LSI clock source is a low accuracy internal clock of about 40kHz
* frequency, and the HSE clock source is the external high speed clock
* divided by 128.
*
* Initial configuration of the RTC consists of:
*
* @li perform a Backup Domain reset if appropriate;
* @li select the clock to be used;
* @li set the prescaler, counter and configuration values;
* @li enable the RTC.
*
* @note reading the RTC registers may result in a corrupted value being
* returned in certain cases. Refer to the STM32F1xx Reference Manual.
*
* LGPL License Terms @ref lgpl_license
*/
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Uwe Hermann <uwe@hermann-uwe.de>
* Copyright (C) 2010 Lord James <lordjames@y7mail.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/rcc.h>
#include <libopencm3/stm32/rtc.h>
#include <libopencm3/stm32/pwr.h>
/*---------------------------------------------------------------------------*/
/** @brief RTC Set Operational from the Off state.
Power up the backup domain clocks, enable write access to the backup domain,
select the clock source, clear the RTC registers and enable the RTC.
@param[in] clock_source ::rcc_osc. RTC clock source. Only the values HSE, LSE
and LSI are permitted.
*/
void rtc_awake_from_off(enum rcc_osc clock_source)
{
uint32_t reg32;
/* Enable power and backup interface clocks. */
rcc_periph_clock_enable(RCC_PWR);
rcc_periph_clock_enable(RCC_BKP);
/* Enable access to the backup registers and the RTC. */
pwr_disable_backup_domain_write_protect();
/* Set the clock source */
rcc_set_rtc_clock_source(clock_source);
/* Clear the RTC Control Register */
RTC_CRH = 0;
RTC_CRL = 0;
/* Enable the RTC. */
rcc_enable_rtc_clock();
/* Clear the Registers */
rtc_enter_config_mode();
RTC_PRLH = 0;
RTC_PRLL = 0;
RTC_CNTH = 0;
RTC_CNTL = 0;
RTC_ALRH = 0xFFFF;
RTC_ALRL = 0xFFFF;
rtc_exit_config_mode();
/* Wait for the RSF bit in RTC_CRL to be set by hardware. */
RTC_CRL &= ~RTC_CRL_RSF;
while ((reg32 = (RTC_CRL & RTC_CRL_RSF)) == 0);
}
/*---------------------------------------------------------------------------*/
/** @brief RTC Enter Configuration Mode.
Prime the RTC for configuration changes by giving access to the prescaler,
and counter and alarm registers.
*/
void rtc_enter_config_mode(void)
{
uint32_t reg32;
/* Wait until the RTOFF bit is 1 (no RTC register writes ongoing). */
while ((reg32 = (RTC_CRL & RTC_CRL_RTOFF)) == 0);
/* Enter configuration mode. */
RTC_CRL |= RTC_CRL_CNF;
}
/*---------------------------------------------------------------------------*/
/** @brief RTC Leave Configuration Mode.
Revert the RTC to operational state.
*/
void rtc_exit_config_mode(void)
{
uint32_t reg32;
/* Exit configuration mode. */
RTC_CRL &= ~RTC_CRL_CNF;
/* Wait until the RTOFF bit is 1 (our RTC register write finished). */
while ((reg32 = (RTC_CRL & RTC_CRL_RTOFF)) == 0);
}
/*---------------------------------------------------------------------------*/
/** @brief RTC Set the Alarm Time.
@param[in] alarm_time uint32_t. time at which the alarm event is triggered.
*/
void rtc_set_alarm_time(uint32_t alarm_time)
{
rtc_enter_config_mode();
RTC_ALRL = (alarm_time & 0x0000ffff);
RTC_ALRH = (alarm_time & 0xffff0000) >> 16;
rtc_exit_config_mode();
}
/*---------------------------------------------------------------------------*/
/** @brief RTC Enable the Alarm.
*/
void rtc_enable_alarm(void)
{
rtc_enter_config_mode();
RTC_CRH |= RTC_CRH_ALRIE;
rtc_exit_config_mode();
}
/*---------------------------------------------------------------------------*/
/** @brief RTC Disable the Alarm.
*/
void rtc_disable_alarm(void)
{
rtc_enter_config_mode();
RTC_CRH &= ~RTC_CRH_ALRIE;
rtc_exit_config_mode();
}
/*---------------------------------------------------------------------------*/
/** @brief RTC Set the prescaler Value
@param[in] prescale_val uint32_t. 20 bit prescale divider.
*/
void rtc_set_prescale_val(uint32_t prescale_val)
{
rtc_enter_config_mode();
RTC_PRLL = prescale_val & 0x0000ffff; /* PRL[15:0] */
RTC_PRLH = (prescale_val & 0x000f0000) >> 16; /* PRL[19:16] */
rtc_exit_config_mode();
}
/*---------------------------------------------------------------------------*/
/** @brief RTC return the Counter Value
@returns uint32_t: the 32 bit counter value.
*/
uint32_t rtc_get_counter_val(void)
{
return (RTC_CNTH << 16) | RTC_CNTL;
}
/*---------------------------------------------------------------------------*/
/** @brief RTC return the prescaler Value
@returns uint32_t: the 20 bit prescale divider.
*/
uint32_t rtc_get_prescale_div_val(void)
{
return (RTC_DIVH << 16) | RTC_DIVL;
}
/*---------------------------------------------------------------------------*/
/** @brief RTC return the Alarm Value
@returns uint32_t: the 32 bit alarm value.
*/
uint32_t rtc_get_alarm_val(void)
{
return (RTC_ALRH << 16) | RTC_ALRL;
}
/*---------------------------------------------------------------------------*/
/** @brief RTC set the Counter
@param[in] counter_val 32 bit time setting for the counter.
*/
void rtc_set_counter_val(uint32_t counter_val)
{
rtc_enter_config_mode();
RTC_CNTH = (counter_val & 0xffff0000) >> 16; /* CNT[31:16] */
RTC_CNTL = counter_val & 0x0000ffff; /* CNT[15:0] */
rtc_exit_config_mode();
}
/*---------------------------------------------------------------------------*/
/** @brief RTC Enable Interrupt
@param[in] flag_val ::rtcflag_t: The flag to enable.
*/
void rtc_interrupt_enable(rtcflag_t flag_val)
{
rtc_enter_config_mode();
/* Set the correct interrupt enable. */
switch (flag_val) {
case RTC_SEC:
RTC_CRH |= RTC_CRH_SECIE;
break;
case RTC_ALR:
RTC_CRH |= RTC_CRH_ALRIE;
break;
case RTC_OW:
RTC_CRH |= RTC_CRH_OWIE;
break;
}
rtc_exit_config_mode();
}
/*---------------------------------------------------------------------------*/
/** @brief RTC Disable Interrupt
@param[in] flag_val ::rtcflag_t: The flag to disable.
*/
void rtc_interrupt_disable(rtcflag_t flag_val)
{
rtc_enter_config_mode();
/* Disable the correct interrupt enable. */
switch (flag_val) {
case RTC_SEC:
RTC_CRH &= ~RTC_CRH_SECIE;
break;
case RTC_ALR:
RTC_CRH &= ~RTC_CRH_ALRIE;
break;
case RTC_OW:
RTC_CRH &= ~RTC_CRH_OWIE;
break;
}
rtc_exit_config_mode();
}
/*---------------------------------------------------------------------------*/
/** @brief RTC Clear an Interrupt Flag
@param[in] flag_val ::rtcflag_t: The flag to clear.
*/
void rtc_clear_flag(rtcflag_t flag_val)
{
/* Configuration mode not needed. */
/* Clear the correct flag. */
switch (flag_val) {
case RTC_SEC:
RTC_CRL &= ~RTC_CRL_SECF;
break;
case RTC_ALR:
RTC_CRL &= ~RTC_CRL_ALRF;
break;
case RTC_OW:
RTC_CRL &= ~RTC_CRL_OWF;
break;
}
}
/*---------------------------------------------------------------------------*/
/** @brief RTC Return a Flag Setting
@param[in] flag_val ::rtcflag_t: The flag to check.
@returns uint32_t: a nonzero value if the flag is set, zero otherwise.
*/
uint32_t rtc_check_flag(rtcflag_t flag_val)
{
uint32_t reg32;
/* Read correct flag. */
switch (flag_val) {
case RTC_SEC:
reg32 = RTC_CRL & RTC_CRL_SECF;
break;
case RTC_ALR:
reg32 = RTC_CRL & RTC_CRL_ALRF;
break;
case RTC_OW:
reg32 = RTC_CRL & RTC_CRL_OWF;
break;
default:
reg32 = 0;
break;
}
return reg32;
}
/*---------------------------------------------------------------------------*/
/** @brief RTC Start RTC after Standby Mode.
Enable the backup domain clocks, enable write access to the backup
domain and the RTC, and synchronise the RTC register access.
*/
void rtc_awake_from_standby(void)
{
uint32_t reg32;
/* Enable power and backup interface clocks. */
rcc_periph_clock_enable(RCC_PWR);
rcc_periph_clock_enable(RCC_BKP);
/* Enable access to the backup registers and the RTC. */
pwr_disable_backup_domain_write_protect();
/* Wait for the RSF bit in RTC_CRL to be set by hardware. */
RTC_CRL &= ~RTC_CRL_RSF;
while ((reg32 = (RTC_CRL & RTC_CRL_RSF)) == 0);
/* Wait for the last write operation to finish. */
/* TODO: Necessary? */
while ((reg32 = (RTC_CRL & RTC_CRL_RTOFF)) == 0);
}
/*---------------------------------------------------------------------------*/
/** @brief RTC Configuration on Wakeup
Enable the backup domain clocks and write access to the backup domain.
If the RTC has not been enabled, set the clock source and prescaler value.
The parameters are not used if the RTC has already been enabled.
@param[in] clock_source ::rcc_osc. RTC clock source. Only HSE, LSE
and LSI are permitted.
@param[in] prescale_val uint32_t. 20 bit prescale divider.
*/
void rtc_auto_awake(enum rcc_osc clock_source, uint32_t prescale_val)
{
uint32_t reg32;
/* Enable power and backup interface clocks. */
rcc_periph_clock_enable(RCC_PWR);
rcc_periph_clock_enable(RCC_BKP);
reg32 = rcc_rtc_clock_enabled_flag();
if (reg32 != 0) {
rtc_awake_from_standby();
} else {
rtc_awake_from_off(clock_source);
rtc_set_prescale_val(prescale_val);
}
}
/**@}*/

View File

@@ -0,0 +1,53 @@
/** @defgroup timer_file TIMER peripheral API
@ingroup peripheral_apis
@brief <b>libopencm3 STM32F1xx 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>
/**@{*/
/*---------------------------------------------------------------------------*/
/** @brief Set Input Polarity
@param[in] timer_peripheral Unsigned int32. Timer register address base
@param[in] ic ::tim_ic_id. Input Capture channel designator.
@param[in] pol ::tim_ic_pol. Input Capture polarity.
*/
void timer_ic_set_polarity(uint32_t timer_peripheral, enum tim_ic_id ic,
enum tim_ic_pol pol)
{
if (pol) {
TIM_CCER(timer_peripheral) |= (0x2 << (ic * 4));
} else {
TIM_CCER(timer_peripheral) &= ~(0x2 << (ic * 4));
}
}
/**@}*/