aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorPiotr Esden-Tempski2013-02-18 13:53:57 -0800
committerPiotr Esden-Tempski2013-02-18 13:53:57 -0800
commitdaf4cc0feb7efe52ac9c7ca8097fd65a8f012b4e (patch)
tree68f157136f42bfa9ed6426e6e8f1b5943258ef24
parent9193d3d27376e337348685a402033e09cbb5ef35 (diff)
parent7ba100f56919374b111991198a0691ab5ab78c1e (diff)
Merging pull request #76 "LM4F clock api"
Merge remote-tracking branch 'mrnuke/lm4f_clock_api'
-rw-r--r--examples/lm4f/stellaris-ek-lm4f120xl/miniblink/README21
-rw-r--r--examples/lm4f/stellaris-ek-lm4f120xl/miniblink/miniblink.c193
-rw-r--r--include/libopencm3/lm4f/rcc.h126
-rw-r--r--include/libopencm3/lm4f/systemcontrol.h272
-rw-r--r--lib/lm4f/Makefile2
-rw-r--r--lib/lm4f/rcc.c493
-rw-r--r--lib/lm4f/systemcontrol.c40
7 files changed, 1108 insertions, 39 deletions
diff --git a/examples/lm4f/stellaris-ek-lm4f120xl/miniblink/README b/examples/lm4f/stellaris-ek-lm4f120xl/miniblink/README
index f6441be..a19550d 100644
--- a/examples/lm4f/stellaris-ek-lm4f120xl/miniblink/README
+++ b/examples/lm4f/stellaris-ek-lm4f120xl/miniblink/README
@@ -2,8 +2,21 @@
README
------------------------------------------------------------------------------
-Flashes the Red, Green and Blue diodes on the board, in order.
-RED controlled by PF1
-Green controlled by PF3
-Blue controlled by PF2
+This example demonstrates the following:
+ * Configuriong GPIO pins
+ * Toggling GPIO pins
+ * Setting up and using GPIO interrupts
+ * Unlocking protected GPIO pins
+ * Controlling the system clock
+ * Changing the system clock on the fly
+
+Flashes the Red, Green and Blue diodes on the board, in order. The system clock
+starts at 80MHz.
+Pressing SW2 toggles the system clock between 80MHz, 57MHz, 40MHz ,20MHz, and
+16MHz by changing the PLL divisor.
+Pressing SW1 bypasses the PLL completely, and runs off the raw 16MHz clock
+provided by the external crystal oscillator.
+The LEDs will toggle at different speeds, depending on the system clock. The
+system clock changes are handled within the interrupt service routine.
+
diff --git a/examples/lm4f/stellaris-ek-lm4f120xl/miniblink/miniblink.c b/examples/lm4f/stellaris-ek-lm4f120xl/miniblink/miniblink.c
index 0231a90..d03be0c 100644
--- a/examples/lm4f/stellaris-ek-lm4f120xl/miniblink/miniblink.c
+++ b/examples/lm4f/stellaris-ek-lm4f120xl/miniblink/miniblink.c
@@ -2,7 +2,7 @@
* This file is part of the libopencm3 project.
*
* Copyright (C) 2011 Gareth McMullin <gareth@blacksphere.co.nz>
- * Copyright (C) 2012 Alexandru Gagniuc <mr.nuke.me@gmail.com>
+ * Copyright (C) 2012-2013 Alexandru Gagniuc <mr.nuke.me@gmail.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
@@ -27,66 +27,193 @@
* Green controlled by PF3
* Blue controlled by PF2
*/
+#include <libopencm3/cm3/nvic.h>
#include <libopencm3/lm4f/systemcontrol.h>
+#include <libopencm3/lm4f/rcc.h>
#include <libopencm3/lm4f/gpio.h>
+#include <libopencm3/lm4f/nvic.h>
+
+#include <stdbool.h>
+#include <stdio.h>
+
+/* This is how the RGB LED is connected on the stellaris launchpad */
+#define RGB_PORT GPIOF
+enum {
+ LED_R = GPIO1,
+ LED_G = GPIO3,
+ LED_B = GPIO2,
+};
+
+/* This is how the user switches are connected to GPIOF */
+enum {
+ USR_SW1 = GPIO4,
+ USR_SW2 = GPIO0,
+};
+
+/* The divisors we loop through when the user presses SW2 */
+enum {
+ PLL_DIV_80MHZ = 5,
+ PLL_DIV_57MHZ = 7,
+ PLL_DIV_40MHZ = 10,
+ PLL_DIV_20MHZ = 20,
+ PLL_DIV_16MHZ = 25,
+};
+
+static const u8 plldiv[] = {
+ PLL_DIV_80MHZ,
+ PLL_DIV_57MHZ,
+ PLL_DIV_40MHZ,
+ PLL_DIV_20MHZ,
+ PLL_DIV_16MHZ,
+ 0
+};
+/* The PLL divisor we are currently on */
+static size_t ipll = 0;
+/* Are we bypassing the PLL, or not? */
+static bool bypass = false;
-void gpio_setup(void)
+/*
+ * Clock setup:
+ * Take the main crystal oscillator at 16MHz, run it through the PLL, and divide
+ * the 400MHz PLL clock to get a system clock of 80MHz.
+ */
+static void clock_setup(void)
+{
+ rcc_sysclk_config(OSCSRC_MOSC, XTAL_16M, PLL_DIV_80MHZ);
+}
+
+/*
+ * GPIO setup:
+ * Enable the pins driving the RGB LED as outputs.
+ */
+static void gpio_setup(void)
{
- SYSCTL_RCGCGPIO |= 0x20; /* Enable GPIOF in run mode. */
- const u32 outpins = ((1<<3) | (1<<2) | (1<<1));
+ /*
+ * Configure GPIOF
+ * This port is used to control the RGB LED
+ */
+ periph_clock_enable(RCC_GPIOF);
+ const u32 outpins = (LED_R | LED_G | LED_B);
+
+ GPIO_DIR(RGB_PORT) |= outpins; /* Configure outputs. */
+ GPIO_DEN(RGB_PORT) |= outpins; /* Enable digital function on outputs. */
+
+ /*
+ * Now take care of our buttons
+ */
+ const u32 btnpins = USR_SW1 | USR_SW2;
+
+ /*
+ * PF0 is locked by default. We need to unlock the GPIO_CR register,
+ * then enable PF0 commit. After we do this, we can setup PF0. If we
+ * don't do this, any configuration done to PF0 is lost, and we will not
+ * have a PF0 interrupt.
+ */
+ GPIO_LOCK(GPIOF) = 0x4C4F434B;
+ GPIO_CR(GPIOF) |= USR_SW2;
+
+ /* Configure pins as inputs. */
+ GPIO_DIR(GPIOF) &= ~btnpins;
+ /* Enable digital function on the pins. */
+ GPIO_DEN(GPIOF) |= btnpins;
+ /* Pull-up the pins. We don't have an external pull-up */
+ GPIO_PUR(GPIOF) |= btnpins;
+}
- GPIO_DIR(GPIOF) |= outpins; /* Configure outputs. */
- GPIO_DEN(GPIOF) |= outpins; /* Enable digital function on outputs. */
+/*
+ * IRQ setup:
+ * Trigger an interrupt whenever a button is depressed.
+ */
+static void irq_setup(void)
+{
+ const u32 btnpins = USR_SW1 | USR_SW2;
+ /* Configure interrupt as edge-sensitive */
+ GPIO_IS(GPIOF) &= ~btnpins;
+ /* Interrupt only respond to rising or falling edge (single-edge) */
+ GPIO_IBE(GPIOF) &= ~btnpins;
+ /* Trigger interrupt on rising-edge (when button is depressed) */
+ GPIO_IEV(GPIOF) |= btnpins;
+ /* Finally, Enable interrupt */
+ GPIO_IM(GPIOF) |= btnpins;
+ /* Enable the interrupt in the NVIC as well */
+ nvic_enable_irq(NVIC_GPIOF_IRQ);
}
#define FLASH_DELAY 800000
+static void delay(void)
+{
+ int i;
+ for (i = 0; i < FLASH_DELAY; i++) /* Wait a bit. */
+ __asm__("nop");
+}
+
int main(void)
{
int i;
+ clock_setup();
gpio_setup();
+ irq_setup();
- /* Blink STATUS LED (PF0) on the board. */
+ /* Blink each color of the RGB LED in order. */
while (1) {
/*
* Flash the Red diode
*/
- gpio_set(GPIOF, GPIO1);
-
- for (i = 0; i < FLASH_DELAY; i++) /* Wait a bit. */
- __asm__("nop");
-
- gpio_clear(GPIOF, GPIO1);
-
- for (i = 0; i < FLASH_DELAY; i++) /* Wait a bit. */
- __asm__("nop");
+ gpio_set(RGB_PORT, LED_R);
+ delay(); /* Wait a bit. */
+ gpio_clear(RGB_PORT, LED_R);
+ delay(); /* Wait a bit. */
/*
* Flash the Green diode
*/
- gpio_set(GPIOF, GPIO3);
-
- for (i = 0; i < FLASH_DELAY; i++) /* Wait a bit. */
- __asm__("nop");
-
- gpio_clear(GPIOF, GPIO3);
-
- for (i = 0; i < FLASH_DELAY; i++) /* Wait a bit. */
- __asm__("nop");
+ gpio_set(RGB_PORT, LED_G);
+ delay(); /* Wait a bit. */
+ gpio_clear(RGB_PORT, LED_G);
+ delay(); /* Wait a bit. */
/*
* Flash the Blue diode
*/
- gpio_set(GPIOF, GPIO2);
-
- for (i = 0; i < FLASH_DELAY; i++) /* Wait a bit. */
- __asm__("nop");
+ gpio_set(RGB_PORT, LED_B);
+ delay(); /* Wait a bit. */
+ gpio_clear(RGB_PORT, LED_B);
+ delay(); /* Wait a bit. */
+ }
- gpio_clear(GPIOF, GPIO2);
+ return 0;
+}
- for (i = 0; i < FLASH_DELAY; i++) /* Wait a bit. */
- __asm__("nop");
+void gpiof_isr(void)
+{
+ if (GPIO_RIS(GPIOF) & USR_SW1) {
+ /* SW1 was just depressed */
+ bypass = !bypass;
+ if (bypass) {
+ rcc_pll_bypass_enable();
+ /*
+ * The divisor is still applied to the raw clock.
+ * Disable the divisor, or we'll divide the raw clock.
+ */
+ SYSCTL_RCC &= ~SYSCTL_RCC_USESYSDIV;
+ }
+ else
+ {
+ rcc_change_pll_divisor(plldiv[ipll]);
+ }
+ /* Clear interrupt source */
+ GPIO_ICR(GPIOF) = USR_SW1;
}
- return 0;
+ if (GPIO_RIS(GPIOF) & USR_SW2) {
+ /* SW2 was just depressed */
+ if (!bypass) {
+ if (plldiv[++ipll] == 0)
+ ipll = 0;
+ rcc_change_pll_divisor(plldiv[ipll]);
+ }
+ /* Clear interrupt source */
+ GPIO_ICR(GPIOF) = USR_SW2;
+ }
}
diff --git a/include/libopencm3/lm4f/rcc.h b/include/libopencm3/lm4f/rcc.h
new file mode 100644
index 0000000..1c15f4b
--- /dev/null
+++ b/include/libopencm3/lm4f/rcc.h
@@ -0,0 +1,126 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2012 Alexandru Gagniuc <mr.nuke.me@gmail.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/>.
+ */
+
+/**
+ * @defgroup rcc_defines RCC Defines
+ *
+ * @ingroup LM4F_defines
+ *
+ * \brief <b>Defined Constants and Types for the LM4F Clock control API</b>
+ * @{
+ */
+
+#ifndef LM4F_RCC_H
+#define LM4F_RCC_H
+
+#include <libopencm3/lm4f/systemcontrol.h>
+
+/**
+ * \brief Oscillator source values
+ *
+ * Possible values of the oscillator source.
+ */
+typedef enum {
+ OSCSRC_MOSC = SYSCTL_RCC2_OSCSRC2_MOSC,
+ OSCSRC_PIOSC = SYSCTL_RCC2_OSCSRC2_PIOSC,
+ OSCSRC_PIOSC_D4 = SYSCTL_RCC2_OSCSRC2_PIOSC_D4,
+ OSCSRC_30K_INT = SYSCTL_RCC2_OSCSRC2_30K,
+ OSCSRC_32K_EXT = SYSCTL_RCC2_OSCSRC2_32K768,
+} osc_src_t;
+
+/**
+ * \brief PWM clock divisor values
+ *
+ * Possible values of the binary divisor used to predivide the system clock down
+ * for use as the timing reference for the PWM module.
+ */
+typedef enum {
+ PWMDIV_2 = SYSCTL_RCC_PWMDIV_2,
+ PWMDIV_4 = SYSCTL_RCC_PWMDIV_4,
+ PWMDIV_8 = SYSCTL_RCC_PWMDIV_8,
+ PWMDIV_16 = SYSCTL_RCC_PWMDIV_16,
+ PWMDIV_32 = SYSCTL_RCC_PWMDIV_32,
+ PWMDIV_64 = SYSCTL_RCC_PWMDIV_64,
+} pwm_clkdiv_t;
+
+/**
+ * \brief Predefined crystal values
+ *
+ * Predefined crystal values for the XTAL field in SYSCTL_RCC.
+ * Using these predefined values in the XTAL field, the SYSCTL_PLLFREQ0 and
+ * SYSCTL_PLLFREQ1 are automatically adjusted in hardware to provide a PLL clock
+ * of 400MHz.
+ */
+typedef enum {
+ XTAL_4M = SYSCTL_RCC_XTAL_4M,
+ XTAL_4M_096 = SYSCTL_RCC_XTAL_4M_096,
+ XTAL_4M_9152 = SYSCTL_RCC_XTAL_4M_9152,
+ XTAL_5M = SYSCTL_RCC_XTAL_5M,
+ XTAL_5M_12 = SYSCTL_RCC_XTAL_5M_12,
+ XTAL_6M = SYSCTL_RCC_XTAL_6M,
+ XTAL_6M_144 = SYSCTL_RCC_XTAL_6M_144,
+ XTAL_7M_3728 = SYSCTL_RCC_XTAL_7M_3728,
+ XTAL_8M = SYSCTL_RCC_XTAL_8M,
+ XTAL_8M_192 = SYSCTL_RCC_XTAL_8M_192,
+ XTAL_10M = SYSCTL_RCC_XTAL_10M,
+ XTAL_12M = SYSCTL_RCC_XTAL_12M,
+ XTAL_12M_288 = SYSCTL_RCC_XTAL_12M_288,
+ XTAL_13M_56 = SYSCTL_RCC_XTAL_13M_56,
+ XTAL_14M_31818 = SYSCTL_RCC_XTAL_14M_31818,
+ XTAL_16M = SYSCTL_RCC_XTAL_16M,
+ XTAL_16M_384 = SYSCTL_RCC_XTAL_16M_384,
+ XTAL_18M = SYSCTL_RCC_XTAL_18M,
+ XTAL_20M = SYSCTL_RCC_XTAL_20M,
+ XTAL_24M = SYSCTL_RCC_XTAL_24M,
+ XTAL_25M = SYSCTL_RCC_XTAL_25M,
+} xtal_t;
+
+/**
+ * @}
+ */
+/* =============================================================================
+ * Function prototypes
+ * ---------------------------------------------------------------------------*/
+BEGIN_DECLS
+/* Low-level clock API */
+void rcc_configure_xtal(xtal_t xtal);
+void rcc_disable_main_osc(void);
+void rcc_disable_interal_osc(void);
+void rcc_enable_main_osc(void);
+void rcc_enable_interal_osc(void);
+void rcc_enable_rcc2(void);
+void rcc_pll_off(void);
+void rcc_pll_on(void);
+void rcc_set_osc_source(osc_src_t src);
+void rcc_pll_bypass_disable(void);
+void rcc_pll_bypass_enable(void);
+void rcc_set_pll_divisor(u8 div400);
+void rcc_set_pwm_divisor(pwm_clkdiv_t div);
+void rcc_usb_pll_off(void);
+void rcc_usb_pll_on(void);
+void rcc_wait_for_pll_ready(void);
+/* High-level clock API */
+void rcc_change_pll_divisor(u8 plldiv400);
+u32 rcc_get_system_clock_frequency(void);
+void rcc_sysclk_config(osc_src_t src, xtal_t xtal, u8 pll_div400);
+
+END_DECLS
+
+
+#endif /* LM4F_RCC_H */
diff --git a/include/libopencm3/lm4f/systemcontrol.h b/include/libopencm3/lm4f/systemcontrol.h
index af4b71f..30fa1c9 100644
--- a/include/libopencm3/lm4f/systemcontrol.h
+++ b/include/libopencm3/lm4f/systemcontrol.h
@@ -21,6 +21,7 @@
#define LM4F_SYSTEMCONTROL_H
#include <libopencm3/cm3/common.h>
+#include <libopencm3/lm4f/memorymap.h>
#define SYSCTL_DID0 MMIO32(SYSCTL_BASE + 0x000)
#define SYSCTL_DID1 MMIO32(SYSCTL_BASE + 0x004)
@@ -369,9 +370,11 @@
/** Auto Clock Gating */
#define SYSCTL_RCC2_ACG (1 << 27)
/** System Clock Divisor 2 */
-#define SYSCTL_RCC2_SYSDIV2_MASK (0xF << 23)
+#define SYSCTL_RCC2_SYSDIV2_MASK (0x3F << 23)
/** Additional LSB for SYSDIV2 */
#define SYSCTL_RCC2_SYSDIV2LSB (1 << 22)
+/** System clock divisor mask when RCC2_DIV400 is set */
+#define SYSCTL_RCC2_SYSDIV400_MASK (0x7F << 22)
/** Power-Down USB PLL */
#define SYSCTL_RCC2_USBPWRDN (1 << 14)
/** PLL Power Down 2 */
@@ -450,6 +453,273 @@
/** PLL lock */
#define SYSCTL_PLLSTAT_LOCK (1 << 0)
+/* =============================================================================
+ * Convenience definitions for a readable API
+ * ---------------------------------------------------------------------------*/
+/**
+ * \brief Clock enable definitions
+ *
+ * The definitions are specified in the form
+ * 31:5 register offset from SYSCTL_BASE for the clock register
+ * 4:0 bit offset for the given peripheral
+ *
+ * The names have the form [clock_type]_[periph_type]_[periph_number]
+ * Where clock_type is
+ * RCC for run clock
+ * SCC for sleep clock
+ * DCC for deep-sleep clock
+ */
+typedef enum {
+ /*
+ * Run clock control
+ */
+ RCC_WD0 = ((u32)&SYSCTL_RCGCWD - SYSCTL_BASE) << 5,
+ RCC_WD1,
+
+ RCC_TIMER0 = ((u32)&SYSCTL_RCGCTIMER - SYSCTL_BASE) << 5,
+ RCC_TIMER1,
+ RCC_TIMER2,
+ RCC_TIMER3,
+ RCC_TIMER4,
+ RCC_TIMER5,
+
+ RCC_GPIOA = ((u32)&SYSCTL_RCGCGPIO - SYSCTL_BASE) << 5,
+ RCC_GPIOB,
+ RCC_GPIOC,
+ RCC_GPIOD,
+ RCC_GPIOE,
+ RCC_GPIOF,
+ RCC_GPIOG,
+ RCC_GPIOH,
+ RCC_GPIOJ,
+ RCC_GPIOK,
+ RCC_GPIOL,
+ RCC_GPIOM,
+ RCC_GPION,
+ RCC_GPIOP,
+ RCC_GPIOQ,
+
+ RCC_DMA = ((u32)&SYSCTL_RCGCDMA - SYSCTL_BASE) << 5,
+
+ RCC_HIB = ((u32)&SYSCTL_RCGCGPIO - SYSCTL_BASE) << 5,
+
+ RCC_UART0 = ((u32)&SYSCTL_RCGCUART - SYSCTL_BASE) << 5,
+ RCC_UART1,
+ RCC_UART2,
+ RCC_UART3,
+ RCC_UART4,
+ RCC_UART5,
+ RCC_UART6,
+ RCC_UART7,
+
+ RCC_SSI0 = ((u32)&SYSCTL_RCGCSSI - SYSCTL_BASE) << 5,
+ RCC_SSI1,
+ RCC_SSI2,
+ RCC_SSI3,
+
+ RCC_I2C0 = ((u32)&SYSCTL_RCGCI2C - SYSCTL_BASE) << 5,
+ RCC_I2C1,
+ RCC_I2C2,
+ RCC_I2C3,
+ RCC_I2C4,
+ RCC_I2C5,
+
+ RCC_USB0 = ((u32)&SYSCTL_RCGCUSB - SYSCTL_BASE) << 5,
+
+ RCC_CAN0 = ((u32)&SYSCTL_RCGCCAN - SYSCTL_BASE) << 5,
+ RCC_CAN1,
+
+ RCC_ADC0 = ((u32)&SYSCTL_RCGCADC - SYSCTL_BASE) << 5,
+ RCC_ADC1,
+
+ RCC_ACMP0 = ((u32)&SYSCTL_RCGCACMP - SYSCTL_BASE) << 5,
+
+ RCC_PWM0 = ((u32)&SYSCTL_RCGCPWM - SYSCTL_BASE) << 5,
+ RCC_PWM1,
+
+ RCC_QEI0 = ((u32)&SYSCTL_RCGCQEI - SYSCTL_BASE) << 5,
+ RCC_QEI1,
+
+ RCC_EEPROM0 = ((u32)&SYSCTL_RCGCEEPROM - SYSCTL_BASE) << 5,
+
+ RCC_WTIMER0 = ((u32)&SYSCTL_RCGCWTIMER - SYSCTL_BASE) << 5,
+ RCC_WTIMER1,
+ RCC_WTIMER2,
+ RCC_WTIMER3,
+ RCC_WTIMER4,
+ RCC_WTIMER5,
+
+
+ /*
+ * Sleep clock control
+ */
+ SCC_WD0 = ((u32)&SYSCTL_SCGCWD - SYSCTL_BASE) << 5,
+ SCC_WD1,
+
+ SCC_TIMER0 = ((u32)&SYSCTL_SCGCTIMER - SYSCTL_BASE) << 5,
+ SCC_TIMER1,
+ SCC_TIMER2,
+ SCC_TIMER3,
+ SCC_TIMER4,
+ SCC_TIMER5,
+
+ SCC_GPIOA = ((u32)&SYSCTL_SCGCGPIO - SYSCTL_BASE) << 5,
+ SCC_GPIOB,
+ SCC_GPIOC,
+ SCC_GPIOD,
+ SCC_GPIOE,
+ SCC_GPIOF,
+ SCC_GPIOG,
+ SCC_GPIOH,
+ SCC_GPIOJ,
+ SCC_GPIOK,
+ SCC_GPIOL,
+ SCC_GPIOM,
+ SCC_GPION,
+ SCC_GPIOP,
+ SCC_GPIOQ,
+
+ SCC_DMA = ((u32)&SYSCTL_SCGCDMA - SYSCTL_BASE) << 5,
+
+ SCC_HIB = ((u32)&SYSCTL_SCGCGPIO - SYSCTL_BASE) << 5,
+
+ SCC_UART0 = ((u32)&SYSCTL_SCGCUART - SYSCTL_BASE) << 5,
+ SCC_UART1,
+ SCC_UART2,
+ SCC_UART3,
+ SCC_UART4,
+ SCC_UART5,
+ SCC_UART6,
+ SCC_UART7,
+
+ SCC_SSI0 = ((u32)&SYSCTL_SCGCSSI - SYSCTL_BASE) << 5,
+ SCC_SSI1,
+ SCC_SSI2,
+ SCC_SSI3,
+
+ SCC_I2C0 = ((u32)&SYSCTL_SCGCI2C - SYSCTL_BASE) << 5,
+ SCC_I2C1,
+ SCC_I2C2,
+ SCC_I2C3,
+ SCC_I2C4,
+ SCC_I2C5,
+
+ SCC_USB0 = ((u32)&SYSCTL_SCGCUSB - SYSCTL_BASE) << 5,
+
+ SCC_CAN0 = ((u32)&SYSCTL_SCGCCAN - SYSCTL_BASE) << 5,
+ SCC_CAN1,
+
+ SCC_ADC0 = ((u32)&SYSCTL_SCGCADC - SYSCTL_BASE) << 5,
+ SCC_ADC1,
+
+ SCC_ACMP0 = ((u32)&SYSCTL_SCGCACMP - SYSCTL_BASE) << 5,
+
+ SCC_PWM0 = ((u32)&SYSCTL_SCGCPWM - SYSCTL_BASE) << 5,
+ SCC_PWM1,
+
+ SCC_QEI0 = ((u32)&SYSCTL_SCGCQEI - SYSCTL_BASE) << 5,
+ SCC_QEI1,
+
+ SCC_EEPROM0 = ((u32)&SYSCTL_SCGCEEPROM - SYSCTL_BASE) << 5,
+
+ SCC_WTIMER0 = ((u32)&SYSCTL_SCGCWTIMER - SYSCTL_BASE) << 5,
+ SCC_WTIMER1,
+ SCC_WTIMER2,
+ SCC_WTIMER3,
+ SCC_WTIMER4,
+ SCC_WTIMER5,
+
+ /*
+ * Deep-sleep clock control
+ */
+ DCC_WD0 = ((u32)&SYSCTL_DCGCWD - SYSCTL_BASE) << 5,
+ DCC_WD1,
+
+ DCC_TIMER0 = ((u32)&SYSCTL_DCGCTIMER - SYSCTL_BASE) << 5,
+ DCC_TIMER1,
+ DCC_TIMER2,
+ DCC_TIMER3,
+ DCC_TIMER4,
+ DCC_TIMER5,
+
+ DCC_GPIOA = ((u32)&SYSCTL_DCGCGPIO - SYSCTL_BASE) << 5,
+ DCC_GPIOB,
+ DCC_GPIOC,
+ DCC_GPIOD,
+ DCC_GPIOE,
+ DCC_GPIOF,
+ DCC_GPIOG,
+ DCC_GPIOH,
+ DCC_GPIOJ,
+ DCC_GPIOK,
+ DCC_GPIOL,
+ DCC_GPIOM,
+ DCC_GPION,
+ DCC_GPIOP,
+ DCC_GPIOQ,
+
+ DCC_DMA = ((u32)&SYSCTL_DCGCDMA - SYSCTL_BASE) << 5,
+
+ DCC_HIB = ((u32)&SYSCTL_DCGCGPIO - SYSCTL_BASE) << 5,
+
+ DCC_UART0 = ((u32)&SYSCTL_DCGCUART - SYSCTL_BASE) << 5,
+ DCC_UART1,
+ DCC_UART2,
+ DCC_UART3,
+ DCC_UART4,
+ DCC_UART5,
+ DCC_UART6,
+ DCC_UART7,
+
+ DCC_SSI0 = ((u32)&SYSCTL_DCGCSSI - SYSCTL_BASE) << 5,
+ DCC_SSI1,
+ DCC_SSI2,
+ DCC_SSI3,
+
+ DCC_I2C0 = ((u32)&SYSCTL_DCGCI2C - SYSCTL_BASE) << 5,
+ DCC_I2C1,
+ DCC_I2C2,
+ DCC_I2C3,
+ DCC_I2C4,
+ DCC_I2C5,
+
+ DCC_USB0 = ((u32)&SYSCTL_DCGCUSB - SYSCTL_BASE) << 5,
+
+ DCC_CAN0 = ((u32)&SYSCTL_DCGCCAN - SYSCTL_BASE) << 5,
+ DCC_CAN1,
+
+ DCC_ADC0 = ((u32)&SYSCTL_DCGCADC - SYSCTL_BASE) << 5,
+ DCC_ADC1,
+
+ DCC_ACMP0 = ((u32)&SYSCTL_DCGCACMP - SYSCTL_BASE) << 5,
+
+ DCC_PWM0 = ((u32)&SYSCTL_DCGCPWM - SYSCTL_BASE) << 5,
+ DCC_PWM1,
+
+ DCC_QEI0 = ((u32)&SYSCTL_DCGCQEI - SYSCTL_BASE) << 5,
+ DCC_QEI1,
+
+ DCC_EEPROM0 = ((u32)&SYSCTL_DCGCEEPROM - SYSCTL_BASE) << 5,
+
+ DCC_WTIMER0 = ((u32)&SYSCTL_DCGCWTIMER - SYSCTL_BASE) << 5,
+ DCC_WTIMER1,
+ DCC_WTIMER2,
+ DCC_WTIMER3,
+ DCC_WTIMER4,
+ DCC_WTIMER5,
+
+} clken_t;
+
+/* =============================================================================
+ * Function prototypes
+ * ---------------------------------------------------------------------------*/
+BEGIN_DECLS
+
+void periph_clock_enable(clken_t periph);
+void periph_clock_disable(clken_t periph);
+
+END_DECLS
+
#endif /* LM4F_SYSTEMCONTROL_H */
diff --git a/lib/lm4f/Makefile b/lib/lm4f/Makefile
index 8f4c151..a3b7dce 100644
--- a/lib/lm4f/Makefile
+++ b/lib/lm4f/Makefile
@@ -28,7 +28,7 @@ CFLAGS = -Os -g -Wall -Wextra -I../../include -fno-common \
-ffunction-sections -fdata-sections -MD -DLM4F
# ARFLAGS = rcsv
ARFLAGS = rcs
-OBJS = gpio.o vector.o assert.o
+OBJS = gpio.o vector.o assert.o systemcontrol.o rcc.o
VPATH += ../cm3
diff --git a/lib/lm4f/rcc.c b/lib/lm4f/rcc.c
new file mode 100644
index 0000000..48eb2a2
--- /dev/null
+++ b/lib/lm4f/rcc.c
@@ -0,0 +1,493 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2012 Alexandru Gagniuc <mr.nuke.me@gmail.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/>.
+ *
+ */
+
+/**
+ * @defgroup rcc_file RCC
+ *
+ * @ingroup LM4F
+ *
+ * \brief <b>libopencm3 LM4F Clock control API</b>
+ *
+ * The LM$F clock API provides functionaliity for manipulating the system clock,
+ * oscillator, and PLL. Functions are provided for fine-grained control of clock
+ * control registers, while also providing higher level functionality to easily
+ * configure the main system clock source.
+ *
+ * The following code snippet uses fine-grained mechanisms to configures the
+ * chip to run off an external 16MHz crystal, and use the PLL to derive a clock
+ * frequency of 80MHz.
+ * @code{.c}
+ * // A divisor of 5 gives us a clock of 400/5 = 80MHz
+ * #define PLLDIV_80MHZ 5
+ *
+ * // Enable the main oscillator
+ * rcc_enable_main_osc();
+ *
+ * // Make RCC2 override RCC
+ * rcc_enable_rcc2();
+ *
+ * // Set XTAL value to 16MHz
+ * rcc_configure_xtal(XTAL_16M);
+ * // Set the oscillator source as the main oscillator
+ * rcc_set_osc_source(OSCSRC_MOSC);
+ * // Enable the PLL
+ * rcc_pll_on();
+ *
+ * // Change the clock divisor
+ * rcc_set_pll_divisor(PLLDIV_80MHZ);
+ *
+ * // We cannot use the PLL as a clock source until it locks
+ * rcc_wait_for_pll_ready();
+ * // Disable PLL bypass to derive the system clock from the PLL clock
+ * rcc_pll_bypass_disable();
+ *
+ * // Keep track of frequency
+ * lm4f_rcc_sysclk_freq = 80E6;
+ * @endcode
+ *
+ * The same can be achieved by a simple call to high-level routines:
+ * @code
+ * // A divisor of 5 gives us a clock of 400/5 = 80MHz
+ * #define PLLDIV_80MHZ 5
+ *
+ * rcc_sysclk_config(OSCSRC_MOSC, XTAL_16M, PLLDIV_80MHZ);
+ * @endcode
+ *
+ * @{
+ */
+
+#include <libopencm3/lm4f/rcc.h>
+
+/**
+ * @defgroup rcc_low_level Low-level clock control API
+ * @{
+ */
+/**
+ * \brief System clock frequency
+ *
+ * This variable is provided to keep track of the system clock frequency. It
+ * should be updated every time the system clock is changed via the fine-grained
+ * mechanisms. The initial value is 16MHz, which corresponds to the clock of the
+ * internal 16MHz oscillator.
+ *
+ * High-level routines update the system clock automatically.
+ * For read access, it is recommended to acces this variable via
+ * @code
+ * rcc_get_system_clock_frequency();
+ * @endcode
+ *
+ * If write access is desired (i.e. when changing the system clock via the
+ * fine-grained mechanisms), then include the following line in your code:
+ * @code
+ * extern u32 lm4f_rcc_sysclk_freq;
+ * @endcode
+ */
+u32 lm4f_rcc_sysclk_freq = 16000000;
+
+
+/**
+ * \brief Configure the crystal type connected to the device.
+ *
+ * Configure the crystal type connected between the OSCO and OSCI pins by
+ * writing the appropriate value to the XTAL field in SYSCTL_RCC. The PLL
+ * parameters are automatically adjusted in hardware to provide a PLL clock of
+ * 400MHz.
+ *
+ * @param[in] xtal predefined crystal type @see xtal_t
+ */
+void rcc_configure_xtal(xtal_t xtal)
+{
+ u32 reg32;
+
+ reg32 = SYSCTL_RCC;
+ reg32 &= ~SYSCTL_RCC_XTAL_MASK;
+ reg32 |= (xtal & SYSCTL_RCC_XTAL_MASK);
+ SYSCTL_RCC = reg32;
+}
+
+/**
+ * \brief Disable the main oscillator
+ *
+ * Sets the IOSCDIS bit in SYSCTL_RCC, disabling the main oscillator.
+ */
+void rcc_disable_main_osc(void)
+{
+ SYSCTL_RCC |= SYSCTL_RCC_MOSCDIS;
+}
+
+/**
+ * \brief Disable the internal oscillator
+ *
+ * Sets the IOSCDIS bit in SYSCTL_RCC, disabling the internal oscillator.
+ */
+void rcc_disable_interal_osc(void)
+{
+ SYSCTL_RCC |= SYSCTL_RCC_IOSCDIS;
+}
+
+/**
+ * \brief Enable the main oscillator
+ *
+ * Clears the MOSCDIS bit in SYSCTL_RCC, enabling the main oscillator.
+ */
+void rcc_enable_main_osc(void)
+{
+ SYSCTL_RCC &= ~SYSCTL_RCC_MOSCDIS;
+}
+
+/**
+ * \brief Enable the internal oscillator
+ *
+ * Clears the IOSCDIS bit in SYSCTL_RCC, enabling the internal oscillator.
+ */
+void rcc_enable_interal_osc(void)
+{
+ SYSCTL_RCC &= ~SYSCTL_RCC_IOSCDIS;
+}
+
+/**
+ * \brief Enable the use of SYSCTL_RCC2 register for clock control
+ *
+ * Enables the USERCC2 bit in SYSCTTL_RCC2. Settings in SYSCTL_RCC2 will
+ * override settings in SYSCTL_RCC.
+ * This function must be called before other calls to manipulate the clock, as
+ * libopencm3 uses the SYSCTL_RCC2 register.
+ */
+void rcc_enable_rcc2(void)
+{
+ SYSCTL_RCC2 |= SYSCTL_RCC2_USERCC2;
+}
+
+/**
+ * \brief Power down the main PLL
+ *
+ * Sets the SYSCTL_RCC2_PWRDN2 in SYSCTL_RCC2 to power down the PLL.
+ *
+ * USERCC2 must have been set by a call to rcc_enable_rcc2() before calling this
+ * function.
+ */
+void rcc_pll_off(void)
+{
+ SYSCTL_RCC2 |= SYSCTL_RCC2_PWRDN2;
+}
+
+/**
+ * \brief Power up the main PLL
+ *
+ * Clears the PWRDN2 in SYSCTL_RCC2 to power on the PLL.
+ *
+ * USERCC2 must have been set by a call to rcc_enable_rcc2() before calling this
+ * function.
+ */
+void rcc_pll_on(void)
+{
+ SYSCTL_RCC2 &= ~SYSCTL_RCC2_PWRDN2;
+}
+
+/**
+ * \brief Set the oscillator source to be used by the system clock
+ *
+ * Set the clock source for the system clock.
+ *
+ * USERCC2 must have been set by a call to rcc_enable_rcc2() before calling this
+ * function.
+ */
+void rcc_set_osc_source(osc_src_t src)
+{
+ u32 reg32;
+
+ reg32 = SYSCTL_RCC2;
+ reg32 &= ~SYSCTL_RCC2_OSCSRC2_MASK;
+ reg32 |= (src & SYSCTL_RCC2_OSCSRC2_MASK);
+ SYSCTL_RCC2 = reg32;
+}
+
+/**
+ * \brief Disable the PLL bypass and use the PLL clock
+ *
+ * Clear BYPASS2 in SYSCTL_RCC2. The system clock is derived from the PLL
+ * clock divided by the divisor specified in SYSDIV2.
+ *
+ * USERCC2 must have been set by a call to rcc_enable_rcc2() before calling this
+ * function.
+ */
+void rcc_pll_bypass_disable(void)
+{
+ SYSCTL_RCC2 &= ~SYSCTL_RCC2_BYPASS2;
+}
+
+/**
+ * \brief Enable the PLL bypass and use the oscillator clock
+ *
+ * Set BYPASS2 in SYSCTL_RCC2. The system clock is derived from the oscillator
+ * clock divided by the divisor specified in SYSDIV2.
+ *
+ * USERCC2 must have been set by a call to rcc_enable_rcc2() before calling this
+ * function.
+ */
+void rcc_pll_bypass_enable(void)
+{
+ SYSCTL_RCC2 |= SYSCTL_RCC2_BYPASS2;
+}
+
+/**
+ * \brief Set the PLL clock divisor (from 400MHz)
+ *
+ * Set the binary divisor used to predivide the system clock down for use as the
+ * timing reference for the PWM module. The divisor is expected to be a divisor
+ * from 400MHz, not 200MHz. The DIV400 is also set.
+ *
+ * Specifies the divisor that used to generate the system clock from either the
+ * PLL output or the oscillator source (depending on the BYPASS2 bit in
+ * SYSCTL_RCC2). SYSDIV2 is used for the divisor when both the USESYSDIV bit in
+ * SYSCTL_RCC is set.
+ *
+ * USERCC2 must have been set by a call to rcc_enable_rcc2() before calling this
+ * function.
+ *
+ * @param[in] div clock divisor to apply to the 400MHz PLL clock. It is the
+ * caller's responsibility to ensure that the divisor will not create
+ * a system clock that is out of spec.
+ */
+void rcc_set_pll_divisor(u8 div400)
+{
+ u32 reg32;
+
+ SYSCTL_RCC |= SYSCTL_RCC_USESYSDIV;
+
+ reg32 = SYSCTL_RCC2;
+ reg32 &= ~SYSCTL_RCC2_SYSDIV400_MASK;
+ reg32 |= (div400 << 22) & SYSCTL_RCC2_SYSDIV400_MASK;
+ /* We are expecting a divider from 400MHz */
+ reg32 |= SYSCTL_RCC2_DIV400;
+ SYSCTL_RCC2 = reg32;
+}
+/**
+ * \brief Set the PWM unit clock divisor
+ *
+ * Set the binary divisor used to predivide the system clock down for use as the
+ * timing reference for the PWM module.
+ *
+ * @param[in] div clock divisor to use @see pwm_clkdiv_t
+ */
+void rcc_set_pwm_divisor(pwm_clkdiv_t div)
+{
+ u32 reg32;
+
+ reg32 = SYSCTL_RCC;
+ reg32 &= ~SYSCTL_RCC_PWMDIV_MASK;
+ reg32 |= (div & SYSCTL_RCC_PWMDIV_MASK);
+ SYSCTL_RCC = reg32;
+}
+
+/**
+ * \brief Power down the USB PLL
+ *
+ * Sets the USBPWRDN in SYSCTL_RCC2 to power down the USB PLL.
+ *
+ * USERCC2 must have been set by a call to rcc_enable_rcc2() before calling this
+ * function.
+ */
+void rcc_usb_pll_off(void)
+{
+ SYSCTL_RCC2 |= SYSCTL_RCC2_USBPWRDN;
+}
+
+/**
+ * \brief Power up the USB PLL
+ *
+ * Clears the USBPWRDN in SYSCTL_RCC2 to power on the USB PLL.
+ *
+ * USERCC2 must have been set by a call to rcc_enable_rcc2() before calling this
+ * function.
+ */
+void rcc_usb_pll_on(void)
+{
+ SYSCTL_RCC2 &= ~SYSCTL_RCC2_USBPWRDN;
+}
+
+/**
+ * \brief Wait for main PLL to lock
+ *
+ * Waits until the LOCK bit in SYSCTL_PLLSTAT is set. This guarantees that the
+ * PLL is locked, and ready to use.
+ */
+void rcc_wait_for_pll_ready(void)
+{
+ while(!(SYSCTL_PLLSTAT & SYSCTL_PLLSTAT_LOCK));
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @defgroup rcc_high_level High-level clock control API
+ * @{
+ */
+
+/**
+ * \brief Change the PLL divisor
+ *
+ * Changes the divisor applied to the 400MHz PLL clock. The PLL must have
+ * previously been configured by selecting an appropriate XTAL value, and
+ * turning on the PLL. This function does not reconfigure the XTAL value or
+ * oscillator source. It only changes the PLL divisor.
+ *
+ * The PLL is bypassed before modifying the divisor, and the function blocks
+ * until the PLL is locked, then the bypass is disabled, before returning.
+ *
+ * @param [in] pll_div400 The clock divisor to apply to the 400MHz PLL clock.
+ */
+void rcc_change_pll_divisor(u8 pll_div400)
+{
+ /* Bypass the PLL while its settings are modified */
+ rcc_pll_bypass_enable();
+ /* Change the clock divisor */
+ rcc_set_pll_divisor(pll_div400);
+ /* We cannot use the PLL as a clock source until it locks */
+ rcc_wait_for_pll_ready();
+ /* Disable PLL bypass to derive the system clock from the PLL clock */
+ rcc_pll_bypass_disable();
+ /* Update the system clock frequency for housekeeping */
+ lm4f_rcc_sysclk_freq = (u32)400E6 / pll_div400;
+}
+
+/**
+ * \brief Get the system clock frequency
+ *
+ * @return System clock frequency in Hz
+ */
+u32 rcc_get_system_clock_frequency(void)
+{
+ return lm4f_rcc_sysclk_freq;
+}
+
+/* Get the clock frequency corresponging to a given XTAL value */
+static u32 xtal_to_freq(xtal_t xtal)
+{
+ const u32 freqs[] = {
+ 4000000, /* XTAL_4M */
+ 4096000, /* XTAL_4M_096 */
+ 4915200, /* XTAL_4M_9152 */
+ 5000000, /* ,XTAL_5M */
+ 5120000, /* XTAL_5M_12 */
+ 6000000, /* XTAL_6M */
+ 6144000, /* XTAL_6M_144 */
+ 7372800, /* XTAL_7M_3728 */
+ 8000000, /* XTAL_8M */
+ 8192000, /* XTAL_8M_192 */
+ 10000000, /* XTAL_10M */
+ 12000000, /* XTAL_12M */
+ 12288000, /* XTAL_12M_288 */
+ 13560000, /* XTAL_13M_56 */
+ 14318180, /* XTAL_14M_31818 */
+ 16000000, /* XTAL_16M */
+ 16384000, /* XTAL_16M_384 */
+ 18000000, /* XTAL_18M */
+ 20000000, /* XTAL_20M */
+ 24000000, /* XTAL_24M */
+ 25000000, /* XTAL_25M */
+ };
+
+ return freqs[xtal - XTAL_4M];
+}
+
+/**
+ * \brief Configure the system clock source
+ *
+ * Sets up the system clock, including configuring the oscillator source, and
+ * PLL to acheve the desired system clock frequency. Where applicable, The LM4F
+ * clock API uses the new RCC2 register to configure clock parameters.
+ *
+ * Enables the main oscillator if the clock source is OSCSRC_MOSC. If the main
+ * oscillator was previously enabled, it will not be disabled. If desired, it
+ * can be separately disabled by a call to rcc_disable_main_osc().
+ *
+ * Configures the system clock to run from the 400MHz PLL with a divisor of
+ * pll_div400 applied. If pll_div400 is 0, then the PLL is disabled, and the
+ * system clock is configured to run off a "raw" clock. If the PLL was
+ * previously powered on, it will not be disabled. If desired, it can de powered
+ * off by a call to rcc_pll_off().
+ *
+ * @param [in] osc_src Oscillator from where to derive the system clock.
+ * @param [in] xtal Type of crystal connected to the OSCO/OSCI pins
+ * @param [in] pll_div400 The clock divisor to apply to the 400MHz PLL clock.
+ * If 0, then the PLL is disabled, and the system runs
+ * off a "raw" clock.
+ *
+ * @return System clock frequency in Hz
+ */
+void rcc_sysclk_config(osc_src_t osc_src, xtal_t xtal, u8 pll_div400)
+{
+ /*
+ * We could be using the PLL at this point, or we could be running of a
+ * raw clock. Either way, it is safer to bypass the PLL now.
+ */
+ rcc_pll_bypass_enable();
+
+ /* Enable the main oscillator, if needed */
+ if (osc_src == OSCSRC_MOSC)
+ rcc_enable_main_osc();
+
+ /* Make RCC2 override RCC */
+ rcc_enable_rcc2();
+
+ /* Set XTAL value to 16MHz */
+ rcc_configure_xtal(xtal);
+ /* Set the oscillator source */
+ rcc_set_osc_source(osc_src);
+ if (pll_div400) {
+ /* Enable the PLL */
+ rcc_pll_on();
+ /* Configure the PLL to the divisor we want */
+ rcc_change_pll_divisor(pll_div400);
+ } else {
+ /* We are running off a raw clock */
+ switch (osc_src) {
+ case OSCSRC_PIOSC:
+ lm4f_rcc_sysclk_freq = 16000000;
+ break;
+ case OSCSRC_PIOSC_D4:
+ lm4f_rcc_sysclk_freq = 4000000;
+ break;
+ case OSCSRC_MOSC:
+ lm4f_rcc_sysclk_freq = xtal_to_freq(xtal);
+ break;
+ case OSCSRC_32K_EXT:
+ lm4f_rcc_sysclk_freq = 32768;
+ break;
+ case OSCSRC_30K_INT: /* Fall through. */
+ default:
+ /*
+ * We either are running off the internal 30KHz
+ * oscillator, which is +- 50% imprecise, or we got a
+ * bad osc_src parameter.
+ */
+ lm4f_rcc_sysclk_freq = 0;
+ }
+ }
+
+}
+
+/**
+ * @}
+ * @}
+ */
diff --git a/lib/lm4f/systemcontrol.c b/lib/lm4f/systemcontrol.c
new file mode 100644
index 0000000..691b661
--- /dev/null
+++ b/lib/lm4f/systemcontrol.c
@@ -0,0 +1,40 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2012 Alexandru Gagniuc <mr.nuke.me@gmail.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/lm4f/systemcontrol.h>
+
+/**
+ * \brief Enable the clock source for the peripheral
+ *
+ * @param[in] periph peripheral and clock type to enable @see clken_t
+ */
+void periph_clock_enable(clken_t periph)
+{
+ MMIO32(SYSCTL_BASE + (periph >> 5)) |= 1 << (periph & 0x1f);
+}
+
+/**
+ * \brief Disable the clock source for the peripheral
+ *
+ * @param[in] periph peripheral and clock type to enable @see clken_t
+ */
+void periph_clock_disable(clken_t periph)
+{
+ MMIO32(SYSCTL_BASE + (periph >> 5)) &= ~(1 << (periph & 0x1f));
+}