--- /dev/null
+TE! Don't add files that are generated in specific
+# subdirectories here. Add them in the ".gitignore" file
+# in that subdirectory instead.
+#
+# NOTE! Please use 'git ls-files -i --exclude-standard'
+# command after changing this file, to see if there are
+# any tracked files which get ignored after the change.
+#
+# Normal rules
+#
+*.o
+*.d
+*.bin
+*.map
+*/objs/*
+*.zip
+*.svg
+*.dump
--- /dev/null
+# Makefile for control
+
+NAME = mod_gpio
+LPC = lpc1224
+CPU = cortex-m0
+ARCH = armv6-m
+
+CROSS_COMPILE = arm-linux-gnueabi-
+CC = $(CROSS_COMPILE)gcc
+
+FOPTS = -fmessage-length=0 -ffunction-sections -fdata-sections \
+ -static -fno-builtin
+CFLAGS = -Wall -O2 -mthumb -mcpu=$(CPU) $(FOPTS)
+#CFLAGS = -Wall -O2 -mthumb -march=$(ARCH) $(FOPTS)
+LINKOPTS = -nostartfiles -Wl,--gc-sections -Wl,--build-id=none \
+ -Wl,-Map=lpc_map_$(LPC).map -Tlpc_link_$(LPC).ld
+
+
+.PHONY: all
+all: $(NAME)
+
+
+INCLUDES = include/
+OBJDIR = objs
+
+SRC = $(shell find . -name \*.c)
+OBJS = ${SRC:%.c=${OBJDIR}/%.o}
+
+$(NAME): $(OBJS)
+ @echo "Linking ..."
+ @$(CC) $(CFLAGS) $(LINKOPTS) $(OBJS) -o $@ -I$(INCLUDES)
+ @echo "Creating image : \e[32m$@.bin\e[37m"
+ @$(CROSS_COMPILE)objcopy -R .stack -R .bss -O binary $@ $@.bin
+ @ls -l $@.bin
+ @echo Done.
+
+${OBJDIR}/%.o: %.c
+ @mkdir -p $(dir $@)
+ @echo "-- compiling" $<
+ @$(CC) -MMD -MP -MF ${OBJDIR}/$*.d $(CFLAGS) $< -c -o $@ -I$(INCLUDES)
+
+clean:
+ find ${OBJDIR} -name "*.o" -exec rm {} \;
+ find ${OBJDIR} -name "*.d" -exec rm {} \;
+ rm -f *.map
+
+mrproper: clean
+ rm -f $(NAME)*
--- /dev/null
+/****************************************************************************
+ * core/bootstrap.c
+ *
+ * This file holds the bootstrap code, the vector table, and nothing more.
+ * The bootstrap code is the code of the reset handler, which is called by
+ * the bootloader (executed from internal ROM after power on or reset).
+ * The reset handler code perform copy of data section, clears bss, and
+ * calls the main function.
+ *
+ *
+ * Copyright 2012 Nathael Pajani <nathael.pajani@ed3l.fr>
+ *
+ * Example code from frozeneskimo.com :
+ * http://dev.frozeneskimo.com/notes/getting_started_with_cortex_m3_cmsis_and_gnu_tools
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program 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 General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *****************************************************************************/
+
+
+extern unsigned int _end_stack;
+extern unsigned int _end_text;
+extern unsigned int _start_data;
+extern unsigned int _end_data;
+extern unsigned int _start_bss;
+extern unsigned int _end_bss;
+
+extern int main(void);
+
+/* Cortex M0 core interrupt handlers */
+void Reset_Handler(void);
+void NMI_Handler(void) __attribute__ ((weak, alias ("Dummy_Handler")));
+void HardFault_Handler(void) __attribute__ ((weak, alias ("Dummy_Handler")));
+void SVC_Handler(void) __attribute__ ((weak, alias ("Dummy_Handler")));
+void PendSV_Handler(void) __attribute__ ((weak, alias ("Dummy_Handler")));
+void SysTick_Handler(void) __attribute__ ((weak, alias ("Dummy_Handler")));
+/* LPC12xx specific interrupt handlers */
+void WAKEUP_Handler(void) __attribute__ ((weak, alias ("Dummy_Handler")));
+void I2C_0_Handler(void) __attribute__ ((weak, alias ("Dummy_Handler")));
+void TIMER_0_Handler(void) __attribute__ ((weak, alias ("Dummy_Handler")));
+void TIMER_1_Handler(void) __attribute__ ((weak, alias ("Dummy_Handler")));
+void TIMER_2_Handler(void) __attribute__ ((weak, alias ("Dummy_Handler")));
+void TIMER_3_Handler(void) __attribute__ ((weak, alias ("Dummy_Handler")));
+void SSP_0_Handler(void) __attribute__ ((weak, alias ("Dummy_Handler")));
+void UART_0_Handler(void) __attribute__ ((weak, alias ("Dummy_Handler")));
+void UART_1_Handler(void) __attribute__ ((weak, alias ("Dummy_Handler")));
+void Comparator_Handler(void) __attribute__ ((weak, alias ("Dummy_Handler")));
+void ADC_Handler(void) __attribute__ ((weak, alias ("Dummy_Handler")));
+void WDT_Handler(void) __attribute__ ((weak, alias ("Dummy_Handler")));
+void BOD_Handler(void) __attribute__ ((weak, alias ("Dummy_Handler")));
+void PIO_0_Handler(void) __attribute__ ((weak, alias ("Dummy_Handler")));
+void PIO_1_Handler(void) __attribute__ ((weak, alias ("Dummy_Handler")));
+void PIO_2_Handler(void) __attribute__ ((weak, alias ("Dummy_Handler")));
+void DMA_Handler(void) __attribute__ ((weak, alias ("Dummy_Handler")));
+void RTC_Handler(void) __attribute__ ((weak, alias ("Dummy_Handler")));
+
+
+
+void Dummy_Handler(void);
+
+
+/***************************************************************************** */
+/* Vector table */
+/***************************************************************************** */
+void *vector_table[] __attribute__ ((section(".vectors"))) = {
+ &_end_stack, /* Initial SP value */ /* 0 */
+ Reset_Handler,
+ NMI_Handler,
+ HardFault_Handler,
+ 0,
+ 0, /* 5 */
+ 0,
+ /* Entry 7 (8th entry) must contain the 2’s complement of the check-sum
+ of table entries 0 through 6. This causes the checksum of the first 8
+ table entries to be 0 */
+ (void *)0xDEADBEEF, /* Actually, this is done using an external tool. */
+ 0,
+ 0,
+ 0, /* 10 */
+ SVC_Handler,
+ 0,
+ 0,
+ PendSV_Handler,
+ SysTick_Handler, /* 15 */
+ /* LPC12xx specific interrupt vectors, see chapter 3 of LPC12xx User manual (UM10441) */
+ WAKEUP_Handler, /* 16 */ /* IRQ0 */
+ WAKEUP_Handler,
+ WAKEUP_Handler,
+ WAKEUP_Handler,
+ WAKEUP_Handler, /* 20 */
+ WAKEUP_Handler, /* 21 */ /* IRQ5 */
+ WAKEUP_Handler,
+ WAKEUP_Handler,
+ WAKEUP_Handler,
+ WAKEUP_Handler, /* 25 */
+ WAKEUP_Handler, /* 26 */ /* IRQ10 */
+ WAKEUP_Handler,
+ I2C_0_Handler,
+ TIMER_0_Handler, /* CT16B0 */
+ TIMER_1_Handler, /* CT16B1 */ /* 30 */
+ TIMER_2_Handler, /* CT32B0 */ /* IRQ15 */
+ TIMER_3_Handler, /* CT32B1 */
+ SSP_0_Handler,
+ UART_0_Handler,
+ UART_1_Handler, /* 35 */
+ Comparator_Handler, /* IRQ20 */
+ ADC_Handler,
+ WDT_Handler,
+ BOD_Handler,
+ 0, /* 40 */
+ PIO_0_Handler, /* IRQ25 */
+ PIO_1_Handler,
+ PIO_2_Handler,
+ 0,
+ DMA_Handler, /* 45 */
+ RTC_Handler, /* IRQ30 */
+ 0,
+};
+
+
+extern void rom_div_helpers_init(void);
+/*
+ * This is the entry point of the programm
+ * It does the set up of the memory and then starts the main.
+ */
+void Reset_Handler(void) {
+ unsigned int *src, *dst;
+
+ /* Copy data section from flash to RAM */
+ src = &_end_text;
+ dst = &_start_data;
+ while (dst < &_end_data)
+ *dst++ = *src++;
+
+ /* Clear the bss section */
+ dst = &_start_bss;
+ while (dst < &_end_bss)
+ *dst++ = 0;
+
+ /* Initialize rom based division helpers */
+ rom_div_helpers_init();
+ /* Start main programm */
+ main();
+}
+
+void Dummy_Handler(void) {
+ while (1);
+}
+
--- /dev/null
+/****************************************************************************
+ * core/fault_handlers.c
+ *
+ *
+ * Copyright 2012 Nathael Pajani <nathael.pajani@ed3l.fr>
+ *
+ * Example code from frozeneskimo.com :
+ * http://dev.frozeneskimo.com/notes/getting_started_with_cortex_m3_cmsis_and_gnu_tools
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program 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 General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *****************************************************************************/
+
+#include "core/lpc_regs_12xx.h"
+#include "lib/string.h"
+
+#if 0
+extern char* UARTBUFFER;
+extern volatile int UARTPTR;
+extern volatile int UARTSENDPTR;
+extern volatile int UARTSENDING;
+
+void fault_info(const char* name, uint32_t len)
+{
+ struct lpc_uart* uart = LPC_UART_1;
+ char* dest = &UARTBUFFER[UARTPTR];
+ UARTPTR += len;
+ memcpy(dest, name, len);
+ if (UARTSENDING == 0) {
+ uart->func.buffer = UARTBUFFER[UARTSENDPTR++];
+ }
+}
+
+/* Cortex M0 core interrupt handlers */
+void NMI_Handler(void)
+{
+ fault_info(__FUNCTION__, sizeof(__FUNCTION__));
+}
+void HardFault_Handler(void)
+{
+ fault_info(__FUNCTION__, sizeof(__FUNCTION__));
+}
+void SVC_Handler(void)
+{
+ fault_info(__FUNCTION__, sizeof(__FUNCTION__));
+}
+void PendSV_Handler(void)
+{
+ fault_info(__FUNCTION__, sizeof(__FUNCTION__));
+}
+void SysTick_Handler(void)
+{
+ fault_info(__FUNCTION__, sizeof(__FUNCTION__));
+}
+#endif
+
+
+
--- /dev/null
+/****************************************************************************
+ * core/system.c
+ *
+ * All low-level functions for clocks configuration and switch, system
+ * power-up, reset, and power-down.
+ *
+ * Copyright 2012 Nathael Pajani <nathael.pajani@ed3l.fr>
+ *
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program 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 General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *************************************************************************** */
+
+#include <stdint.h>
+
+#include "core/lpc_regs_12xx.h"
+#include "core/lpc_core_cm0.h"
+#include "core/system.h"
+
+
+/* Private defines */
+#define LPC_IRC_OSC_CLK (12000000UL) /* Internal RC oscillator frequency : 12MHz */
+
+/***************************************************************************** */
+/* Global data */
+/***************************************************************************** */
+struct lpc_desc_private {
+ uint32_t main_clock;
+ uint32_t brown_out_detection_enabled;
+};
+struct lpc_desc_private global = {
+ .main_clock = LPC_IRC_OSC_CLK,
+ .brown_out_detection_enabled = 0,
+};
+
+/***************************************************************************** */
+/* Requiered system inits */
+/***************************************************************************** */
+/* Set up number of CPU clocks for flash access (see chapter 4.5.42 and 4.10.4 of
+ * LPC12xx User manual (UM10441.pdf))
+ * freq_sel : code for CPU freq, as defined in system.h header file :
+ * A clock frequency is defined as the integer value in MHz shifted by 3 and or'ed
+ * with the value to be programmed in the flash config register for the flash access
+ * time at the given frequency shifted by one and the flash override bit in the LSB
+ */
+static void flash_accelerator_config(uint32_t freq_sel)
+{
+ struct lpc_flash_control* fcfg = LPC_FLASH_CONTROL;
+ struct lpc_sys_control* sys_ctrl = LPC_SYS_CONTROL;
+
+ if (freq_sel & 0x01) {
+ /* 1 cycle read mode */
+ sys_ctrl->peripheral_reset_ctrl |= LPC_FLASH_OVERRIDE;
+ } else {
+ /* multiple cycle flash read mode */
+ sys_ctrl->peripheral_reset_ctrl &= ~(LPC_FLASH_OVERRIDE);
+ fcfg->flash_cfg &= ~(LPC_FLASH_CFG_MASK);
+ fcfg->flash_cfg |= ((freq_sel & 0x06) >> 1);
+ }
+}
+
+/* Stop the watchdog */
+void stop_watchdog(void)
+{
+ struct lpc_sys_control* sys_ctrl = LPC_SYS_CONTROL;
+ struct lpc_watchdog* wdt = LPC_WDT;
+
+ /* Power wadchdog block before changing it's configuration */
+ if (! (sys_ctrl->sys_AHB_clk_ctrl & LPC_SYS_ABH_CLK_CTRL_Watchdog)) {
+ sys_ctrl->sys_AHB_clk_ctrl |= LPC_SYS_ABH_CLK_CTRL_Watchdog;
+ }
+ /* Stop watchdog */
+ wdt->mode = 0;
+ wdt->feed_seqence = 0xAA;
+ wdt->feed_seqence = 0x55;
+ /* And power it down */
+ sys_ctrl->sys_AHB_clk_ctrl &= ~(LPC_SYS_ABH_CLK_CTRL_Watchdog);
+ sys_ctrl->powerdown_run_cfg |= LPC_POWER_DOWN_WDT_OSC;
+}
+
+/* Configure the brown-out detection */
+void system_brown_out_detection_config(uint32_t level)
+{
+ struct lpc_sys_control* sys_ctrl = LPC_SYS_CONTROL;
+
+ if (level == 0) {
+ /* Disable Brown-Out Detection, power it down */
+ sys_ctrl->powerdown_run_cfg |= LPC_POWER_DOWN_BOD;
+ global.brown_out_detection_enabled = 0;
+ } else {
+ global.brown_out_detection_enabled = 1;
+ /* Configure Brown-Out Detection */
+ /* FIXME */
+ }
+}
+
+/***************************************************************************** */
+/* Power */
+/***************************************************************************** */
+/* Set up power-down control
+ * Change reset power state to our default, removing power from unused interfaces
+ */
+void system_set_default_power_state(void)
+{
+ struct lpc_sys_control* sys_ctrl = LPC_SYS_CONTROL;
+ /* Start with all memory powered on and nothing else */
+ sys_ctrl->sys_AHB_clk_ctrl = LPC_SYS_ABH_CLK_CTRL_MEM_ALL;
+}
+
+void enter_deep_sleep(void)
+{
+ struct lpc_sys_control* sys_ctrl = LPC_SYS_CONTROL;
+
+ /* Ask for the same clock status when waking up */
+ sys_ctrl->powerdown_awake_cfg = sys_ctrl->powerdown_run_cfg;
+ /* Set deep_sleep config */
+ if (global.brown_out_detection_enabled) {
+ sys_ctrl->powerdown_sleep_cfg = LPC_DEEP_SLEEP_CFG_NOWDTLOCK_BOD_ON;
+ } else {
+ sys_ctrl->powerdown_sleep_cfg = LPC_DEEP_SLEEP_CFG_NOWDTLOCK_BOD_OFF;
+ }
+ /* Enter deep sleep */
+ /* FIXME */
+}
+
+/***************************************************************************** */
+/* System Clock */
+/***************************************************************************** */
+static void propagate_main_clock(void);
+
+/* Main clock config : set up the system clock
+ * We use internal RC oscilator as sys_pllclkin if pll is ussed
+ * Note that during PLL lock wait we are running on internal RC
+ * Note for M and P calculation :
+ * FCCO must be between 156MHz and 320MHz
+ * M ranges from 1 to 32, steps of 1, M = Freq_out / Freq_in
+ * P ranges from 1 to 8, P must be a power of two, FCCO = 2 * P * Freq_out
+ * Freq_out < 100 MHz
+ * Freq_in is between 10 and 25 MHz
+ * M = Freq_out / Freq_in
+ *
+ * freq_sel : set to one of the predefined values. See core/system.h
+ */
+void clock_config(uint32_t freq_sel)
+{
+ struct lpc_sys_control* sys_ctrl = LPC_SYS_CONTROL;
+
+ lpc_disable_irq();
+ /* Turn on IRC */
+ sys_ctrl->powerdown_run_cfg &= ~(LPC_POWER_DOWN_IRC);
+ sys_ctrl->powerdown_run_cfg &= ~(LPC_POWER_DOWN_IRC_OUT);
+ /* Use IRC clock for main clock */
+ sys_ctrl->main_clk_sel = 0;
+ /* Switch the main clock source */
+ sys_ctrl->main_clk_upd_en = 0;
+ sys_ctrl->main_clk_upd_en = 1;
+
+ /* Turn off / power off external crystal */
+ sys_ctrl->powerdown_run_cfg |= LPC_POWER_DOWN_SYS_OSC;
+ /* Set AHB clock divider : divide by one ... */
+ sys_ctrl->sys_AHB_clk_div = 1;
+ /* Configure number of CPU clocks for flash access before setting the new clock */
+ flash_accelerator_config(freq_sel);
+
+ /* power off PLL */
+ sys_ctrl->powerdown_run_cfg |= LPC_POWER_DOWN_SYSPLL;
+
+ /* If using only internal RC, we are done */
+ if (freq_sel == FREQ_SEL_IRC) {
+ global.main_clock = LPC_IRC_OSC_CLK;
+ } else {
+ uint32_t M = ((freq_sel >> 3) & 0xFF);
+ uint32_t N = 0; /* P = 2 ^ N */
+
+ /* Select value for N */
+ switch (freq_sel) {
+ case 3: /* FREQ_SEL_36MHz */
+ case 2: /* FREQ_SEL_24MHz */
+ N = 2;
+ break;
+ default: /* 48MHz to 60 MHz */
+ N = 1;
+ break;
+ }
+ global.main_clock = (((freq_sel >> 3) & 0xFF) * 12 * 1000 * 1000);
+ /* Setup PLL dividers */
+ sys_ctrl->sys_pll_ctrl = (((M - 1) & 0x1F) | (N << 5));
+ /* Set sys_pllclkin to internal RC */
+ sys_ctrl->sys_pll_clk_sel = 0;
+ sys_ctrl->sys_pll_clk_upd_en = 0; /* (SYSPLLCLKUEN must go from LOW to HIGH */
+ sys_ctrl->sys_pll_clk_upd_en = 1;
+ /* Power-up PLL */
+ sys_ctrl->powerdown_run_cfg &= ~(LPC_POWER_DOWN_SYSPLL);
+ /* Wait Until PLL Locked */
+ while (!(sys_ctrl->sys_pll_status & 0x01));
+ /* Use PLL as main clock */
+ sys_ctrl->main_clk_sel = 0x03;
+ /* Switch the main clock source */
+ sys_ctrl->main_clk_upd_en = 0;
+ sys_ctrl->main_clk_upd_en = 1;
+ }
+
+ /* And call all clock updaters */
+ propagate_main_clock();
+ /* Turn interrupts on once again*/
+ lpc_enable_irq();
+}
+
+uint32_t get_main_clock(void)
+{
+ return global.main_clock;
+}
+
+/***************************************************************************** */
+/* Peripheral Clocks */
+/***************************************************************************** */
+void Dummy_Clk_Updater(void) {
+ do { } while (0);
+}
+
+void uart_clk_update(void) __attribute__ ((weak, alias ("Dummy_Clk_Updater")));
+void i2c_clock_update(void) __attribute__ ((weak, alias ("Dummy_Clk_Updater")));
+void spi_clk_update(void) __attribute__ ((weak, alias ("Dummy_Clk_Updater")));
+
+static void propagate_main_clock(void)
+{
+ uart_clk_update();
+ i2c_clock_update();
+ spi_clk_update();
+}
+
+/***************************************************************************** */
+/* CLK Out */
+/***************************************************************************** */
+/* This is mainly a debug feature, but can be used to provide a clock to an
+ * external peripheral */
+/* Note that the CLK_Out pin PIO0_12 is multiplexed with ISP mode selection on reset */
+void clkout_on(uint32_t src, uint32_t div)
+{
+}
+void clkout_off(void)
+{
+}
+
+/***************************************************************************** */
+/* Peripheral Pins */
+/***************************************************************************** */
+void Dummy_Pin_Config(void) {
+ do { } while (0);
+}
+
+void set_i2c_pins(void) __attribute__ ((weak, alias ("Dummy_Pin_Config")));
+void set_spi_pins(void) __attribute__ ((weak, alias ("Dummy_Pin_Config")));
+void set_uarts_pins(void) __attribute__ ((weak, alias ("Dummy_Pin_Config")));
+void set_gpio_pins(void) __attribute__ ((weak, alias ("Dummy_Pin_Config")));
+
+void system_set_default_pins(void)
+{
+ set_uarts_pins();
+ set_i2c_pins();
+ set_spi_pins();
+ set_gpio_pins();
+}
--- /dev/null
+/****************************************************************************
+ * core/uidiv.c
+ *
+ *
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program 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 General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *************************************************************************** */
+
+#include <stdint.h>
+
+/*******************************************************************************/
+/* Integer division using ROM based division routines */
+/*******************************************************************************/
+
+struct idiv_return {
+ int quotient;
+ int remainder;
+};
+struct uidiv_return {
+ unsigned quotient;
+ unsigned remainder;
+};
+
+struct lpc_rom_div_helpers {
+ /* Signed integer division */
+ int (*rom_sidiv)(int numerator, int denominator);
+ /* Unsigned integer division */
+ unsigned (*rom_uidiv)(unsigned numerator, unsigned denominator);
+ /* Signed integer division with remainder */
+ struct idiv_return (*rom_sidivmod)(int numerator, int denominator);
+ /* Unsigned integer division with remainder */
+ struct uidiv_return (*rom_uidivmod)(unsigned numerator, unsigned denominator);
+};
+
+#define LPC_122x_DIVROM_LOC (0x1FFC0000)
+static struct lpc_rom_div_helpers* rom_div_helpers;
+
+void rom_div_helpers_init(void)
+{
+ rom_div_helpers = *((struct lpc_rom_div_helpers**)LPC_122x_DIVROM_LOC);
+}
+
+/* Division (/) */
+int __aeabi_idiv(int numerator, int denominator)
+{
+ return rom_div_helpers->rom_sidiv(numerator, denominator);
+}
+unsigned __aeabi_uidiv(unsigned numerator, unsigned denominator)
+{
+ return rom_div_helpers->rom_uidiv(numerator, denominator);
+}
+
+/* Modulo (%) */
+void __aeabi_idivmod(int numerator, int denominator)
+{
+ struct idiv_return result = rom_div_helpers->rom_sidivmod(numerator, denominator);
+ register uint32_t r0 asm("r0") = result.quotient;
+ register uint32_t r1 asm("r1") = result.remainder;
+ asm volatile("" : "+r"(r0), "+r"(r1) : "r"(r0), "r"(r1));
+}
+void __aeabi_uidivmod(unsigned numerator, unsigned denominator)
+{
+ struct uidiv_return result = rom_div_helpers->rom_uidivmod(numerator, denominator);
+ register uint32_t r0 asm("r0") = result.quotient;
+ register uint32_t r1 asm("r1") = result.remainder;
+ asm volatile("" : "+r"(r0), "+r"(r1) : "r"(r0), "r"(r1));
+}
+
--- /dev/null
+/****************************************************************************
+ * drivers/gpio.c
+ *
+ * Copyright 2012 Nathael Pajani <nathael.pajani@ed3l.fr>
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program 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 General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *************************************************************************** */
+
+/***************************************************************************** */
+/* GPIOs */
+/***************************************************************************** */
+
+
+
+#include <stdint.h>
+#include "core/lpc_regs_12xx.h"
+#include "core/lpc_core_cm0.h"
+#include "core/system.h"
+#include "drivers/gpio.h"
+
+
+/***************************************************************************** */
+/* Public access to GPIO setup */
+
+void config_gpio(volatile uint32_t* handle, uint32_t mode)
+{
+ struct lpc_sys_control* sys_ctrl = LPC_SYS_CONTROL;
+
+ /* Make sure IO_Config is clocked */
+ sys_ctrl->sys_AHB_clk_ctrl |= LPC_SYS_ABH_CLK_CTRL_IO_CONFIG;
+ *handle = mode;
+ /* Config done, power off IO_CONFIG block */
+ sys_ctrl->sys_AHB_clk_ctrl &= ~LPC_SYS_ABH_CLK_CTRL_IO_CONFIG;
+}
+
+void gpio_on(void)
+{
+ struct lpc_sys_control* sys_ctrl = LPC_SYS_CONTROL;
+ /* Provide power to IO ports */
+ sys_ctrl->sys_AHB_clk_ctrl |= LPC_SYS_ABH_CLK_CTRL_GPIO0;
+ sys_ctrl->sys_AHB_clk_ctrl |= LPC_SYS_ABH_CLK_CTRL_GPIO1;
+}
+void gpio_off(void)
+{
+ struct lpc_sys_control* sys_ctrl = LPC_SYS_CONTROL;
+ /* Provide power to IO ports */
+ sys_ctrl->sys_AHB_clk_ctrl &= ~(LPC_SYS_ABH_CLK_CTRL_GPIO0);
+ sys_ctrl->sys_AHB_clk_ctrl &= ~(LPC_SYS_ABH_CLK_CTRL_GPIO1);
+}
+
+
+/* Set all GPIO used on the GPIO_Demo module in a default state */
+void set_gpio_pins(void)
+{
+ struct lpc_sys_control* sys_ctrl = LPC_SYS_CONTROL;
+ struct lpc_io_control* ioctrl = LPC_IO_CONTROL;
+
+ /* Make sure IO_Config is clocked */
+ sys_ctrl->sys_AHB_clk_ctrl |= LPC_SYS_ABH_CLK_CTRL_IO_CONFIG;
+
+ /* Configure GPIO pins */
+ ioctrl->pio0_0 = LPC_IO_FUNC_ALT(0) | LPC_IO_MODE_PULL_UP;
+ ioctrl->pio0_3 = LPC_IO_FUNC_ALT(0) | LPC_IO_MODE_PULL_UP;
+ ioctrl->pio0_4 = LPC_IO_FUNC_ALT(0) | LPC_IO_MODE_PULL_UP;
+ ioctrl->pio0_5 = LPC_IO_FUNC_ALT(0) | LPC_IO_MODE_PULL_UP;
+ ioctrl->pio0_6 = LPC_IO_FUNC_ALT(0) | LPC_IO_MODE_PULL_UP;
+ ioctrl->pio0_19 = LPC_IO_FUNC_ALT(0) | LPC_IO_MODE_PULL_UP;
+ ioctrl->pio0_20 = LPC_IO_FUNC_ALT(0) | LPC_IO_MODE_PULL_UP;
+ ioctrl->pio0_21 = LPC_IO_FUNC_ALT(0) | LPC_IO_MODE_PULL_UP;
+ ioctrl->pio0_22 = LPC_IO_FUNC_ALT(0) | LPC_IO_MODE_PULL_UP;
+ ioctrl->pio0_23 = LPC_IO_FUNC_ALT(0) | LPC_IO_MODE_PULL_UP;
+ ioctrl->pio0_24 = LPC_IO_FUNC_ALT(0) | LPC_IO_MODE_PULL_UP;
+ ioctrl->pio0_25 = LPC_IO_FUNC_ALT(0) | LPC_IO_MODE_PULL_UP;
+ ioctrl->pio0_26 = LPC_IO_FUNC_ALT(0) | LPC_IO_MODE_PULL_UP;
+ ioctrl->pio0_27 = LPC_IO_FUNC_ALT(0) | LPC_IO_MODE_PULL_UP;
+ ioctrl->pio0_28 = LPC_IO_FUNC_ALT(0) | LPC_IO_MODE_PULL_UP;
+ ioctrl->pio0_29 = LPC_IO_FUNC_ALT(0) | LPC_IO_MODE_PULL_UP;
+ /* Configure ADC pins */
+ ioctrl->pio0_30 = LPC_IO_FUNC_ALT(1) | LPC_IO_ANALOG;
+ ioctrl->pio0_31 = LPC_IO_FUNC_ALT(1) | LPC_IO_ANALOG;
+ ioctrl->pio1_0 = LPC_IO_FUNC_ALT(1) | LPC_IO_ANALOG;
+ ioctrl->pio1_1 = LPC_IO_FUNC_ALT(1) | LPC_IO_ANALOG;
+ ioctrl->pio1_2 = LPC_IO_FUNC_ALT(1) | LPC_IO_ANALOG;
+ ioctrl->pio1_3 = LPC_IO_FUNC_ALT(1) | LPC_IO_ANALOG;
+
+ /* Config done, power off IO_CONFIG block */
+ sys_ctrl->sys_AHB_clk_ctrl &= ~LPC_SYS_ABH_CLK_CTRL_IO_CONFIG;
+}
+
+/* Handlers */
+void PIO_0_Handler(void)
+{
+}
+void PIO_1_Handler(void)
+{
+}
+void PIO_2_Handler(void)
+{
+}
+
+
+/***************************************************************************** */
+/* Status LED */
+/* The status LED is on GPIO Port 1, pin 4 (PIO1_4) and Port 1, pin 5 (PIO1_5) */
+void status_led_config(void)
+{
+ struct lpc_io_control* ioctrl = LPC_IO_CONTROL;
+ struct lpc_gpio* gpio1 = LPC_GPIO_1;
+ uint32_t mode = (LPC_IO_MODE_PULL_UP | LPC_IO_DIGITAL |LPC_IO_DRIVE_HIGHCURENT);
+ /* Status Led GPIO */
+ ioctrl->pio1_4 = (LPC_IO_FUNC_ALT(0) | mode);
+ ioctrl->pio1_5 = (LPC_IO_FUNC_ALT(0) | mode);
+ /* Configure both as output */
+ gpio1->data_dir = (1 << 4) | (1 << 5);
+ /* Turn both LEDs on */
+ //gpio1->set = (1 << 4) | (1 << 5);
+ gpio1->set = (1 << 4);
+}
+
+void status_led(uint32_t val)
+{
+ struct lpc_gpio* gpio1 = LPC_GPIO_1;
+
+ switch (val) {
+ case red_only:
+ gpio1->set = (1 << 5);
+ gpio1->clear = (1 << 4);
+ break;
+ case red_on:
+ gpio1->set = (1 << 5);
+ break;
+ case red_off:
+ gpio1->clear = (1 << 5);
+ break;
+ case red_toggle:
+ gpio1->invert = (1 << 5);
+ break;
+ case green_only:
+ gpio1->set = (1 << 4);
+ gpio1->clear = (1 << 5);
+ break;
+ case green_on:
+ gpio1->set = (1 << 4);
+ break;
+ case green_off:
+ gpio1->clear = (1 << 4);
+ break;
+ case green_toggle:
+ gpio1->invert = (1 << 4);
+ break;
+ case both:
+ gpio1->set = (1 << 4) | (1 << 5);
+ break;
+ case toggle:
+ gpio1->invert = (1 << 4) | (1 << 5);
+ break;
+ case none:
+ default:
+ gpio1->clear = (1 << 4) | (1 << 5);
+ break;
+ }
+}
+
+void chenillard(uint32_t ms)
+{
+ status_led(red_only);
+ msleep(ms);
+ status_led(green_only);
+ msleep(ms);
+ status_led(none);
+ msleep(ms);
+ status_led(both);
+ msleep(ms);
+ status_led(none);
+ msleep(ms);
+ status_led(red_only);
+ msleep(ms);
+ status_led(red_only);
+ msleep(ms);
+ status_led(none);
+ msleep(ms);
+ status_led(green_only);
+ msleep(ms);
+ status_led(green_only);
+ msleep(ms);
+ status_led(none);
+ msleep(ms);
+}
--- /dev/null
+/****************************************************************************
+ * drivers/serial.c
+ *
+ * Copyright 2012 Nathael Pajani <nathael.pajani@ed3l.fr>
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program 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 General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *************************************************************************** */
+
+
+
+/***************************************************************************** */
+/* UARTs */
+/***************************************************************************** */
+/* Both UARTs are available, UART numbers are in the range 0 - 1 */
+
+#include <stdint.h>
+#include "core/lpc_regs_12xx.h"
+#include "core/lpc_core_cm0.h"
+#include "core/system.h"
+
+struct uart_device
+{
+ uint32_t num;
+ struct lpc_uart* regs;
+ uint32_t baudrate;
+
+ /* Output buffer */
+ volatile char* out_buff;
+ volatile uint32_t sending; /* Actual sending position in out buffer */
+ volatile uint32_t out_lock;
+ volatile uint32_t out_length; /* actual position to add in out buffer */
+
+ /* Input buffer */
+};
+
+#define NUM_UARTS 2
+static struct uart_device uarts[NUM_UARTS] = {
+ {
+ .num = 0,
+ .regs = (struct lpc_uart*)LPC_UART_0,
+ .baudrate = 0,
+ .out_buff = NULL,
+ .sending = 0,
+ .out_lock = 0,
+ },
+ {
+ .num = 1,
+ .regs = (struct lpc_uart*)LPC_UART_1,
+ .baudrate = 0,
+ .out_buff = NULL,
+ .sending = 0,
+ .out_lock = 0,
+ },
+};
+
+#if 0
+#define DEBUG
+extern char* UARTBUFFER;
+extern volatile int UARTPTR;
+extern volatile int UARTSENDPTR;
+extern volatile int UARTSENDING;
+#endif
+
+
+/* Generic UART handler */
+static void UART_Handler(struct uart_device* uart)
+{
+ uint32_t intr = uart->regs->func.intr_pending;
+
+ if ((intr & LPC_UART_INT_MASK) == LPC_UART_INT_RX) {
+ uint8_t data = uart->regs->func.buffer;
+ /* Echo */
+ uart->regs->func.buffer = data;
+ }
+ /* We are currently sending, send next char */
+ if ((intr & LPC_UART_INT_MASK) == LPC_UART_INT_TX) {
+ if (uart->out_buff && uart->sending && (uart->out_length > uart->sending)) {
+ uart->regs->func.buffer = uart->out_buff[uart->sending];
+ uart->sending++;
+#ifdef DEBUG
+ } else if (UARTPTR > UARTSENDPTR) {
+ uart->regs->func.buffer = UARTBUFFER[UARTSENDPTR++];
+#endif
+ } else {
+ uart->sending = 0;
+#ifdef DEBUG
+ UARTSENDING = 0;
+#endif
+ }
+ }
+}
+
+
+/* Handlers */
+void UART_0_Handler(void)
+{
+ UART_Handler(&uarts[0]);
+}
+void UART_1_Handler(void)
+{
+ UART_Handler(&uarts[1]);
+}
+
+
+/* Start sending buffer content */
+static void uart_start_sending(uint32_t uart_num)
+{
+ struct uart_device* uart = &uarts[uart_num];
+
+ if (uart->out_buff == NULL)
+ return;
+
+ if (!uart->sending && (uart->out_length != 0)) {
+ uart->sending++;
+ uart->regs->func.buffer = uart->out_buff[0];
+ }
+}
+
+
+/***************************************************************************** */
+/* Serial Write */
+
+int serial_write(uint32_t uart_num, char *buf, uint32_t length)
+{
+ struct uart_device* uart = NULL;
+
+ if (uart_num >= NUM_UARTS)
+ return -1;
+
+ uart = &uarts[uart_num];
+ /* Lock acquire */
+ if (sync_lock_test_and_set(&uart->out_lock, 1) == 1) {
+ return -1;
+ }
+
+ /* If UART is sending wait for buffer empty */
+ do {} while (uart->sending != 0);
+
+ uart->out_buff = buf;
+ uart->out_length = length;
+
+ /* Turn output on */
+ uart_start_sending(uart_num);
+
+ /* Release the lock */
+ sync_lock_release(&uart->out_lock);
+
+ return length;
+}
+
+
+
+
+/***************************************************************************** */
+/* UART Setup : private part : Clocks, Pins, Power and Mode */
+
+/* UART Clock Setup */
+/* Note : for both uarts we use full peripheral clock.
+ * With a minimum main clock of 12MHz, ths gives 12MHz/16 = 750kbauds at least
+ * for UARTs baudrates.
+ * Note : IRQ are off, whether called by system update or by UART on helper
+ */
+static void uart_clk_on(uint32_t uart_num, uint32_t baudrate)
+{
+ struct lpc_sys_control* sys_ctrl = LPC_SYS_CONTROL;
+ struct lpc_uart* uart = uarts[uart_num].regs; /* Get the right registers */
+ uint32_t div = 0, pclk = 0;
+ /* Save baudrate value */
+ uarts[uart_num].baudrate = baudrate;
+ /* Configure UART clock */
+ pclk = get_main_clock(); /* See above note */
+ sys_ctrl->uart_clk_div[uart_num] = 0x01;
+ div = (pclk / (baudrate * 16));
+ uart->line_ctrl |= LPC_UART_ENABLE_DLAB;
+ uart->ctrl.divisor_latch_lsb = (div & 0xff);
+ uart->ctrl.divisor_latch_msb = ((div >> 8) & 0xFF);
+ uart->line_ctrl &= ~LPC_UART_ENABLE_DLAB;
+}
+static void uart_clk_off(uint32_t uart_num)
+{
+ struct lpc_sys_control* sys_ctrl = LPC_SYS_CONTROL;
+ /* Erase saved baudrate */
+ uarts[uart_num].baudrate = 0;
+ sys_ctrl->uart_clk_div[uart_num] = 0;
+}
+
+static void uart_power(uint32_t power_bit, uint32_t on_off)
+{
+ struct lpc_sys_control* sys_ctrl = LPC_SYS_CONTROL;
+ if (on_off == 1) {
+ sys_ctrl->sys_AHB_clk_ctrl |= power_bit;
+ } else {
+ sys_ctrl->sys_AHB_clk_ctrl &= ~(power_bit);
+ }
+}
+
+static uint32_t uart_mode_setup(uint32_t uart_num)
+{
+ struct lpc_uart* uart = uarts[uart_num].regs; /* Get the right registers */
+ uint32_t status = 0;
+ /* Set up UART mode : 8n1 */
+ uart->line_ctrl = (LPC_UART_8BIT | LPC_UART_NO_PAR | LPC_UART_1STOP);
+ /* Clear all fifo, reset and enable them */
+ /* Note : fifo trigger level is one bit */
+ uart->ctrl.fifo_ctrl = (LPC_UART_FIFO_EN | LPC_UART_TX_CLR | LPC_UART_RX_CLR);
+ /* Clear the Line Status Register, return it to prevent compiler from removing the read */
+ status = uart->line_status;
+ /* Enable UART Interrupt */
+ uart->func.intr_enable = (LPC_UART_RX_INT_EN | LPC_UART_TX_INT_EN);
+
+ return status;
+}
+
+/* Pin settings */
+/* Note : We MUST set LPC_IO_DIGITAL for Rx even if the bit is marked as "Reserved" in
+ * the datasheet !
+ */
+static void uart_set_pin_func(uint32_t uart_num)
+{
+ struct lpc_sys_control* sys_ctrl = LPC_SYS_CONTROL;
+ struct lpc_io_control* ioctrl = LPC_IO_CONTROL;
+
+ /* Make sure IO_Config is clocked */
+ sys_ctrl->sys_AHB_clk_ctrl |= LPC_SYS_ABH_CLK_CTRL_IO_CONFIG;
+ /* Configure UART pins (Only Rx and Tx) */
+ switch (uart_num) {
+ case 0:
+ ioctrl->pio0_1 = LPC_IO_FUNC_ALT(2) | LPC_IO_DIGITAL;
+ ioctrl->pio0_2 = LPC_IO_FUNC_ALT(2) | LPC_IO_DIGITAL;
+ break;
+ case 1:
+ ioctrl->pio0_8 = LPC_IO_FUNC_ALT(2) | LPC_IO_DIGITAL;
+ ioctrl->pio0_9 = LPC_IO_FUNC_ALT(2) | LPC_IO_DIGITAL;
+ break;
+ }
+ /* Config done, power off IO_CONFIG block */
+ sys_ctrl->sys_AHB_clk_ctrl &= ~LPC_SYS_ABH_CLK_CTRL_IO_CONFIG;
+}
+struct uart_def
+{
+ uint32_t irq;
+ uint32_t power_offset;
+};
+static struct uart_def uart_defs[NUM_UARTS] = {
+ { UART0_IRQ, LPC_SYS_ABH_CLK_CTRL_UART0 },
+ { UART1_IRQ, LPC_SYS_ABH_CLK_CTRL_UART1 },
+};
+
+/***************************************************************************** */
+/* Public access to UART setup */
+
+void set_uarts_pins(void)
+{
+ int i = 0;
+ for (i = 0; i < NUM_UARTS; i++) {
+ uart_set_pin_func(i);
+ }
+}
+
+/* Allow any change to the main clock to be forwarded to us */
+void uart_clk_update(void)
+{
+ int i = 0;
+ for (i = 0; i < NUM_UARTS; i++) {
+ if (uarts[i].baudrate != 0) {
+ uart_clk_on(i, uarts[i].baudrate);
+ }
+ }
+}
+
+/* Do we need to allow setting of other parameters ? (Other than 8n1) */
+/* Do we need to allow specifying an interrupt handler ? */
+int uart_on(uint32_t uart_num, uint32_t baudrate)
+{
+ struct uart_def* uart = NULL;
+ uint32_t status = 0;
+
+ if (uart_num >= NUM_UARTS)
+ return -EINVAL;
+ uart = &uart_defs[uart_num];
+
+ NVIC_DisableIRQ( uart->irq );
+ /* Setup pins, must be done before clock setup and with uart powered off. */
+ uart_clk_off(uart_num);
+ uart_power(uart->power_offset, 0);
+ uart_set_pin_func(uart_num);
+ /* Turn On power */
+ uart_power(uart->power_offset, 1);
+ /* Setup clock acording to baudrate */
+ uart_clk_on(uart_num, baudrate);
+ /* Setup mode, fifo, ... */
+ status = uart_mode_setup(uart_num);
+ /* Enable interrupts back on */
+ NVIC_EnableIRQ( uart->irq );
+
+ return status;
+}
+
+void uart_off(uint32_t uart_num)
+{
+ struct uart_def* uart = NULL;
+ if (uart_num >= NUM_UARTS)
+ return;
+ uart = &uart_defs[uart_num];
+
+ NVIC_DisableIRQ( uart->irq );
+ uart_clk_off(uart_num);
+ /* Turn Off power */
+ uart_power(uart->power_offset, 0);
+}
+
+
+
--- /dev/null
+/****************************************************************************
+ * core/lpc_core_cm0.h
+ *
+ * Helper functions to access some registers and Cortex M0 core functionalities.
+ *
+ *
+ * Most of the code from here comes from CMSIS. Should this be rewritten ?
+ *
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program 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 General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *************************************************************************** */
+
+#ifndef LPC_CORE_CM0_H
+#define LPC_CORE_CM0_H
+
+#include <stdint.h> /* standard types definitions */
+#include "core/lpc_regs_12xx.h"
+
+
+/*******************************************************************************/
+/* Core Instructions */
+/*******************************************************************************/
+/* NOP */
+#define nop() __asm volatile ("nop" : : : "memory")
+/* SEV : Send Event */
+#define sev() __asm volatile ("sev" : : : "memory")
+/* WFE : Wait For Event */
+#define wfe() __asm volatile ("wfe" : : : "memory")
+/* WFI : Wait For Interrupt */
+#define wfi() __asm volatile ("wfi" : : : "memory")
+
+
+/* Synchronization */
+/* Instruction Synchronization Barrier : Flushes pipeline */
+#define isb() __asm volatile ("isb" : : : "memory")
+/* Data Synchronization Barrier : All explicit memory access completed */
+#define dsb() __asm volatile ("dsb" : : : "memory")
+/* Data Memory Barrier : Ensures apparent order but not completion */
+#define dmb() __asm volatile ("dmb" : : : "memory")
+
+
+
+/* Access to the Application Program Status Register (APSR). */
+static inline uint32_t get_APSR(void)
+{
+ uint32_t r; __asm volatile ("mrs %0, apsr" : "=r" (r)); return (r);
+}
+#define APSR_SATURATION (get_APSR & (0x1 << 27)) /* bit 27 Saturation condition flag */
+#define APSR_OVERFLOW (get_APSR & (0x1 << 28)) /* bit 28 Overflow condition code flag */
+#define APSR_CARRY (get_APSR & (0x1 << 29)) /* bit 29 Carry condition code flag */
+#define APSR_ZERO (get_APSR & (0x1 << 30)) /* bit 30 Zero condition code flag */
+#define APSR_NEGATIVE (get_APSR & (0x1 << 31)) /* bit 31 Negative condition code flag */
+
+
+/* Access the Interrupt Program Status Register (IPSR). */
+static inline uint32_t get_IPSR(void)
+{
+ uint32_t r; __asm volatile ("mrs %0, ipsr" : "=r" (r)); return (r);
+}
+#define IPSR (get_IPSR & 0x1FF) /* bit: 0..8 Exception number */
+#define IPSR_IRQ0 16
+#define IRQ_NUM (IPSR - IPSR_IRQ0)
+
+
+/* Control Register */
+static inline uint32_t get_CONTROL(void)
+{
+ uint32_t r; __asm volatile ("mrs %0, control" : "=r" (r)); return (r);
+}
+static inline void set_CONTROL(uint32_t control)
+{
+ __asm volatile ("msr control, %0" : : "r" (control));
+}
+
+
+/* Process Stack Pointer */
+static inline uint32_t get_process_stack_pointer(void)
+{
+ register uint32_t r; __asm volatile ("mrs %0, psp" : "=r" (r)); return (r);
+}
+static inline void set_process_stack_pointer(uint32_t top_of_stack)
+{
+ __asm volatile ("msr psp, %0" : : "r" (top_of_stack));
+}
+
+
+/* Main Stack Pointer */
+static inline uint32_t get_main_stack_pointer(void)
+{
+ register uint32_t r; __asm volatile ("mrs %0, msp" : "=r" (r)); return (r);
+}
+static inline void set_main_stack_pointer(uint32_t top_of_stack)
+{
+ __asm volatile ("msr msp, %0" : : "r" (top_of_stack));
+}
+
+
+/* Priority Mask */
+static inline uint32_t get_priority_mask(void)
+{
+ uint32_t r; __asm volatile ("mrs %0, primask" : "=r" (r)); return (r);
+}
+static inline void set_priority_mask(uint32_t mask)
+{
+ __asm volatile ("msr primask, %0" : : "r" (mask));
+}
+
+
+/* Base Priority */
+static inline uint32_t get_base_priority(void)
+{
+ uint32_t r; __asm volatile ("mrs %0, basepri_max" : "=r" (r)); return (r);
+}
+static inline void set_base_priority(uint32_t prio)
+{
+ __asm volatile ("msr basepri, %0" : : "r" (prio));
+}
+
+
+/* Fault Mask */
+static inline uint32_t get_fault_mask(void)
+{
+ uint32_t r; __asm volatile ("mrs %0, faultmask" : "=r" (r)); return (r);
+}
+static inline void set_fault_mask(uint32_t mask)
+{
+ __asm volatile ("msr faultmask, %0" : : "r" (mask));
+}
+
+
+
+/*******************************************************************************/
+/* Interrupts */
+/*******************************************************************************/
+
+/* Cortex-M0 Processor Exceptions Numbers */
+/* Note : entry 0 is "end stack pointer" */
+#define RESET_IRQ ( -15 ) /* 1 - Reset ... not an interrupt ... */
+#define NMI_IRQ ( -14 ) /* 2 - Non Maskable Interrupt */
+#define HARD_FAULT_IRQ ( -13 ) /* 3 - Cortex-M0 Hard Fault Interrupt */
+/* Note : entry 7 is the 2’s complement of the check-sum of the previous 7 entries */
+#define SV_CALL_IRQ ( -5 ) /* 11 - Cortex-M0 Supervisor Call Interrupt */
+#define PEND_SV_IRQ ( -2 ) /* 14 - Cortex-M0 Pend SV Interrupt */
+#define SYSTICK_IRQ ( -1 ) /* 15 - Cortex-M0 System Tick Interrupt */
+/* LPC12xx Specific Interrupt Numbers */
+#define WAKEUP0_IRQ 0 /* I/O pins can be used as wakeup source. */
+#define WAKEUP1_IRQ 1
+#define WAKEUP2_IRQ 2
+#define WAKEUP3_IRQ 3
+#define WAKEUP4_IRQ 4
+#define WAKEUP5_IRQ 5
+#define WAKEUP6_IRQ 6
+#define WAKEUP7_IRQ 7
+#define WAKEUP8_IRQ 8
+#define WAKEUP9_IRQ 9
+#define WAKEUP10_IRQ 10
+#define WAKEUP11_IRQ 11
+#define I2C0_IRQ 12 /* 12 - I2C 0 */
+#define TIMER0_IRQ 13 /* 13 - Timer 0 */
+#define TIMER1_IRQ 14 /* 14 - Timer 1 */
+#define TIMER2_IRQ 15 /* 15 - Timer 2 */
+#define TIMER3_IRQ 16 /* 16 - Timer 3 */
+#define SSP0_IRQ 17 /* 17 - SSP 0 */
+#define UART0_IRQ 18 /* 18 - UART 0 */
+#define UART1_IRQ 19 /* 19 - UART 1 */
+#define COMPARATOR_IRQ 20 /* 20 - Comparator */
+#define ADC_IRQ 21 /* 21 - A/D Converter */
+#define WDT_IRQ 22 /* 22 - Watchdog */
+#define BOD_IRQ 23 /* 23 - Brown Out Detect(BOD) */
+/* No IRQ 24 */
+#define PIO_0_IRQ 25 /* 25 - GPIO int for port 0 */
+#define PIO_1_IRQ 26 /* 26 - GPIO int for port 1 */
+#define PIO_2_IRQ 27 /* 27 - GPIO int for port 2 */
+/* No IRQ 28 */
+#define DMA_IRQ 29 /* 29 - General Purpose DMA */
+#define RTC_IRQ 30 /* 30 - RTC */
+
+
+/* Enable IRQ Interrupts
+ Enables IRQ interrupts by clearing the I-bit in the CPSR.
+ Can only be executed in Privileged modes.
+ */
+static inline void lpc_enable_irq(void)
+{
+ __asm volatile ("cpsie i");
+}
+
+/* Disable IRQ Interrupts
+ Disables IRQ interrupts by setting the I-bit in the CPSR.
+ Can only be executed in Privileged modes.
+ */
+static inline void lpc_disable_irq(void)
+{
+ __asm volatile ("cpsid i");
+}
+
+
+/*******************************************************************************/
+/* Hardware Abstraction Layer : NVIC Functions */
+/*******************************************************************************/
+/* Enable External Interrupt
+ This function enables a device specific interrupt in the NVIC interrupt controller.
+ The interrupt number cannot be a negative value.
+ IRQ : Number of the external interrupt to enable
+ */
+static inline void NVIC_EnableIRQ(uint32_t IRQ)
+{
+ struct nvic_regs* nvic = LPC_NVIC;
+ nvic->int_set_enable = (1 << (IRQ & 0x1F));
+}
+
+/* Disable External Interrupt
+ This function disables a device specific interupt in the NVIC interrupt controller.
+ The interrupt number cannot be a negative value.
+ IRQ : Number of the external interrupt to disable
+ */
+static inline void NVIC_DisableIRQ(uint32_t IRQ)
+{
+ struct nvic_regs* nvic = LPC_NVIC;
+ nvic->int_clear_enable = (1 << (IRQ & 0x1F));
+}
+
+/* Get Pending Interrupt
+ This function reads the pending register in the NVIC and returns the pending bit
+ for the specified interrupt.
+ IRQ : Number of the interrupt for get pending
+ return :
+ 0 Interrupt status is not pending
+ 1 Interrupt status is pending
+ */
+static inline uint32_t NVIC_GetPendingIRQ(uint32_t IRQ)
+{
+ struct nvic_regs* nvic = LPC_NVIC;
+ return (uint32_t)((nvic->int_set_pending & (1 << (IRQ & 0x1F)))?1:0);
+}
+
+/* Set Pending Interrupt
+ This function sets the pending bit for the specified interrupt.
+ The interrupt number cannot be a negative value.
+ IRQ : Number of the interrupt for set pending
+ */
+static inline void NVIC_SetPendingIRQ(uint32_t IRQ)
+{
+ struct nvic_regs* nvic = LPC_NVIC;
+ nvic->int_set_pending = (1 << (IRQ & 0x1F));
+}
+
+/* Clear Pending Interrupt
+ This function clears the pending bit for the specified interrupt.
+ The interrupt number cannot be a negative value.
+ IRQ : Number of the interrupt for clear pending
+ */
+static inline void NVIC_ClearPendingIRQ(uint32_t IRQ)
+{
+ struct nvic_regs* nvic = LPC_NVIC;
+ nvic->int_clear_pending = (1 << (IRQ & 0x1F));
+}
+
+
+/* The following MACROS handle generation of the register offset and byte masks */
+#define LPC_NVIC_PRIO_BITS 5 /* Number of Bits used for Priority Levels */
+#define LPC_IRQ_BIT_SHIFT(IRQ) (((uint32_t)(IRQ) & 0x03) * 8)
+#define LPC_IRQ_SHP_IDX(IRQ) ((((int32_t)(IRQ) + 16) >> 2) - 1)
+#define LPC_IRQ_IP_IDX(IRQ) ((uint32_t)(IRQ) >> 2)
+
+/* Set Interrupt Priority
+ This function sets the priority for the specified interrupt. The interrupt
+ number can be positive to specify an external (device specific)
+ interrupt, or negative to specify an internal (core) interrupt.
+ Note: The priority cannot be set for every core interrupt.
+ IRQ : Number of the interrupt for set priority
+ priority : Priority to set
+ */
+static inline void NVIC_SetPriority(uint32_t IRQ, uint32_t priority)
+{
+ if ((int32_t)IRQ < 0) {
+ if ((int32_t)IRQ > (-12)) {
+ struct syst_ctrl_block_regs* scb = LPC_SCB;
+ scb->shp[LPC_IRQ_SHP_IDX(IRQ)] = (scb->shp[LPC_IRQ_SHP_IDX(IRQ)] & ~(0xFF << LPC_IRQ_BIT_SHIFT(IRQ))) |
+ (((priority << (8 - LPC_NVIC_PRIO_BITS)) & 0xFF) << LPC_IRQ_BIT_SHIFT(IRQ));
+ }
+ } else if (LPC_IRQ_IP_IDX(IRQ) < 8) {
+ struct nvic_regs* nvic = LPC_NVIC;
+ nvic->int_priority[LPC_IRQ_IP_IDX(IRQ)] = (nvic->int_priority[LPC_IRQ_IP_IDX(IRQ)] & ~(0xFF << LPC_IRQ_BIT_SHIFT(IRQ))) |
+ (((priority << (8 - LPC_NVIC_PRIO_BITS)) & 0xFF) << LPC_IRQ_BIT_SHIFT(IRQ));
+ }
+}
+
+
+/* Get Interrupt Priority
+ This function reads the priority for the specified interrupt. The interrupt
+ number can be positive to specify an external (device specific)
+ interrupt, or negative to specify an internal (core) interrupt.
+ The returned priority value is automatically aligned to the implemented
+ priority bits of the microcontroller.
+ IRQ : Number of the interrupt for get priority
+ return : Interrupt Priority
+ */
+static inline uint32_t NVIC_GetPriority(uint32_t IRQ)
+{
+ if ((int32_t)IRQ < 0) {
+ if ((int32_t)IRQ > (-12)) {
+ struct syst_ctrl_block_regs* scb = LPC_SCB;
+ /* Get priority for Cortex-M0 system interrupts */
+ return ((uint32_t)((scb->shp[LPC_IRQ_SHP_IDX(IRQ)] >> LPC_IRQ_BIT_SHIFT(IRQ) ) >> (8 - LPC_NVIC_PRIO_BITS)));
+ }
+ } else if (LPC_IRQ_IP_IDX(IRQ) < 8) {
+ struct nvic_regs* nvic = LPC_NVIC;
+ /* Get priority for device specific interrupts */
+ return ((uint32_t)((nvic->int_priority[LPC_IRQ_IP_IDX(IRQ)] >> LPC_IRQ_BIT_SHIFT(IRQ) ) >> (8 - LPC_NVIC_PRIO_BITS)));
+ }
+}
+
+
+/* System Reset
+ This function initiate a system reset request to reset the MCU.
+ */
+static inline void NVIC_SystemReset(void)
+{
+ struct syst_ctrl_block_regs* scb = LPC_SCB;
+ dsb(); /* Ensure all outstanding memory accesses included buffered write are completed before reset */
+ scb->aircr = ((0x5FA << SCB_AIRCR_VECTKEY_Pos) | SCB_AIRCR_SYSRESETREQ_Msk);
+ dsb(); /* Ensure completion of memory access */
+ while (1); /* wait until reset */
+}
+
+
+
+/*******************************************************************************/
+/* Sync lock */
+/*******************************************************************************/
+/* There is no syncro instructions on Cortex-M0 */
+static inline uint32_t sync_lock_test_and_set(volatile uint32_t *addr, uint32_t value)
+{
+ lpc_disable_irq();
+ dsb();
+ if (*addr == value)
+ return 0;
+ *addr = value;
+ dsb();
+ lpc_enable_irq();
+ return value;
+}
+/* Remove the lock */
+static inline void sync_lock_release(volatile uint32_t *addr)
+{
+ *addr = 0;
+ dsb();
+}
+
+
+
+#endif /* LPC_CORE_CM0_H */
+
--- /dev/null
+/****************************************************************************
+ * core/lpc12xx_regs.h
+ *
+ * Cortex-M0 Core Registers definitions
+ *
+ * Copyright 2012 Nathael Pajani <nathael.pajani@ed3l.fr>
+ *
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program 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 General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *************************************************************************** */
+#ifndef LPC_REGS_H
+#define LPC_REGS_H
+
+/* Get size_t, and NULL from <stddef.h>. */
+#undef __need_malloc_and_calloc
+#define __need_size_t
+#define __need_NULL
+#include <stddef.h>
+#include <stdint.h>
+
+
+
+/***************************************************************************** */
+/* Memory Map */
+/***************************************************************************** */
+/* Base addresses */
+#define LPC_FLASH_BASE (0x00000000UL)
+#define LPC_RAM_BASE (0x10000000UL)
+#define LPC_APB0_BASE (0x40000000UL)
+#define LPC_APB1_BASE (0x40080000UL) /* unused in LPC12xx */
+#define LPC_AHB_BASE (0x50000000UL)
+
+/* Memory mapping of Cortex-M0 Hardware */
+#define LPC_SCS_BASE (0xE000E000UL) /* System Control Space Base Address */
+#define LPC_COREDEBUG_BASE (0xE000EDF0UL) /* Core Debug Base Address */
+#define LPC_SYSTICK_BASE (LPC_SCS_BASE + 0x0010UL) /* SysTick Base Address */
+#define LPC_NVIC_BASE (LPC_SCS_BASE + 0x0100UL) /* NVIC Base Address */
+#define LPC_SCB_BASE (LPC_SCS_BASE + 0x0D00UL) /* System Control Block Base Address */
+
+/* APB0 peripherals */
+#define LPC_I2C0_BASE (LPC_APB0_BASE + 0x00000)
+#define LPC_WDT_BASE (LPC_APB0_BASE + 0x04000)
+#define LPC_UART0_BASE (LPC_APB0_BASE + 0x08000)
+#define LPC_UART1_BASE (LPC_APB0_BASE + 0x0C000)
+#define LPC_TIMER0_BASE (LPC_APB0_BASE + 0x10000)
+#define LPC_TIMER1_BASE (LPC_APB0_BASE + 0x14000)
+#define LPC_TIMER2_BASE (LPC_APB0_BASE + 0x18000)
+#define LPC_TIMER3_BASE (LPC_APB0_BASE + 0x1C000)
+#define LPC_ADC_BASE (LPC_APB0_BASE + 0x20000)
+#define LPC_PMU_BASE (LPC_APB0_BASE + 0x38000)
+#define LPC_SSP0_BASE (LPC_APB0_BASE + 0x40000)
+#define LPC_IOCON_BASE (LPC_APB0_BASE + 0x44000)
+#define LPC_SYSCON_BASE (LPC_APB0_BASE + 0x48000)
+#define LPC_DMA_BASE (LPC_APB0_BASE + 0x4C000)
+#define LPC_RTC_BASE (LPC_APB0_BASE + 0x50000)
+#define LPC_COMPARATOR_BASE (LPC_APB0_BASE + 0x54000)
+
+/* AHB peripherals */
+#define LPC_GPIO_0_BASE (LPC_AHB_BASE + 0x00000)
+#define LPC_GPIO_1_BASE (LPC_AHB_BASE + 0x10000)
+#define LPC_GPIO_2_BASE (LPC_AHB_BASE + 0x20000)
+#define LPC_FLASH_CONFIG_BASE (LPC_AHB_BASE + 0x60000)
+#define LPC_CRC_BASE (LPC_AHB_BASE + 0x70000)
+
+
+
+/***************************************************************************** */
+/* System Control */
+/***************************************************************************** */
+/* System Control (SYSCON) */
+struct lpc_sys_start_logic_ctrl
+{
+ volatile uint32_t edge_ctrl; /* 0x00 : edge control Register 0 (R/W) */
+ volatile uint32_t signal_en; /* 0x04 : signal enable Register 0 (R/W) */
+ volatile uint32_t reset; /* 0x08 : reset Register 0 (-/W) */
+ volatile uint32_t status; /* 0x0C : status Register 0 (R/-) */
+};
+struct lpc_sys_control
+{
+ volatile uint32_t sys_mem_remap; /* 0x000 System memory remap (R/W) */
+ volatile uint32_t peripheral_reset_ctrl; /* 0x004 Peripheral reset control (R/W) */
+ volatile uint32_t sys_pll_ctrl; /* 0x008 System PLL control (R/W) */
+ volatile uint32_t sys_pll_status; /* 0x00C System PLL status (R/ ) */
+ uint32_t reserved_0[4];
+
+ volatile uint32_t sys_osc_ctrl; /* 0x020 : System oscillator control (R/W) */
+ volatile uint32_t WDT_osc_ctrl; /* 0x024 : Watchdog oscillator control (R/W) */
+ volatile uint32_t IRC_ctrl; /* 0x028 : IRC control (R/W) */
+ uint32_t reserved_1[1];
+ volatile uint32_t sys_reset_status; /* 0x030 : System reset status Register (R/ ) */
+ uint32_t reserved_2[3];
+ volatile uint32_t sys_pll_clk_sel; /* 0x040 : System PLL clock source select (R/W) */
+ volatile uint32_t sys_pll_clk_upd_en; /* 0x044 : System PLL clock source update enable (R/W) */
+ uint32_t reserved_3[10];
+
+ volatile uint32_t main_clk_sel; /* 0x070 : Main clock source select (R/W) */
+ volatile uint32_t main_clk_upd_en; /* 0x074 : Main clock source update enable (R/W) */
+ volatile uint32_t sys_AHB_clk_div; /* 0x078 : System AHB clock divider (R/W) */
+ uint32_t reserved_4[1];
+
+ volatile uint32_t sys_AHB_clk_ctrl; /* 0x080 : System AHB clock control (R/W) */
+ uint32_t reserved_5[4];
+
+ volatile uint32_t ssp0_clk_div; /* 0x094 : SSP0 clock divider (R/W) */
+ volatile uint32_t uart_clk_div[2]; /* 0x098 - 0x09C : UART0 and UART1 clock divider (R/W) */
+ volatile uint32_t rtc_clk_div; /* 0x0A0 : RTC clock divider (R/W) */
+ uint32_t reserved_6[15];
+
+ volatile uint32_t clk_out_src_sel; /* 0x0E0 : CLKOUT clock source select (R/W) */
+ volatile uint32_t clk_out_upd_en; /* 0x0E4 : CLKOUT clock source update enable (R/W) */
+ volatile uint32_t clk_out_div; /* 0x0E8 : CLKOUT clock divider (R/W) */
+ uint32_t reserved_7[5];
+
+ volatile uint32_t por_captured_io_status_0; /* 0x100 : POR captured PIO status 0 (R/ ) */
+ volatile uint32_t por_captured_io_status_1; /* 0x104 : POR captured PIO status 1 (R/ ) */
+ uint32_t reserved_8[11];
+
+ volatile uint32_t IO_config_clk_div[7]; /* 0x134 - 0x14C : Peripheral clocks 6 to 0 for glitch filter */
+
+ volatile uint32_t BOD_ctrl; /* 0x150 : BOD control (R/W) */
+ volatile uint32_t sys_tick_cal; /* 0x154 : System tick counter calibration (R/W) */
+ volatile uint32_t ahb_prio_set; /* 0x158 : AHB priority setting (-/-) */
+ uint32_t reserved_9[5];
+ volatile uint32_t irq_latency; /* 0x170 : IRQ delay, alloxs trade-off bw latency and determinism */
+ volatile uint32_t int_nmi_cfg; /* 0x174 : NMI interrupt source configuration control */
+ uint32_t reserved_10[34];
+
+ struct lpc_sys_start_logic_ctrl start_log_strl[2]; /* 0x200 to 0x20C and 0x210 to 0x21C :
+ Start logic 0 and Start logic 1/peripheral interrupts */
+ uint32_t reserved_11[4];
+
+ volatile uint32_t powerdown_sleep_cfg; /* 0x230 : Power-down states in Deep-sleep mode (R/W) */
+ volatile uint32_t powerdown_awake_cfg; /* 0x234 : Power-down states after wake-up (R/W) */
+ volatile uint32_t powerdown_run_cfg; /* 0x238 : Power-down configuration Register (R/W) */
+ uint32_t reserved_12[110];
+ volatile const uint32_t device_id; /* 0x3F4 : Device ID (R/ ) */
+};
+
+#define LPC_SYS_CONTROL ((struct lpc_sys_control *) LPC_SYSCON_BASE)
+
+/* AHB control bits
+ * Note : 14 is reserved
+ * 0 (System (cortexM0, syscon, PMU, ...)) is a read only bit (system cannot be disabled)
+ */
+#define LPC_SYS_ABH_CLK_CTRL_SYSTEM (1 << 0) /* Read only */
+#define LPC_SYS_ABH_CLK_CTRL_ROM (1 << 1)
+#define LPC_SYS_ABH_CLK_CTRL_RAM (1 << 2)
+#define LPC_SYS_ABH_CLK_CTRL_FLASH_REG (1 << 3)
+#define LPC_SYS_ABH_CLK_CTRL_FLASH (1 << 4)
+#define LPC_SYS_ABH_CLK_CTRL_I2C (1 << 5)
+#define LPC_SYS_ABH_CLK_CTRL_CRC (1 << 6)
+#define LPC_SYS_ABH_CLK_CTRL_CT16B0 (1 << 7)
+#define LPC_SYS_ABH_CLK_CTRL_CT16B1 (1 << 8)
+#define LPC_SYS_ABH_CLK_CTRL_CT32B0 (1 << 9)
+#define LPC_SYS_ABH_CLK_CTRL_CT32B1 (1 << 10)
+#define LPC_SYS_ABH_CLK_CTRL_SSP0 (1 << 11)
+#define LPC_SYS_ABH_CLK_CTRL_UART0 (1 << 12)
+#define LPC_SYS_ABH_CLK_CTRL_UART1 (1 << 13)
+#define LPC_SYS_ABH_CLK_CTRL_ADC (1 << 14)
+#define LPC_SYS_ABH_CLK_CTRL_Watchdog (1 << 15)
+#define LPC_SYS_ABH_CLK_CTRL_IO_CONFIG (1 << 16)
+#define LPC_SYS_ABH_CLK_CTRL_DMA (1 << 17)
+#define LPC_SYS_ABH_CLK_CTRL_RTC (1 << 19)
+#define LPC_SYS_ABH_CLK_CTRL_CMP (1 << 20)
+#define LPC_SYS_ABH_CLK_CTRL_GPIO2 (1 << 29)
+#define LPC_SYS_ABH_CLK_CTRL_GPIO1 (1 << 30)
+#define LPC_SYS_ABH_CLK_CTRL_GPIO0 (1 << 31)
+/* Helper */
+#define LPC_SYS_ABH_CLK_CTRL_MEM_ALL 0x0000001F
+/* Flash override in Peripheral reset control register */
+#define LPC_FLASH_OVERRIDE (1 << 15 )
+
+#define LPC_SSP_RESET_N (1 << 0)
+#define LPC_I2C_RESET_N (1 << 1)
+#define LPC_UART0_RESET_N (1 << 2)
+#define LPC_UART1_RESET_N (1 << 3)
+
+#define LPC_POWER_DOWN_IRC_OUT (1 << 0)
+#define LPC_POWER_DOWN_IRC (1 << 1)
+#define LPC_POWER_DOWN_FLASH (1 << 2)
+#define LPC_POWER_DOWN_BOD (1 << 3)
+#define LPC_POWER_DOWN_ADC (1 << 4)
+#define LPC_POWER_DOWN_SYS_OSC (1 << 5)
+#define LPC_POWER_DOWN_WDT_OSC (1 << 6)
+#define LPC_POWER_DOWN_SYSPLL (1 << 7)
+#define LPC_POWER_DOWN_COPARATOR (1 << 15)
+
+#define LPC_DEEP_SLEEP_CFG_NOWDTLOCK_BOD_ON 0x0000FFF7
+#define LPC_DEEP_SLEEP_CFG_NOWDTLOCK_BOD_OFF 0x0000FFFF
+
+
+
+/***************************************************************************** */
+/* Flash Control */
+/***************************************************************************** */
+/* Flash configuration */
+struct lpc_flash_control
+{
+ uint32_t reserved_0[10];
+ volatile uint32_t flash_cfg; /* 0x028 Flash configuration (R/W) */
+};
+#define LPC_FLASH_CONTROL ((struct lpc_flash_control *) LPC_FLASH_CONFIG_BASE)
+#define LPC_FLASH_CFG_MASK 0x03
+#define LPC_FLASH_CFG_SHIFT 0
+
+
+
+/***************************************************************************** */
+/* Cortex-M0 NVIC */
+/***************************************************************************** */
+/* Cortex-M0 NVIC Registers */
+struct nvic_regs {
+ volatile uint32_t int_set_enable; /* 0x000 : Interrupt Set Enable Register (R/W) */
+ uint32_t reserved_0[31];
+ volatile uint32_t int_clear_enable; /* 0x080 : Interrupt Clear Enable Register (R/W) */
+ uint32_t reserved_1[31];
+ volatile uint32_t int_set_pending; /* 0x100 : Interrupt Set Pending Register (R/W) */
+ uint32_t reserved_2[31];
+ volatile uint32_t int_clear_pending; /* 0x180 : Interrupt Clear Pending Register (R/W) */
+ uint32_t reserved_3[31];
+ uint32_t reserved_4[64];
+ volatile uint32_t int_priority[8]; /* 0x3EC : Interrupt Priority Register (R/W) */
+};
+#define LPC_NVIC ((struct nvic_regs *) LPC_NVIC_BASE) /* NVIC configuration struct */
+
+
+/***************************************************************************** */
+/* Cortex-M0 System Control Block */
+/***************************************************************************** */
+/* Cortex-M0 System Control Block Registers */
+struct syst_ctrl_block_regs {
+ volatile const uint32_t cpuid; /* 0x000 : CPU ID Base Register (R/ ) */
+ volatile uint32_t icsr; /* 0x004 : Interrupt Control State Register (R/W) */
+ uint32_t reserved_0;
+ volatile uint32_t aircr; /* 0x00C : Application Interrupt / Reset Control Register (R/W) */
+ volatile uint32_t scr; /* 0x010 : System Control Register (R/W) */
+ volatile uint32_t ccr; /* 0x014 : Configuration Control Register (R/W) */
+ uint32_t reserved_1;
+ volatile uint32_t shp[2]; /* 0x01C : System Handlers Priority Registers. [0] is reserved_ (R/W) */
+};
+#define LPC_SCB ((struct syst_ctrl_block_regs *) LPC_SCB_BASE) /* SCB configuration struct */
+
+/* SCB CPUID Register Definitions */
+#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << 24) /* SCB CPUID: IMPLEMENTER Mask */
+#define SCB_CPUID_VARIANT_Msk (0xFUL << 20) /* SCB CPUID: VARIANT Mask */
+#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << 16) /* SCB CPUID: ARCHITECTURE Mask */
+#define SCB_CPUID_PARTNO_Msk (0xFFFUL << 4) /* SCB CPUID: PARTNO Mask */
+#define SCB_CPUID_REVISION_Msk (0xFUL << 0) /* SCB CPUID: REVISION Mask */
+
+/* SCB Interrupt Control State Register Definitions */
+#define SCB_ICSR_NMIPENDSET_Msk (1UL << 31) /* SCB ICSR: NMIPENDSET Mask */
+#define SCB_ICSR_PENDSVSET_Msk (1UL << 28) /* SCB ICSR: PENDSVSET Mask */
+#define SCB_ICSR_PENDSVCLR_Msk (1UL << 27) /* SCB ICSR: PENDSVCLR Mask */
+#define SCB_ICSR_PENDSTSET_Msk (1UL << 26) /* SCB ICSR: PENDSTSET Mask */
+#define SCB_ICSR_PENDSTCLR_Msk (1UL << 25) /* SCB ICSR: PENDSTCLR Mask */
+#define SCB_ICSR_ISRPREEMPT_Msk (1UL << 23) /* SCB ICSR: ISRPREEMPT Mask */
+#define SCB_ICSR_ISRPENDING_Msk (1UL << 22) /* SCB ICSR: ISRPENDING Mask */
+#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << 12) /* SCB ICSR: VECTPENDING Mask */
+#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL << 0) /* SCB ICSR: VECTACTIVE Mask */
+
+/* SCB Application Interrupt and Reset Control Register Definitions */
+#define SCB_AIRCR_VECTKEY_Pos 16
+#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << 16) /* SCB AIRCR: VECTKEY Mask */
+#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << 16) /* SCB AIRCR: VECTKEYSTAT Mask */
+#define SCB_AIRCR_ENDIANESS_Msk (1UL << 15) /* SCB AIRCR: ENDIANESS Mask */
+#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << 2) /* SCB AIRCR: SYSRESETREQ Mask */
+#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << 1) /* SCB AIRCR: VECTCLRACTIVE Mask */
+
+/* SCB System Control Register Definitions */
+#define SCB_SCR_SEVONPEND_Msk (1UL << 4) /* SCB SCR: SEVONPEND Mask */
+#define SCB_SCR_SLEEPDEEP_Msk (1UL << 2) /* SCB SCR: SLEEPDEEP Mask */
+#define SCB_SCR_SLEEPONEXIT_Msk (1UL << 1) /* SCB SCR: SLEEPONEXIT Mask */
+
+/* SCB Configuration Control Register Definitions */
+#define SCB_CCR_STKALIGN_Msk (1UL << 9) /* SCB CCR: STKALIGN Mask */
+#define SCB_CCR_UNALIGN_TRP_Msk (1UL << 3) /* SCB CCR: UNALIGN_TRP Mask */
+
+
+
+/***************************************************************************** */
+/* Cortex-M0 System Timer */
+/***************************************************************************** */
+/* Cortex-M0 System Timer Registers */
+struct system_tick_regs {
+ volatile uint32_t ctrl; /* 0x000 : SysTick Control and Status Register (R/W) */
+ volatile uint32_t load; /* 0x004 : SysTick Reload Value Register (R/W) */
+ volatile uint32_t val; /* 0x008 : SysTick Current Value Register (R/W) */
+ volatile const uint32_t calib; /* 0x00C : SysTick Calibration Register (R/ ) */
+};
+#define LPC_SYSTICK ((struct system_tick_regs *) LPC_SYSTICK_BASE) /* SysTick configuration struct */
+
+/* SysTick Control / Status Register Definitions */
+#define SysTick_CTRL_COUNTFLAG_Msk (1UL << 16) /* SysTick CTRL: COUNTFLAG Mask */
+#define SysTick_CTRL_CLKSOURCE_Msk (1UL << 2) /* SysTick CTRL: CLKSOURCE Mask */
+#define SysTick_CTRL_TICKINT_Msk (1UL << 1) /* SysTick CTRL: TICKINT Mask */
+#define SysTick_CTRL_ENABLE_Msk (1UL << 0) /* SysTick CTRL: ENABLE Mask */
+
+/* SysTick Reload Register Definitions */
+#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL) /* SysTick LOAD: RELOAD Mask */
+
+/* SysTick Current Register Definitions */
+#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL) /* SysTick VAL: CURRENT Mask */
+
+/* SysTick Calibration Register Definitions */
+#define SysTick_CALIB_NOREF_Msk (1UL << 31) /* SysTick CALIB: NOREF Mask */
+#define SysTick_CALIB_SKEW_Msk (1UL << 30) /* SysTick CALIB: SKEW Mask */
+#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL) /* SysTick CALIB: TENMS Mask */
+
+
+
+/***************************************************************************** */
+/* Power Management Unit */
+/***************************************************************************** */
+/* Power Management Unit (PMU) */
+struct lpc_pm_unit
+{
+ volatile uint32_t power_ctrl; /* 0x000 : Power control Register (R/W) */
+ volatile uint32_t gp_data[4]; /* 0x004 to 0x010 : General purpose Register 0 to 3 (R/W) */
+ volatile uint32_t system_config; /* 0x014 : System configuration register (R/W) */
+ /* (RTC clock control and hysteresis of the WAKEUP pin) */
+};
+#define LPC_PMU ((struct lpc_pm_unit *) LPC_PMU_BASE)
+
+
+/***************************************************************************** */
+/* IO Control */
+/***************************************************************************** */
+/* Pin Connect Block (IOCON) */
+struct lpc_io_control
+{
+ uint32_t reserved_0[2];
+ volatile uint32_t pio0_19; /* 0x008 : I/O configuration for pin pio0_19 (R/W) */
+ volatile uint32_t pio0_20; /* 0x00C : I/O configuration for pin pio0_20 (R/W) */
+ volatile uint32_t pio0_21; /* 0x010 : I/O configuration for pin pio0_21 (R/W) */
+ volatile uint32_t pio0_22; /* 0x014 : I/O configuration for pin pio0_22 (R/W) */
+ volatile uint32_t pio0_23; /* 0x018 : I/O configuration for pin pio0_23 (R/W) */
+ volatile uint32_t pio0_24; /* 0x01C : I/O configuration for pin pio0_24 (R/W) */
+ volatile uint32_t pio0_25; /* 0x020 : I/O configuration for pin pio0_25 (R/W) */
+ volatile uint32_t pio0_26; /* 0x024 : I/O configuration for pin pio0_26 (R/W) */
+ volatile uint32_t pio0_27; /* 0x028 : I/O configuration for pin pio0_27 (R/W) */
+
+ volatile uint32_t pio2_12; /* 0x02C : I/O configuration for pin pio2_12 (R/W) */
+ volatile uint32_t pio2_13; /* 0x030 : I/O configuration for pin pio2_13 (R/W) */
+ volatile uint32_t pio2_14; /* 0x034 : I/O configuration for pin pio2_14 (R/W) */
+ volatile uint32_t pio2_15; /* 0x038 : I/O configuration for pin pio2_15 (R/W) */
+
+ volatile uint32_t pio0_28; /* 0x03C : I/O configuration for pin pio0_28 (R/W) */
+ volatile uint32_t pio0_29; /* 0x040 : I/O configuration for pin pio0_29 (R/W) */
+
+ volatile uint32_t pio0_0; /* 0x044 : I/O configuration for pin pio0_0 (R/W) */
+ volatile uint32_t pio0_1; /* 0x048 : I/O configuration for pin pio0_1 (R/W) */
+ volatile uint32_t pio0_2; /* 0x04C : I/O configuration for pin pio0_2 (R/W) */
+ uint32_t reserved_1[1];
+ volatile uint32_t pio0_3; /* 0x054 : I/O configuration for pin pio0_3 (R/W) */
+ volatile uint32_t pio0_4; /* 0x058 : I/O configuration for pin pio0_4 (R/W) */
+ volatile uint32_t pio0_5; /* 0x05C : I/O configuration for pin pio0_5 (R/W) */
+ volatile uint32_t pio0_6; /* 0x060 : I/O configuration for pin pio0_6 (R/W) */
+ volatile uint32_t pio0_7; /* 0x064 : I/O configuration for pin pio0_7 (R/W) */
+ volatile uint32_t pio0_8; /* 0x068 : I/O configuration for pin pio0_8 (R/W) */
+ volatile uint32_t pio0_9; /* 0x06C : I/O configuration for pin pio0_9 (R/W) */
+
+ volatile uint32_t pio2_0; /* 0x070 : I/O configuration for pin pio2_0 (R/W) */
+ volatile uint32_t pio2_1; /* 0x074 : I/O configuration for pin TDI2_1 (R/W) */
+ volatile uint32_t pio2_2; /* 0x078 : I/O configuration for pin TMS2_2 (R/W) */
+ volatile uint32_t pio2_3; /* 0x07C : I/O configuration for pin TDO2_3 (R/W) */
+ volatile uint32_t pio2_4; /* 0x080 : I/O configuration for pin nTR2_4 (R/W) */
+ volatile uint32_t pio2_5; /* 0x084 : I/O configuration for pin pio2_5 (R/W) */
+ volatile uint32_t pio2_6; /* 0x088 : I/O configuration for pin pio2_6 (R/W) */
+ volatile uint32_t pio2_7; /* 0x08C : I/O configuration for pin pio2_7 (R/W) */
+
+ volatile uint32_t pio0_10; /* 0x090 : I/O configuration for pin SWD0_10 (R/W) */
+ volatile uint32_t pio0_11; /* 0x094 : I/O configuration for pin pio0_11 (R/W) */
+ volatile uint32_t pio0_12; /* 0x098 : I/O configuration for pin pio0_12 (R/W) */
+ volatile uint32_t pio0_13; /* 0x09C : I/O configuration for pin pio0_13 (R/W) */
+ volatile uint32_t pio0_14; /* 0x0A0 : I/O configuration for pin pio0_14 (R/W) */
+ volatile uint32_t pio0_15; /* 0x0A4 : I/O configuration for pin pio0_15 (R/W) */
+ volatile uint32_t pio0_16; /* 0x0A8 : I/O configuration for pin pio0_16 (R/W) */
+ volatile uint32_t pio0_17; /* 0x0AC : I/O configuration for pin pio0_17 (R/W) */
+ volatile uint32_t pio0_18; /* 0x0B0 : I/O configuration for pin pio0_18 (R/W) */
+
+ volatile uint32_t pio0_30; /* 0x0B4 : I/O configuration for pin pio0_30 (R/W) */
+ volatile uint32_t pio0_31; /* 0x0B8 : I/O configuration for pin pio0_31 (R/W) */
+
+ volatile uint32_t pio1_0; /* 0x0BC : I/O configuration for pin pio1_0 (R/W) */
+ volatile uint32_t pio1_1; /* 0x0C0 : I/O configuration for pin pio1_1 (R/W) */
+ volatile uint32_t pio1_2; /* 0x0C4 : I/O configuration for pin pio1_2 (R/W) */
+ volatile uint32_t pio1_3; /* 0x0C8 : I/O configuration for pin pio1_3 (R/W) */
+ volatile uint32_t pio1_4; /* 0x0CC : I/O configuration for pin pio1_4 (R/W) */
+ volatile uint32_t pio1_5; /* 0x0D0 : I/O configuration for pin pio1_5 (R/W) */
+ volatile uint32_t pio1_6; /* 0x0D4 : I/O configuration for pin pio1_6 (R/W) */
+ uint32_t reserved_2[2];
+
+ volatile uint32_t pio2_8; /* 0x0E0 : I/O configuration for pin pio2_8 (R/W) */
+ volatile uint32_t pio2_9; /* 0x0E4 : I/O configuration for pin pio2_9 (R/W) */
+ volatile uint32_t pio2_10; /* 0x0E8 : I/O configuration for pin pio2_10 (R/W) */
+ volatile uint32_t pio2_11; /* 0x0EC : I/O configuration for pin pio2_11 (R/W) */
+
+};
+#define LPC_IO_CONTROL ((struct lpc_io_control *) LPC_IOCON_BASE)
+
+/* FIXME : to be completed */
+#define LPC_IO_FUNC_ALT(x) ((x & 0x07) << 0)
+
+#define LPC_IO_MODE_INACTIVE (0x00 << 4)
+#define LPC_IO_MODE_PULL_UP (0x01 << 4)
+
+#define LPC_IO_INVERTED (0x01 << 6)
+
+#define LPC_IO_ANALOG (0x00 << 7)
+#define LPC_IO_DIGITAL (0x01 << 7)
+
+#define LPC_IO_DRIVE_LOWCURENT (0x00 << 9)
+#define LPC_IO_DRIVE_HIGHCURENT (0x01 << 9)
+
+#define LPC_IO_OPEN_DRAIN_ENABLE (0x01 << 10)
+
+#define LPC_IO_SAMPLE_MODE_BYP (0x00 << 11)
+#define LPC_FILTER_ONE_CLK 1
+#define LPC_FILTER_TWO_CLK 2
+#define LPC_FILTER_THREE_CLK 3
+#define LPC_IO_SAMPLE_MODE(x) ((x & 0x03) << 11)
+#define LPC_IO_SAMPLE_CLK_DIV(x) ((x & 0x07) << 13)
+
+
+/***************************************************************************** */
+/* General Purpose Input/Output */
+/***************************************************************************** */
+/* General Purpose Input/Output (GPIO) */
+struct lpc_gpio
+{
+ volatile uint32_t mask; /* 0x00 : Pin mask, affects data, out, set, clear and invert */
+ volatile uint32_t in; /* 0x04 : Port data Register (R/-) */
+ volatile uint32_t out; /* 0x08 : Port output Register (R/W) */
+ volatile uint32_t set; /* 0x0C : Port output set Register (-/W) */
+ volatile uint32_t clear; /* 0x10 : Port output clear Register (-/W) */
+ volatile uint32_t invert; /* 0x14 : Port output invert Register (-/W) */
+ uint32_t reserved_1[2];
+ volatile uint32_t data_dir; /* 0x20 : Data direction Register (R/W) */
+ volatile uint32_t int_sense; /* 0x24 : Interrupt sense Register (R/W) */
+ volatile uint32_t int_both_edges; /* 0x28 : Interrupt both edges Register (R/W) */
+ volatile uint32_t int_event; /* 0x2C : Interrupt event Register (R/W) */
+ volatile uint32_t int_enable; /* 0x30 : Interrupt mask Register (R/W) */
+ volatile uint32_t raw_int_status; /* 0x34 : Raw interrupt status Register (R/-) */
+ volatile uint32_t masked_int_status; /* 0x38 : Masked interrupt status Register (R/-) */
+ volatile uint32_t int_clear; /* 0x3C : Interrupt clear Register (R/W) */
+};
+#define LPC_GPIO_0 ((struct lpc_gpio *) LPC_GPIO_0_BASE)
+#define LPC_GPIO_1 ((struct lpc_gpio *) LPC_GPIO_1_BASE)
+#define LPC_GPIO_2 ((struct lpc_gpio *) LPC_GPIO_2_BASE)
+
+
+
+/***************************************************************************** */
+/* Universal Asynchronous Receiver Transmitter */
+/***************************************************************************** */
+/* Universal Asynchronous Receiver Transmitter (UART) */
+struct lpc_uart_func {
+ volatile uint32_t buffer; /* 0x000 : Transmit / Receiver Buffer Register (R/W) */
+ volatile uint32_t intr_enable; /* 0x004 : Interrupt Enable Register (R/W) */
+ volatile uint32_t intr_pending; /* 0x008 : Interrupt ID Register (R/-) */
+};
+struct lpc_uart_ctrl {
+ volatile uint32_t divisor_latch_lsb; /* 0x000 : Divisor Latch LSB (R/W) */
+ volatile uint32_t divisor_latch_msb; /* 0x004 : Divisor Latch MSB (R/W) */
+ volatile uint32_t fifo_ctrl; /* 0x008 : Fifo Control Register (-/W) */
+};
+struct lpc_uart
+{
+ union {
+ struct lpc_uart_func func;
+ struct lpc_uart_ctrl ctrl;
+ };
+ volatile uint32_t line_ctrl; /* 0x00C : Line Control Register (R/W) */
+ volatile uint32_t modem_ctrl; /* 0x010 : Modem control Register (R/W) */
+ volatile const uint32_t line_status; /* 0x014 : Line Status Register (R/ ) */
+ volatile const uint32_t modem_status; /* 0x018 : Modem status Register (R/ ) */
+ volatile uint32_t scratch_pad; /* 0x01C : Scratch Pad Register (R/W) */
+ volatile uint32_t auto_baud_ctrl; /* 0x020 : Auto-baud Control Register (R/W) */
+ uint32_t reserved_0;
+ volatile uint32_t fractional_div; /* 0x028 : Fractional Divider Register (R/W) */
+ uint32_t reserved_1;
+ volatile uint32_t transmit_enable; /* 0x030 : Transmit Enable Register (R/W) */
+ uint32_t reserved_2[6];
+ volatile uint32_t RS485_ctrl; /* 0x04C : RS-485/EIA-485 Control Register (R/W) */
+ volatile uint32_t RS485_addr_match; /* 0x050 : RS-485/EIA-485 address match Register (R/W) */
+ volatile uint32_t RS485_dir_ctrl_delay; /* 0x054 : RS-485/EIA-485 direction control delay Register (R/W) */
+ volatile uint32_t fifo_level; /* 0x058 : Fifo Level Register (R/-) */
+};
+#define LPC_UART_0 ((struct lpc_uart *) LPC_UART0_BASE)
+#define LPC_UART_1 ((struct lpc_uart *) LPC_UART1_BASE)
+
+/* Line Control Register */
+#define LPC_UART_8BIT (0x03 << 0)
+#define LPC_UART_1STOP (0x00 << 2)
+#define LPC_UART_NO_PAR (0x00 << 3)
+#define LPC_UART_ENABLE_DLAB (0x01 << 7)
+/* FIFO Control Register */
+#define LPC_UART_FIFO_EN (0x01 << 0)
+#define LPC_UART_TX_CLR (0x01 << 1)
+#define LPC_UART_RX_CLR (0x01 << 2)
+#define LPC_UART_FIFO_TRIG(x) ((x & 0x03) << 6) /* 1 / 4 / 8 / 14 chars */
+/* Interrupt Enable Register */
+#define LPC_UART_RX_INT_EN (0x01 << 0)
+#define LPC_UART_TX_INT_EN (0x01 << 1)
+#define LPC_UART_RX_STATUS_INT_EN (0x01 << 2)
+/* Interrupt status */
+#define LPC_UART_INT_MASK (0x7 << 1)
+#define LPC_UART_INT_MODEM (0x0 << 1)
+#define LPC_UART_INT_TX (0x1 << 1)
+#define LPC_UART_INT_RX (0x2 << 1)
+#define LPC_UART_INT_RX_STATUS (0x3 << 1)
+#define LPC_UART_INT_TIMEOUT (0x6 << 1)
+
+
+/***************************************************************************** */
+/* Inter-Integrated Circuit */
+/***************************************************************************** */
+/* Inter-Integrated Circuit (I2C) */
+struct lpc_i2c
+{
+ volatile uint32_t ctrl_set; /* 0x000 : I2C Control Set Register (R/W) */
+ volatile const uint32_t status; /* 0x004 : I2C Status Register (R/-) */
+ volatile uint32_t data; /* 0x008 : I2C Data Register (R/W) */
+ volatile uint32_t slave_addr_0; /* 0x00C : I2C Slave Address Register 0 (R/W) */
+ volatile uint32_t clk_duty_high; /* 0x010 : SCL Duty Cycle Register High Half Word (R/W) */
+ volatile uint32_t clk_duty_low; /* 0x014 : SCL Duty Cycle Register Low Half Word (R/W) */
+ volatile uint32_t ctrl_clear; /* 0x018 : I2C Control Clear Register (-/W) */
+ volatile uint32_t monitor_mode_ctrl; /* 0x01C : Monitor mode control register (R/W) */
+ volatile uint32_t slave_addr_1; /* 0x020 : I2C Slave Address Register 1 (R/W) */
+ volatile uint32_t slave_addr_2; /* 0x024 : I2C Slave Address Register 2 (R/W) */
+ volatile uint32_t slave_addr_3; /* 0x028 : I2C Slave Address Register 3 (R/W) */
+ volatile const uint32_t data_buffer; /* 0x02C : Data buffer register (-/W) */
+ volatile uint32_t slave_addr_mask[4]; /* 0x030 to 0x03C : I2C Slave address mask register 0 to 3 (R/W) */
+};
+#define LPC_I2C0 ((struct lpc_i2c *) LPC_I2C0_BASE)
+
+#define I2C_ASSERT_ACK (0x01 << 2)
+#define I2C_INTR_FLAG (0x01 << 3)
+#define I2C_STOP_FLAG (0x01 << 4)
+#define I2C_START_FLAG (0x01 << 5)
+#define I2C_ENABLE_FLAG (0x01 << 6)
+
+
+/***************************************************************************** */
+/* Synchronous Serial Communication */
+/***************************************************************************** */
+/* Synchronous Serial Communication (SSP) */
+struct lpc_ssp
+{
+ volatile uint32_t ctrl_0; /* 0x000 : Control Register 0 (R/W) */
+ volatile uint32_t ctrl_1; /* 0x004 : Control Register 1 (R/W) */
+ volatile uint32_t data; /* 0x008 : Data Register (R/W) */
+ volatile const uint32_t status; /* 0x00C : Status Registe (R/-) */
+ volatile uint32_t clk_prescale; /* 0x010 : Clock Prescale Register (R/W) */
+ volatile uint32_t int_mask; /* 0x014 : Interrupt Mask Set and Clear Register (R/W) */
+ volatile uint32_t raw_int_status; /* 0x018 : Raw Interrupt Status Register (R/-) */
+ volatile uint32_t masked_int_status; /* 0x01C : Masked Interrupt Status Register (R/-) */
+ volatile uint32_t int_clear; /* 0x020 : SSPICR Interrupt Clear Register (-/W) */
+ volatile uint32_t dma_ctrl;; /* 0x024 : DMA Control Register (R/W) */
+};
+#define LPC_SSP0 ((struct lpc_ssp *) LPC_SSP0_BASE)
+
+
+
+/***************************************************************************** */
+/* Timer */
+/***************************************************************************** */
+/* Timer (TMR) */
+struct lpc_timer
+{
+ volatile uint32_t int_reg; /* 0x000 : Interrupt Register (R/W) */
+ volatile uint32_t timer_ctrl; /* 0x004 : Timer Control Register (R/W) */
+ volatile uint32_t timer_counter; /* 0x008 : Timer Counter Register (R/W) */
+ volatile uint32_t prescale; /* 0x00C : Prescale Register (R/W) */
+ volatile uint32_t prescale_counter; /* 0x010 : Prescale Counter Register (R/W) */
+ volatile uint32_t match_ctrl; /* 0x014 : Match Control Register (R/W) */
+ volatile uint32_t match_reg[4]; /* 0x018 : Match Register 0 to 3 (R/W) */
+ volatile uint32_t capture_ctrl; /* 0x028 : Capture Control Register (R/W) */
+ volatile const uint32_t capture_reg[4]; /* 0x02C : Capture Register 0 to 3 (R/ ) */
+ volatile uint32_t external_match; /* 0x03C : External Match Register (R/W) */
+ uint32_t reserved_2[12];
+ volatile uint32_t count_ctrl; /* 0x070 : Count Control Register (R/W) */
+ volatile uint32_t pwm_ctrl; /* 0x074 : PWM Control Register (R/W) */
+};
+#define LPC_TMR16B0 ((struct lpc_timer *) LPC_TIMER0_BASE)
+#define LPC_TMR16B1 ((struct lpc_timer *) LPC_TIMER1_BASE)
+#define LPC_TMR32B0 ((struct lpc_timer *) LPC_TIMER2_BASE)
+#define LPC_TMR32B1 ((struct lpc_timer *) LPC_TIMER3_BASE)
+
+
+
+/***************************************************************************** */
+/* Watchdog Timer */
+/***************************************************************************** */
+/* Watchdog Timer (WDT) */
+struct lpc_watchdog
+{
+ volatile uint32_t mode; /* 0x000 : Watchdog mode register (R/W) */
+ volatile uint32_t timer_const; /* 0x004 : Watchdog timer constant register (R/W) */
+ volatile uint32_t feed_seqence; /* 0x008 : Watchdog feed sequence register ( /W) */
+ volatile const uint32_t timer_value; /* 0x00C : Watchdog timer value register (R/ ) */
+ volatile uint32_t clk_src_sel; /* 0x010 : Wathdog Clock Source Selection Register (R/W) */
+ volatile uint32_t warning_int_compare; /* 0x014 : Watchdog Warning Interrupt compare value. */
+ volatile uint32_t window_compare; /* 0x018 : Watchdog Window compare value. */
+};
+#define LPC_WDT ((struct lpc_watchdog *) LPC_WDT_BASE)
+
+
+/***************************************************************************** */
+/* Analog-to-Digital Converter */
+/***************************************************************************** */
+/* Analog-to-Digital Converter (ADC) */
+struct lpc_adc
+{
+ volatile uint32_t ctrl; /* 0x000 : A/D Control Register (R/W) */
+ volatile uint32_t global_data; /* 0x004 : A/D Global Data Register (R/W) */
+ uint32_t reserved_0;
+ volatile uint32_t int_en; /* 0x00C : A/D Interrupt Enable Register (R/W) */
+ volatile uint32_t data[8]; /* Offset: 0x010-0x02C A/D Channel 0..7 Data Register (R/W) */
+ volatile const uint32_t status; /* 0x030 : A/D Status Register (R/ ) */
+ volatile uint32_t trim; /* 0x034 : A/D Trim Register (R/W) */
+};
+#define LPC_ADC ((struct lpc_adc *) LPC_ADC_BASE)
+
+#define LPC_ADC_10BITS (0x00 << 17)
+#define LPC_ADC_9BITS (0x01 << 17)
+#define LPC_ADC_8BITS (0x02 << 17)
+#define LPC_ADC_7BITS (0x03 << 17)
+#define LPC_ADC_6BITS (0x04 << 17)
+#define LPC_ADC_START_CONV_NOW (0x01 << 24)
+#define LPC_ADC_START_CONV_MASK (0x07 << 24)
+#define LPC_ADC_CONV_AD0 (0x01 << 0)
+
+#define LPC_ADC_INT_EN_AD0 (0x01 << 0)
+
+
+
+
+#endif /* LPC_REGS_H */
--- /dev/null
+/****************************************************************************
+ * core/system.h
+ *
+ * All low-level functions for clocks configuration and switch, system
+ * power-up, reset, and power-down.
+ *
+ * Copyright 2012 Nathael Pajani <nathael.pajani@ed3l.fr>
+ *
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program 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 General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *************************************************************************** */
+
+#ifndef CORE_SYSTEM_H
+#define CORE_SYSTEM_H
+
+#include <stdint.h>
+
+#include "core/lpc_regs_12xx.h"
+#include "core/lpc_core_cm0.h"
+
+
+/* Error Values, from glibc errno.h and errno-base.h */
+/* I2C */
+#define EIO 5 /* Bad one: Illegal start or stop, or illegal state in i2c state machine */
+#define EAGAIN 11 /* Device already in use */
+#define EFAULT 14 /* address above eeprom size */
+#define EBUSY 16 /* Device or ressource Busy or Arbitration lost */
+#define EINVAL 22 /* Invalid argument */
+#define EBADFD 77 /* Device not initialized */
+#define EREMOTEIO 121 /* Device did not acknowledge */
+
+
+/***************************************************************************** */
+/* Power up defaults */
+/***************************************************************************** */
+/* Change reset power state to our default, removing power from unused
+ * interfaces */
+void system_set_default_power_state(void);
+
+/* Configure all default pin functions for dtplug, even if modules or functions
+ * are not used */
+void system_set_default_pins(void);
+
+/* Stop the watchdog */
+void stop_watchdog(void);
+
+/***************************************************************************** */
+/* Power */
+/***************************************************************************** */
+void enter_deep_sleep(void);
+
+/* Configure the brown-out detection */
+void system_brown_out_detection_config(uint32_t level);
+
+/***************************************************************************** */
+/* System Clock */
+/***************************************************************************** */
+/* A clock frequency is defined as the integer value in MHz divided by 12, shifted
+ * by 3 and or'ed with the value to be programmed in the flash config register for
+ * the flash access time at the given frequency shifted by one and the flash
+ * override bit in the LSB
+ */
+/* PLL may fail to lock for frenquencies above 60MHz */
+#define FREQ_SEL_60MHz ((5 << 3) | (0x01 << 1) | 0)
+#define FREQ_SEL_48MHz ((4 << 3) | (0x00 << 1) | 0)
+#define FREQ_SEL_36MHz ((3 << 3) | (0x00 << 1) | 0)
+#define FREQ_SEL_24MHz ((2 << 3) | (0x00 << 1) | 1)
+#define FREQ_SEL_12MHz ((1 << 3) | (0x00 << 1) | 1)
+#define FREQ_SEL_IRC FREQ_SEL_12MHz
+
+/* Main clock config
+ * We use external crystal and PLL0
+ * Note that during PLL lock wait we are running on internal RC
+ */
+void clock_config(uint32_t freq_sel);
+
+/* return current main clock */
+uint32_t get_main_clock(void);
+
+
+/* This is mainly a debug feature, but can be used to provide a clock to an
+ * external peripheral */
+void clkout_on(uint32_t src, uint32_t div);
+void clkout_off(void);
+
+
+static inline void msleep(uint32_t ms)
+{
+ volatile uint32_t dec = ms * 1000;
+ while (dec--);
+}
+
+#endif /* CORE_SYSTEM_H */
--- /dev/null
+/****************************************************************************
+ * drivers/gpio.h
+ *
+ * Copyright 2012 Nathael Pajani <nathael.pajani@ed3l.fr>
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program 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 General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *************************************************************************** */
+
+#ifndef DRIVERS_GPIO_H
+#define DRIVERS_GPIO_H
+
+
+#include <stdint.h>
+
+
+/***************************************************************************** */
+/* Public access to GPIO setup */
+
+
+void config_gpio(volatile uint32_t* handle, uint32_t mode);
+
+void gpio_on(void);
+void gpio_off(void);
+
+/***************************************************************************** */
+/* Status LED */
+/* The status LED is on GPIO Port 1, pin 4 (PIO1_4) and Port 1, pin 5 (PIO1_5) */
+void status_led_config(void);
+
+void status_led(uint32_t val);
+
+void chenillard(uint32_t ms);
+
+enum led_status {
+ none = 0,
+ red_only,
+ red_on,
+ red_off,
+ red_toggle,
+ green_only,
+ green_on,
+ green_off,
+ green_toggle,
+ both,
+ toggle,
+};
+
+
+#endif /* DRIVERS_GPIO_H */
--- /dev/null
+/****************************************************************************
+ * serial.h
+ *
+ * Copyright 2012 Nathael Pajani <nathael.pajani@ed3l.fr>
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program 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 General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *************************************************************************** */
+
+#ifndef DRIVERS_SERIAL_H
+#define DRIVERS_SERIAL_H
+
+
+#include <stdint.h>
+
+
+/***************************************************************************** */
+/* Serial Write */
+
+int serial_write(uint32_t uart_num, char *buf, uint32_t length);
+
+
+
+
+
+/***************************************************************************** */
+/* Public access to UART setup */
+
+
+void set_uarts_pins(void);
+
+
+/* Allow any change to the main clock to be forwarded to us */
+void uart_clk_update(void);
+
+
+/* Do we need to allow setting of other parameters ? (Other than 8n1) */
+/* Do we need to allow specifying an interrupt handler ? */
+void uart_on(uint32_t uart_num, uint32_t baudrate);
+
+void uart_off(uint32_t uart_num);
+
+
+
+#endif /* DRIVERS_SERIAL_H */
--- /dev/null
+/****************************************************************************
+ * lib/stdio.h
+ *
+ * Copyright 2012 Nathael Pajani <nathael.pajani@ed3l.fr>
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program 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 General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *************************************************************************** */
+
+#ifndef LIB_STDIO_H
+#define LIB_STDIO_H
+
+#include <stdarg.h>
+#include <stdint.h>
+#include "lib/string.h"
+
+
+int vsnprintf(char *buf, size_t size, const char *fmt, va_list args);
+
+
+int snprintf(char* buf, size_t size, const char *format, ...);
+
+#endif /* LIB_STDIO_H */
--- /dev/null
+/*
+ * lib/string.h
+ *
+ * From linux/lib/string.h :
+ *
+ * Copyright (C) 1991, 1992 Linus Torvalds
+ */
+
+/*
+ * stupid library routines.. The optimized versions should generally be found
+ * as inline code in <asm-xx/string.h>
+ *
+ * These are buggy as well..
+ *
+ * * Fri Jun 25 1999, Ingo Oeser <ioe@informatik.tu-chemnitz.de>
+ * - Added strsep() which will replace strtok() soon (because strsep() is
+ * reentrant and should be faster). Use only strsep() in new code, please.
+ */
+
+#ifndef LIB_STRING_H
+#define LIB_STRING_H
+
+/* Get size_t, and NULL from <stddef.h>. */
+#undef __need_malloc_and_calloc
+#define __need_size_t
+#define __need_NULL
+#include <stddef.h>
+#include <stdint.h>
+
+/**
+ * memcpy - Copy one area of memory to another
+ * @dest: Where to copy to
+ * @src: Where to copy from
+ * @count: The size of the area.
+ *
+ * You should not use this function to access IO space, use memcpy_toio()
+ * or memcpy_fromio() instead.
+ */
+void * memcpy(void *dest, const void *src, size_t count);
+
+/**
+ * memset - Fill a region of memory with the given value
+ * @s: Pointer to the start of the area.
+ * @c: The byte to fill the area with
+ * @count: The size of the area.
+ *
+ * Do not use memset() to access IO space, use memset_io() instead.
+ */
+void * memset(void * s, int c, size_t count);
+
+/**
+ * strcpy - Copy a %NUL terminated string
+ * @dest: Where to copy the string to
+ * @src: Where to copy the string from
+ */
+char * strcpy(char * dest, const char *src);
+
+/**
+ * strncpy - Copy a length-limited, %NUL-terminated string
+ * @dest: Where to copy the string to
+ * @src: Where to copy the string from
+ * @count: The maximum number of bytes to copy
+ *
+ * Note that unlike userspace strncpy, this does not %NUL-pad the buffer.
+ * However, the result is not %NUL-terminated if the source exceeds
+ * @count bytes.
+ */
+char * strncpy(char * dest, const char *src, size_t count);
+
+/**
+ * strcmp - Compare two strings
+ * @cs: One string
+ * @ct: Another string
+ */
+int strcmp(const char * cs, const char * ct);
+
+/**
+ * strncmp - Compare two length-limited strings
+ * @cs: One string
+ * @ct: Another string
+ * @count: The maximum number of bytes to compare
+ */
+int strncmp(const char * cs, const char * ct, size_t count);
+
+/**
+ * strchr - Find the first occurrence of a character in a string
+ * @s: The string to be searched
+ * @c: The character to search for
+ */
+char * strchr(const char * s, int c);
+
+/**
+ * strlen - Find the length of a string
+ * @s: The string to be sized
+ */
+size_t strlen(const char * s);
+
+/**
+ * strrchr - Find the last occurrence of a character in a string
+ * @s: The string to be searched
+ * @c: The character to search for
+ */
+char * strrchr(const char * s, int c);
+
+/**
+ * strnlen - Find the length of a length-limited string
+ * @s: The string to be sized
+ * @count: The maximum number of bytes to search
+ */
+size_t strnlen(const char * s, size_t count);
+
+
+#endif /* LIB_STRING_H */
--- /dev/null
+/*
+ * linux/lib/string.c
+ *
+ * Copyright (C) 1991, 1992 Linus Torvalds
+ */
+
+/*
+ * stupid library routines.. The optimized versions should generally be found
+ * as inline code in <asm-xx/string.h>
+ *
+ * These are buggy as well..
+ *
+ * * Fri Jun 25 1999, Ingo Oeser <ioe@informatik.tu-chemnitz.de>
+ * - Added strsep() which will replace strtok() soon (because strsep() is
+ * reentrant and should be faster). Use only strsep() in new code, please.
+ */
+
+/* Get size_t, and NULL from <stddef.h>. */
+#undef __need_malloc_and_calloc
+#define __need_size_t
+#define __need_NULL
+#include <stddef.h>
+
+#include <stdint.h>
+
+/**
+ * memcpy - Copy one area of memory to another
+ * @dest: Where to copy to
+ * @src: Where to copy from
+ * @count: The size of the area.
+ *
+ * You should not use this function to access IO space, use memcpy_toio()
+ * or memcpy_fromio() instead.
+ */
+void * memcpy(void *dest, const void *src, size_t count)
+{
+ unsigned long *dl = (unsigned long *)dest, *sl = (unsigned long *)src;
+ char *d8, *s8;
+
+ if (src == dest)
+ return dest;
+
+ /* while all data is aligned (common case), copy a word at a time */
+ if ( (((uint32_t)dest | (uint32_t)src) & (sizeof(*dl) - 1)) == 0) {
+ while (count >= sizeof(*dl)) {
+ *dl++ = *sl++;
+ count -= sizeof(*dl);
+ }
+ }
+ /* copy the reset one byte at a time */
+ d8 = (char *)dl;
+ s8 = (char *)sl;
+ while (count--)
+ *d8++ = *s8++;
+
+ return dest;
+}
+
+/**
+ * memset - Fill a region of memory with the given value
+ * @s: Pointer to the start of the area.
+ * @c: The byte to fill the area with
+ * @count: The size of the area.
+ *
+ * Do not use memset() to access IO space, use memset_io() instead.
+ */
+void * memset(void * s,int c,size_t count)
+{
+ unsigned long *sl = (unsigned long *) s;
+ unsigned long cl = 0;
+ char *s8;
+ int i;
+
+ /* do it one word at a time (32 bits or 64 bits) while possible */
+ if ( ((uint32_t)s & (sizeof(*sl) - 1)) == 0) {
+ for (i = 0; i < sizeof(*sl); i++) {
+ cl <<= 8;
+ cl |= c & 0xff;
+ }
+ while (count >= sizeof(*sl)) {
+ *sl++ = cl;
+ count -= sizeof(*sl);
+ }
+ }
+ /* fill 8 bits at a time */
+ s8 = (char *)sl;
+ while (count--)
+ *s8++ = c;
+
+ return s;
+}
+
+/**
+ * strcpy - Copy a %NUL terminated string
+ * @dest: Where to copy the string to
+ * @src: Where to copy the string from
+ */
+char * strcpy(char * dest,const char *src)
+{
+ char *tmp = dest;
+
+ while ((*dest++ = *src++) != '\0')
+ /* nothing */;
+ return tmp;
+}
+
+/**
+ * strncpy - Copy a length-limited, %NUL-terminated string
+ * @dest: Where to copy the string to
+ * @src: Where to copy the string from
+ * @count: The maximum number of bytes to copy
+ *
+ * Note that unlike userspace strncpy, this does not %NUL-pad the buffer.
+ * However, the result is not %NUL-terminated if the source exceeds
+ * @count bytes.
+ */
+char * strncpy(char * dest,const char *src,size_t count)
+{
+ char *tmp = dest;
+
+ while (count-- && (*dest++ = *src++) != '\0')
+ /* nothing */;
+
+ return tmp;
+}
+
+/**
+ * strcmp - Compare two strings
+ * @cs: One string
+ * @ct: Another string
+ */
+int strcmp(const char * cs,const char * ct)
+{
+ register signed char __res;
+
+ while (1) {
+ if ((__res = *cs - *ct++) != 0 || !*cs++)
+ break;
+ }
+
+ return __res;
+}
+
+/**
+ * strncmp - Compare two length-limited strings
+ * @cs: One string
+ * @ct: Another string
+ * @count: The maximum number of bytes to compare
+ */
+int strncmp(const char * cs,const char * ct,size_t count)
+{
+ register signed char __res = 0;
+
+ while (count) {
+ if ((__res = *cs - *ct++) != 0 || !*cs++)
+ break;
+ count--;
+ }
+
+ return __res;
+}
+
+/**
+ * strchr - Find the first occurrence of a character in a string
+ * @s: The string to be searched
+ * @c: The character to search for
+ */
+char * strchr(const char * s, int c)
+{
+ for(; *s != (char) c; ++s)
+ if (*s == '\0')
+ return NULL;
+ return (char *) s;
+}
+
+/**
+ * strlen - Find the length of a string
+ * @s: The string to be sized
+ */
+size_t strlen(const char * s)
+{
+ const char *sc;
+
+ for (sc = s; *sc != '\0'; ++sc)
+ /* nothing */;
+ return sc - s;
+}
+
+/**
+ * strrchr - Find the last occurrence of a character in a string
+ * @s: The string to be searched
+ * @c: The character to search for
+ */
+char * strrchr(const char * s, int c)
+{
+ const char *p = s + strlen(s);
+ do {
+ if (*p == (char)c)
+ return (char *)p;
+ } while (--p >= s);
+ return NULL;
+}
+
+/**
+ * strnlen - Find the length of a length-limited string
+ * @s: The string to be sized
+ * @count: The maximum number of bytes to search
+ */
+size_t strnlen(const char * s, size_t count)
+{
+ const char *sc;
+
+ for (sc = s; count-- && *sc != '\0'; ++sc)
+ /* nothing */;
+ return sc - s;
+}
--- /dev/null
+/****************************************************************************
+ * lib/vsprintf.c
+ *
+ * Code based on lib/vsprintf.c from linux kernel.
+ *
+ * Copyright 2012 Nathael Pajani <nathael.pajani@ed3l.fr>
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program 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 General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *************************************************************************** */
+
+#include <stdarg.h>
+#include <stdint.h>
+#include "lib/string.h"
+
+#define ZEROPAD (1 << 0) /* pad with zero */
+#define SIGNED (1 << 1) /* unsigned/signed long */
+#define SIGN (1 << 2) /* show plus */
+#define SPACE (1 << 3) /* space if plus */
+#define LEFT (1 << 4) /* left justified */
+#define LOWERCASE (1 << 5) /* use lowercase in hex (must be 32 == 0x20) */
+#define SPECIAL (1 << 6) /* prefix hex with "0x", octal with "0" */
+#define HEXA (1 << 7) /* output hexa-decimal */
+
+/* In our case, anything that does not fit in 20 chars does not fit in an unsigned int. */
+#define TMP_NUM_BUF_SIZE 20
+static int convert(char* buf, char* end, uint32_t flags, uint32_t width, uint32_t num)
+{
+ static const char digits[16] = "0123456789ABCDEF";
+ char tmp[TMP_NUM_BUF_SIZE];
+ int i = 0, length = 0;
+ char sign = 0;
+
+ if (width > TMP_NUM_BUF_SIZE) {
+ width = TMP_NUM_BUF_SIZE;
+ }
+
+ /* Store sign, and convert to unsigned */
+ if (flags & SIGNED) {
+ if (width) {
+ width--;
+ }
+ if ((signed long)num < 0) {
+ sign = '-';
+ num = -(signed long)num;
+ }
+ } /* Do we need to remove 2 to width in case of "SPECIAL" flag ? */
+
+ /* Generate full string in tmp[], in reverse order */
+ if (num == 0) {
+ tmp[i++] = '0';
+ } else if (flags & HEXA) {
+ /* low_case = 0 or 0x20. ORing digits or letters with 'low_case'
+ * produces same digits or (maybe lowercased) letters */
+ uint32_t low_case = (flags & LOWERCASE) ? 0x20 : 0;
+ do {
+ tmp[i++] = (digits[num & 0x0F] | low_case);
+ num = (num >> 4);
+ } while (num);
+ } else {
+ while (num) {
+ tmp[i++] = (num % 10) + '0';
+ num = num / 10;
+ }
+ }
+
+ /* Add sign, pad if reqiered */
+ if (flags & ZEROPAD) {
+ while (i < width) {
+ tmp[i++] = '0';
+ }
+ }
+ if (sign) {
+ tmp[i++] = sign;
+ } else if (flags & SIGN) {
+ tmp[i++] = '+';
+ } else if (flags & SPACE) {
+ tmp[i++] = ' ';
+ } else if (flags & SPECIAL) {
+ tmp[i++] = 'x';
+ tmp[i++] = '0';
+ }
+ while (i < width) {
+ tmp[i++] = ' ';
+ }
+
+ /* And reverse string */
+ length = i;
+ while (i && (buf < end)) {
+ i--;
+ *(buf++) = tmp[i];
+ }
+ if (i)
+ return -i;
+
+ return length;
+}
+
+int vsnprintf(char *buf, size_t size, const char *fmt, va_list args)
+{
+ char* start = buf;
+ char* end = buf + size - 1; /* leave one char for terminating null byte */
+
+ /* Parse format string */
+ while ((buf < end) && *fmt) {
+ uint32_t flags = 0;
+ uint32_t width = 0;
+
+ if (*fmt != '%') {
+ *buf++ = *fmt++;
+ continue;
+ }
+
+ /* Do we have a conversion specifier ? */
+ fmt++;
+ if (*fmt == '%') {
+ *buf++ = *fmt++;
+ continue;
+ }
+ /* We got a conversion specifier, any modifier ? */
+ /* Note that '-' won't be handled */
+ while (1) {
+ int found = 1;
+ switch (*fmt) {
+ case '-': flags |= LEFT; break;
+ case '+': flags |= SIGN; break;
+ case ' ': flags |= SPACE; break;
+ case '#': flags |= SPECIAL; break;
+ case '0': flags |= ZEROPAD; break;
+ default: found = 0;
+ }
+ if (!found)
+ break;
+ fmt++;
+ }
+ /* Field width ? */
+ while ((*fmt >= '0') && (*fmt <= '9')) {
+ width = (width * 10) + (*fmt - '0');
+ fmt++;
+ }
+ /* We do not handle floats, floats have nothing to do with embeded systems */
+ /* Skip any precision */
+ if (*fmt == '.') {
+ do {
+ fmt++;
+ } while ((*fmt >= '0') && (*fmt <= '9'));
+ }
+ /* Qualifier ? Should we really handle length modifiers ?
+ * The while loop is here to skip these. */
+ /* Handle conversion, if supported. Note that we may spend some time in here
+ * while waiting for the buffer to get available again */
+ while (*fmt) {
+ int found = 1;
+ switch (*fmt) {
+ /* signed */
+ case 'd':
+ case 'i':
+ flags |= SIGNED;
+ buf += convert(buf, end, flags, width, (uint32_t)va_arg(args, signed int));
+ break;
+ /* unsigned */
+ case 'x':
+ flags |= LOWERCASE;
+ case 'X':
+ flags |= HEXA;
+ case 'u':
+ buf += convert(buf, end, flags, width, (uint32_t)va_arg(args, unsigned int));
+ break;
+ /* string */
+ case 's': {
+ /* Copy string to buf */
+ char* tmp = va_arg(args, char *);
+ while ((buf < end) && *tmp) {
+ *buf++ = *tmp++;
+ }
+ break;
+ }
+ /* character */
+ case 'c':
+ *buf++ = (char)va_arg(args, unsigned int);
+ break;
+ default:
+ found = 0;
+ }
+ fmt++;
+ if (found)
+ break;
+ }
+ }
+ *buf = '\0';
+ return (buf - start);
+}
+
+
+int snprintf(char* buf, size_t size, const char *format, ...)
+{
+ va_list args;
+ int r;
+
+ va_start(args, format);
+ r = vsnprintf(buf, size, format, args);
+ va_end(args);
+
+ return r;
+}
+
+
--- /dev/null
+/*
+ * C linker script file for LPC1114
+ */
+
+MEMORY
+{
+ sram (rwx) : ORIGIN = 0x10000000, LENGTH = 4k
+ flash (rx) : ORIGIN = 0x00000000, LENGTH = 32k
+}
+
+_sram_size = 4k;
+_sram_base = 0x10000000;
+_end_stack = (_sram_base + _sram_size);
+
+ENTRY(Reset_Handler)
+
+SECTIONS {
+ . = ORIGIN(flash);
+
+ .text :
+ {
+ FILL(0xFF);
+ KEEP(*(.vectors))
+ *(.text.Reset_Handler .text.SystemInit)
+ . = 0x000002FC;
+ KEEP(*(.crp))
+ *(.text*)
+ *(.rodata*)
+ *(.got*)
+ _end_text = .;
+ } >flash
+
+ . = ALIGN(4);
+
+ .data :
+ {
+ _start_data = .;
+ *(.data*)
+ _end_data = .;
+ } >sram AT >flash
+
+ . = ALIGN(4);
+
+ .bss :
+ {
+ _start_bss = .;
+ *(.bss*)
+ *(COMMON)
+ _end_bss = .;
+ } >sram
+
+
+ . = ALIGN(4);
+}
+
+_end = .;
+PROVIDE(end = .);