sam/4l: monster commit

The original submitter of this squished everything into one series, and
has not returned. The code mostly appears good, and review comments were
followed for the most part.  The project doesn't really maintain any
testing or board farm for sam3/sam4 parts, so we're going to just trust
our users.

Reviewed-by: Karl Palsson <karlp@tweak.net.au>

sam/4l: IRQ Configuration file (irq.json)

sam/4l: Basic Memory Map.

sam/4l: GPIO Defines.

sam/4l: GPIO Functions

Added everything that needed to compile the library: Makefile, Linker
Script and common includes.

sam/4l: SCIF function to start OSC.

sam/4l: GPIO Enable/Disable and Multiplexing configuration functions.

sam/4l: PLL Clock configuration.

sam/4l: Peripheral clock configuration and basic USART support.

sam: USART Character length configuration.

sam/4l: Generic Clock configuration functions.

sam/4l: Analog to Digital Converter Interface (ADCIFE) basic support.
This commit is contained in:
Maxim Sloyko
2016-04-16 07:30:48 -07:00
committed by Karl Palsson
parent b4f195b488
commit 2b1ddc8490
31 changed files with 2003 additions and 23 deletions

View File

@@ -31,7 +31,7 @@ TGT_CFLAGS += $(DEBUG_FLAGS)
TGT_CFLAGS += $(STANDARD_FLAGS)
# ARFLAGS = rcsv
ARFLAGS = rcs
OBJS = gpio_common_all.o gpio_common_3a3u3x.o pmc.o usart.o
OBJS = gpio_common_all.o gpio_common_3a3u3x.o pmc.o usart_common_all.o usart_common_3.o
VPATH += ../../usb:../../cm3:../common

View File

@@ -31,7 +31,7 @@ TGT_CFLAGS += $(DEBUG_FLAGS)
TGT_CFLAGS += $(STANDARD_FLAGS)
# ARFLAGS = rcsv
ARFLAGS = rcs
OBJS = gpio_common_all.o gpio_common_3n3s.o pmc.o usart.o
OBJS = gpio_common_all.o gpio_common_3n3s.o pmc.o usart_common_all.o usart_common_3.o
VPATH += ../../cm3:../common

View File

@@ -32,7 +32,7 @@ TGT_CFLAGS += $(DEBUG_FLAGS)
TGT_CFLAGS += $(STANDARD_FLAGS)
# ARFLAGS = rcsv
ARFLAGS = rcs
OBJS = gpio_common_all.o gpio_common_3n3s.o pmc.o usart.o
OBJS = gpio_common_all.o gpio_common_3n3s.o pmc.o usart_common_all.o usart_common_3.o
VPATH += ../../usb:../../cm3:../common

View File

@@ -32,7 +32,7 @@ TGT_CFLAGS += $(DEBUG_FLAGS)
TGT_CFLAGS += $(STANDARD_FLAGS)
# ARFLAGS = rcsv
ARFLAGS = rcs
OBJS = gpio_common_all.o gpio_common_3a3u3x.o pmc.o usart.o
OBJS = gpio_common_all.o gpio_common_3a3u3x.o pmc.o usart_common_all.o usart_common_3.o
VPATH += ../../usb:../../cm3:../common

View File

@@ -31,7 +31,7 @@ TGT_CFLAGS += $(DEBUG_FLAGS)
TGT_CFLAGS += $(STANDARD_FLAGS)
# ARFLAGS = rcsv
ARFLAGS = rcs
OBJS = gpio_common_all.o gpio_common_3a3u3x.o pmc.o usart.o
OBJS = gpio_common_all.o gpio_common_3a3u3x.o pmc.o usart_common_all.o usart_common_3.o
VPATH += ../../usb:../../cm3:../common

37
lib/sam/4l/Makefile Normal file
View File

@@ -0,0 +1,37 @@
##
## 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/>.
##
LIBNAME = libopencm3_sam4l
SRCLIBDIR ?= ../..
PREFIX ?= arm-none-eabi
FP_FLAGS ?= -msoft-float
CC = $(PREFIX)-gcc
AR = $(PREFIX)-ar
TGT_CFLAGS = -Os -Wall -Wextra -I../../../include -fno-common \
-mcpu=cortex-m4 -mthumb $(FP_FLAGS) -Wstrict-prototypes \
-ffunction-sections -fdata-sections -MD -DSAM4L
TGT_CFLAGS += $(DEBUG_FLAGS)
# ARFLAGS = rcsv
ARFLAGS = rcs
OBJS = adcife.o gpio.o scif.o pm.o usart_common_all.o usart.o
VPATH += ../../usb:../../cm3:../common
include ../../Makefile.include

121
lib/sam/4l/adcife.c Normal file
View File

@@ -0,0 +1,121 @@
/** @addtogroup scif
*
* @brief <b>Access functions for the SAM4 Analog to Digital Converter Interface (ADCIFE)</b>
* @ingroup SAM4
* LGPL License Terms @ref lgpl_license
* @author @htmlonly &copy; @endhtmlonly 2016
* Maxim Sloyko <maxims@google.com>
*
*/
#include <libopencm3/sam/adcife.h>
/** @brief Enable ADC interface. Must be done before any other configuration.
*
* This function does it synchronously and returns only when the interface is
* actually enabled.
*/
void adcife_enable_sync(void)
{
ADCIFE_CR = ADCIFE_CR_EN;
while (!(ADCIFE_SR & ADCIFE_SR_EN));
}
void adcife_configure(
enum adcife_refsel ref,
enum adcife_speed speed,
enum adcife_clk clk,
enum adcife_prescal prescal)
{
ADCIFE_CFG = ADCIFE_CFG_REFSEL_MASKED(ref)
| ADCIFE_CFG_SPEED_MASKED(speed)
| ADCIFE_CFG_PRESCAL_MASKED(prescal)
| clk;
}
void adcife_select_channel(enum adcife_channel ad)
{
ADCIFE_SEQCFG |= ADCIFE_SEQCFG_MUXPOS_MASKED(ad);
}
void adcife_set_resolution(enum adcife_resolution res)
{
if (ADCIFE_RESOLUTION_12BITS == res) {
ADCIFE_SEQCFG &= ~ADCIFE_SEQCFG_RES;
} else {
ADCIFE_SEQCFG |= ADCIFE_SEQCFG_RES;
}
}
void adcife_select_trigger(enum adcife_trigger trig)
{
ADCIFE_SEQCFG &= ~ADCIFE_SEQCFG_TRGSEL_MASK;
ADCIFE_SEQCFG |= ADCIFE_SEQCFG_TRGSEL_MASKED(trig);
}
void adcife_set_gain(enum adcife_gain gain)
{
ADCIFE_SEQCFG &= ~ADCIFE_SEQCFG_GAIN_MASK;
ADCIFE_SEQCFG |= ADCIFE_SEQCFG_GAIN_MASKED(gain);
}
void adcife_set_bipolar(bool enable)
{
if (enable) {
ADCIFE_SEQCFG |= ADCIFE_SEQCFG_BIPOLAR;
} else {
ADCIFE_SEQCFG &= ~ADCIFE_SEQCFG_BIPOLAR;
}
}
void adcife_set_left_adjust(bool enable)
{
if (enable) {
ADCIFE_SEQCFG |= ADCIFE_SEQCFG_HWLA;
} else {
ADCIFE_SEQCFG &= ~ADCIFE_SEQCFG_HWLA;
}
}
void adcife_start_conversion(void)
{
ADCIFE_CR = ADCIFE_CR_STRIG;
}
void adcife_wait_conversion(void)
{
while (!(ADCIFE_SR & ADCIFE_SR_SEOC));
ADCIFE_SCR = ADCIFE_SR_SEOC;
}
struct adcife_lcv adcife_get_lcv(void)
{
struct adcife_lcv res;
res._lc_u.lcv = ADCIFE_LCV;
return res;
}
void adcife_enable_interrupts(uint32_t imask)
{
ADCIFE_IER = imask;
}
void adcife_disable_interrupts(uint32_t imask)
{
ADCIFE_IDR = imask;
}
void adcife_timer_start(void)
{
ADCIFE_CR = ADCIFE_CR_TSTART;
}
void adcife_timer_stop(void)
{
ADCIFE_CR = ADCIFE_CR_TSTOP;
}
void adcife_timer_set_timeout(uint16_t timeout)
{
ADCIFE_TIM = timeout;
}

100
lib/sam/4l/gpio.c Normal file
View File

@@ -0,0 +1,100 @@
/** @addtogroup gpio_defines
*
* @brief <b>Access functions for the SAM4 I/O Controller</b>
* @ingroup SAM4_defines
* LGPL License Terms @ref lgpl_license
* @author @htmlonly &copy; @endhtmlonly 2016
* Maxim Sloyko <maxims@google.com>
*
*/
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2012 Gareth McMullin <gareth@blacksphere.co.nz>
* Copyright (C) 2014 Felix Held <felix-libopencm3@felixheld.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/sam/gpio.h>
/** @brief Atomic set output
*
* @param[in] gpioport uint32_t: GPIO Port base address
* @param[in] gpios uint32_t
*/
void gpio_set(uint32_t gpioport, uint32_t gpios)
{
GPIO_OVRS(gpioport) = gpios;
}
/** @brief Atomic clear output
*
* @param[in] gpioport uint32_t: GPIO Port base address
* @param[in] gpios uint32_t
*/
void gpio_clear(uint32_t gpioport, uint32_t gpios)
{
GPIO_OVRC(gpioport) = gpios;
}
/** @brief Atomic toggle output
*
* @param[in] gpioport uint32_t: GPIO Port base address
* @param[in] gpios uint32_t
*/
void gpio_toggle(uint32_t gpioport, uint32_t gpios)
{
GPIO_OVRT(gpioport) = gpios;
}
/** @brief Enable output pins.
*
* Onlyc the ones where bits are set to "1" are touched, everything else
* remains in the old state.
*
* @param[in] gpioport uint32_t: GPIO Port base address
* @param[in] gpios uint32_t
* @param[in] mode enum gpio_mode GPIO mode. IN, OUT or peripheral function.
*/
void gpio_enable(uint32_t gpioport, uint32_t gpios, enum gpio_mode mode)
{
if (mode < GPIO_MODE_IN) {
GPIO_GPERC(gpioport) = gpios;
uint8_t i = 0;
for (; i < 3; ++i, mode >>= 1) {
GPIO_PMR_SETVAL(gpioport, i, mode & 1) = gpios;
}
} else if (mode == GPIO_MODE_OUT) {
GPIO_GPERS(gpioport) = gpios;
GPIO_ODERS(gpioport) = gpios;
} else if (mode == GPIO_MODE_IN) {
GPIO_GPERS(gpioport) = gpios;
GPIO_ODERC(gpioport) = gpios;
}
}
/** @brief Disable output pins.
*
* Onlyc the ones where bits are set to "1" are touched, everything else
* remains in the old state.
*
* @param[in] gpioport uint32_t: GPIO Port base address
* @param[in] gpios uint32_t
*/
void gpio_disable(uint32_t gpioport, uint32_t gpios)
{
GPIO_GPERC(gpioport) = gpios;
}

View File

@@ -0,0 +1,105 @@
/*
* 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 SAM4L 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));

75
lib/sam/4l/pm.c Normal file
View File

@@ -0,0 +1,75 @@
/** @addtogroup scif
*
* @brief <b>Access functions for the SAM4 Power Manager (PM)</b>
* @ingroup SAM4
* LGPL License Terms @ref lgpl_license
* @author @htmlonly &copy; @endhtmlonly 2016
* Maxim Sloyko <maxims@google.com>
*
*/
/*
* 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/sam/pm.h>
void pm_select_main_clock(enum mck_src source_clock)
{
PM_UNLOCK = PM_MCCTRL_KEY;
PM_MCCTRL = ((source_clock & PM_MCCTRL_MCSEL_MASK) << PM_MCCTRL_MCSEL_SHIFT);
while (!(PM_SR & PM_SR_CKRDY));
}
void pm_enable_clock_div(enum pm_cksel sel_target, uint8_t div)
{
while (!(PM_SR & PM_SR_CKRDY));
uint32_t reg = (PM_CKSEL_DIV | (div & PM_CKSEL_MASK));
PM_UNLOCK = PM_CKSEL_KEY(sel_target);
PM_CKSEL(sel_target) = reg;
while (!(PM_SR & PM_SR_CKRDY));
}
void pm_set_divmask_clock(uint8_t mask)
{
PM_UNLOCK = PM_PBADIVMASK_KEY;
PM_PBADIVMASK = mask;
}
static void set_peripheral_clock_status(enum pm_peripheral periph, bool on)
{
uint8_t reg_id = periph/32;
uint8_t bit_offset = periph % 32;
uint32_t reg_mask = PM_MASK(reg_id);
if (on) {
reg_mask |= (1 << bit_offset);
} else {
reg_mask &= ~(1 << bit_offset);
}
PM_UNLOCK = PM_MASK_KEY(reg_id);
PM_MASK(reg_id) = reg_mask;
}
void pm_enable_peripheral_clock(enum pm_peripheral periph)
{
set_peripheral_clock_status(periph, true);
}
void pm_disable_peripheral_clock(enum pm_peripheral periph)
{
set_peripheral_clock_status(periph, false);
}

133
lib/sam/4l/scif.c Normal file
View File

@@ -0,0 +1,133 @@
/** @addtogroup scif
*
* @brief <b>Access functions for the SAM4 System Controf Interface (SCIF)</b>
* @ingroup SAM4
* LGPL License Terms @ref lgpl_license
* @author @htmlonly &copy; @endhtmlonly 2016
* Maxim Sloyko <maxims@google.com>
*
*/
/*
* 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/sam/scif.h>
/** @brief Enable external oscillator.
*
* @param[in] mode enum osc_mode: Oscillator mode (which pins oscillator connected to).
* @param[in] freq uint32_t: External Oscillator frequency, in Hertz. Must be 0.6MHz - 30MHz
* @param[in] startup enum osc_startup: Oscillator start time in RCSYS clock cycles.
*
* @returns zero upon success.
*/
int scif_osc_enable(enum osc_mode mode, uint32_t freq, enum osc_startup startup)
{
uint8_t gain;
const uint32_t kHz = 1000;
const uint32_t MHz = 1000 * kHz;
if (freq > 600 * kHz && freq <= 2 * MHz) {
gain = 0;
} else if (freq > 2 * MHz && freq <= 4 * MHz) {
gain = 1;
} else if (freq > 4 * MHz && freq <= 8 * MHz) {
gain = 2;
} else if (freq > 8 * MHz && freq <= 16 * MHz) {
gain = 3;
} else if (freq > 16 * MHz && freq <= 30 * MHz) {
gain = 4;
} else {
return -1;
}
SCIF_UNLOCK = SCIF_OSCCTRL0_KEY;
SCIF_OSCCTRL0 = mode | SCIF_OSCCTRL_OSCEN |
(gain << SCIF_OSCCTRL_GAIN_SHIFT) | (startup << SCIF_OSCCTRL_STARTUP_SHIFT);
while (!(SCIF_PCLKSR & SCIF_OSC0RDY));
return 0;
}
/** @brief Configure and enable PLL clock.
*
* @param[in] delay uint8_t: Specifies the number of RCSYS clock cycles before
* ISR.PLLLOCKn will be set after PLL has been written, or after PLL has
* been automatically re-enabled after exiting a sleep mode.
* @param[in] mul uint8_t: Multiply factor.
* @param[in] div uint8_t: Division factor.These fields determine the ratio of
* the PLL output frequency to the source oscillator frequency:
* f_vco = (PLLMUL+1)/PLLDIV * f_ref if PLLDIV >0
* f_vco = 2*(PLLMUL+1) * f_ref if PLLDIV = 0
* Note that the PLLMUL field should always be greater than 1 or the
* behavior of the PLL will be undefined.
* @param[in] pll_opt uint8_t: PLL Options.
* @param[in] pll_opt uint8_t: PLL Options.
*
* @returns zero upon success.
*/
int scif_enable_pll(uint8_t delay, uint8_t mul, uint8_t div, uint8_t pll_opt, enum pll_clk_src source_clock)
{
// First, PLL needs to be disabled, otherwise the configuration register
// is unaccessible.
uint32_t pll_val = SCIF_PLL0;
if (pll_val & SCIF_PLL0_PLLEN) {
SCIF_UNLOCK = SCIF_PLL0_KEY;
SCIF_PLL0 = pll_val & (~SCIF_PLL0_PLLEN);
}
if (mul == 0)
mul = 1;
pll_val = SCIF_PLL0_PLLOSC_MASKED(source_clock)
| SCIF_PLL0_PLLOPT_MASKED(pll_opt)
| SCIF_PLL0_PLLDIV_MASKED(div)
| SCIF_PLL0_PLLMUL_MASKED(mul)
| SCIF_PLL0_PLLCOUNT_MASKED(delay);
SCIF_UNLOCK = SCIF_PLL0_KEY;
SCIF_PLL0 = pll_val;
// Now enable TODO: does this really need to be separate operation?
SCIF_UNLOCK = SCIF_PLL0_KEY;
SCIF_PLL0 = pll_val | SCIF_PLL0_PLLEN;
while(!(SCIF_PCLKSR & SCIF_PLL0LOCK));
return 0;
}
/** @brief Configure and enable Generic Clock
*
* @param[in] gclk enum generic_clock: Generic Clock to configure and enable.
* @param[in] source_clock enum gclk_src: Source Clock for this Generic Clock.
* @param[in] div uint16_t: Division Factor. Upper 8 bits only used for Generic Clock 11,
* If 0, clock is undivided.
*/
void scif_enable_gclk(enum generic_clock gclk, enum gclk_src source_clock, uint16_t div)
{
uint32_t reg_val = SCIF_GCCTRL_CEN | SCIF_GCCTRL_OSCSEL_MASKED(source_clock);
if (div) {
if (gclk < GENERIC_CLOCK11) {
div &= 0xf;
}
reg_val |= SCIF_GCCTRL_DIV_MASKED(div) | SCIF_GCCTRL_DIVEN;
}
SCIF_GCTRL(gclk) = reg_val;
}

26
lib/sam/4l/usart.c Normal file
View File

@@ -0,0 +1,26 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2013 Gareth McMullin <gareth@blacksphere.co.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/sam/usart.h>
void usart_set_baudrate(uint32_t usart, uint32_t baud)
{
USART_BRGR(usart) = baud;
}

View File

@@ -0,0 +1,27 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2013 Gareth McMullin <gareth@blacksphere.co.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/sam/usart.h>
extern uint32_t pmc_mck_frequency;
void usart_set_baudrate(uint32_t usart, uint32_t baud)
{
USART_BRGR(usart) = pmc_mck_frequency / (16 * baud);
}

View File

@@ -18,12 +18,6 @@
*/
#include <libopencm3/sam/usart.h>
#include <libopencm3/sam/pmc.h>
void usart_set_baudrate(uint32_t usart, uint32_t baud)
{
USART_BRGR(usart) = pmc_mck_frequency / (16 * baud);
}
void usart_set_databits(uint32_t usart, int bits)
{
@@ -58,12 +52,12 @@ void usart_set_flow_control(uint32_t usart, enum usart_flowcontrol fc)
void usart_enable(uint32_t usart)
{
(void)usart;
USART_CR(usart) = USART_CR_TXEN | USART_CR_RXEN;
}
void usart_disable(uint32_t usart)
{
(void)usart;
USART_CR(usart) = USART_CR_TXDIS | USART_CR_RXDIS;
}
void usart_send(uint32_t usart, uint16_t data)
@@ -108,3 +102,25 @@ void usart_disable_rx_interrupt(uint32_t usart)
{
USART_IDR(usart) = USART_CSR_RXRDY;
}
void usart_wp_enable(uint32_t usart)
{
USART_WPMR(usart) = USART_WPMR_KEY | USART_WPMR_WPEN;
}
void usart_wp_disable(uint32_t usart)
{
USART_WPMR(usart) = USART_WPMR_KEY & (~USART_WPMR_WPEN);
}
void usart_select_clock(uint32_t usart, enum usart_clock clk)
{
uint32_t reg_mr = USART_MR(usart) & (~USART_MR_USCLKS_MASK);
USART_MR(usart) = ((clk << USART_MR_USCLKS_SHIFT) & USART_MR_USCLKS_MASK) | reg_mr;
}
void usart_set_character_length(uint32_t usart, enum usart_chrl chrl)
{
uint32_t reg_mr = USART_MR(usart) & (~USART_MR_CHRL_MASK);
USART_MR(usart) = reg_mr | (chrl << USART_MR_CHRL_SHIFT);
}