aboutsummaryrefslogtreecommitdiff
path: root/lib
diff options
context:
space:
mode:
Diffstat (limited to 'lib')
-rw-r--r--lib/lpc43xx/Makefile61
-rw-r--r--lib/lpc43xx/gpio.c35
-rw-r--r--lib/lpc43xx/i2c.c93
-rw-r--r--lib/lpc43xx/libopencm3_lpc43xx.ld96
-rw-r--r--lib/lpc43xx/libopencm3_lpc43xx_rom_to_ram.ld97
-rw-r--r--lib/lpc43xx/nvic.c76
-rw-r--r--lib/lpc43xx/scu.c30
-rw-r--r--lib/lpc43xx/ssp.c160
-rw-r--r--lib/lpc43xx/systick.c69
-rw-r--r--lib/lpc43xx/vector.c263
-rw-r--r--lib/stm32/f1/rcc.c56
-rw-r--r--lib/stm32/f2/gpio.c2
-rw-r--r--lib/stm32/f4/gpio.c2
13 files changed, 1035 insertions, 5 deletions
diff --git a/lib/lpc43xx/Makefile b/lib/lpc43xx/Makefile
new file mode 100644
index 0000000..91169d4
--- /dev/null
+++ b/lib/lpc43xx/Makefile
@@ -0,0 +1,61 @@
+##
+## This file is part of the libopencm3 project.
+##
+## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+## Copyright (C) 2012 Michael Ossmann <mike@ossmann.com>
+## Copyright (C) 2012 Benjamin Vernoux <titanmkd@gmail.com>
+##
+## This library is free software: you can redistribute it and/or modify
+## it under the terms of the GNU Lesser General Public License as published by
+## the Free Software Foundation, either version 3 of the License, or
+## (at your option) any later version.
+##
+## This library is distributed in the hope that it will be useful,
+## but WITHOUT ANY WARRANTY; without even the implied warranty of
+## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+## GNU Lesser General Public License for more details.
+##
+## You should have received a copy of the GNU Lesser General Public License
+## along with this library. If not, see <http://www.gnu.org/licenses/>.
+##
+
+LIBNAME = libopencm3_lpc43xx
+
+PREFIX ?= arm-none-eabi
+#PREFIX ?= arm-elf
+CC = $(PREFIX)-gcc
+AR = $(PREFIX)-ar
+CFLAGS = -O2 -g3 -Wall -Wextra -I../../include -fno-common \
+ -mcpu=cortex-m4 -mthumb -Wstrict-prototypes \
+ -ffunction-sections -fdata-sections -MD \
+ -mfloat-abi=hard -mfpu=fpv4-sp-d16
+# ARFLAGS = rcsv
+ARFLAGS = rcs
+OBJS = gpio.o vector.o scu.o i2c.o ssp.o nvic.o systick.o
+
+# VPATH += ../usb
+
+# Be silent per default, but 'make V=1' will show all compiler calls.
+ifneq ($(V),1)
+Q := @
+endif
+
+all: $(LIBNAME).a
+
+$(LIBNAME).a: $(OBJS)
+ @printf " AR $(subst $(shell pwd)/,,$(@))\n"
+ $(Q)$(AR) $(ARFLAGS) $@ $^
+
+%.o: %.c
+ @printf " CC $(subst $(shell pwd)/,,$(@))\n"
+ $(Q)$(CC) $(CFLAGS) -o $@ -c $<
+
+clean:
+ @printf " CLEAN lib/lpc43xx\n"
+ $(Q)rm -f *.o *.d
+ $(Q)rm -f $(LIBNAME).a
+
+.PHONY: clean
+
+-include $(OBJS:.o=.d)
+
diff --git a/lib/lpc43xx/gpio.c b/lib/lpc43xx/gpio.c
new file mode 100644
index 0000000..1256fd0
--- /dev/null
+++ b/lib/lpc43xx/gpio.c
@@ -0,0 +1,35 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2010 Uwe Hermann <uwe@hermann-uwe.de>
+ *
+ * This library is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public License
+ * along with this library. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+#include <libopencm3/lpc43xx/gpio.h>
+
+void gpio_set(u32 gpioport, u32 gpios)
+{
+ GPIO_SET(gpioport) = gpios;
+}
+
+void gpio_clear(u32 gpioport, u32 gpios)
+{
+ GPIO_CLR(gpioport) = gpios;
+}
+
+void gpio_toggle(u32 gpioport, u32 gpios)
+{
+ GPIO_NOT(gpioport) = gpios;
+} \ No newline at end of file
diff --git a/lib/lpc43xx/i2c.c b/lib/lpc43xx/i2c.c
new file mode 100644
index 0000000..f006615
--- /dev/null
+++ b/lib/lpc43xx/i2c.c
@@ -0,0 +1,93 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2012 Michael Ossmann <mike@ossmann.com>
+ *
+ * This library is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public License
+ * along with this library. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+/*
+ * This is a very minimal I2C driver just to make sure we can get the
+ * peripheral working.
+ */
+
+#include <libopencm3/lpc43xx/i2c.h>
+#include <libopencm3/lpc43xx/scu.h>
+#include <libopencm3/lpc43xx/cgu.h>
+
+void i2c0_init(void)
+{
+ /* enable input on SCL and SDA pins */
+ SCU_SFSI2C0 = SCU_I2C0_NOMINAL;
+
+ /* use IRC as clock source for APB1 (including I2C0) */
+ CGU_BASE_APB1_CLK = (CGU_SRC_IRC << CGU_BASE_CLK_SEL_SHIFT);
+
+ /* FIXME assuming we're on IRC at 12 MHz */
+
+ /* 400 kHz I2C */
+ I2C0_SCLH = 15;
+ I2C0_SCLL = 15;
+
+ /* 100 kHz I2C */
+ /*
+ I2C0_SCLH = 60;
+ I2C0_SCLL = 60;
+ */
+
+ /* clear the control bits */
+ I2C0_CONCLR = (I2C_CONCLR_AAC | I2C_CONCLR_SIC
+ | I2C_CONCLR_STAC | I2C_CONCLR_I2ENC);
+
+ /* enable I2C0 */
+ I2C0_CONSET = I2C_CONSET_I2EN;
+}
+
+/* transmit start bit */
+void i2c0_tx_start(void)
+{
+ I2C0_CONCLR = I2C_CONCLR_SIC;
+ I2C0_CONSET = I2C_CONSET_STA;
+ while (!(I2C0_CONSET & I2C_CONSET_SI));
+ I2C0_CONCLR = I2C_CONCLR_STAC;
+}
+
+/* transmit data byte */
+void i2c0_tx_byte(u8 byte)
+{
+ if (I2C0_CONSET & I2C_CONSET_STA)
+ I2C0_CONCLR = I2C_CONCLR_STAC;
+ I2C0_DAT = byte;
+ I2C0_CONCLR = I2C_CONCLR_SIC;
+ while (!(I2C0_CONSET & I2C_CONSET_SI));
+}
+
+/* receive data byte */
+u8 i2c0_rx_byte(void)
+{
+ if (I2C0_CONSET & I2C_CONSET_STA)
+ I2C0_CONCLR = I2C_CONCLR_STAC;
+ I2C0_CONCLR = I2C_CONCLR_SIC;
+ while (!(I2C0_CONSET & I2C_CONSET_SI));
+ return I2C0_DAT;
+}
+
+/* transmit stop bit */
+void i2c0_stop(void)
+{
+ if (I2C0_CONSET & I2C_CONSET_STA)
+ I2C0_CONCLR = I2C_CONCLR_STAC;
+ I2C0_CONSET = I2C_CONSET_STO;
+ I2C0_CONCLR = I2C_CONCLR_SIC;
+}
diff --git a/lib/lpc43xx/libopencm3_lpc43xx.ld b/lib/lpc43xx/libopencm3_lpc43xx.ld
new file mode 100644
index 0000000..47b403b
--- /dev/null
+++ b/lib/lpc43xx/libopencm3_lpc43xx.ld
@@ -0,0 +1,96 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+ * Copyright (C) 2012 Michael Ossmann <mike@ossmann.com>
+ * Copyright (C) 2012 Benjamin Vernoux <titanmkd@gmail.com>
+ *
+ * This library is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public License
+ * along with this library. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+/* Generic linker script for LPC43XX targets using libopencm3. */
+
+/* Memory regions must be defined in the ld script which includes this one. */
+
+/* Enforce emmition of the vector table. */
+EXTERN (vector_table)
+
+/* Define the entry point of the output file. */
+ENTRY(reset_handler)
+
+/* Define sections. */
+SECTIONS
+{
+ . = ORIGIN(rom);
+
+ .text : {
+ . = ALIGN(0x400);
+ _text_ram = 0; /* Start of Code in RAM NULL because Copy of Code from ROM to RAM disabled */
+ *(.vectors) /* Vector table */
+ *(.text*) /* Program code */
+ . = ALIGN(4);
+ *(.rodata*) /* Read-only data */
+ . = ALIGN(4);
+ } >rom
+
+ /* exception index - required due to libgcc.a issuing /0 exceptions */
+ __exidx_start = .;
+ .ARM.exidx : {
+ *(.ARM.exidx*)
+ } > rom
+ __exidx_end = .;
+
+ _etext = .;
+ _etext_ram = 0; /* Start of Code in RAM NULL because Copy of Code from ROM to RAM disabled */
+ _etext_rom = 0; /* Start of Code in RAM NULL because Copy of Code from ROM to RAM disabled */
+
+ . = ORIGIN(ram);
+
+ .data : {
+ _data = .;
+ *(.data*) /* Read-write initialized data */
+ . = ALIGN(4);
+ _edata = .;
+ } >ram AT >rom
+
+ .bss : {
+ *(.bss*) /* Read-write zero initialized data */
+ *(COMMON)
+ . = ALIGN(4);
+ _ebss = .;
+ } >ram
+
+ /* exception unwind data - required due to libgcc.a issuing /0 exceptions */
+ .ARM.extab : {
+ *(.ARM.extab*)
+ } >ram
+
+ /*
+ * The .eh_frame section appears to be used for C++ exception handling.
+ * You may need to fix this if you're using C++.
+ */
+ /DISCARD/ : { *(.eh_frame) }
+
+ /*
+ * Another section used by C++ stuff, appears when using newlib with
+ * 64bit (long long) printf support - discard it for now.
+ */
+ /DISCARD/ : { *(.ARM.exidx) }
+
+ end = .;
+
+ /* Leave room above stack for IAP to run. */
+ __StackTop = ORIGIN(ram) + LENGTH(ram) - 32;
+ PROVIDE(_stack = __StackTop);
+}
diff --git a/lib/lpc43xx/libopencm3_lpc43xx_rom_to_ram.ld b/lib/lpc43xx/libopencm3_lpc43xx_rom_to_ram.ld
new file mode 100644
index 0000000..0270ea8
--- /dev/null
+++ b/lib/lpc43xx/libopencm3_lpc43xx_rom_to_ram.ld
@@ -0,0 +1,97 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+ * Copyright (C) 2012 Michael Ossmann <mike@ossmann.com>
+ * Copyright (C) 2012 Benjamin Vernoux <titanmkd@gmail.com>
+ *
+ * This library is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public License
+ * along with this library. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+/* Generic linker script for LPC43XX targets using libopencm3. */
+
+/* Memory regions must be defined in the ld script which includes this one. */
+
+/* Enforce emmition of the vector table. */
+EXTERN (vector_table)
+
+/* Define the entry point of the output file. */
+ENTRY(reset_handler)
+
+/* Define sections. */
+SECTIONS
+{
+ . = ORIGIN(rom);
+
+ .text : {
+ . = ALIGN(0x400);
+ _text_ram = (. - ORIGIN(rom)) + ORIGIN(ram); /* Start of Code in RAM */
+
+ *(.vectors) /* Vector table */
+ *(.text*) /* Program code */
+ . = ALIGN(4);
+ *(.rodata*) /* Read-only data */
+ . = ALIGN(4);
+ } >rom
+
+ /* exception index - required due to libgcc.a issuing /0 exceptions */
+ __exidx_start = .;
+ .ARM.exidx : {
+ *(.ARM.exidx*)
+ } > rom
+ __exidx_end = .;
+
+ _etext = .;
+ _etext_ram = (. - ORIGIN(rom)) + ORIGIN(ram);
+ _etext_rom = (. - ORIGIN(rom)) + ORIGIN(rom_flash);
+
+ .data : {
+ _data = .;
+ *(.data*) /* Read-write initialized data */
+ . = ALIGN(4);
+ _edata = .;
+ } >ram_data AT >rom
+
+ .bss : {
+ . = _edata;
+ *(.bss*) /* Read-write zero initialized data */
+ *(COMMON)
+ . = ALIGN(4);
+ _ebss = .;
+ } >ram_data
+
+ /* exception unwind data - required due to libgcc.a issuing /0 exceptions */
+ .ARM.extab : {
+ . = _ebss;
+ *(.ARM.extab*)
+ } >ram_data
+
+ /*
+ * The .eh_frame section appears to be used for C++ exception handling.
+ * You may need to fix this if you're using C++.
+ */
+ /DISCARD/ : { *(.eh_frame) }
+
+ /*
+ * Another section used by C++ stuff, appears when using newlib with
+ * 64bit (long long) printf support - discard it for now.
+ */
+ /DISCARD/ : { *(.ARM.exidx) }
+
+ end = .;
+
+ /* Leave room above stack for IAP to run. */
+ __StackTop = ORIGIN(ram) + LENGTH(ram) - 32;
+ PROVIDE(_stack = __StackTop);
+}
diff --git a/lib/lpc43xx/nvic.c b/lib/lpc43xx/nvic.c
new file mode 100644
index 0000000..4793312
--- /dev/null
+++ b/lib/lpc43xx/nvic.c
@@ -0,0 +1,76 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
+ * Copyright (C) 2012 Fergus Noble <fergusnoble@gmail.com>
+ * Copyright (C) 2012 Benjamin Vernoux <titanmkd@gmail.com>
+ *
+ * This library is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public License
+ * along with this library. If not, see <http://www.gnu.org/licenses/>.
+ */
+#include <libopencm3/cm3/scs.h>
+#include <libopencm3/lpc43xx/nvic.h>
+
+void nvic_enable_irq(u8 irqn)
+{
+ NVIC_ISER(irqn / 32) = (1 << (irqn % 32));
+}
+
+void nvic_disable_irq(u8 irqn)
+{
+ NVIC_ICER(irqn / 32) = (1 << (irqn % 32));
+}
+
+u8 nvic_get_pending_irq(u8 irqn)
+{
+ return NVIC_ISPR(irqn / 32) & (1 << (irqn % 32)) ? 1 : 0;
+}
+
+void nvic_set_pending_irq(u8 irqn)
+{
+ NVIC_ISPR(irqn / 32) = (1 << (irqn % 32));
+}
+
+void nvic_clear_pending_irq(u8 irqn)
+{
+ NVIC_ICPR(irqn / 32) = (1 << (irqn % 32));
+}
+
+u8 nvic_get_active_irq(u8 irqn)
+{
+ return NVIC_IABR(irqn / 32) & (1 << (irqn % 32)) ? 1 : 0;
+}
+
+u8 nvic_get_irq_enabled(u8 irqn)
+{
+ return NVIC_ISER(irqn / 32) & (1 << (irqn % 32)) ? 1 : 0;
+}
+
+void nvic_set_priority(u8 irqn, u8 priority)
+{
+ if(irqn>NVIC_M4_QEI_IRQ)
+ {
+ /* Cortex-M system interrupts */
+ SCS_SHPR( (irqn&0xF)-4 ) = priority;
+ }else
+ {
+ /* Device specific interrupts */
+ NVIC_IPR(irqn) = priority;
+ }
+}
+
+void nvic_generate_software_interrupt(u8 irqn)
+{
+ if (irqn <= 239)
+ NVIC_STIR |= irqn;
+}
diff --git a/lib/lpc43xx/scu.c b/lib/lpc43xx/scu.c
new file mode 100644
index 0000000..addf5e2
--- /dev/null
+++ b/lib/lpc43xx/scu.c
@@ -0,0 +1,30 @@
+/*
+* This file is part of the libopencm3 project.
+*
+* Copyright (C) 2012 Benjamin Vernoux <titanmkd@gmail.com>
+*
+* This library is free software: you can redistribute it and/or modify
+* it under the terms of the GNU Lesser General Public License as published by
+* the Free Software Foundation, either version 3 of the License, or
+* (at your option) any later version.
+*
+* This library is distributed in the hope that it will be useful,
+* but WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+* GNU Lesser General Public License for more details.
+*
+* You should have received a copy of the GNU Lesser General Public License
+* along with this library. If not, see <http://www.gnu.org/licenses/>.
+*/
+
+#include <libopencm3/lpc43xx/scu.h>
+
+/* For pin_conf_normal value see scu.h define SCU_CONF_XXX or Configuration for different I/O pins types */
+void scu_pinmux(scu_grp_pin_t group_pin, u32 scu_conf)
+{
+ MMIO32(group_pin) = scu_conf;
+}
+
+/* For other special SCU register USB1, I2C0, ADC0/1, DAC, EMC clock delay See scu.h */
+
+/* For Pin interrupt select register see scu.h SCU_PINTSEL0 & SCU_PINTSEL1 */
diff --git a/lib/lpc43xx/ssp.c b/lib/lpc43xx/ssp.c
new file mode 100644
index 0000000..e9cf5b0
--- /dev/null
+++ b/lib/lpc43xx/ssp.c
@@ -0,0 +1,160 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2012 Benjamin Vernoux <titanmkd@gmail.com>
+ *
+ * This library is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public License
+ * along with this library. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+#include <libopencm3/lpc43xx/ssp.h>
+#include <libopencm3/lpc43xx/cgu.h>
+
+#define CGU_SRC_32K 0x00
+#define CGU_SRC_IRC 0x01
+#define CGU_SRC_ENET_RX 0x02
+#define CGU_SRC_ENET_TX 0x03
+#define CGU_SRC_GP_CLKIN 0x04
+#define CGU_SRC_XTAL 0x06
+#define CGU_SRC_PLL0USB 0x07
+#define CGU_SRC_PLL0AUDIO 0x08
+#define CGU_SRC_PLL1 0x09
+#define CGU_SRC_IDIVA 0x0C
+#define CGU_SRC_IDIVB 0x0D
+#define CGU_SRC_IDIVC 0x0E
+#define CGU_SRC_IDIVD 0x0F
+#define CGU_SRC_IDIVE 0x10
+
+#define CGU_AUTOBLOCK_CLOCK_BIT 11
+#define CGU_BASE_CLK_SEL_SHIFT 24 /* clock source selection (5 bits) */
+
+/* Disable SSP */
+void ssp_disable(ssp_num_t ssp_num)
+{
+ u32 ssp_port;
+
+ if(ssp_num == SSP0_NUM)
+ {
+ ssp_port = SSP0;
+ }else
+ {
+ ssp_port = SSP1;
+ }
+ /* Disable SSP */
+ SSP_CR1(ssp_port) = 0x0;
+}
+
+/*
+* SSP Init function
+*/
+void ssp_init(ssp_num_t ssp_num,
+ ssp_datasize_t data_size,
+ ssp_frame_format_t frame_format,
+ ssp_cpol_cpha_t cpol_cpha_format,
+ u8 serial_clock_rate,
+ u8 clk_prescale,
+ ssp_mode_t mode,
+ ssp_master_slave_t master_slave,
+ ssp_slave_option_t slave_option)
+{
+ u32 ssp_port;
+ u32 clock;
+
+ if(ssp_num == SSP0_NUM)
+ {
+ ssp_port = SSP0;
+ }else
+ {
+ ssp_port = SSP1;
+ }
+
+ /* use PLL1 as clock source for SSP1 */
+ CGU_BASE_SSP1_CLK = (CGU_SRC_PLL1<<CGU_BASE_CLK_SEL_SHIFT) | (1<<CGU_AUTOBLOCK_CLOCK_BIT);
+
+ /* Disable SSP before to configure it */
+ SSP_CR1(ssp_port) = 0x0;
+
+ /* Configure SSP */
+ clock = serial_clock_rate;
+ SSP_CPSR(ssp_port) = clk_prescale;
+ SSP_CR0(ssp_port) = (data_size | frame_format | cpol_cpha_format | (clock<<8) );
+
+ /* Enable SSP */
+ SSP_CR1(ssp_port) = (SSP_ENABLE | mode | master_slave | slave_option);
+}
+
+/*
+* This Function Wait until Data RX Ready, and return Data Read from SSP.
+*/
+u16 ssp_read(ssp_num_t ssp_num)
+{
+ u32 ssp_port;
+
+ if(ssp_num == SSP0_NUM)
+ {
+ ssp_port = SSP0;
+ }else
+ {
+ ssp_port = SSP1;
+ }
+ /* Wait Until Data Received (Rx FIFO not Empty) */
+ while( (SSP_SR(ssp_port) & SSP_SR_RNE) == 0);
+
+ return SSP_DR(ssp_port);
+}
+
+void ssp_wait_until_not_busy(ssp_num_t ssp_num)
+{
+ u32 ssp_port;
+
+ if(ssp_num == SSP0_NUM)
+ {
+ ssp_port = SSP0;
+ }else
+ {
+ ssp_port = SSP1;
+ }
+
+ while( (SSP_SR(ssp_port) & SSP_SR_BSY) );
+}
+
+/* This Function Wait Data TX Ready, and Write Data to SSP */
+void ssp_write(ssp_num_t ssp_num, u16 data)
+{
+ u32 ssp_port;
+
+ if(ssp_num == SSP0_NUM)
+ {
+ ssp_port = SSP0;
+ }else
+ {
+ ssp_port = SSP1;
+ }
+
+ /* Wait Until FIFO not full */
+ while( (SSP_SR(ssp_port) & SSP_SR_TNF) == 0);
+
+ SSP_DR(ssp_port) = data;
+
+ /* Wait for not busy, since we're controlling CS# of
+ * devices manually and need to wait for the data to
+ * be sent. It may also be important to wait here
+ * in case we're configuring devices via SPI and also
+ * with GPIO control -- we need to know when SPI
+ * commands are effective before altering a device's
+ * state with GPIO. I'm thinking the MAX2837, for
+ * example...
+ */
+ ssp_wait_until_not_busy(ssp_num);
+}
+
diff --git a/lib/lpc43xx/systick.c b/lib/lpc43xx/systick.c
new file mode 100644
index 0000000..82345a9
--- /dev/null
+++ b/lib/lpc43xx/systick.c
@@ -0,0 +1,69 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
+ * Copyright (C) 2012 Benjamin Vernoux <titanmkd@gmail.com>
+ *
+ * This library is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public License
+ * along with this library. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+#include <libopencm3/lpc43xx/systick.h>
+
+void systick_set_reload(u32 value)
+{
+ STK_LOAD = (value & 0x00FFFFFF);
+}
+
+u32 systick_get_value(void)
+{
+ return STK_VAL;
+}
+
+void systick_set_clocksource(u8 clocksource)
+{
+ STK_CTRL |= clocksource;
+}
+
+void systick_interrupt_enable(void)
+{
+ STK_CTRL |= STK_CTRL_TICKINT;
+}
+
+void systick_interrupt_disable(void)
+{
+ STK_CTRL &= ~STK_CTRL_TICKINT;
+}
+
+void systick_counter_enable(void)
+{
+ STK_CTRL |= STK_CTRL_ENABLE;
+}
+
+void systick_counter_disable(void)
+{
+ STK_CTRL &= ~STK_CTRL_ENABLE;
+}
+
+u8 systick_get_countflag(void)
+{
+ if (STK_CTRL & STK_CTRL_COUNTFLAG)
+ return 1;
+ else
+ return 0;
+}
+
+u32 systick_get_calib(void)
+{
+ return (STK_CALIB&0x00FFFFFF);
+}
diff --git a/lib/lpc43xx/vector.c b/lib/lpc43xx/vector.c
new file mode 100644
index 0000000..daef5a9
--- /dev/null
+++ b/lib/lpc43xx/vector.c
@@ -0,0 +1,263 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
+ * Copyright (C) 2012 Michael Ossmann <mike@ossmann.com>
+ *
+ * This library is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public License
+ * along with this library. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+#define WEAK __attribute__ ((weak))
+
+/* Symbols exported by the linker script(s). */
+extern unsigned _etext, _data, _edata, _ebss, _stack;
+extern unsigned _etext_ram, _text_ram, _etext_rom;
+
+void main(void);
+void reset_handler(void);
+void blocking_handler(void);
+void null_handler(void);
+
+void WEAK nmi_handler(void);
+void WEAK hard_fault_handler(void);
+void WEAK mem_manage_handler(void);
+void WEAK bus_fault_handler(void);
+void WEAK usage_fault_handler(void);
+void WEAK sv_call_handler(void);
+void WEAK debug_monitor_handler(void);
+void WEAK pend_sv_handler(void);
+void WEAK sys_tick_handler(void);
+void WEAK dac_irqhandler(void);
+void WEAK m0core_irqhandler(void);
+void WEAK dma_irqhandler(void);
+void WEAK ethernet_irqhandler(void);
+void WEAK sdio_irqhandler(void);
+void WEAK lcd_irqhandler(void);
+void WEAK usb0_irqhandler(void);
+void WEAK usb1_irqhandler(void);
+void WEAK sct_irqhandler(void);
+void WEAK ritimer_irqhandler(void);
+void WEAK timer0_irqhandler(void);
+void WEAK timer1_irqhandler(void);
+void WEAK timer2_irqhandler(void);
+void WEAK timer3_irqhandler(void);
+void WEAK mcpwm_irqhandler(void);
+void WEAK adc0_irqhandler(void);
+void WEAK i2c0_irqhandler(void);
+void WEAK i2c1_irqhandler(void);
+void WEAK spi_irqhandler(void);
+void WEAK adc1_irqhandler(void);
+void WEAK ssp0_irqhandler(void);
+void WEAK ssp1_irqhandler(void);
+void WEAK usart0_irqhandler(void);
+void WEAK uart1_irqhandler(void);
+void WEAK usart2_irqhandler(void);
+void WEAK usart3_irqhandler(void);
+void WEAK i2s0_irqhandler(void);
+void WEAK i2s1_irqhandler(void);
+void WEAK spifi_irqhandler(void);
+void WEAK sgpio_irqhandler(void);
+void WEAK pin_int0_irqhandler(void);
+void WEAK pin_int1_irqhandler(void);
+void WEAK pin_int2_irqhandler(void);
+void WEAK pin_int3_irqhandler(void);
+void WEAK pin_int4_irqhandler(void);
+void WEAK pin_int5_irqhandler(void);
+void WEAK pin_int6_irqhandler(void);
+void WEAK pin_int7_irqhandler(void);
+void WEAK gint0_irqhandler(void);
+void WEAK gint1_irqhandler(void);
+void WEAK eventrouter_irqhandler(void);
+void WEAK c_can1_irqhandler(void);
+void WEAK atimer_irqhandler(void);
+void WEAK rtc_irqhandler(void);
+void WEAK wwdt_irqhandler(void);
+void WEAK c_can0_irqhandler(void);
+void WEAK qei_irqhandler(void);
+
+__attribute__ ((section(".vectors")))
+void (*const vector_table[]) (void) = {
+ /* Cortex-M4 interrupts */
+ (void*)&_stack,
+ reset_handler,
+ nmi_handler,
+ hard_fault_handler,
+ mem_manage_handler,
+ bus_fault_handler,
+ usage_fault_handler,
+ 0, 0, 0, 0, /* reserved */
+ sv_call_handler,
+ debug_monitor_handler,
+ 0, /* reserved */
+ pend_sv_handler,
+ sys_tick_handler,
+
+ /* LPC43xx interrupts */
+ dac_irqhandler,
+ m0core_irqhandler,
+ dma_irqhandler,
+ 0, /* reserved */
+ 0, /* reserved */
+ ethernet_irqhandler,
+ sdio_irqhandler,
+ lcd_irqhandler,
+ usb0_irqhandler,
+ usb1_irqhandler,
+ sct_irqhandler,
+ ritimer_irqhandler,
+ timer0_irqhandler,
+ timer1_irqhandler,
+ timer2_irqhandler,
+ timer3_irqhandler,
+ mcpwm_irqhandler,
+ adc0_irqhandler,
+ i2c0_irqhandler,
+ i2c1_irqhandler,
+ spi_irqhandler,
+ adc1_irqhandler,
+ ssp0_irqhandler,
+ ssp1_irqhandler,
+ usart0_irqhandler,
+ uart1_irqhandler,
+ usart2_irqhandler,
+ usart3_irqhandler,
+ i2s0_irqhandler,
+ i2s1_irqhandler,
+ spifi_irqhandler,
+ sgpio_irqhandler,
+ pin_int0_irqhandler,
+ pin_int1_irqhandler,
+ pin_int2_irqhandler,
+ pin_int3_irqhandler,
+ pin_int4_irqhandler,
+ pin_int5_irqhandler,
+ pin_int6_irqhandler,
+ pin_int7_irqhandler,
+ gint0_irqhandler,
+ gint1_irqhandler,
+ eventrouter_irqhandler,
+ c_can1_irqhandler,
+ 0, /* reserved */
+ 0, /* reserved */
+ atimer_irqhandler,
+ rtc_irqhandler,
+ 0, /* reserved */
+ wwdt_irqhandler,
+ 0, /* reserved */
+ c_can0_irqhandler,
+ qei_irqhandler,
+};
+
+#define MMIO32(addr) (*(volatile unsigned long*)(addr))
+#define CREG_M4MEMMAP MMIO32( (0x40043000 + 0x100) )
+
+void reset_handler(void)
+{
+ volatile unsigned *src, *dest;
+ __asm__("MSR msp, %0" : : "r"(&_stack));
+
+ /* Copy the code from ROM to Real RAM (if enabled) */
+ if( (&_etext_ram-&_text_ram) > 0 )
+ {
+ src = &_etext_rom-(&_etext_ram-&_text_ram);
+ /* Change Shadow memory to ROM (for Debug Purpose in case Boot has not set correctly the M4MEMMAP because of debug) */
+ CREG_M4MEMMAP = (unsigned long)src;
+
+ for(dest = &_text_ram; dest < &_etext_ram; )
+ {
+ *dest++ = *src++;
+ }
+
+ /* Change Shadow memory to Real RAM */
+ CREG_M4MEMMAP = (unsigned long)&_text_ram;
+
+ /* Continue Execution in RAM */
+ }
+
+ for (src = &_etext, dest = &_data; dest < &_edata; src++, dest++)
+ *dest = *src;
+
+ while (dest < &_ebss)
+ *dest++ = 0;
+
+ /* Call the application's entry point. */
+ main();
+}
+
+void blocking_handler(void)
+{
+ while (1) ;
+}
+
+void null_handler(void)
+{
+ /* Do nothing. */
+}
+
+#pragma weak nmi_handler = null_handler
+#pragma weak hard_fault_handler = blocking_handler
+#pragma weak mem_manage_handler = blocking_handler
+#pragma weak bus_fault_handler = blocking_handler
+#pragma weak usage_fault_handler = blocking_handler
+#pragma weak sv_call_handler = null_handler
+#pragma weak debug_monitor_handler = null_handler
+#pragma weak pend_sv_handler = null_handler
+#pragma weak sys_tick_handler = null_handler
+#pragma weak dac_irqhandler = null_handler
+#pragma weak m0core_irqhandler = null_handler
+#pragma weak dma_irqhandler = null_handler
+#pragma weak ethernet_irqhandler = null_handler
+#pragma weak sdio_irqhandler = null_handler
+#pragma weak lcd_irqhandler = null_handler
+#pragma weak usb0_irqhandler = null_handler
+#pragma weak usb1_irqhandler = null_handler
+#pragma weak sct_irqhandler = null_handler
+#pragma weak ritimer_irqhandler = null_handler
+#pragma weak timer0_irqhandler = null_handler
+#pragma weak timer1_irqhandler = null_handler
+#pragma weak timer2_irqhandler = null_handler
+#pragma weak timer3_irqhandler = null_handler
+#pragma weak mcpwm_irqhandler = null_handler
+#pragma weak adc0_irqhandler = null_handler
+#pragma weak i2c0_irqhandler = null_handler
+#pragma weak i2c1_irqhandler = null_handler
+#pragma weak spi_irqhandler = null_handler
+#pragma weak adc1_irqhandler = null_handler
+#pragma weak ssp0_irqhandler = null_handler
+#pragma weak ssp1_irqhandler = null_handler
+#pragma weak usart0_irqhandler = null_handler
+#pragma weak uart1_irqhandler = null_handler
+#pragma weak usart2_irqhandler = null_handler
+#pragma weak usart3_irqhandler = null_handler
+#pragma weak i2s0_irqhandler = null_handler
+#pragma weak i2s1_irqhandler = null_handler
+#pragma weak spifi_irqhandler = null_handler
+#pragma weak sgpio_irqhandler = null_handler
+#pragma weak pin_int0_irqhandler = null_handler
+#pragma weak pin_int1_irqhandler = null_handler
+#pragma weak pin_int2_irqhandler = null_handler
+#pragma weak pin_int3_irqhandler = null_handler
+#pragma weak pin_int4_irqhandler = null_handler
+#pragma weak pin_int5_irqhandler = null_handler
+#pragma weak pin_int6_irqhandler = null_handler
+#pragma weak pin_int7_irqhandler = null_handler
+#pragma weak gint0_irqhandler = null_handler
+#pragma weak gint1_irqhandler = null_handler
+#pragma weak eventrouter_irqhandler = null_handler
+#pragma weak c_can1_irqhandler = null_handler
+#pragma weak atimer_irqhandler = null_handler
+#pragma weak rtc_irqhandler = null_handler
+#pragma weak wwdt_irqhandler = null_handler
+#pragma weak c_can0_irqhandler = null_handler
+#pragma weak qei_irqhandler = null_handler
diff --git a/lib/stm32/f1/rcc.c b/lib/stm32/f1/rcc.c
index 8945e80..e700074 100644
--- a/lib/stm32/f1/rcc.c
+++ b/lib/stm32/f1/rcc.c
@@ -1,8 +1,34 @@
+/** @file
+
+@ingroup STM32F1xx
+
+@brief <b>libopencm3 STM32F1xx Reset and Clock Control</b>
+
+@version 1.0.0
+
+@author @htmlonly &copy; @endhtmlonly 2009 Federico Ruiz-Ugalde \<memeruiz at gmail dot com\>
+@author @htmlonly &copy; @endhtmlonly 2009 Uwe Hermann <uwe@hermann-uwe.de>
+@author @htmlonly &copy; @endhtmlonly 2010 Thomas Otto <tommi@viadmin.org>
+
+@date 18 May 2012
+
+This library supports the Reset and Clock
+Control System in the STM32F1xx series of ARM Cortex Microcontrollers
+by ST Microelectronics.
+
+Clock settings and resets for many peripherals are given here rather than in the
+peripheral library.
+
+The library also provides a number of common configurations for the processor
+system clock. Not all possible configurations are given here.
+
+@bugs None known
+
+LGPL License Terms @ref lgpl_license
+ */
/*
* This file is part of the libopencm3 project.
*
- * Copyright (C) 2009 Federico Ruiz-Ugalde <memeruiz at gmail dot com>
- * Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
* Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
*
* This library is free software: you can redistribute it and/or modify
@@ -19,13 +45,23 @@
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
+
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/flash.h>
-/* Set the default ppre1 and ppre2 peripheral clock frequencies after reset. */
+/** Default ppre1 peripheral clock frequency after reset. */
u32 rcc_ppre1_frequency = 8000000;
+/** Default ppre2 peripheral clock frequency after reset. */
u32 rcc_ppre2_frequency = 8000000;
+//-----------------------------------------------------------------------------
+/** @brief RCC Clear the Oscillator Ready Interrupt
+
+Clear the interrupt flag that was set when a clock oscillator became ready to use.
+
+@param[in] enum ::osc_t. Oscillator ID
+*/
+
void rcc_osc_ready_int_clear(osc_t osc)
{
switch (osc) {
@@ -230,6 +266,20 @@ void rcc_osc_bypass_disable(osc_t osc)
}
}
+//-----------------------------------------------------------------------------
+/** @brief RCC Enable a peripheral clock.
+
+Enable the clock on a particular peripheral. Several peripherals could be
+enabled simultaneously if they are controlled by the same register.
+
+@param[in] Unsigned int32 *reg. Pointer to a Clock Enable Register
+ (either RCC_AHBENR, RCC_APB1RENR or RCC_APB2RENR)
+@param[in] Unsigned int32 en. OR of all enables to be set
+@li If register is RCC_AHBER, from @ref rcc_ahbenr_en
+@li If register is RCC_APB1RENR, from @ref rcc_apb1enr_en
+@li If register is RCC_APB2RENR, from @ref rcc_apb2enr_en
+*/
+
void rcc_peripheral_enable_clock(volatile u32 *reg, u32 en)
{
*reg |= en;
diff --git a/lib/stm32/f2/gpio.c b/lib/stm32/f2/gpio.c
index fc7a5b6..984cddb 100644
--- a/lib/stm32/f2/gpio.c
+++ b/lib/stm32/f2/gpio.c
@@ -111,7 +111,7 @@ u16 gpio_get(u32 gpioport, u16 gpios)
void gpio_toggle(u32 gpioport, u16 gpios)
{
- GPIO_ODR(gpioport) = GPIO_IDR(gpioport) ^ gpios;
+ GPIO_ODR(gpioport) ^= gpios;
}
u16 gpio_port_read(u32 gpioport)
diff --git a/lib/stm32/f4/gpio.c b/lib/stm32/f4/gpio.c
index e721f3f..1d7739d 100644
--- a/lib/stm32/f4/gpio.c
+++ b/lib/stm32/f4/gpio.c
@@ -111,7 +111,7 @@ u16 gpio_get(u32 gpioport, u16 gpios)
void gpio_toggle(u32 gpioport, u16 gpios)
{
- GPIO_ODR(gpioport) = GPIO_IDR(gpioport) ^ gpios;
+ GPIO_ODR(gpioport) ^= gpios;
}
u16 gpio_port_read(u32 gpioport)