Initial commit.

This commit is contained in:
Piotr Esden-Tempski
2013-04-19 17:19:32 -07:00
commit 9d5526f773
324 changed files with 22845 additions and 0 deletions

View File

@@ -0,0 +1,172 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
## Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
PREFIX ?= arm-none-eabi
#PREFIX ?= arm-elf
CC = $(PREFIX)-gcc
LD = $(PREFIX)-gcc
OBJCOPY = $(PREFIX)-objcopy
OBJDUMP = $(PREFIX)-objdump
GDB = $(PREFIX)-gdb
TOOLCHAIN_DIR ?= ../../../../..
ifeq ($(wildcard ../../../../../lib/libopencm3_stm32f1.a),)
ifneq ($(strip $(shell which $(CC))),)
TOOLCHAIN_DIR := $(shell dirname `which $(CC)`)/../$(PREFIX)
endif
else
ifeq ($(V),1)
$(info We seem to be building the example in the source directory. Using local library!)
endif
endif
ARCH_FLAGS = -mthumb -mcpu=cortex-m3 -msoft-float
CFLAGS += -Os -g \
-Wall -Wextra -Wimplicit-function-declaration \
-Wredundant-decls -Wmissing-prototypes -Wstrict-prototypes \
-Wundef -Wshadow \
-I$(TOOLCHAIN_DIR)/include \
-fno-common $(ARCH_FLAGS) -MD -DSTM32F1
LDSCRIPT ?= $(BINARY).ld
LDFLAGS += --static -Wl,--start-group -lc -lgcc -lnosys -Wl,--end-group \
-L$(TOOLCHAIN_DIR)/lib \
-T$(LDSCRIPT) -nostartfiles -Wl,--gc-sections \
$(ARCH_FLAGS) -mfix-cortex-m3-ldrd
ifneq ($(OPENCM3_DIR),)
CFLAGS += -I$(OPENCM3_DIR)/include
LDFLAGS += -L$(OPENCM3_DIR)/lib -L$(OPENCM3_DIR)/lib/stm32/f1
SCRIPT_DIR = $(OPENCM3_DIR)/share
else
SCRIPT_DIR = $(shell dirname $(shell readlink -f $(shell which $(PREFIX)-gcc)))/../$(PREFIX)/share
endif
OBJS += $(BINARY).o
OOCD ?= openocd
OOCD_INTERFACE ?= flossjtag
OOCD_BOARD ?= olimex_stm32_h103
# Black magic probe specific variables
# Set the BMP_PORT to a serial port and then BMP is used for flashing
BMP_PORT ?=
# texane/stlink can be used by uncommenting this...
# or defining it in your own makefiles
#STLINK_PORT ?= :4242
# Be silent per default, but 'make V=1' will show all compiler calls.
ifneq ($(V),1)
Q := @
NULL := 2>/dev/null
else
LDFLAGS += -Wl,--print-gc-sections
endif
.SUFFIXES: .elf .bin .hex .srec .list .images
.SECONDEXPANSION:
.SECONDARY:
all: images
images: $(BINARY).images
flash: $(BINARY).flash
%.images: %.bin %.hex %.srec %.list
@#echo "*** $* images generated ***"
%.bin: %.elf
@#printf " OBJCOPY $(*).bin\n"
$(Q)$(OBJCOPY) -Obinary $(*).elf $(*).bin
%.hex: %.elf
@#printf " OBJCOPY $(*).hex\n"
$(Q)$(OBJCOPY) -Oihex $(*).elf $(*).hex
%.srec: %.elf
@#printf " OBJCOPY $(*).srec\n"
$(Q)$(OBJCOPY) -Osrec $(*).elf $(*).srec
%.list: %.elf
@#printf " OBJDUMP $(*).list\n"
$(Q)$(OBJDUMP) -S $(*).elf > $(*).list
%.elf: $(OBJS) $(LDSCRIPT) $(TOOLCHAIN_DIR)/lib/libopencm3_stm32f1.a
@#printf " LD $(subst $(shell pwd)/,,$(@))\n"
$(Q)$(LD) -o $(*).elf $(OBJS) -lopencm3_stm32f1 $(LDFLAGS)
%.o: %.c Makefile
@#printf " CC $(subst $(shell pwd)/,,$(@))\n"
$(Q)$(CC) $(CFLAGS) -o $@ -c $<
clean:
$(Q)rm -f *.o
$(Q)rm -f *.d
$(Q)rm -f *.elf
$(Q)rm -f *.bin
$(Q)rm -f *.hex
$(Q)rm -f *.srec
$(Q)rm -f *.list
ifeq ($(STLINK_PORT),)
ifeq ($(BMP_PORT),)
ifeq ($(OOCD_SERIAL),)
%.flash: %.hex
@printf " FLASH $<\n"
@# IMPORTANT: Don't use "resume", only "reset" will work correctly!
$(Q)$(OOCD) -f interface/$(OOCD_INTERFACE).cfg \
-f board/$(OOCD_BOARD).cfg \
-c "init" -c "reset init" \
-c "stm32f1x mass_erase 0" \
-c "flash write_image $(*).hex" \
-c "reset" \
-c "shutdown" $(NULL)
else
%.flash: %.hex
@printf " FLASH $<\n"
@# IMPORTANT: Don't use "resume", only "reset" will work correctly!
$(Q)$(OOCD) -f interface/$(OOCD_INTERFACE).cfg \
-f board/$(OOCD_BOARD).cfg \
-c "ft2232_serial $(OOCD_SERIAL)" \
-c "init" -c "reset init" \
-c "stm32f1x mass_erase 0" \
-c "flash write_image $(*).hex" \
-c "reset" \
-c "shutdown" $(NULL)
endif
else
%.flash: %.elf
@echo " GDB $(*).elf (flash)"
$(Q)$(GDB) --batch \
-ex 'target extended-remote $(BMP_PORT)' \
-x $(TOOLCHAIN_DIR)/scripts/black_magic_probe_flash.scr \
$(*).elf
endif
else
%.flash: %.elf
@echo " GDB $(*).elf (flash)"
$(Q)$(GDB) --batch \
-ex 'target extended-remote $(STLINK_PORT)' \
-x $(SCRIPT_DIR)/libopencm3/scripts/stlink_flash.scr \
$(*).elf
endif
.PHONY: images clean
-include $(OBJS:.o=.d)

View File

@@ -0,0 +1,25 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = can
LDSCRIPT = ../lisa-m.ld
include ../../Makefile.include

View File

@@ -0,0 +1,4 @@
This test sets up the CAN interface on Lisa/M and transmits 8 bites every
100ms. The first byte is being incremented in each cycle. The demo also
receives messages and is displaing the first 4 bits of the first byte on the
board LEDs.

View File

@@ -0,0 +1,237 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
* Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/flash.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/cm3/nvic.h>
#include <libopencm3/cm3/systick.h>
#include <libopencm3/stm32/can.h>
struct can_tx_msg {
u32 std_id;
u32 ext_id;
u8 ide;
u8 rtr;
u8 dlc;
u8 data[8];
};
struct can_rx_msg {
u32 std_id;
u32 ext_id;
u8 ide;
u8 rtr;
u8 dlc;
u8 data[8];
u8 fmi;
};
struct can_tx_msg can_tx_msg;
struct can_rx_msg can_rx_msg;
static void gpio_setup(void)
{
/* Enable Alternate Function clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
/* Enable GPIOA clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
/* Enable GPIOB clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
/* Enable GPIOC clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
/* Preconfigure LEDs. */
gpio_set(GPIOA, GPIO8); /* LED0 off */
gpio_set(GPIOB, GPIO4); /* LED1 off */
gpio_set(GPIOC, GPIO15); /* LED2 off */
gpio_set(GPIOC, GPIO2); /* LED3 off */
gpio_set(GPIOC, GPIO5); /* LED4 off */
/* Configure LED GPIOOs. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO8);
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO4);
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO15);
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO2);
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO5);
/* Configure PB4 as GPIO. */
AFIO_MAPR |= AFIO_MAPR_SWJ_CFG_FULL_SWJ_NO_JNTRST;
}
static void systick_setup(void)
{
/* 72MHz / 8 => 9000000 counts per second */
systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
/* 9000000/9000 = 1000 overflows per second - every 1ms one interrupt */
/* SysTick interrupt every N clock pulses: set reload to N-1 */
systick_set_reload(8999);
systick_interrupt_enable();
/* Start counting. */
systick_counter_enable();
}
static void can_setup(void)
{
/* Enable peripheral clocks. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_CANEN);
AFIO_MAPR |= AFIO_MAPR_CAN1_REMAP_PORTB;
/* Configure CAN pin: RX (input pull-up). */
gpio_set_mode(GPIO_BANK_CAN1_PB_RX, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_PULL_UPDOWN, GPIO_CAN1_PB_RX);
gpio_set(GPIOB, GPIO_CAN1_PB_RX);
/* Configure CAN pin: TX. */
gpio_set_mode(GPIO_BANK_CAN1_PB_TX, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_CAN1_PB_TX);
/* NVIC setup. */
nvic_enable_irq(NVIC_USB_LP_CAN_RX0_IRQ);
nvic_set_priority(NVIC_USB_LP_CAN_RX0_IRQ, 1);
/* Reset CAN. */
can_reset(CAN1);
/* CAN cell init. */
if (can_init(CAN1,
false, /* TTCM: Time triggered comm mode? */
true, /* ABOM: Automatic bus-off management? */
false, /* AWUM: Automatic wakeup mode? */
false, /* NART: No automatic retransmission? */
false, /* RFLM: Receive FIFO locked mode? */
false, /* TXFP: Transmit FIFO priority? */
CAN_BTR_SJW_1TQ,
CAN_BTR_TS1_3TQ,
CAN_BTR_TS2_4TQ,
12, /* BRP+1: Baud rate prescaler */
false, /* loopback mode */
false)) /* silent mode */
{
gpio_set(GPIOA, GPIO8); /* LED0 off */
gpio_set(GPIOB, GPIO4); /* LED1 off */
gpio_set(GPIOC, GPIO15); /* LED2 off */
gpio_clear(GPIOC, GPIO2); /* LED3 on */
gpio_set(GPIOC, GPIO5); /* LED4 off */
/* Die because we failed to initialize. */
while (1)
__asm__("nop");
}
/* CAN filter 0 init. */
can_filter_id_mask_32bit_init(CAN1,
0, /* Filter ID */
0, /* CAN ID */
0, /* CAN ID mask */
0, /* FIFO assignment (here: FIFO0) */
true); /* Enable the filter. */
/* Enable CAN RX interrupt. */
can_enable_irq(CAN1, CAN_IER_FMPIE0);
}
void sys_tick_handler(void)
{
static int temp32 = 0;
static u8 data[8] = {0, 1, 2, 0, 0, 0, 0, 0};
/* We call this handler every 1ms so 100ms = 1s
* Resulting in 100Hz message frequency.
*/
if (++temp32 != 100)
return;
temp32 = 0;
/* Transmit CAN frame. */
data[0]++;
if (can_transmit(CAN1,
0, /* (EX/ST)ID: CAN ID */
false, /* IDE: CAN ID extended? */
false, /* RTR: Request transmit? */
8, /* DLC: Data length */
data) == -1)
{
gpio_set(GPIOA, GPIO8); /* LED0 off */
gpio_set(GPIOB, GPIO4); /* LED1 off */
gpio_set(GPIOC, GPIO15); /* LED2 off */
gpio_set(GPIOC, GPIO2); /* LED3 off */
gpio_clear(GPIOC, GPIO5); /* LED4 on */
}
}
void usb_lp_can_rx0_isr(void)
{
u32 id, fmi;
bool ext, rtr;
u8 length, data[8];
can_receive(CAN1, 0, false, &id, &ext, &rtr, &fmi, &length, data);
if (data[0] & 1)
gpio_clear(GPIOA, GPIO8);
else
gpio_set(GPIOA, GPIO8);
if (data[0] & 2)
gpio_clear(GPIOB, GPIO4);
else
gpio_set(GPIOB, GPIO4);
if (data[0] & 4)
gpio_clear(GPIOC, GPIO15);
else
gpio_set(GPIOC, GPIO15);
if (data[0] & 8)
gpio_clear(GPIOC, GPIO2);
else
gpio_set(GPIOC, GPIO2);
can_fifo_release(CAN1, 0);
}
int main(void)
{
rcc_clock_setup_in_hse_12mhz_out_72mhz();
gpio_setup();
can_setup();
systick_setup();
while (1); /* Halt. */
return 0;
}

View File

@@ -0,0 +1,218 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
* Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
*
* 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 3 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 <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/flash.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/stm32/nvic.h>
#include <libopencm3/stm32/systick.h>
#include <libopencm3/stm32/can.h>
struct can_tx_msg {
u32 std_id;
u32 ext_id;
u8 ide;
u8 rtr;
u8 dlc;
u8 data[8];
};
struct can_rx_msg {
u32 std_id;
u32 ext_id;
u8 ide;
u8 rtr;
u8 dlc;
u8 data[8];
u8 fmi;
};
struct can_tx_msg can_tx_msg;
struct can_rx_msg can_rx_msg;
void gpio_setup(void)
{
/* Enable GPIOA clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
/* Enable GPIOB clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
gpio_set(GPIOA, GPIO6); /* LED0 off */
gpio_set(GPIOA, GPIO7); /* LED1 off */
gpio_set(GPIOB, GPIO0); /* LED2 off */
gpio_set(GPIOB, GPIO1); /* LED3 off */
/* Set GPIO6/7 (in GPIO port A) to 'output push-pull' for the LEDs. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO6);
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO7);
/* Set GPIO0/1 (in GPIO port B) to 'output push-pull' for the LEDs. */
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO0);
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO1);
}
void systick_setup(void)
{
/* 72MHz / 8 => 9000000 counts per second */
systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
/* 9000000/9000 = 1000 overflows per second - every 1ms one interrupt */
systick_set_reload(9000);
systick_interrupt_enable();
/* Start counting. */
systick_counter_enable();
}
void can_setup(void)
{
/* Enable peripheral clocks. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_CANEN);
AFIO_MAPR = AFIO_MAPR_CAN1_REMAP_PORTB;
/* Configure CAN pin: RX (input pull-up). */
gpio_set_mode(GPIOB, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_PULL_UPDOWN, GPIO_CAN1_PB_RX);
gpio_set(GPIOB, GPIO_CAN1_PB_RX);
/* Configure CAN pin: TX. */
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_CAN1_PB_TX);
/* NVIC setup. */
nvic_enable_irq(NVIC_USB_LP_CAN_RX0_IRQ);
nvic_set_priority(NVIC_USB_LP_CAN_RX0_IRQ, 1);
/* Reset CAN. */
can_reset(CAN1);
/* CAN cell init. */
if (can_init(CAN1,
false, /* TTCM: Time triggered comm mode? */
true, /* ABOM: Automatic bus-off management? */
false, /* AWUM: Automatic wakeup mode? */
false, /* NART: No automatic retransmission? */
false, /* RFLM: Receive FIFO locked mode? */
false, /* TXFP: Transmit FIFO priority? */
CAN_BTR_SJW_1TQ,
CAN_BTR_TS1_3TQ,
CAN_BTR_TS2_4TQ,
12)) /* BRP+1: Baud rate prescaler */
{
gpio_set(GPIOA, GPIO6); /* LED0 off */
gpio_set(GPIOA, GPIO7); /* LED1 off */
gpio_set(GPIOB, GPIO0); /* LED2 off */
gpio_clear(GPIOB, GPIO1); /* LED3 on */
/* Die because we failed to initialize. */
while (1)
__asm__("nop");
}
/* CAN filter 0 init. */
can_filter_id_mask_32bit_init(CAN1,
0, /* Filter ID */
0, /* CAN ID */
0, /* CAN ID mask */
0, /* FIFO assignment (here: FIFO0) */
true); /* Enable the filter. */
/* Enable CAN RX interrupt. */
can_enable_irq(CAN1, CAN_IER_FMPIE0);
}
void sys_tick_handler(void)
{
static int temp32 = 0;
static u8 data[8] = {0, 1, 2, 0, 0, 0, 0, 0};
/* We call this handler every 1ms so 1000ms = 1s on/off. */
if (++temp32 != 1000)
return;
temp32 = 0;
/* Transmit CAN frame. */
data[0]++;
if (can_transmit(CAN1,
0, /* (EX/ST)ID: CAN ID */
false, /* IDE: CAN ID extended? */
false, /* RTR: Request transmit? */
8, /* DLC: Data length */
data) == -1)
{
gpio_set(GPIOA, GPIO6); /* LED0 off */
gpio_set(GPIOA, GPIO7); /* LED1 off */
gpio_clear(GPIOB, GPIO0); /* LED2 on */
gpio_set(GPIOB, GPIO1); /* LED3 off */
}
}
void usb_lp_can_rx0_isr(void)
{
u32 id, fmi;
bool ext, rtr;
u8 length, data[8];
can_receive(CAN1, 0, false, &id, &ext, &rtr, &fmi, &length, data);
if (data[0] & 1)
gpio_clear(GPIOA, GPIO6);
else
gpio_set(GPIOA, GPIO6);
if (data[0] & 2)
gpio_clear(GPIOA, GPIO7);
else
gpio_set(GPIOA, GPIO7);
if (data[0] & 4)
gpio_clear(GPIOB, GPIO0);
else
gpio_set(GPIOB, GPIO0);
if (data[0] & 8)
gpio_clear(GPIOB, GPIO1);
else
gpio_set(GPIOB, GPIO1);
can_fifo_release(CAN1, 0);
}
int main(void)
{
rcc_clock_setup_in_hse_12mhz_out_72mhz();
gpio_setup();
can_setup();
systick_setup();
while (1); /* Halt. */
return 0;
}

View File

@@ -0,0 +1,25 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = fancyblink
LDSCRIPT = ../lisa-m.ld
include ../../Makefile.include

View File

@@ -0,0 +1,68 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
* Copyright (C) 2011 Piotr Esden-Tempski <piotr@esden.net>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/gpio.h>
/* Set STM32 to 72 MHz. */
static void clock_setup(void)
{
rcc_clock_setup_in_hse_12mhz_out_72mhz();
/* Enable GPIOB, GPIOC, and AFIO clocks. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
}
static void gpio_setup(void)
{
/* Set GPIO13 (in GPIO port C) to 'output push-pull'. */
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO13);
/* Set GPIO4 (in GPIO port B) to 'output push-pull'. */
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO4);
AFIO_MAPR |= AFIO_MAPR_SWJ_CFG_FULL_SWJ_NO_JNTRST;
/* Preconfigure the LEDs. */
gpio_set(GPIOB, GPIO4); /* Switch off LED. */
gpio_clear(GPIOC, GPIO13); /* Switch on LED. */
}
int main(void)
{
int i;
clock_setup();
gpio_setup();
/* Blink the LEDs (PC13 and PB4) on the board. */
while (1) {
gpio_toggle(GPIOC, GPIO13); /* LED on/off */
gpio_toggle(GPIOB, GPIO4); /* LED on/off */
for (i = 0; i < 800000; i++) /* Wait a bit. */
__asm__("nop");
}
return 0;
}

View File

@@ -0,0 +1,32 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
/* Linker script for Lisa-M (STM32F103RBT6, 128K flash, 20K RAM). */
/* TODO: Chip name and sizes correct? */
/* Define memory regions. */
MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
}
/* Include the common ld script. */
INCLUDE libopencm3_stm32f1.ld

View File

@@ -0,0 +1,25 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = cdcacm
LDSCRIPT = ../lisa-m.ld
include ../../Makefile.include

View File

@@ -0,0 +1,7 @@
------------------------------------------------------------------------------
README
------------------------------------------------------------------------------
This example implements a USB CDC-ACM device (aka Virtual Serial Port)
to demonstrate the use of the USB device stack.

View File

@@ -0,0 +1,261 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Gareth McMullin <gareth@blacksphere.co.nz>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdlib.h>
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/usb/usbd.h>
#include <libopencm3/usb/cdc.h>
static const struct usb_device_descriptor dev = {
.bLength = USB_DT_DEVICE_SIZE,
.bDescriptorType = USB_DT_DEVICE,
.bcdUSB = 0x0200,
.bDeviceClass = USB_CLASS_CDC,
.bDeviceSubClass = 0,
.bDeviceProtocol = 0,
.bMaxPacketSize0 = 64,
.idVendor = 0x0483,
.idProduct = 0x5740,
.bcdDevice = 0x0200,
.iManufacturer = 1,
.iProduct = 2,
.iSerialNumber = 3,
.bNumConfigurations = 1,
};
/*
* This notification endpoint isn't implemented. According to CDC spec it's
* optional, but its absence causes a NULL pointer dereference in the
* Linux cdc_acm driver.
*/
static const struct usb_endpoint_descriptor comm_endp[] = {{
.bLength = USB_DT_ENDPOINT_SIZE,
.bDescriptorType = USB_DT_ENDPOINT,
.bEndpointAddress = 0x83,
.bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT,
.wMaxPacketSize = 16,
.bInterval = 255,
}};
static const struct usb_endpoint_descriptor data_endp[] = {{
.bLength = USB_DT_ENDPOINT_SIZE,
.bDescriptorType = USB_DT_ENDPOINT,
.bEndpointAddress = 0x01,
.bmAttributes = USB_ENDPOINT_ATTR_BULK,
.wMaxPacketSize = 64,
.bInterval = 1,
}, {
.bLength = USB_DT_ENDPOINT_SIZE,
.bDescriptorType = USB_DT_ENDPOINT,
.bEndpointAddress = 0x82,
.bmAttributes = USB_ENDPOINT_ATTR_BULK,
.wMaxPacketSize = 64,
.bInterval = 1,
}};
static const struct {
struct usb_cdc_header_descriptor header;
struct usb_cdc_call_management_descriptor call_mgmt;
struct usb_cdc_acm_descriptor acm;
struct usb_cdc_union_descriptor cdc_union;
} __attribute__((packed)) cdcacm_functional_descriptors = {
.header = {
.bFunctionLength = sizeof(struct usb_cdc_header_descriptor),
.bDescriptorType = CS_INTERFACE,
.bDescriptorSubtype = USB_CDC_TYPE_HEADER,
.bcdCDC = 0x0110,
},
.call_mgmt = {
.bFunctionLength =
sizeof(struct usb_cdc_call_management_descriptor),
.bDescriptorType = CS_INTERFACE,
.bDescriptorSubtype = USB_CDC_TYPE_CALL_MANAGEMENT,
.bmCapabilities = 0,
.bDataInterface = 1,
},
.acm = {
.bFunctionLength = sizeof(struct usb_cdc_acm_descriptor),
.bDescriptorType = CS_INTERFACE,
.bDescriptorSubtype = USB_CDC_TYPE_ACM,
.bmCapabilities = 0,
},
.cdc_union = {
.bFunctionLength = sizeof(struct usb_cdc_union_descriptor),
.bDescriptorType = CS_INTERFACE,
.bDescriptorSubtype = USB_CDC_TYPE_UNION,
.bControlInterface = 0,
.bSubordinateInterface0 = 1,
}
};
static const struct usb_interface_descriptor comm_iface[] = {{
.bLength = USB_DT_INTERFACE_SIZE,
.bDescriptorType = USB_DT_INTERFACE,
.bInterfaceNumber = 0,
.bAlternateSetting = 0,
.bNumEndpoints = 1,
.bInterfaceClass = USB_CLASS_CDC,
.bInterfaceSubClass = USB_CDC_SUBCLASS_ACM,
.bInterfaceProtocol = USB_CDC_PROTOCOL_AT,
.iInterface = 0,
.endpoint = comm_endp,
.extra = &cdcacm_functional_descriptors,
.extralen = sizeof(cdcacm_functional_descriptors)
}};
static const struct usb_interface_descriptor data_iface[] = {{
.bLength = USB_DT_INTERFACE_SIZE,
.bDescriptorType = USB_DT_INTERFACE,
.bInterfaceNumber = 1,
.bAlternateSetting = 0,
.bNumEndpoints = 2,
.bInterfaceClass = USB_CLASS_DATA,
.bInterfaceSubClass = 0,
.bInterfaceProtocol = 0,
.iInterface = 0,
.endpoint = data_endp,
}};
static const struct usb_interface ifaces[] = {{
.num_altsetting = 1,
.altsetting = comm_iface,
}, {
.num_altsetting = 1,
.altsetting = data_iface,
}};
static const struct usb_config_descriptor config = {
.bLength = USB_DT_CONFIGURATION_SIZE,
.bDescriptorType = USB_DT_CONFIGURATION,
.wTotalLength = 0,
.bNumInterfaces = 2,
.bConfigurationValue = 1,
.iConfiguration = 0,
.bmAttributes = 0x80,
.bMaxPower = 0x32,
.interface = ifaces,
};
static const char *usb_strings[] = {
"Black Sphere Technologies",
"CDC-ACM Demo",
"DEMO",
};
static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, u8 **buf,
u16 *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req))
{
(void)complete;
(void)buf;
(void)usbd_dev;
switch (req->bRequest) {
case USB_CDC_REQ_SET_CONTROL_LINE_STATE: {
/*
* This Linux cdc_acm driver requires this to be implemented
* even though it's optional in the CDC spec, and we don't
* advertise it in the ACM functional descriptor.
*/
char local_buf[10];
struct usb_cdc_notification *notif = (void*)local_buf;
/* We echo signals back to host as notification. */
notif->bmRequestType = 0xA1;
notif->bNotification = USB_CDC_NOTIFY_SERIAL_STATE;
notif->wValue = 0;
notif->wIndex = 0;
notif->wLength = 2;
local_buf[8] = req->wValue & 3;
local_buf[9] = 0;
// usbd_ep_write_packet(0x83, buf, 10);
return 1;
}
case USB_CDC_REQ_SET_LINE_CODING:
if (*len < sizeof(struct usb_cdc_line_coding))
return 0;
return 1;
}
return 0;
}
static void cdcacm_data_rx_cb(usbd_device *usbd_dev, u8 ep)
{
(void)ep;
char buf[64];
int len = usbd_ep_read_packet(usbd_dev, 0x01, buf, 64);
if (len) {
while (usbd_ep_write_packet(usbd_dev, 0x82, buf, len) == 0)
;
buf[len] = 0;
}
gpio_toggle(GPIOC, GPIO5);
}
static void cdcacm_set_config(usbd_device *usbd_dev, u16 wValue)
{
(void)wValue;
usbd_ep_setup(usbd_dev, 0x01, USB_ENDPOINT_ATTR_BULK, 64, cdcacm_data_rx_cb);
usbd_ep_setup(usbd_dev, 0x82, USB_ENDPOINT_ATTR_BULK, 64, NULL);
usbd_ep_setup(usbd_dev, 0x83, USB_ENDPOINT_ATTR_INTERRUPT, 16, NULL);
usbd_register_control_callback(
usbd_dev,
USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE,
USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT,
cdcacm_control_request);
}
int main(void)
{
int i;
usbd_device *usbd_dev;
rcc_clock_setup_in_hsi_out_48mhz();
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
rcc_peripheral_enable_clock(&RCC_AHBENR, RCC_AHBENR_OTGFSEN);
gpio_set(GPIOC, GPIO2);
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO2);
gpio_set(GPIOC, GPIO5);
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO5);
usbd_dev = usbd_init(&stm32f107_usb_driver, &dev, &config, usb_strings, 3);
usbd_register_set_config_callback(usbd_dev, cdcacm_set_config);
for (i = 0; i < 0x800000; i++)
__asm__("nop");
gpio_clear(GPIOC, GPIO2);
while (1)
usbd_poll(usbd_dev);
}

View File

@@ -0,0 +1,56 @@
#! /usr/bin/env python
#
# This file is part of the libopencm3 project.
#
# Copyright (C) 2011 Piotr Esden-Tempski <piotr@esden.net>
#
# This library is free software: you can redistribute it and/or modify
# it under the terms of the GNU Lesser General Public License as published by
# the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version.
#
# This library is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU Lesser General Public License for more details.
#
# You should have received a copy of the GNU Lesser General Public License
# along with this library. If not, see <http://www.gnu.org/licenses/>.
#
import serial
import signal
import sys
import time
def signal_handler(signal, frame):
print 'You pressed Ctrl+C!'
ser.close();
sys.exit(0)
signal.signal(signal.SIGINT, signal_handler);
ser = serial.Serial('/dev/cu.usbmodemDEM1', 115200, timeout=0.05);
error = 0
tim = time.time();
cycles = 0
while 1==1:
ser.write("abcdefghijklmnopqrstuvwxyzABCDEFGHIJKLMNOPQRSTUVWXYZ1234567890!@#$%^&*(){}");
buf = ser.read(1024);
cycles += 1
if buf != "abcdefghijklmnopqrstuvwxyzABCDEFGHIJKLMNOPQRSTUVWXYZ1234567890!@#$%^&*(){}" :
error+=1
print "received " + buf + " errors: " + str(error) + " cycles: " + str(cycles) + " runtime: " + str(time.time() - tim)
#time.sleep(0.1);
ser.close();

View File

@@ -0,0 +1,25 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = usbdfu
LDSCRIPT = ../lisa-m.ld
include ../../Makefile.include

View File

@@ -0,0 +1,7 @@
------------------------------------------------------------------------------
README
------------------------------------------------------------------------------
This example implements a USB Device Firmware Upgrade (DFU) bootloader
to demonstrate the use of the USB device stack.

View File

@@ -0,0 +1,272 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Gareth McMullin <gareth@blacksphere.co.nz>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <string.h>
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/stm32/f1/flash.h>
#include <libopencm3/cm3/scb.h>
#include <libopencm3/usb/usbd.h>
#include <libopencm3/usb/dfu.h>
#define APP_ADDRESS 0x08002000
/* Commands sent with wBlockNum == 0 as per ST implementation. */
#define CMD_SETADDR 0x21
#define CMD_ERASE 0x41
/* We need a special large control buffer for this device: */
u8 usbd_control_buffer[1024];
static enum dfu_state usbdfu_state = STATE_DFU_IDLE;
static struct {
u8 buf[sizeof(usbd_control_buffer)];
u16 len;
u32 addr;
u16 blocknum;
} prog;
const struct usb_device_descriptor dev = {
.bLength = USB_DT_DEVICE_SIZE,
.bDescriptorType = USB_DT_DEVICE,
.bcdUSB = 0x0200,
.bDeviceClass = 0,
.bDeviceSubClass = 0,
.bDeviceProtocol = 0,
.bMaxPacketSize0 = 64,
.idVendor = 0x0483,
.idProduct = 0xDF11,
.bcdDevice = 0x0200,
.iManufacturer = 1,
.iProduct = 2,
.iSerialNumber = 3,
.bNumConfigurations = 1,
};
const struct usb_dfu_descriptor dfu_function = {
.bLength = sizeof(struct usb_dfu_descriptor),
.bDescriptorType = DFU_FUNCTIONAL,
.bmAttributes = USB_DFU_CAN_DOWNLOAD | USB_DFU_WILL_DETACH,
.wDetachTimeout = 255,
.wTransferSize = 1024,
.bcdDFUVersion = 0x011A,
};
const struct usb_interface_descriptor iface = {
.bLength = USB_DT_INTERFACE_SIZE,
.bDescriptorType = USB_DT_INTERFACE,
.bInterfaceNumber = 0,
.bAlternateSetting = 0,
.bNumEndpoints = 0,
.bInterfaceClass = 0xFE, /* Device Firmware Upgrade */
.bInterfaceSubClass = 1,
.bInterfaceProtocol = 2,
/* The ST Microelectronics DfuSe application needs this string.
* The format isn't documented... */
.iInterface = 4,
.extra = &dfu_function,
.extralen = sizeof(dfu_function),
};
const struct usb_interface ifaces[] = {{
.num_altsetting = 1,
.altsetting = &iface,
}};
const struct usb_config_descriptor config = {
.bLength = USB_DT_CONFIGURATION_SIZE,
.bDescriptorType = USB_DT_CONFIGURATION,
.wTotalLength = 0,
.bNumInterfaces = 1,
.bConfigurationValue = 1,
.iConfiguration = 0,
.bmAttributes = 0xC0,
.bMaxPower = 0x32,
.interface = ifaces,
};
static const char *usb_strings[] = {
"Black Sphere Technologies",
"DFU Demo",
"DEMO",
/* This string is used by ST Microelectronics' DfuSe utility. */
"@Internal Flash /0x08000000/8*001Ka,56*001Kg",
};
static u8 usbdfu_getstatus(u32 *bwPollTimeout)
{
switch (usbdfu_state) {
case STATE_DFU_DNLOAD_SYNC:
usbdfu_state = STATE_DFU_DNBUSY;
*bwPollTimeout = 100;
return DFU_STATUS_OK;
case STATE_DFU_MANIFEST_SYNC:
/* Device will reset when read is complete. */
usbdfu_state = STATE_DFU_MANIFEST;
return DFU_STATUS_OK;
default:
return DFU_STATUS_OK;
}
}
static void usbdfu_getstatus_complete(usbd_device *usbd_dev, struct usb_setup_data *req)
{
int i;
(void)req;
(void)usbd_dev;
switch (usbdfu_state) {
case STATE_DFU_DNBUSY:
flash_unlock();
if (prog.blocknum == 0) {
switch (prog.buf[0]) {
case CMD_ERASE:
{
u32 *dat = (u32 *)(prog.buf + 1);
flash_erase_page(*dat);
}
case CMD_SETADDR:
{
u32 *dat = (u32 *)(prog.buf + 1);
prog.addr = *dat;
}
}
} else {
u32 baseaddr = prog.addr + ((prog.blocknum - 2) *
dfu_function.wTransferSize);
for (i = 0; i < prog.len; i += 2) {
u16 *dat = (u16 *)(prog.buf + i);
flash_program_half_word(baseaddr + i,
*dat);
}
}
flash_lock();
/* Jump straight to dfuDNLOAD-IDLE, skipping dfuDNLOAD-SYNC. */
usbdfu_state = STATE_DFU_DNLOAD_IDLE;
return;
case STATE_DFU_MANIFEST:
/* USB device must detach, we just reset... */
scb_reset_system();
return; /* Will never return. */
default:
return;
}
}
static int usbdfu_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, u8 **buf,
u16 *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req))
{
(void)usbd_dev;
if ((req->bmRequestType & 0x7F) != 0x21)
return 0; /* Only accept class request. */
switch (req->bRequest) {
case DFU_DNLOAD:
if ((len == NULL) || (*len == 0)) {
usbdfu_state = STATE_DFU_MANIFEST_SYNC;
return 1;
} else {
/* Copy download data for use on GET_STATUS. */
prog.blocknum = req->wValue;
prog.len = *len;
memcpy(prog.buf, *buf, *len);
usbdfu_state = STATE_DFU_DNLOAD_SYNC;
return 1;
}
case DFU_CLRSTATUS:
/* Clear error and return to dfuIDLE. */
if (usbdfu_state == STATE_DFU_ERROR)
usbdfu_state = STATE_DFU_IDLE;
return 1;
case DFU_ABORT:
/* Abort returns to dfuIDLE state. */
usbdfu_state = STATE_DFU_IDLE;
return 1;
case DFU_UPLOAD:
/* Upload not supported for now. */
return 0;
case DFU_GETSTATUS: {
u32 bwPollTimeout = 0; /* 24-bit integer in DFU class spec */
(*buf)[0] = usbdfu_getstatus(&bwPollTimeout);
(*buf)[1] = bwPollTimeout & 0xFF;
(*buf)[2] = (bwPollTimeout >> 8) & 0xFF;
(*buf)[3] = (bwPollTimeout >> 16) & 0xFF;
(*buf)[4] = usbdfu_state;
(*buf)[5] = 0; /* iString not used here */
*len = 6;
*complete = usbdfu_getstatus_complete;
return 1;
}
case DFU_GETSTATE:
/* Return state with no state transision. */
*buf[0] = usbdfu_state;
*len = 1;
return 1;
}
return 0;
}
int main(void)
{
usbd_device *usbd_dev;
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
if (!gpio_get(GPIOA, GPIO10)) {
/* Boot the application if it's valid. */
if ((*(volatile u32 *)APP_ADDRESS & 0x2FFE0000) == 0x20000000) {
/* Set vector table base address. */
SCB_VTOR = APP_ADDRESS & 0xFFFF;
/* Initialise master stack pointer. */
asm volatile("msr msp, %0"::"g"
(*(volatile u32 *)APP_ADDRESS));
/* Jump to application. */
(*(void (**)())(APP_ADDRESS + 4))();
}
}
rcc_clock_setup_in_hsi_out_48mhz();
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
rcc_peripheral_enable_clock(&RCC_AHBENR, RCC_AHBENR_OTGFSEN);
gpio_set(GPIOC, GPIO2);
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO2);
usbd_dev = usbd_init(&stm32f107_usb_driver, &dev, &config, usb_strings, 4);
usbd_set_control_buffer_size(usbd_dev, sizeof(usbd_control_buffer));
usbd_register_control_callback(
usbd_dev,
USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE,
USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT,
usbdfu_control_request);
gpio_clear(GPIOC, GPIO2);
while (1)
usbd_poll(usbd_dev);
}

View File

@@ -0,0 +1,25 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = usbhid
LDSCRIPT = ../lisa-m.ld
include ../../Makefile.include

View File

@@ -0,0 +1,7 @@
------------------------------------------------------------------------------
README
------------------------------------------------------------------------------
This example implements a USB Human Interface Device (HID)
to demonstrate the use of the USB device stack.

View File

@@ -0,0 +1,38 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2011 Gareth McMullin <gareth@blacksphere.co.nz>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef __ADXL345_H
#define __ADXL345_H
/* Register addresses */
#define ADXL345_DEVID 0x00
#define ADXL345_POWER_CTL 0x2D
#define ADXL345_DATA_FORMAT 0x31
#define ADXL345_DATAX0 0x32
#define ADXL345_DATAX1 0x33
#define ADXL345_DATAY0 0x34
#define ADXL345_DATAY1 0x35
#define ADXL345_DATAZ0 0x36
#define ADXL345_DATAZ1 0x37
#define ADXL345_POWER_CTL_MEASURE (1 << 3)
#define ADXL345_DATA_FORMAT_LALIGN (1 << 2)
#endif

View File

@@ -0,0 +1,369 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Gareth McMullin <gareth@blacksphere.co.nz>
* Copyright (C) 2011 Piotr Esden-Tempski <piotr@esden.net>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdlib.h>
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/cm3/systick.h>
#include <libopencm3/stm32/spi.h>
#include <libopencm3/stm32/otg_fs.h>
#include <libopencm3/stm32/f1/nvic.h>
#include <libopencm3/usb/usbd.h>
#include <libopencm3/usb/hid.h>
#include "adxl345.h"
/* Define this to include the DFU APP interface. */
#define INCLUDE_DFU_INTERFACE
#ifdef INCLUDE_DFU_INTERFACE
#include <libopencm3/cm3/scb.h>
#include <libopencm3/usb/dfu.h>
#endif
static usbd_device *usbd_dev;
const struct usb_device_descriptor dev_descr = {
.bLength = USB_DT_DEVICE_SIZE,
.bDescriptorType = USB_DT_DEVICE,
.bcdUSB = 0x0200,
.bDeviceClass = 0,
.bDeviceSubClass = 0,
.bDeviceProtocol = 0,
.bMaxPacketSize0 = 64,
.idVendor = 0x0483,
.idProduct = 0x5710,
.bcdDevice = 0x0200,
.iManufacturer = 1,
.iProduct = 2,
.iSerialNumber = 3,
.bNumConfigurations = 1,
};
/* I have no idea what this means. I haven't read the HID spec. */
static const u8 hid_report_descriptor[] = {
0x05, 0x01, 0x09, 0x02, 0xA1, 0x01, 0x09, 0x01,
0xA1, 0x00, 0x05, 0x09, 0x19, 0x01, 0x29, 0x03,
0x15, 0x00, 0x25, 0x01, 0x95, 0x03, 0x75, 0x01,
0x81, 0x02, 0x95, 0x01, 0x75, 0x05, 0x81, 0x01,
0x05, 0x01, 0x09, 0x30, 0x09, 0x31, 0x09, 0x38,
0x15, 0x81, 0x25, 0x7F, 0x75, 0x08, 0x95, 0x03,
0x81, 0x06, 0xC0, 0x09, 0x3c, 0x05, 0xff, 0x09,
0x01, 0x15, 0x00, 0x25, 0x01, 0x75, 0x01, 0x95,
0x02, 0xb1, 0x22, 0x75, 0x06, 0x95, 0x01, 0xb1,
0x01, 0xc0,
};
static const struct {
struct usb_hid_descriptor hid_descriptor;
struct {
u8 bReportDescriptorType;
u16 wDescriptorLength;
} __attribute__((packed)) hid_report;
} __attribute__((packed)) hid_function = {
.hid_descriptor = {
.bLength = sizeof(hid_function),
.bDescriptorType = USB_DT_HID,
.bcdHID = 0x0100,
.bCountryCode = 0,
.bNumDescriptors = 1,
},
.hid_report = {
.bReportDescriptorType = USB_DT_REPORT,
.wDescriptorLength = sizeof(hid_report_descriptor),
}
};
const struct usb_endpoint_descriptor hid_endpoint = {
.bLength = USB_DT_ENDPOINT_SIZE,
.bDescriptorType = USB_DT_ENDPOINT,
.bEndpointAddress = 0x81,
.bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT,
.wMaxPacketSize = 4,
.bInterval = 0x02,
};
const struct usb_interface_descriptor hid_iface = {
.bLength = USB_DT_INTERFACE_SIZE,
.bDescriptorType = USB_DT_INTERFACE,
.bInterfaceNumber = 0,
.bAlternateSetting = 0,
.bNumEndpoints = 1,
.bInterfaceClass = USB_CLASS_HID,
.bInterfaceSubClass = 1, /* boot */
.bInterfaceProtocol = 2, /* mouse */
.iInterface = 0,
.endpoint = &hid_endpoint,
.extra = &hid_function,
.extralen = sizeof(hid_function),
};
#ifdef INCLUDE_DFU_INTERFACE
const struct usb_dfu_descriptor dfu_function = {
.bLength = sizeof(struct usb_dfu_descriptor),
.bDescriptorType = DFU_FUNCTIONAL,
.bmAttributes = USB_DFU_CAN_DOWNLOAD | USB_DFU_WILL_DETACH,
.wDetachTimeout = 255,
.wTransferSize = 1024,
.bcdDFUVersion = 0x011A,
};
const struct usb_interface_descriptor dfu_iface = {
.bLength = USB_DT_INTERFACE_SIZE,
.bDescriptorType = USB_DT_INTERFACE,
.bInterfaceNumber = 1,
.bAlternateSetting = 0,
.bNumEndpoints = 0,
.bInterfaceClass = 0xFE,
.bInterfaceSubClass = 1,
.bInterfaceProtocol = 1,
.iInterface = 0,
.extra = &dfu_function,
.extralen = sizeof(dfu_function),
};
#endif
const struct usb_interface ifaces[] = {{
.num_altsetting = 1,
.altsetting = &hid_iface,
#ifdef INCLUDE_DFU_INTERFACE
}, {
.num_altsetting = 1,
.altsetting = &dfu_iface,
#endif
}};
const struct usb_config_descriptor config = {
.bLength = USB_DT_CONFIGURATION_SIZE,
.bDescriptorType = USB_DT_CONFIGURATION,
.wTotalLength = 0,
#ifdef INCLUDE_DFU_INTERFACE
.bNumInterfaces = 2,
#else
.bNumInterfaces = 1,
#endif
.bConfigurationValue = 1,
.iConfiguration = 0,
.bmAttributes = 0xC0,
.bMaxPower = 0x32,
.interface = ifaces,
};
static const char *usb_strings[] = {
"Black Sphere Technologies",
"HID Demo",
"DEMO",
};
static int hid_control_request(usbd_device *dev, struct usb_setup_data *req, u8 **buf, u16 *len,
void (**complete)(usbd_device *dev, struct usb_setup_data *req))
{
(void)complete;
(void)dev;
if((req->bmRequestType != 0x81) ||
(req->bRequest != USB_REQ_GET_DESCRIPTOR) ||
(req->wValue != 0x2200))
return 0;
/* Handle the HID report descriptor. */
*buf = (u8 *)hid_report_descriptor;
*len = sizeof(hid_report_descriptor);
return 1;
}
#ifdef INCLUDE_DFU_INTERFACE
static void dfu_detach_complete(usbd_device *dev, struct usb_setup_data *req)
{
(void)req;
(void)dev;
gpio_set_mode(GPIOA, GPIO_MODE_INPUT, 0, GPIO15);
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO10);
gpio_set(GPIOA, GPIO10);
scb_reset_core();
}
static int dfu_control_request(usbd_device *dev, struct usb_setup_data *req, u8 **buf, u16 *len,
void (**complete)(usbd_device *dev, struct usb_setup_data *req))
{
(void)buf;
(void)len;
(void)dev;
if ((req->bmRequestType != 0x21) || (req->bRequest != DFU_DETACH))
return 0; /* Only accept class request. */
*complete = dfu_detach_complete;
return 1;
}
#endif
static void hid_set_config(usbd_device *dev, u16 wValue)
{
(void)wValue;
usbd_ep_setup(dev, 0x81, USB_ENDPOINT_ATTR_INTERRUPT, 4, NULL);
usbd_register_control_callback(
dev,
USB_REQ_TYPE_STANDARD | USB_REQ_TYPE_INTERFACE,
USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT,
hid_control_request);
#ifdef INCLUDE_DFU_INTERFACE
usbd_register_control_callback(
dev,
USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE,
USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT,
dfu_control_request);
#endif
systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
/* SysTick interrupt every N clock pulses: set reload to N-1 */
systick_set_reload(99999);
systick_interrupt_enable();
systick_counter_enable();
}
static u8 spi_readwrite(u32 spi, u8 data)
{
while (SPI_SR(spi) & SPI_SR_BSY)
;
SPI_DR(spi) = data;
while (!(SPI_SR(spi) & SPI_SR_RXNE))
;
return SPI_DR(spi);
}
static u8 accel_read(u8 addr)
{
u8 ret;
gpio_clear(GPIOB, GPIO12);
spi_readwrite(SPI2, addr | 0x80);
ret = spi_readwrite(SPI2, 0);
gpio_set(GPIOB, GPIO12);
return ret;
}
static void accel_write(u8 addr, u8 data)
{
gpio_clear(GPIOB, GPIO12);
spi_readwrite(SPI2, addr);
spi_readwrite(SPI2, data);
gpio_set(GPIOB, GPIO12);
}
static void accel_get(s16 *x, s16 *y, s16 *z)
{
if (x)
*x = accel_read(ADXL345_DATAX0) |
(accel_read(ADXL345_DATAX1) << 8);
if (y)
*y = accel_read(ADXL345_DATAY0) |
(accel_read(ADXL345_DATAY1) << 8);
if (z)
*z = accel_read(ADXL345_DATAZ0) |
(accel_read(ADXL345_DATAZ1) << 8);
}
int main(void)
{
int i;
rcc_clock_setup_in_hse_12mhz_out_72mhz();
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_SPI2EN);
rcc_peripheral_enable_clock(&RCC_AHBENR, RCC_AHBENR_OTGFSEN);
/* Configure SPI2: PB13(SCK), PB14(MISO), PB15(MOSI). */
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_10_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL,
GPIO_SPI2_SCK | GPIO_SPI2_MOSI);
gpio_set_mode(GPIOB, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT,
GPIO_SPI2_MISO);
/* Enable CS pin on PB12. */
gpio_set(GPIOB, GPIO12);
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_10_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO12);
/* Force to SPI mode. This should be default after reset! */
SPI2_I2SCFGR = 0;
spi_init_master(SPI2,
SPI_CR1_BAUDRATE_FPCLK_DIV_256,
SPI_CR1_CPOL_CLK_TO_1_WHEN_IDLE,
SPI_CR1_CPHA_CLK_TRANSITION_2,
SPI_CR1_DFF_8BIT,
SPI_CR1_MSBFIRST);
/* Ignore the stupid NSS pin. */
spi_enable_software_slave_management(SPI2);
spi_set_nss_high(SPI2);
spi_enable(SPI2);
(void)accel_read(ADXL345_DEVID);
accel_write(ADXL345_POWER_CTL, ADXL345_POWER_CTL_MEASURE);
accel_write(ADXL345_DATA_FORMAT, ADXL345_DATA_FORMAT_LALIGN);
/* USB_DETECT as input. */
gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, GPIO8);
/* Green LED off, as output. */
gpio_set(GPIOC, GPIO2);
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO2);
usbd_dev = usbd_init(&stm32f107_usb_driver, &dev_descr, &config, usb_strings, 3);
usbd_register_set_config_callback(usbd_dev, hid_set_config);
/* Delay some seconds to show that pull-up switch works. */
for (i = 0; i < 0x800000; i++)
__asm__("nop");
/* Wait for USB Vbus. */
while (gpio_get(GPIOA, GPIO8) == 0)
__asm__("nop");
/* Green LED on, connect USB. */
gpio_clear(GPIOC, GPIO2);
// OTG_FS_GCCFG &= ~OTG_FS_GCCFG_VBUSBSEN;
while (1)
usbd_poll(usbd_dev);
}
void sys_tick_handler(void)
{
s16 x, y;
u8 buf[4] = {0, 0, 0, 0};
accel_get(&x, &y, NULL);
buf[1] = x >> 9;
buf[2] = y >> 9;
usbd_ep_write_packet(usbd_dev, 0x81, buf, 4);
}

View File

@@ -0,0 +1,28 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = adc_injec
# Comment the following line if you _don't_ have luftboot flashed!
LDFLAGS += -Wl,-Ttext=0x8002000
CFLAGS += -std=c99
LDSCRIPT = ../lisa-m.ld
include ../../Makefile.include

View File

@@ -0,0 +1,11 @@
------------------------------------------------------------------------------
README
------------------------------------------------------------------------------
This is a simple polling example that sends the value read out from the
temperature sensor ADC channel of the STM32 to the USART2.
This example polls injected channels.
The terminal settings for the receiving device/PC are 115200 8n1.

View File

@@ -0,0 +1,174 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
* Copyright (C) 2012 Piotr Esden-Tempski <piotr@esden.net>
* Copyright (C) 2012 Stephen Dwyer <dwyer.sc@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/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/flash.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/stm32/f1/adc.h>
#include <libopencm3/stm32/usart.h>
static void usart_setup(void)
{
/* Enable clocks for GPIO port A (for GPIO_USART1_TX) and USART1. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USART2EN);
/* Setup GPIO pin GPIO_USART1_TX/GPIO9 on GPIO port A for transmit. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART2_TX);
/* Setup UART parameters. */
usart_set_baudrate(USART2, 115200);
usart_set_databits(USART2, 8);
usart_set_stopbits(USART2, USART_STOPBITS_1);
usart_set_mode(USART2, USART_MODE_TX_RX);
usart_set_parity(USART2, USART_PARITY_NONE);
usart_set_flow_control(USART2, USART_FLOWCONTROL_NONE);
/* Finally enable the USART. */
usart_enable(USART2);
}
static void gpio_setup(void)
{
/* Enable GPIO clocks. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
/* Setup the LEDs. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO8);
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO15);
}
static void adc_setup(void)
{
int i;
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_ADC1EN);
/* Make sure the ADC doesn't run during config. */
adc_off(ADC1);
/* We configure everything for one single injected conversion. */
adc_disable_scan_mode(ADC1);
adc_set_single_conversion_mode(ADC1);
/* We can only use discontinuous mode on either the regular OR injected channels, not both */
adc_disable_discontinuous_mode_regular(ADC1);
adc_enable_discontinuous_mode_injected(ADC1);
/* We want to start the injected conversion in software */
adc_enable_external_trigger_injected(ADC1,ADC_CR2_JEXTSEL_JSWSTART);
adc_set_right_aligned(ADC1);
/* We want to read the temperature sensor, so we have to enable it. */
adc_enable_temperature_sensor(ADC1);
adc_set_sample_time_on_all_channels(ADC1, ADC_SMPR_SMP_28DOT5CYC);
adc_power_on(ADC1);
/* Wait for ADC starting up. */
for (i = 0; i < 800000; i++) /* Wait a bit. */
__asm__("nop");
adc_reset_calibration(ADC1);
while ((ADC_CR2(ADC1) & ADC_CR2_RSTCAL) != 0); //added this check
adc_calibration(ADC1);
while ((ADC_CR2(ADC1) & ADC_CR2_CAL) != 0); //added this check
}
static void my_usart_print_int(u32 usart, int value)
{
s8 i;
u8 nr_digits = 0;
char buffer[25];
if (value < 0) {
usart_send_blocking(usart, '-');
value = value * -1;
}
while (value > 0) {
buffer[nr_digits++] = "0123456789"[value % 10];
value /= 10;
}
for (i = (nr_digits - 1); i >= 0; i--) {
usart_send_blocking(usart, buffer[i]);
}
usart_send_blocking(usart, '\r');
}
int main(void)
{
u8 channel_array[16];
u16 temperature = 0;
rcc_clock_setup_in_hse_12mhz_out_72mhz();
gpio_setup();
usart_setup();
adc_setup();
gpio_set(GPIOA, GPIO8); /* LED1 on */
gpio_set(GPIOC, GPIO15); /* LED2 on */
/* Send a message on USART1. */
usart_send_blocking(USART2, 's');
usart_send_blocking(USART2, 't');
usart_send_blocking(USART2, 'm');
usart_send_blocking(USART2, '\r');
usart_send_blocking(USART2, '\n');
/* Select the channel we want to convert. 16=temperature_sensor. */
channel_array[0] = 16;
/* Set the injected sequence here, with number of channels */
adc_set_injected_sequence(ADC1, 1, channel_array);
/* Continously convert and poll the temperature ADC. */
while (1) {
/*
* If the ADC_CR2_ON bit is already set -> setting it another time
* starts a regular conversion. Injected conversion is started
* explicitly with the JSWSTART bit as an external trigger. It may
* also work by setting no regular channels and setting JAUTO to
* automatically convert the injected channels after the regular
* channels (of which there would be none). (Not tested.)
*/
adc_start_conversion_injected(ADC1);
/* Wait for end of conversion. */
while (!(adc_eoc_injected(ADC1)));
ADC_SR(ADC2) &= ~ADC_SR_JEOC; //clear injected end of conversion
temperature = adc_read_injected(ADC1,1); //get the result from ADC_JDR1 on ADC1 (only bottom 16bits)
/*
* That's actually not the real temperature - you have to compute it
* as described in the datasheet.
*/
my_usart_print_int(USART2, temperature);
gpio_toggle(GPIOA, GPIO8); /* LED2 on */
}
return 0;
}

View File

@@ -0,0 +1,28 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = adc_injec_timtrig
# Comment the following line if you _don't_ have luftboot flashed!
LDFLAGS += -Wl,-Ttext=0x8002000
CFLAGS += -std=c99
LDSCRIPT = ../lisa-m.ld
include ../../Makefile.include

View File

@@ -0,0 +1,11 @@
------------------------------------------------------------------------------
README
------------------------------------------------------------------------------
This is a simple example that sends the value read out from the
temperature sensor ADC channel of the STM32 to the USART2.
This example uses a timer trigger to automatically sample the adc channel.
The terminal settings for the receiving device/PC are 115200 8n1.

View File

@@ -0,0 +1,195 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
* Copyright (C) 2012 Piotr Esden-Tempski <piotr@esden.net>
* Copyright (C) 2012 Stephen Dwyer <dwyer.sc@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/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/flash.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/stm32/f1/adc.h>
#include <libopencm3/stm32/usart.h>
#include <libopencm3/stm32/timer.h>
static void usart_setup(void)
{
/* Enable clocks for GPIO port A (for GPIO_USART1_TX) and USART1. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USART2EN);
/* Setup GPIO pin GPIO_USART1_TX/GPIO9 on GPIO port A for transmit. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART2_TX);
/* Setup UART parameters. */
usart_set_baudrate(USART2, 115200);
usart_set_databits(USART2, 8);
usart_set_stopbits(USART2, USART_STOPBITS_1);
usart_set_mode(USART2, USART_MODE_TX_RX);
usart_set_parity(USART2, USART_PARITY_NONE);
usart_set_flow_control(USART2, USART_FLOWCONTROL_NONE);
/* Finally enable the USART. */
usart_enable(USART2);
}
static void gpio_setup(void)
{
/* Enable GPIO clocks. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
/* Setup the LEDs. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO8);
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO15);
}
static void timer_setup(void)
{
/* Set up the timer TIM2 for injected sampling */
uint32_t timer;
volatile uint32_t *rcc_apbenr;
uint32_t rcc_apb;
timer = TIM2;
rcc_apbenr = &RCC_APB1ENR;
rcc_apb = RCC_APB1ENR_TIM2EN;
rcc_peripheral_enable_clock(rcc_apbenr, rcc_apb);
/* Time Base configuration */
timer_reset(timer);
timer_set_mode(timer, TIM_CR1_CKD_CK_INT,
TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP);
timer_set_period(timer, 0xFF);
timer_set_prescaler(timer, 0x8);
timer_set_clock_division(timer, 0x0);
/* Generate TRGO on every update. */
timer_set_master_mode(timer, TIM_CR2_MMS_UPDATE);
timer_enable_counter(timer);
}
static void adc_setup(void)
{
int i;
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_ADC1EN);
/* Make sure the ADC doesn't run during config. */
adc_off(ADC1);
/* We configure everything for one single timer triggered injected conversion. */
adc_disable_scan_mode(ADC1);
adc_set_single_conversion_mode(ADC1);
/* We can only use discontinuous mode on either the regular OR injected channels, not both */
adc_disable_discontinuous_mode_regular(ADC1);
adc_enable_discontinuous_mode_injected(ADC1);
/* We want to start the injected conversion with the TIM2 TRGO */
adc_enable_external_trigger_injected(ADC1,ADC_CR2_JEXTSEL_TIM2_TRGO);
adc_set_right_aligned(ADC1);
/* We want to read the temperature sensor, so we have to enable it. */
adc_enable_temperature_sensor(ADC1);
adc_set_sample_time_on_all_channels(ADC1, ADC_SMPR_SMP_28DOT5CYC);
adc_power_on(ADC1);
/* Wait for ADC starting up. */
for (i = 0; i < 800000; i++) /* Wait a bit. */
__asm__("nop");
adc_reset_calibration(ADC1);
while ((ADC_CR2(ADC1) & ADC_CR2_RSTCAL) != 0);
adc_calibration(ADC1);
while ((ADC_CR2(ADC1) & ADC_CR2_CAL) != 0);
}
static void my_usart_print_int(u32 usart, int value)
{
s8 i;
u8 nr_digits = 0;
char buffer[25];
if (value < 0) {
usart_send_blocking(usart, '-');
value = value * -1;
}
while (value > 0) {
buffer[nr_digits++] = "0123456789"[value % 10];
value /= 10;
}
for (i = (nr_digits - 1); i >= 0; i--) {
usart_send_blocking(usart, buffer[i]);
}
usart_send_blocking(usart, '\r');
}
int main(void)
{
u8 channel_array[16];
u16 temperature = 0;
rcc_clock_setup_in_hse_12mhz_out_72mhz();
gpio_setup();
usart_setup();
timer_setup();
adc_setup();
gpio_set(GPIOA, GPIO8); /* LED1 on */
gpio_set(GPIOC, GPIO15); /* LED2 on */
/* Send a message on USART1. */
usart_send_blocking(USART2, 's');
usart_send_blocking(USART2, 't');
usart_send_blocking(USART2, 'm');
usart_send_blocking(USART2, '\r');
usart_send_blocking(USART2, '\n');
/* Select the channel we want to convert. 16=temperature_sensor. */
channel_array[0] = 16;
/* Set the injected sequence here, with number of channels */
adc_set_injected_sequence(ADC1, 1, channel_array);
/* Continously convert and poll the temperature ADC. */
while (1) {
/*
* Since the injected sampling is triggered by the timer, it gets
* updated automatically, we just need to periodically read out the value.
* It would be better to check if the JEOC bit is set, and clear it following
* so that you do not read the same value twice, especially for a slower
* sampling rate.
*/
temperature = adc_read_injected(ADC1,1); //get the result from ADC_JDR1 on ADC1 (only bottom 16bits)
/*
* That's actually not the real temperature - you have to compute it
* as described in the datasheet.
*/
my_usart_print_int(USART2, temperature);
gpio_toggle(GPIOA, GPIO8); /* LED2 on */
}
return 0;
}

View File

@@ -0,0 +1,28 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = adc_injec_timtrig_irq
# Comment the following line if you _don't_ have luftboot flashed!
LDFLAGS += -Wl,-Ttext=0x8002000
CFLAGS += -std=c99
LDSCRIPT = ../lisa-m.ld
include ../../Makefile.include

View File

@@ -0,0 +1,12 @@
------------------------------------------------------------------------------
README
------------------------------------------------------------------------------
This is a simple example that sends the value read out from the
temperature sensor ADC channel of the STM32 to the USART2.
This example uses a timer trigger to sample an injected adc channel and
then uses an interrupt routine to retrieve the sample from the data register.
The terminal settings for the receiving device/PC are 115200 8n1.

View File

@@ -0,0 +1,211 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
* Copyright (C) 2012 Piotr Esden-Tempski <piotr@esden.net>
* Copyright (C) 2012 Stephen Dwyer <dwyer.sc@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/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/flash.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/stm32/f1/adc.h>
#include <libopencm3/stm32/usart.h>
#include <libopencm3/stm32/timer.h>
#include <libopencm3/cm3/nvic.h>
volatile u16 temperature = 0;
static void usart_setup(void)
{
/* Enable clocks for GPIO port A (for GPIO_USART1_TX) and USART1. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USART2EN);
/* Setup GPIO pin GPIO_USART1_TX/GPIO9 on GPIO port A for transmit. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART2_TX);
/* Setup UART parameters. */
usart_set_baudrate(USART2, 115200);
usart_set_databits(USART2, 8);
usart_set_stopbits(USART2, USART_STOPBITS_1);
usart_set_mode(USART2, USART_MODE_TX_RX);
usart_set_parity(USART2, USART_PARITY_NONE);
usart_set_flow_control(USART2, USART_FLOWCONTROL_NONE);
/* Finally enable the USART. */
usart_enable(USART2);
}
static void gpio_setup(void)
{
/* Enable GPIO clocks. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
/* Setup the LEDs. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO8);
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO15);
}
static void timer_setup(void)
{
/* Set up the timer TIM2 for injected sampling */
uint32_t timer;
volatile uint32_t *rcc_apbenr;
uint32_t rcc_apb;
timer = TIM2;
rcc_apbenr = &RCC_APB1ENR;
rcc_apb = RCC_APB1ENR_TIM2EN;
rcc_peripheral_enable_clock(rcc_apbenr, rcc_apb);
/* Time Base configuration */
timer_reset(timer);
timer_set_mode(timer, TIM_CR1_CKD_CK_INT,
TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP);
timer_set_period(timer, 0xFF);
timer_set_prescaler(timer, 0x8);
timer_set_clock_division(timer, 0x0);
/* Generate TRGO on every update. */
timer_set_master_mode(timer, TIM_CR2_MMS_UPDATE);
timer_enable_counter(timer);
}
static void irq_setup(void)
{
/* Enable the adc1_2_isr() routine */
nvic_set_priority(NVIC_ADC1_2_IRQ, 0);
nvic_enable_irq(NVIC_ADC1_2_IRQ);
}
static void adc_setup(void)
{
int i;
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_ADC1EN);
/* Make sure the ADC doesn't run during config. */
adc_off(ADC1);
/* We configure everything for one single timer triggered injected conversion with interrupt generation. */
/* While not needed for a single channel, try out scan mode which does all channels in one sweep and
* generates the interrupt/EOC/JEOC flags set at the end of all channels, not each one.
*/
adc_enable_scan_mode(ADC1);
adc_set_single_conversion_mode(ADC1);
/* We want to start the injected conversion with the TIM2 TRGO */
adc_enable_external_trigger_injected(ADC1,ADC_CR2_JEXTSEL_TIM2_TRGO);
/* Generate the ADC1_2_IRQ */
adc_enable_eoc_interrupt_injected(ADC1);
adc_set_right_aligned(ADC1);
/* We want to read the temperature sensor, so we have to enable it. */
adc_enable_temperature_sensor(ADC1);
adc_set_sample_time_on_all_channels(ADC1, ADC_SMPR_SMP_28DOT5CYC);
adc_power_on(ADC1);
/* Wait for ADC starting up. */
for (i = 0; i < 800000; i++) /* Wait a bit. */
__asm__("nop");
adc_reset_calibration(ADC1);
while ((ADC_CR2(ADC1) & ADC_CR2_RSTCAL) != 0);
adc_calibration(ADC1);
while ((ADC_CR2(ADC1) & ADC_CR2_CAL) != 0);
}
static void my_usart_print_int(u32 usart, int value)
{
s8 i;
u8 nr_digits = 0;
char buffer[25];
if (value < 0) {
usart_send_blocking(usart, '-');
value = value * -1;
}
while (value > 0) {
buffer[nr_digits++] = "0123456789"[value % 10];
value /= 10;
}
for (i = (nr_digits - 1); i >= 0; i--) {
usart_send_blocking(usart, buffer[i]);
}
usart_send_blocking(usart, '\r');
}
int main(void)
{
u8 channel_array[16];
rcc_clock_setup_in_hse_12mhz_out_72mhz();
gpio_setup();
usart_setup();
timer_setup();
irq_setup();
adc_setup();
gpio_set(GPIOA, GPIO8); /* LED1 on */
gpio_set(GPIOC, GPIO15); /* LED2 on */
/* Send a message on USART1. */
usart_send_blocking(USART2, 's');
usart_send_blocking(USART2, 't');
usart_send_blocking(USART2, 'm');
usart_send_blocking(USART2, '\r');
usart_send_blocking(USART2, '\n');
/* Select the channel we want to convert. 16=temperature_sensor. */
channel_array[0] = 16;
/* Set the injected sequence here, with number of channels */
adc_set_injected_sequence(ADC1, 1, channel_array);
/* Continously convert and poll the temperature ADC. */
while (1) {
/*
* Since sampling is triggered by the timer and copying the value
* out of the data register is handled by the interrupt routine,
* we just need to print the value and toggle the LED. It may be useful
* to buffer the adc values in some cases.
*/
/*
* That's actually not the real temperature - you have to compute it
* as described in the datasheet.
*/
my_usart_print_int(USART2, temperature);
gpio_toggle(GPIOA, GPIO8); /* LED2 on */
}
return 0;
}
void adc1_2_isr(void)
{
/* Clear Injected End Of Conversion (JEOC) */
ADC_SR(ADC1) &= ~ADC_SR_JEOC;
temperature = adc_read_injected(ADC1,1);
}

View File

@@ -0,0 +1,28 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = adc_injec_timtrig_irq_4ch
# Comment the following line if you _don't_ have luftboot flashed!
LDFLAGS += -Wl,-Ttext=0x8002000
CFLAGS += -std=c99
LDSCRIPT = ../lisa-m.ld
include ../../Makefile.include

View File

@@ -0,0 +1,12 @@
------------------------------------------------------------------------------
README
------------------------------------------------------------------------------
This is a simple example that sends the values read out from four ADC
channels of the STM32 to the USART2.
This example uses a timer trigger to sample the injected adc channels and
then uses an interrupt routine to retrieve the samples from the data registers.
The terminal settings for the receiving device/PC are 115200 8n1.

View File

@@ -0,0 +1,230 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
* Copyright (C) 2012 Piotr Esden-Tempski <piotr@esden.net>
* Copyright (C) 2012 Stephen Dwyer <dwyer.sc@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/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/flash.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/stm32/f1/adc.h>
#include <libopencm3/stm32/usart.h>
#include <libopencm3/stm32/timer.h>
#include <libopencm3/cm3/nvic.h>
volatile u16 temperature = 0;
volatile u16 v_refint = 0;
volatile u16 lisam_adc1 = 0;
volatile u16 lisam_adc2 = 0;
u8 channel_array[4]; /* for injected sampling, 4 channels max, for regular, 16 max */
static void usart_setup(void)
{
/* Enable clocks for GPIO port A (for GPIO_USART1_TX) and USART1. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USART2EN);
/* Setup GPIO pin GPIO_USART1_TX/GPIO9 on GPIO port A for transmit. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART2_TX);
/* Setup UART parameters. */
usart_set_baudrate(USART2, 115200);
usart_set_databits(USART2, 8);
usart_set_stopbits(USART2, USART_STOPBITS_1);
usart_set_mode(USART2, USART_MODE_TX_RX);
usart_set_parity(USART2, USART_PARITY_NONE);
usart_set_flow_control(USART2, USART_FLOWCONTROL_NONE);
/* Finally enable the USART. */
usart_enable(USART2);
}
static void gpio_setup(void)
{
/* Enable GPIO clocks. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
/* Setup the LEDs. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO8);
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO15);
/* Setup Lisa/M v2 ADC1,2 on ANALOG1 connector */
gpio_set_mode(GPIOC, GPIO_MODE_INPUT, GPIO_CNF_INPUT_ANALOG, \
GPIO3 | GPIO0 );
}
static void timer_setup(void)
{
/* Set up the timer TIM2 for injected sampling */
uint32_t timer;
volatile uint32_t *rcc_apbenr;
uint32_t rcc_apb;
timer = TIM2;
rcc_apbenr = &RCC_APB1ENR;
rcc_apb = RCC_APB1ENR_TIM2EN;
rcc_peripheral_enable_clock(rcc_apbenr, rcc_apb);
/* Time Base configuration */
timer_reset(timer);
timer_set_mode(timer, TIM_CR1_CKD_CK_INT,
TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP);
timer_set_period(timer, 0xFF);
timer_set_prescaler(timer, 0x8);
timer_set_clock_division(timer, 0x0);
/* Generate TRGO on every update. */
timer_set_master_mode(timer, TIM_CR2_MMS_UPDATE);
timer_enable_counter(timer);
}
static void irq_setup(void)
{
/* Enable the adc1_2_isr() routine */
nvic_set_priority(NVIC_ADC1_2_IRQ, 0);
nvic_enable_irq(NVIC_ADC1_2_IRQ);
}
static void adc_setup(void)
{
int i;
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_ADC1EN);
/* Make sure the ADC doesn't run during config. */
adc_off(ADC1);
/* We configure everything for one single timer triggered injected conversion with interrupt generation. */
/* While not needed for a single channel, try out scan mode which does all channels in one sweep and
* generates the interrupt/EOC/JEOC flags set at the end of all channels, not each one.
*/
adc_enable_scan_mode(ADC1);
adc_set_single_conversion_mode(ADC1);
/* We want to start the injected conversion with the TIM2 TRGO */
adc_enable_external_trigger_injected(ADC1,ADC_CR2_JEXTSEL_TIM2_TRGO);
/* Generate the ADC1_2_IRQ */
adc_enable_eoc_interrupt_injected(ADC1);
adc_set_right_aligned(ADC1);
/* We want to read the temperature sensor, so we have to enable it. */
adc_enable_temperature_sensor(ADC1);
adc_set_sample_time_on_all_channels(ADC1, ADC_SMPR_SMP_28DOT5CYC);
/* Select the channels we want to convert.
* 16=temperature_sensor, 17=Vrefint, 13=ADC1, 10=ADC2
*/
channel_array[0] = 16;
channel_array[1] = 17;
channel_array[2] = 13;
channel_array[3] = 10;
adc_set_injected_sequence(ADC1, 4, channel_array);
adc_power_on(ADC1);
/* Wait for ADC starting up. */
for (i = 0; i < 800000; i++) /* Wait a bit. */
__asm__("nop");
adc_reset_calibration(ADC1);
while ((ADC_CR2(ADC1) & ADC_CR2_RSTCAL) != 0); //added this check
adc_calibration(ADC1);
while ((ADC_CR2(ADC1) & ADC_CR2_CAL) != 0); //added this check
}
static void my_usart_print_int(u32 usart, int value)
{
s8 i;
u8 nr_digits = 0;
char buffer[25];
if (value < 0) {
usart_send_blocking(usart, '-');
value = value * -1;
}
while (value > 0) {
buffer[nr_digits++] = "0123456789"[value % 10];
value /= 10;
}
for (i = (nr_digits - 1); i >= 0; i--) {
usart_send_blocking(usart, buffer[i]);
}
//usart_send_blocking(usart, '\r');
}
int main(void)
{
rcc_clock_setup_in_hse_12mhz_out_72mhz();
gpio_setup();
usart_setup();
timer_setup();
irq_setup();
adc_setup();
gpio_set(GPIOA, GPIO8); /* LED1 off */
gpio_set(GPIOC, GPIO15); /* LED5 off */
/* Send a message on USART1. */
usart_send_blocking(USART2, 's');
usart_send_blocking(USART2, 't');
usart_send_blocking(USART2, 'm');
usart_send_blocking(USART2, '\r');
usart_send_blocking(USART2, '\n');
/* Moved the channel selection and sequence init to adc_setup() */
/* Continously convert and poll the temperature ADC. */
while (1) {
/*
* Since sampling is triggered by the timer and copying the values
* out of the data registers is handled by the interrupt routine,
* we just need to print the values and toggle the LED. It may be useful
* to buffer the adc values in some cases.
*/
my_usart_print_int(USART2, temperature);
usart_send_blocking(USART2, ' ');
my_usart_print_int(USART2, v_refint);
usart_send_blocking(USART2, ' ');
my_usart_print_int(USART2, lisam_adc1);
usart_send_blocking(USART2, ' ');
my_usart_print_int(USART2, lisam_adc2);
usart_send_blocking(USART2, '\r');
gpio_toggle(GPIOA, GPIO8); /* LED2 on */
}
return 0;
}
void adc1_2_isr(void)
{
/* Clear Injected End Of Conversion (JEOC) */
ADC_SR(ADC1) &= ~ADC_SR_JEOC;
temperature = adc_read_injected(ADC1,1);
v_refint = adc_read_injected(ADC1,2);
lisam_adc1 = adc_read_injected(ADC1,3);
lisam_adc2 = adc_read_injected(ADC1,4);
}

View File

@@ -0,0 +1,28 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = adc
# Comment the following line if you _don't_ have luftboot flashed!
LDFLAGS += -Wl,-Ttext=0x8002000
CFLAGS += -std=c99
LDSCRIPT = ../lisa-m.ld
include ../../Makefile.include

View File

@@ -0,0 +1,9 @@
------------------------------------------------------------------------------
README
------------------------------------------------------------------------------
This is a simple polling example that sends the value read out from the
temperature sensor ADC channel of the STM32 to the USART2.
The terminal settings for the receiving device/PC are 115200 8n1.

View File

@@ -0,0 +1,161 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
* Copyright (C) 2012 Piotr Esden-Tempski <piotr@esden.net>
* Copyright (C) 2012 Ken Sarkies <ksarkies@internode.on.net>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/flash.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/stm32/f1/adc.h>
#include <libopencm3/stm32/usart.h>
static void usart_setup(void)
{
/* Enable clocks for GPIO port A (for GPIO_USART1_TX) and USART1. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USART2EN);
/* Setup GPIO pin GPIO_USART1_TX/GPIO9 on GPIO port A for transmit. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART2_TX);
/* Setup UART parameters. */
usart_set_baudrate(USART2, 115200);
usart_set_databits(USART2, 8);
usart_set_stopbits(USART2, USART_STOPBITS_1);
usart_set_mode(USART2, USART_MODE_TX_RX);
usart_set_parity(USART2, USART_PARITY_NONE);
usart_set_flow_control(USART2, USART_FLOWCONTROL_NONE);
/* Finally enable the USART. */
usart_enable(USART2);
}
static void gpio_setup(void)
{
/* Enable GPIO clocks. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
/* Setup the LEDs. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO8);
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO15);
}
static void adc_setup(void)
{
int i;
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_ADC1EN);
/* Make sure the ADC doesn't run during config. */
adc_off(ADC1);
/* We configure everything for one single conversion. */
adc_disable_scan_mode(ADC1);
adc_set_single_conversion_mode(ADC1);
adc_disable_external_trigger_regular(ADC1);
adc_set_right_aligned(ADC1);
/* We want to read the temperature sensor, so we have to enable it. */
adc_enable_temperature_sensor(ADC1);
adc_set_sample_time_on_all_channels(ADC1, ADC_SMPR_SMP_28DOT5CYC);
adc_power_on(ADC1);
/* Wait for ADC starting up. */
for (i = 0; i < 800000; i++) /* Wait a bit. */
__asm__("nop");
adc_reset_calibration(ADC1);
adc_calibration(ADC1);
}
static void my_usart_print_int(u32 usart, int value)
{
s8 i;
u8 nr_digits = 0;
char buffer[25];
if (value < 0) {
usart_send_blocking(usart, '-');
value = value * -1;
}
while (value > 0) {
buffer[nr_digits++] = "0123456789"[value % 10];
value /= 10;
}
for (i = nr_digits; i >= 0; i--) {
usart_send_blocking(usart, buffer[i]);
}
usart_send_blocking(usart, '\r');
}
int main(void)
{
u8 channel_array[16];
u16 temperature = 0;
rcc_clock_setup_in_hse_12mhz_out_72mhz();
gpio_setup();
usart_setup();
adc_setup();
gpio_set(GPIOA, GPIO8); /* LED1 on */
gpio_set(GPIOC, GPIO15); /* LED2 off */
/* Send a message on USART1. */
usart_send_blocking(USART2, 's');
usart_send_blocking(USART2, 't');
usart_send_blocking(USART2, 'm');
usart_send_blocking(USART2, '\r');
usart_send_blocking(USART2, '\n');
/* Select the channel we want to convert. 16=temperature_sensor. */
channel_array[0] = 16;
adc_set_regular_sequence(ADC1, 1, channel_array);
/* Continously convert and poll the temperature ADC. */
while (1) {
/*
* Start the conversion directly (ie without a trigger).
*/
adc_start_conversion_direct(ADC1);
/* Wait for end of conversion. */
while (!(adc_eoc(ADC1)));
temperature = adc_read_regular(ADC1);
/*
* That's actually not the real temperature - you have to compute it
* as described in the datasheet.
*/
my_usart_print_int(USART2, temperature);
gpio_toggle(GPIOA, GPIO8); /* LED2 on */
}
return 0;
}

View File

@@ -0,0 +1,28 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = can
# Comment the following line if you _don't_ have luftboot flashed!
LDFLAGS += -Wl,-Ttext=0x8002000
CFLAGS += -std=c99
LDSCRIPT = ../lisa-m.ld
include ../../Makefile.include

View File

@@ -0,0 +1,4 @@
This test sets up the CAN interface on Lisa/M and transmits 8 bites every
100ms. The first byte is being incremented in each cycle. The demo also
receives messages and is displaing the first 4 bits of the first byte on the
board LEDs.

View File

@@ -0,0 +1,237 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
* Copyright (C) 2010-2011 Piotr Esden-Tempski <piotr@esden.net>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/flash.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/cm3/nvic.h>
#include <libopencm3/cm3/systick.h>
#include <libopencm3/stm32/can.h>
struct can_tx_msg {
u32 std_id;
u32 ext_id;
u8 ide;
u8 rtr;
u8 dlc;
u8 data[8];
};
struct can_rx_msg {
u32 std_id;
u32 ext_id;
u8 ide;
u8 rtr;
u8 dlc;
u8 data[8];
u8 fmi;
};
struct can_tx_msg can_tx_msg;
struct can_rx_msg can_rx_msg;
static void gpio_setup(void)
{
/* Enable Alternate Function clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
/* Enable GPIOA clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
/* Enable GPIOB clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
/* Enable GPIOC clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
/* Preconfigure LEDs. */
gpio_set(GPIOA, GPIO8); /* LED1 off */
gpio_set(GPIOB, GPIO4); /* LED2 off */
gpio_set(GPIOC, GPIO2); /* LED3 off */
gpio_set(GPIOC, GPIO5); /* LED4 off */
gpio_set(GPIOC, GPIO15); /* LED5 off */
/* Configure LED GPIOOs. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO8);
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO4);
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO2);
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO5);
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO15);
/* Configure PB4 as GPIO. */
AFIO_MAPR |= AFIO_MAPR_SWJ_CFG_FULL_SWJ_NO_JNTRST;
}
static void systick_setup(void)
{
/* 72MHz / 8 => 9000000 counts per second */
systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
/* 9000000/9000 = 1000 overflows per second - every 1ms one interrupt */
/* SysTick interrupt every N clock pulses: set reload to N-1 */
systick_set_reload(8999);
systick_interrupt_enable();
/* Start counting. */
systick_counter_enable();
}
static void can_setup(void)
{
/* Enable peripheral clocks. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_CAN1EN);
AFIO_MAPR |= AFIO_MAPR_CAN1_REMAP_PORTB;
/* Configure CAN pin: RX (input pull-up). */
gpio_set_mode(GPIO_BANK_CAN1_PB_RX, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_PULL_UPDOWN, GPIO_CAN1_PB_RX);
gpio_set(GPIO_BANK_CAN1_PB_RX, GPIO_CAN1_PB_RX);
/* Configure CAN pin: TX. */
gpio_set_mode(GPIO_BANK_CAN1_PB_TX, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_CAN1_PB_TX);
/* NVIC setup. */
nvic_enable_irq(NVIC_USB_LP_CAN_RX0_IRQ);
nvic_set_priority(NVIC_USB_LP_CAN_RX0_IRQ, 1);
/* Reset CAN. */
can_reset(CAN1);
/* CAN cell init. */
if (can_init(CAN1,
false, /* TTCM: Time triggered comm mode? */
true, /* ABOM: Automatic bus-off management? */
false, /* AWUM: Automatic wakeup mode? */
false, /* NART: No automatic retransmission? */
false, /* RFLM: Receive FIFO locked mode? */
false, /* TXFP: Transmit FIFO priority? */
CAN_BTR_SJW_1TQ,
CAN_BTR_TS1_3TQ,
CAN_BTR_TS2_4TQ,
12,
false,
false)) /* BRP+1: Baud rate prescaler */
{
gpio_set(GPIOA, GPIO8); /* LED1 off */
gpio_set(GPIOB, GPIO4); /* LED2 off */
gpio_set(GPIOC, GPIO2); /* LED3 off */
gpio_clear(GPIOC, GPIO5); /* LED4 on */
gpio_set(GPIOC, GPIO15); /* LED5 off */
/* Die because we failed to initialize. */
while (1)
__asm__("nop");
}
/* CAN filter 0 init. */
can_filter_id_mask_32bit_init(CAN1,
0, /* Filter ID */
0, /* CAN ID */
0, /* CAN ID mask */
0, /* FIFO assignment (here: FIFO0) */
true); /* Enable the filter. */
/* Enable CAN RX interrupt. */
can_enable_irq(CAN1, CAN_IER_FMPIE0);
}
void sys_tick_handler(void)
{
static int temp32 = 0;
static u8 data[8] = {0, 1, 2, 0, 0, 0, 0, 0};
/* We call this handler every 1ms so every 100ms = 0.1s
* resulting in 100Hz message rate.
*/
if (++temp32 != 100)
return;
temp32 = 0;
/* Transmit CAN frame. */
data[0]++;
if (can_transmit(CAN1,
0, /* (EX/ST)ID: CAN ID */
false, /* IDE: CAN ID extended? */
false, /* RTR: Request transmit? */
8, /* DLC: Data length */
data) == -1)
{
gpio_set(GPIOA, GPIO8); /* LED1 off */
gpio_set(GPIOB, GPIO4); /* LED2 off */
gpio_set(GPIOC, GPIO2); /* LED3 off */
gpio_set(GPIOC, GPIO5); /* LED4 off */
gpio_clear(GPIOC, GPIO15); /* LED5 on */
}
}
void usb_lp_can_rx0_isr(void)
{
u32 id, fmi;
bool ext, rtr;
u8 length, data[8];
can_receive(CAN1, 0, false, &id, &ext, &rtr, &fmi, &length, data);
if (data[0] & 1)
gpio_clear(GPIOA, GPIO8);
else
gpio_set(GPIOA, GPIO8);
if (data[0] & 2)
gpio_clear(GPIOB, GPIO4);
else
gpio_set(GPIOB, GPIO4);
if (data[0] & 4)
gpio_clear(GPIOC, GPIO2);
else
gpio_set(GPIOC, GPIO2);
if (data[0] & 8)
gpio_clear(GPIOC, GPIO5);
else
gpio_set(GPIOC, GPIO5);
can_fifo_release(CAN1, 0);
}
int main(void)
{
rcc_clock_setup_in_hse_12mhz_out_72mhz();
gpio_setup();
can_setup();
systick_setup();
while (1); /* Halt. */
return 0;
}

View File

@@ -0,0 +1,232 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
* Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/flash.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/cm3/nvic.h>
#include <libopencm3/cm3/systick.h>
#include <libopencm3/stm32/can.h>
struct can_tx_msg {
u32 std_id;
u32 ext_id;
u8 ide;
u8 rtr;
u8 dlc;
u8 data[8];
};
struct can_rx_msg {
u32 std_id;
u32 ext_id;
u8 ide;
u8 rtr;
u8 dlc;
u8 data[8];
u8 fmi;
};
struct can_tx_msg can_tx_msg;
struct can_rx_msg can_rx_msg;
void gpio_setup(void)
{
/* Enable Alternate Function clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
/* Enable GPIOA clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
/* Enable GPIOB clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
/* Enable GPIOC clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
/* Preconfigure LEDs. */
gpio_set(GPIOA, GPIO8); /* LED0 off */
gpio_set(GPIOB, GPIO4); /* LED1 off */
gpio_set(GPIOC, GPIO15); /* LED2 off */
gpio_set(GPIOC, GPIO2); /* LED3 off */
gpio_set(GPIOC, GPIO5); /* LED4 off */
/* Configure LED GPIOOs. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO8);
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO4);
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO15);
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO2);
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO5);
/* Configure PB4 as GPIO. */
AFIO_MAPR |= AFIO_MAPR_SWJ_CFG_FULL_SWJ_NO_JNTRST;
}
void systick_setup(void)
{
/* 72MHz / 8 => 9000000 counts per second */
systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
/* 9000000/9000 = 1000 overflows per second - every 1ms one interrupt */
systick_set_reload(9000);
systick_interrupt_enable();
/* Start counting. */
systick_counter_enable();
}
void can_setup(void)
{
/* Enable peripheral clocks. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_CANEN);
AFIO_MAPR = AFIO_MAPR_CAN1_REMAP_PORTB;
/* Configure CAN pin: RX (input pull-up). */
gpio_set_mode(GPIOB, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_PULL_UPDOWN, GPIO_CAN1_PB_RX);
gpio_set(GPIOB, GPIO_CAN1_PB_RX);
/* Configure CAN pin: TX. */
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_CAN1_PB_TX);
/* NVIC setup. */
nvic_enable_irq(NVIC_USB_LP_CAN_RX0_IRQ);
nvic_set_priority(NVIC_USB_LP_CAN_RX0_IRQ, 1);
/* Reset CAN. */
can_reset(CAN1);
/* CAN cell init. */
if (can_init(CAN1,
false, /* TTCM: Time triggered comm mode? */
true, /* ABOM: Automatic bus-off management? */
false, /* AWUM: Automatic wakeup mode? */
false, /* NART: No automatic retransmission? */
false, /* RFLM: Receive FIFO locked mode? */
false, /* TXFP: Transmit FIFO priority? */
CAN_BTR_SJW_1TQ,
CAN_BTR_TS1_3TQ,
CAN_BTR_TS2_4TQ,
12)) /* BRP+1: Baud rate prescaler */
{
gpio_set(GPIOA, GPIO8); /* LED0 off */
gpio_set(GPIOB, GPIO4); /* LED1 off */
gpio_set(GPIOC, GPIO15); /* LED2 off */
gpio_clear(GPIOC, GPIO2); /* LED3 on */
gpio_set(GPIOC, GPIO5); /* LED4 off */
/* Die because we failed to initialize. */
while (1)
__asm__("nop");
}
/* CAN filter 0 init. */
can_filter_id_mask_32bit_init(CAN1,
0, /* Filter ID */
0, /* CAN ID */
0, /* CAN ID mask */
0, /* FIFO assignment (here: FIFO0) */
true); /* Enable the filter. */
/* Enable CAN RX interrupt. */
can_enable_irq(CAN1, CAN_IER_FMPIE0);
}
void sys_tick_handler(void)
{
static int temp32 = 0;
static u8 data[8] = {0, 1, 2, 0, 0, 0, 0, 0};
/* We call this handler every 1ms so 1000ms = 1s on/off. */
if (++temp32 != 1000)
return;
temp32 = 0;
/* Transmit CAN frame. */
data[0]++;
if (can_transmit(CAN1,
0, /* (EX/ST)ID: CAN ID */
false, /* IDE: CAN ID extended? */
false, /* RTR: Request transmit? */
8, /* DLC: Data length */
data) == -1)
{
gpio_set(GPIOA, GPIO8); /* LED0 off */
gpio_set(GPIOB, GPIO4); /* LED1 off */
gpio_set(GPIOC, GPIO15); /* LED2 off */
gpio_set(GPIOC, GPIO2); /* LED3 off */
gpio_clear(GPIOC, GPIO5); /* LED4 on */
}
}
void usb_lp_can_rx0_isr(void)
{
u32 id, fmi;
bool ext, rtr;
u8 length, data[8];
can_receive(CAN1, 0, false, &id, &ext, &rtr, &fmi, &length, data);
if (data[0] & 1)
gpio_clear(GPIOA, GPIO8);
else
gpio_set(GPIOA, GPIO8);
if (data[0] & 2)
gpio_clear(GPIOB, GPIO4);
else
gpio_set(GPIOB, GPIO4);
if (data[0] & 4)
gpio_clear(GPIOC, GPIO15);
else
gpio_set(GPIOC, GPIO15);
if (data[0] & 8)
gpio_clear(GPIOC, GPIO2);
else
gpio_set(GPIOC, GPIO2);
can_fifo_release(CAN1, 0);
}
int main(void)
{
rcc_clock_setup_in_hse_12mhz_out_72mhz();
gpio_setup();
can_setup();
systick_setup();
while (1); /* Halt. */
return 0;
}

View File

@@ -0,0 +1,28 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = fancyblink
# Comment the following line if you _don't_ have luftboot flashed!
LDFLAGS += -Wl,-Ttext=0x8002000
CFLAGS += -std=c99
LDSCRIPT = ../lisa-m.ld
include ../../Makefile.include

View File

@@ -0,0 +1,148 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
* Copyright (C) 2011 Piotr Esden-Tempski <piotr@esden.net>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/gpio.h>
/* Set STM32 to 72 MHz. */
static void clock_setup(void)
{
rcc_clock_setup_in_hse_12mhz_out_72mhz();
/* Enable GPIOA, GPIOB, GPIOC, and AFIO clocks. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
}
static void gpio_setup(void)
{
/* LED1 */
/* Set GPIO8 (in GPIO port A) to 'output push-pull'. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO8);
/* LED2 */
/* Set GPIO15 (in GPIO port C) to 'output push-pull'. */
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO15);
/* JTAG_TRST */
/* Set GPIO4 (in GPIO port B) to 'output push-pull'. */
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO4);
AFIO_MAPR |= AFIO_MAPR_SWJ_CFG_FULL_SWJ_NO_JNTRST;
/* ADC4 */
/* Set GPIO5 (in GPIO port C) to 'output push-pull'. */
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO5);
/* ADC6 */
/* Set GPIO2 (in GPIO port C) to 'output push-pull'. */
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO2);
/* Preconfigure the LEDs. */
gpio_set(GPIOA, GPIO8);
gpio_set(GPIOC, GPIO15);
gpio_set(GPIOB, GPIO4);
gpio_set(GPIOC, GPIO5);
gpio_set(GPIOC, GPIO2);
}
static void led_set(int id, int on)
{
if (on) {
switch (id) {
case 0:
gpio_clear(GPIOA, GPIO8); /* LED1 On */
break;
case 1:
gpio_clear(GPIOB, GPIO4); /* JTAG_TRST On */
break;
case 2:
gpio_clear(GPIOC, GPIO2); /* ADC6 On */
break;
case 3:
gpio_clear(GPIOC, GPIO5); /* ADC4 On */
break;
case 4:
gpio_clear(GPIOC, GPIO15); /* LED2 On */
break;
}
} else {
switch (id) {
case 0:
gpio_set(GPIOA, GPIO8); /* LED1 On */
break;
case 1:
gpio_set(GPIOB, GPIO4); /* JTAG_TRST On */
break;
case 2:
gpio_set(GPIOC, GPIO2); /* ADC6 On */
break;
case 3:
gpio_set(GPIOC, GPIO5); /* ADC4 On */
break;
case 4:
gpio_set(GPIOC, GPIO15); /* LED2 On */
break;
}
}
}
static void led_advance(void)
{
static int state = 0;
if (state < 5) {
led_set(state, 1);
} else if (state < 10) {
led_set(state - 5, 0);
} else if (state < 15) {
led_set(14 - state, 1);
} else if (state < 20) {
led_set(19 - state, 0);
}
state++;
if(state == 20) state = 0;
}
int main(void)
{
int i;
clock_setup();
gpio_setup();
/* Blink the LEDs (PC13 and PB4) on the board. */
while (1) {
led_advance();
for (i = 0; i < 800000; i++) /* Wait a bit. */
__asm__("nop");
}
return 0;
}

View File

@@ -0,0 +1,31 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
/* Linker script for Lisa-M (STM32F103RBT6, 128K flash, 20K RAM). */
/* Define memory regions. */
MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
}
/* Include the common ld script. */
INCLUDE libopencm3_stm32f1.ld

View File

@@ -0,0 +1,28 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = spi
# Comment the following line if you _don't_ have luftboot flashed!
LDFLAGS += -Wl,-Ttext=0x8002000
CFLAGS += -std=c99
LDSCRIPT = ../lisa-m.ld
include ../../Makefile.include

View File

@@ -0,0 +1,14 @@
------------------------------------------------------------------------------
README
------------------------------------------------------------------------------
This example program demonstrates simple SPI transceive on Lisa/M 2.0 board
(http://paparazzi.enac.fr/wiki/Lisa/M_v20 for details).
The terminal settings for the receiving device/PC are 9600 8n1.
The example expects a loopback connection between the MISO and MOSI pins on
SPI1.
A counter increments and the spi sends this byte out, after which it should
come back in to the rx buffer, and the result is reported on the uart.

View File

@@ -0,0 +1,164 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
* Copyright (C) 2013 Stephen Dwyer <scdwyer@ualberta.ca>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/rcc.h>
#include <libopencm3/stm32/gpio.h>
#include <libopencm3/stm32/usart.h>
#include <libopencm3/stm32/dma.h>
#include <libopencm3/cm3/nvic.h>
#include <libopencm3/stm32/spi.h>
#include <stdio.h>
#include <errno.h>
int _write(int file, char *ptr, int len);
static void clock_setup(void)
{
rcc_clock_setup_in_hse_12mhz_out_72mhz();
/* Enable GPIOA, GPIOB, GPIOC clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR,
RCC_APB2ENR_IOPAEN | RCC_APB2ENR_IOPBEN |
RCC_APB2ENR_IOPCEN);
/* Enable clocks for GPIO port A (for GPIO_USART2_TX) and USART2. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN |
RCC_APB2ENR_AFIOEN);
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USART2EN);
/* Enable SPI1 Periph and gpio clocks */
rcc_peripheral_enable_clock(&RCC_APB2ENR,
RCC_APB2ENR_SPI1EN);
}
static void spi_setup(void) {
/* Configure GPIOs: SS=PA4, SCK=PA5, MISO=PA6 and MOSI=PA7 */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO4 |
GPIO5 |
GPIO7 );
gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT,
GPIO6);
/* Reset SPI, SPI_CR1 register cleared, SPI is disabled */
spi_reset(SPI1);
/* Set up SPI in Master mode with:
* Clock baud rate: 1/64 of peripheral clock frequency
* Clock polarity: Idle High
* Clock phase: Data valid on 2nd clock pulse
* Data frame format: 8-bit
* Frame format: MSB First
*/
spi_init_master(SPI1, SPI_CR1_BAUDRATE_FPCLK_DIV_64, SPI_CR1_CPOL_CLK_TO_1_WHEN_IDLE,
SPI_CR1_CPHA_CLK_TRANSITION_2, SPI_CR1_DFF_8BIT, SPI_CR1_MSBFIRST);
/*
* Set NSS management to software.
*
* Note:
* Setting nss high is very important, even if we are controlling the GPIO
* ourselves this bit needs to be at least set to 1, otherwise the spi
* peripheral will not send any data out.
*/
spi_enable_software_slave_management(SPI1);
spi_set_nss_high(SPI1);
/* Enable SPI1 periph. */
spi_enable(SPI1);
}
static void usart_setup(void)
{
/* Setup GPIO pin GPIO_USART2_TX and GPIO_USART2_RX. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART2_TX);
gpio_set_mode(GPIOA, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_FLOAT, GPIO_USART2_RX);
/* Setup UART parameters. */
usart_set_baudrate(USART2, 9600);
usart_set_databits(USART2, 8);
usart_set_stopbits(USART2, USART_STOPBITS_1);
usart_set_mode(USART2, USART_MODE_TX_RX);
usart_set_parity(USART2, USART_PARITY_NONE);
usart_set_flow_control(USART2, USART_FLOWCONTROL_NONE);
/* Finally enable the USART. */
usart_enable(USART2);
}
int _write(int file, char *ptr, int len)
{
int i;
if (file == 1) {
for (i = 0; i < len; i++)
usart_send_blocking(USART2, ptr[i]);
return i;
}
errno = EIO;
return -1;
}
static void gpio_setup(void)
{
/* Set GPIO8 (in GPIO port A) to 'output push-pull'. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO8);
}
int main(void)
{
int counter = 0;
u16 rx_value = 0x42;
clock_setup();
gpio_setup();
usart_setup();
spi_setup();
/* Blink the LED (PA8) on the board with every transmitted byte. */
while (1) {
/* LED on/off */
gpio_toggle(GPIOA, GPIO8);
/* printf the value that SPI should send */
printf("Counter: %i SPI Sent Byte: %i", counter, (uint8_t) counter);
/* blocking send of the byte out SPI1 */
spi_send(SPI1, (uint8_t) counter);
/* Read the byte that just came in (use a loopback between MISO and MOSI
* to get the same byte back)
*/
rx_value = spi_read(SPI1);
/* printf the byte just received */
printf(" SPI Received Byte: %i\r\n", rx_value);
counter++;
}
return 0;
}

View File

@@ -0,0 +1,28 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = spi_dma
# Comment the following line if you _don't_ have luftboot flashed!
LDFLAGS += -Wl,-Ttext=0x8002000
CFLAGS += -std=c99
LDSCRIPT = ../lisa-m.ld
include ../../Makefile.include

View File

@@ -0,0 +1,17 @@
------------------------------------------------------------------------------
README
------------------------------------------------------------------------------
This example program demonstrates SPI transceive with DMA on Lisa/M 2.0 board
(http://paparazzi.enac.fr/wiki/Lisa/M_v20 for details).
The terminal settings for the receiving device/PC are 9600 8n1.
The example expects a loopback connection between the MISO and MOSI pins on
SPI1. The DRDY and SS pins (on the Lisa/M v2.0 SPI1 connector) are used as
GPIO to time the tx and rx ISRs, respectively. Use a scope or logic analyzer.
The tx length is incremented, followed by the rx length, after which both tx
and rx lengths are decremented together. The case where rx is longer than tx
requires greater complexity to ensure all rx data is clocked in. See the adv
example for this.

View File

@@ -0,0 +1,439 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
* Copyright (C) 2013 Stephen Dwyer <scdwyer@ualberta.ca>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/rcc.h>
#include <libopencm3/stm32/gpio.h>
#include <libopencm3/stm32/usart.h>
#include <libopencm3/stm32/dma.h>
#include <libopencm3/cm3/nvic.h>
#include <libopencm3/stm32/spi.h>
#include <stdio.h>
#include <errno.h>
#ifndef USE_16BIT_TRANSFERS
#define USE_16BIT_TRANSFERS 1
#endif
/* This is for the counter state flag */
typedef enum {
TX_UP_RX_HOLD = 0,
TX_HOLD_RX_UP,
TX_DOWN_RX_DOWN
} cnt_state;
/* This is a global spi state flag */
typedef enum {
NONE = 0,
ONE,
DONE
} trans_status;
volatile trans_status transceive_status;
int _write(int file, char *ptr, int len);
static void clock_setup(void)
{
rcc_clock_setup_in_hse_12mhz_out_72mhz();
/* Enable GPIOA, GPIOB, GPIOC clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR,
RCC_APB2ENR_IOPAEN | RCC_APB2ENR_IOPBEN |
RCC_APB2ENR_IOPCEN);
/* Enable clocks for GPIO port A (for GPIO_USART2_TX) and USART2. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN |
RCC_APB2ENR_AFIOEN);
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USART2EN);
/* Enable SPI1 Periph and gpio clocks */
rcc_peripheral_enable_clock(&RCC_APB2ENR,
RCC_APB2ENR_SPI1EN);
/* Enable DMA1 clock */
rcc_peripheral_enable_clock(&RCC_AHBENR, RCC_AHBENR_DMA1EN);
}
static void spi_setup(void) {
/* Configure GPIOs: SS=PA4, SCK=PA5, MISO=PA6 and MOSI=PA7
* For now ignore the SS pin so we can use it to time the ISRs
*/
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, /* GPIO4 | */
GPIO5 |
GPIO7 );
gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT,
GPIO6);
/* Reset SPI, SPI_CR1 register cleared, SPI is disabled */
spi_reset(SPI1);
/* Explicitly disable I2S in favour of SPI operation */
SPI1_I2SCFGR = 0;
/* Set up SPI in Master mode with:
* Clock baud rate: 1/64 of peripheral clock frequency
* Clock polarity: Idle High
* Clock phase: Data valid on 2nd clock pulse
* Data frame format: 8-bit or 16-bit
* Frame format: MSB First
*/
#if USE_16BIT_TRANSFERS
spi_init_master(SPI1, SPI_CR1_BAUDRATE_FPCLK_DIV_64, SPI_CR1_CPOL_CLK_TO_1_WHEN_IDLE,
SPI_CR1_CPHA_CLK_TRANSITION_2, SPI_CR1_DFF_16BIT, SPI_CR1_MSBFIRST);
#else
spi_init_master(SPI1, SPI_CR1_BAUDRATE_FPCLK_DIV_64, SPI_CR1_CPOL_CLK_TO_1_WHEN_IDLE,
SPI_CR1_CPHA_CLK_TRANSITION_2, SPI_CR1_DFF_8BIT, SPI_CR1_MSBFIRST);
#endif
/*
* Set NSS management to software.
*
* Note:
* Setting nss high is very important, even if we are controlling the GPIO
* ourselves this bit needs to be at least set to 1, otherwise the spi
* peripheral will not send any data out.
*/
spi_enable_software_slave_management(SPI1);
spi_set_nss_high(SPI1);
/* Enable SPI1 periph. */
spi_enable(SPI1);
}
static void dma_int_enable(void) {
/* SPI1 RX on DMA1 Channel 2 */
nvic_set_priority(NVIC_DMA1_CHANNEL2_IRQ, 0);
nvic_enable_irq(NVIC_DMA1_CHANNEL2_IRQ);
/* SPI1 TX on DMA1 Channel 3 */
nvic_set_priority(NVIC_DMA1_CHANNEL3_IRQ, 0);
nvic_enable_irq(NVIC_DMA1_CHANNEL3_IRQ);
}
/* Not used in this example
static void dma_int_disable(void) {
nvic_disable_irq(NVIC_DMA1_CHANNEL2_IRQ);
nvic_disable_irq(NVIC_DMA1_CHANNEL3_IRQ);
}
*/
static void dma_setup(void)
{
dma_int_enable();
}
#if USE_16BIT_TRANSFERS
static int spi_dma_transceive(u16 *tx_buf, int tx_len, u16 *rx_buf, int rx_len)
#else
static int spi_dma_transceive(u8 *tx_buf, int tx_len, u8 *rx_buf, int rx_len)
#endif
{
/* Check for 0 length in both tx and rx */
if ((rx_len < 1) && (tx_len < 1)) {
/* return -1 as error */
return -1;
}
/* Reset DMA channels*/
dma_channel_reset(DMA1, DMA_CHANNEL2);
dma_channel_reset(DMA1, DMA_CHANNEL3);
/* Reset SPI data and status registers.
* Here we assume that the SPI peripheral is NOT
* busy any longer, i.e. the last activity was verified
* complete elsewhere in the program.
*/
volatile u8 temp_data __attribute__ ((unused));
while (SPI_SR(SPI1) & (SPI_SR_RXNE | SPI_SR_OVR)) {
temp_data = SPI_DR(SPI1);
}
/* Reset status flag appropriately (both 0 case caught above) */
transceive_status = NONE;
if (rx_len < 1) {
transceive_status = ONE;
}
if (tx_len < 1) {
transceive_status = ONE;
}
/* Set up rx dma, note it has higher priority to avoid overrun */
if (rx_len > 0) {
dma_set_peripheral_address(DMA1, DMA_CHANNEL2, (u32)&SPI1_DR);
dma_set_memory_address(DMA1, DMA_CHANNEL2, (u32)rx_buf);
dma_set_number_of_data(DMA1, DMA_CHANNEL2, rx_len);
dma_set_read_from_peripheral(DMA1, DMA_CHANNEL2);
dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL2);
#if USE_16BIT_TRANSFERS
dma_set_peripheral_size(DMA1, DMA_CHANNEL2, DMA_CCR_PSIZE_16BIT);
dma_set_memory_size(DMA1, DMA_CHANNEL2, DMA_CCR_MSIZE_16BIT);
#else
dma_set_peripheral_size(DMA1, DMA_CHANNEL2, DMA_CCR_PSIZE_8BIT);
dma_set_memory_size(DMA1, DMA_CHANNEL2, DMA_CCR_MSIZE_8BIT);
#endif
dma_set_priority(DMA1, DMA_CHANNEL2, DMA_CCR_PL_VERY_HIGH);
}
/* Set up tx dma */
if (tx_len > 0) {
dma_set_peripheral_address(DMA1, DMA_CHANNEL3, (u32)&SPI1_DR);
dma_set_memory_address(DMA1, DMA_CHANNEL3, (u32)tx_buf);
dma_set_number_of_data(DMA1, DMA_CHANNEL3, tx_len);
dma_set_read_from_memory(DMA1, DMA_CHANNEL3);
dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL3);
#if USE_16BIT_TRANSFERS
dma_set_peripheral_size(DMA1, DMA_CHANNEL3, DMA_CCR_PSIZE_16BIT);
dma_set_memory_size(DMA1, DMA_CHANNEL3, DMA_CCR_MSIZE_16BIT);
#else
dma_set_peripheral_size(DMA1, DMA_CHANNEL3, DMA_CCR_PSIZE_8BIT);
dma_set_memory_size(DMA1, DMA_CHANNEL3, DMA_CCR_MSIZE_8BIT);
#endif
dma_set_priority(DMA1, DMA_CHANNEL3, DMA_CCR_PL_HIGH);
}
/* Enable dma transfer complete interrupts */
if (rx_len > 0) {
dma_enable_transfer_complete_interrupt(DMA1, DMA_CHANNEL2);
}
if (tx_len > 0) {
dma_enable_transfer_complete_interrupt(DMA1, DMA_CHANNEL3);
}
/* Activate dma channels */
if (rx_len > 0) {
dma_enable_channel(DMA1, DMA_CHANNEL2);
}
if (tx_len > 0) {
dma_enable_channel(DMA1, DMA_CHANNEL3);
}
/* Enable the spi transfer via dma
* This will immediately start the transmission,
* after which when the receive is complete, the
* receive dma will activate
*/
if (rx_len > 0) {
spi_enable_rx_dma(SPI1);
}
if (tx_len > 0) {
spi_enable_tx_dma(SPI1);
}
return 0;
}
/* SPI receive completed with DMA */
void dma1_channel2_isr(void)
{
gpio_set(GPIOA,GPIO4);
if ((DMA1_ISR &DMA_ISR_TCIF2) != 0) {
DMA1_IFCR |= DMA_IFCR_CTCIF2;
}
dma_disable_transfer_complete_interrupt(DMA1, DMA_CHANNEL2);
spi_disable_rx_dma(SPI1);
dma_disable_channel(DMA1, DMA_CHANNEL2);
/* Increment the status to indicate one of the transfers is complete */
transceive_status++;
gpio_clear(GPIOA,GPIO4);
}
/* SPI transmit completed with DMA */
void dma1_channel3_isr(void)
{
gpio_set(GPIOB,GPIO1);
if ((DMA1_ISR &DMA_ISR_TCIF3) != 0) {
DMA1_IFCR |= DMA_IFCR_CTCIF3;
}
dma_disable_transfer_complete_interrupt(DMA1, DMA_CHANNEL3);
spi_disable_tx_dma(SPI1);
dma_disable_channel(DMA1, DMA_CHANNEL3);
/* Increment the status to indicate one of the transfers is complete */
transceive_status++;
gpio_clear(GPIOB,GPIO1);
}
static void usart_setup(void)
{
/* Setup GPIO pin GPIO_USART2_TX and GPIO_USART2_RX. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART2_TX);
gpio_set_mode(GPIOA, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_FLOAT, GPIO_USART2_RX);
/* Setup UART parameters. */
usart_set_baudrate(USART2, 9600);
usart_set_databits(USART2, 8);
usart_set_stopbits(USART2, USART_STOPBITS_1);
usart_set_mode(USART2, USART_MODE_TX_RX);
usart_set_parity(USART2, USART_PARITY_NONE);
usart_set_flow_control(USART2, USART_FLOWCONTROL_NONE);
/* Finally enable the USART. */
usart_enable(USART2);
}
int _write(int file, char *ptr, int len)
{
int i;
if (file == 1) {
for (i = 0; i < len; i++)
usart_send_blocking(USART2, ptr[i]);
return i;
}
errno = EIO;
return -1;
}
static void gpio_setup(void)
{
/* Set GPIO8 (in GPIO port A) to 'output push-pull'. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO8);
/* Use the extra pins to signal when the ISRs are running */
/* First, SPI1 - SS pin on Lisa/M v2.0 */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO4);
/* Then, SPI1 - DRDY pin on Lisa/M v2.0 */
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO1);
}
int main(void)
{
int counter_tx = 0;
int counter_rx = 0;
cnt_state counter_state = TX_UP_RX_HOLD;
int i = 0;
/* Transmit and Receive packets, set transmit to index and receive to known unused value to aid in debugging */
#if USE_16BIT_TRANSFERS
u16 tx_packet[16] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15};
u16 rx_packet[16] = {0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42};
#else
u8 tx_packet[16] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15};
u8 rx_packet[16] = {0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42};
#endif
transceive_status = DONE;
clock_setup();
gpio_setup();
usart_setup();
spi_setup();
dma_setup();
#if USE_16BIT_TRANSFERS
printf("SPI with DMA Transfer Test using 16bit option (Use loopback)\r\n\r\n");
#else
printf("SPI with DMA Transfer Test using 8bit option (Use loopback)\r\n\r\n");
#endif
/* Blink the LED (PA8) on the board with every transmitted byte. */
while (1) {
/* LED on/off */
gpio_toggle(GPIOA, GPIO8);
/* Print what is going to be sent on the SPI bus */
printf("Sending packet (tx len %02i):", counter_tx);
for (i = 0; i < counter_tx; i++)
{
printf(" 0x%02x,", tx_packet[i]);
}
printf("\r\n");
/* Start a transceive */
if (spi_dma_transceive(tx_packet, counter_tx, rx_packet, counter_rx)) {
printf("Attempted 0 length tx and rx packets\r\n");
}
/* Wait until transceive complete.
* This checks the state flag as well as follows the
* procedure on the Reference Manual (RM0008 rev 14
* Section 25.3.9 page 692, the note.)
*/
while (transceive_status != DONE)
;
while (!(SPI_SR(SPI1) & SPI_SR_TXE))
;
while (SPI_SR(SPI1) & SPI_SR_BSY)
;
/* Print what was received on the SPI bus */
printf("Received Packet (rx len %02i):", counter_rx);
for (i = 0; i < 16; i++) {
printf(" 0x%02x,", rx_packet[i]);
}
printf("\r\n\r\n");
/* Update counters
* If we use the loopback method, we can not
* have a rx length longer than the tx length.
* Testing rx lengths longer than tx lengths
* requires an actual slave device that will
* return data.
*/
switch (counter_state) {
case TX_UP_RX_HOLD:
counter_tx++;
if (counter_tx > 15) {
counter_state = TX_HOLD_RX_UP;
}
break;
case TX_HOLD_RX_UP:
counter_rx++;
if (counter_rx > 15) {
counter_state = TX_DOWN_RX_DOWN;
}
break;
case TX_DOWN_RX_DOWN:
counter_tx--;
counter_rx--;
if (counter_tx < 1) {
counter_state = TX_UP_RX_HOLD;
}
break;
default:
;
}
/* Reset receive buffer for consistency */
for (i = 0; i < 16; i++) {
rx_packet[i] = 0x42;
}
}
return 0;
}

View File

@@ -0,0 +1,28 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = spi_dma_adv
# Comment the following line if you _don't_ have luftboot flashed!
LDFLAGS += -Wl,-Ttext=0x8002000
CFLAGS += -std=c99
LDSCRIPT = ../lisa-m.ld
include ../../Makefile.include

View File

@@ -0,0 +1,17 @@
------------------------------------------------------------------------------
README
------------------------------------------------------------------------------
This example program demonstrates SPI transceive with DMA on Lisa/M 2.0 board
(http://paparazzi.enac.fr/wiki/Lisa/M_v20 for details).
The terminal settings for the receiving device/PC are 9600 8n1.
The example expects a loopback connection between the MISO and MOSI pins on
SPI1. The DRDY and SS pins (on the Lisa/M v2.0 SPI1 connector) are used as
GPIO to time the tx and rx ISRs, respectively. Use a scope or logic analyzer.
The tx length is incremented, followed by the rx length, after which the tx is
decremented, then the rx is decremented. This is repeated in a loop. In this
example, rx lengths longer than tx lengths are handled by using two dma transmits
one after the other, handled inside the tx dma ISR.

View File

@@ -0,0 +1,506 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
* Copyright (C) 2013 Stephen Dwyer <scdwyer@ualberta.ca>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/rcc.h>
#include <libopencm3/stm32/gpio.h>
#include <libopencm3/stm32/usart.h>
#include <libopencm3/stm32/dma.h>
#include <libopencm3/cm3/nvic.h>
#include <libopencm3/stm32/spi.h>
#include <stdio.h>
#include <errno.h>
#ifndef USE_16BIT_TRANSFERS
#define USE_16BIT_TRANSFERS 0
#endif
/* This is for the counter state flag */
typedef enum {
TX_UP_RX_HOLD = 0,
TX_HOLD_RX_UP,
TX_DOWN_RX_HOLD,
TX_HOLD_RX_DOWN
} cnt_state;
/* This is a global spi state flag */
typedef enum {
NONE = 0,
ONE,
DONE
} trans_status;
volatile trans_status transceive_status;
/* Global for dummy tx dma transfer */
int rx_buf_remainder = 0;
#if USE_16BIT_TRANSFERS
u16 dummy_tx_buf = 0xdd;
#else
u8 dummy_tx_buf = 0xdd;
#endif
int _write(int file, char *ptr, int len);
static void clock_setup(void)
{
rcc_clock_setup_in_hse_12mhz_out_72mhz();
/* Enable GPIOA, GPIOB, GPIOC clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR,
RCC_APB2ENR_IOPAEN | RCC_APB2ENR_IOPBEN |
RCC_APB2ENR_IOPCEN);
/* Enable clocks for GPIO port A (for GPIO_USART2_TX) and USART2. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN |
RCC_APB2ENR_AFIOEN);
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USART2EN);
/* Enable SPI1 Periph and gpio clocks */
rcc_peripheral_enable_clock(&RCC_APB2ENR,
RCC_APB2ENR_SPI1EN);
/* Enable DMA1 clock */
rcc_peripheral_enable_clock(&RCC_AHBENR, RCC_AHBENR_DMA1EN);
}
static void spi_setup(void) {
/* Configure GPIOs: SS=PA4, SCK=PA5, MISO=PA6 and MOSI=PA7
* For now ignore the SS pin so we can use it to time the ISRs
*/
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, /* GPIO4 | */
GPIO5 |
GPIO7 );
gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT,
GPIO6);
/* Reset SPI, SPI_CR1 register cleared, SPI is disabled */
spi_reset(SPI1);
/* Explicitly disable I2S in favour of SPI operation */
SPI1_I2SCFGR = 0;
/* Set up SPI in Master mode with:
* Clock baud rate: 1/64 of peripheral clock frequency
* Clock polarity: Idle High
* Clock phase: Data valid on 2nd clock pulse
* Data frame format: 8-bit or 16-bit
* Frame format: MSB First
*/
#if USE_16BIT_TRANSFERS
spi_init_master(SPI1, SPI_CR1_BAUDRATE_FPCLK_DIV_64, SPI_CR1_CPOL_CLK_TO_1_WHEN_IDLE,
SPI_CR1_CPHA_CLK_TRANSITION_2, SPI_CR1_DFF_16BIT, SPI_CR1_MSBFIRST);
#else
spi_init_master(SPI1, SPI_CR1_BAUDRATE_FPCLK_DIV_64, SPI_CR1_CPOL_CLK_TO_1_WHEN_IDLE,
SPI_CR1_CPHA_CLK_TRANSITION_2, SPI_CR1_DFF_8BIT, SPI_CR1_MSBFIRST);
#endif
/*
* Set NSS management to software.
*
* Note:
* Setting nss high is very important, even if we are controlling the GPIO
* ourselves this bit needs to be at least set to 1, otherwise the spi
* peripheral will not send any data out.
*/
spi_enable_software_slave_management(SPI1);
spi_set_nss_high(SPI1);
/* Enable SPI1 periph. */
spi_enable(SPI1);
}
static void dma_int_enable(void) {
/* SPI1 RX on DMA1 Channel 2 */
nvic_set_priority(NVIC_DMA1_CHANNEL2_IRQ, 0);
nvic_enable_irq(NVIC_DMA1_CHANNEL2_IRQ);
/* SPI1 TX on DMA1 Channel 3 */
nvic_set_priority(NVIC_DMA1_CHANNEL3_IRQ, 0);
nvic_enable_irq(NVIC_DMA1_CHANNEL3_IRQ);
}
/* Not used in this example
static void dma_int_disable(void) {
nvic_disable_irq(NVIC_DMA1_CHANNEL2_IRQ);
nvic_disable_irq(NVIC_DMA1_CHANNEL3_IRQ);
}
*/
static void dma_setup(void)
{
dma_int_enable();
}
#if USE_16BIT_TRANSFERS
static int spi_dma_transceive(u16 *tx_buf, int tx_len, u16 *rx_buf, int rx_len)
#else
static int spi_dma_transceive(u8 *tx_buf, int tx_len, u8 *rx_buf, int rx_len)
#endif
{
/* Check for 0 length in both tx and rx */
if ((rx_len < 1) && (tx_len < 1)) {
/* return -1 as error */
return -1;
}
/* Reset DMA channels*/
dma_channel_reset(DMA1, DMA_CHANNEL2);
dma_channel_reset(DMA1, DMA_CHANNEL3);
/* Reset SPI data and status registers.
* Here we assume that the SPI peripheral is NOT
* busy any longer, i.e. the last activity was verified
* complete elsewhere in the program.
*/
volatile u8 temp_data __attribute__ ((unused));
while (SPI_SR(SPI1) & (SPI_SR_RXNE | SPI_SR_OVR)) {
temp_data = SPI_DR(SPI1);
}
/* Reset status flag appropriately (both 0 case caught above) */
transceive_status = NONE;
if (rx_len < 1) {
transceive_status = ONE;
}
/* Determine tx length case to change behaviour
* If tx_len >= rx_len, then normal case, run both DMAs with normal settings
* If rx_len == 0, just don't run the rx DMA at all
* If tx_len == 0, use a dummy buf and set the tx dma to transfer the same
* amount as the rx_len, to ensure everything is clocked in
* If 0 < tx_len < rx_len, first do a normal case, then on the tx finished
* interrupt, set up a new dummyy buf tx dma transfer for the remaining
* required clock cycles (handled in tx dma complete interrupt)
*/
if ((tx_len > 0) && (tx_len < rx_len)) {
rx_buf_remainder = rx_len - tx_len;
}
/* Set up rx dma, note it has higher priority to avoid overrun */
if (rx_len > 0) {
dma_set_peripheral_address(DMA1, DMA_CHANNEL2, (u32)&SPI1_DR);
dma_set_memory_address(DMA1, DMA_CHANNEL2, (u32)rx_buf);
dma_set_number_of_data(DMA1, DMA_CHANNEL2, rx_len);
dma_set_read_from_peripheral(DMA1, DMA_CHANNEL2);
dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL2);
#if USE_16BIT_TRANSFERS
dma_set_peripheral_size(DMA1, DMA_CHANNEL2, DMA_CCR_PSIZE_16BIT);
dma_set_memory_size(DMA1, DMA_CHANNEL2, DMA_CCR_MSIZE_16BIT);
#else
dma_set_peripheral_size(DMA1, DMA_CHANNEL2, DMA_CCR_PSIZE_8BIT);
dma_set_memory_size(DMA1, DMA_CHANNEL2, DMA_CCR_MSIZE_8BIT);
#endif
dma_set_priority(DMA1, DMA_CHANNEL2, DMA_CCR_PL_VERY_HIGH);
}
/* Set up tx dma (must always run tx to get clock signal) */
if (tx_len > 0) {
/* Here we have a regular tx transfer */
dma_set_peripheral_address(DMA1, DMA_CHANNEL3, (u32)&SPI1_DR);
dma_set_memory_address(DMA1, DMA_CHANNEL3, (u32)tx_buf);
dma_set_number_of_data(DMA1, DMA_CHANNEL3, tx_len);
dma_set_read_from_memory(DMA1, DMA_CHANNEL3);
dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL3);
#if USE_16BIT_TRANSFERS
dma_set_peripheral_size(DMA1, DMA_CHANNEL3, DMA_CCR_PSIZE_16BIT);
dma_set_memory_size(DMA1, DMA_CHANNEL3, DMA_CCR_MSIZE_16BIT);
#else
dma_set_peripheral_size(DMA1, DMA_CHANNEL3, DMA_CCR_PSIZE_8BIT);
dma_set_memory_size(DMA1, DMA_CHANNEL3, DMA_CCR_MSIZE_8BIT);
#endif
dma_set_priority(DMA1, DMA_CHANNEL3, DMA_CCR_PL_HIGH);
} else {
/* Here we aren't transmitting any real data, use the dummy buffer
* and set the length to the rx_len to get all rx data in, while
* not incrementing the memory pointer
*/
dma_set_peripheral_address(DMA1, DMA_CHANNEL3, (u32)&SPI1_DR);
dma_set_memory_address(DMA1, DMA_CHANNEL3, (u32)(&dummy_tx_buf)); // Change here
dma_set_number_of_data(DMA1, DMA_CHANNEL3, rx_len); // Change here
dma_set_read_from_memory(DMA1, DMA_CHANNEL3);
dma_disable_memory_increment_mode(DMA1, DMA_CHANNEL3); // Change here
#if USE_16BIT_TRANSFERS
dma_set_peripheral_size(DMA1, DMA_CHANNEL3, DMA_CCR_PSIZE_16BIT);
dma_set_memory_size(DMA1, DMA_CHANNEL3, DMA_CCR_MSIZE_16BIT);
#else
dma_set_peripheral_size(DMA1, DMA_CHANNEL3, DMA_CCR_PSIZE_8BIT);
dma_set_memory_size(DMA1, DMA_CHANNEL3, DMA_CCR_MSIZE_8BIT);
#endif
dma_set_priority(DMA1, DMA_CHANNEL3, DMA_CCR_PL_HIGH);
}
/* Enable dma transfer complete interrupts */
if (rx_len > 0) {
dma_enable_transfer_complete_interrupt(DMA1, DMA_CHANNEL2);
}
dma_enable_transfer_complete_interrupt(DMA1, DMA_CHANNEL3);
/* Activate dma channels */
if (rx_len > 0) {
dma_enable_channel(DMA1, DMA_CHANNEL2);
}
dma_enable_channel(DMA1, DMA_CHANNEL3);
/* Enable the spi transfer via dma
* This will immediately start the transmission,
* after which when the receive is complete, the
* receive dma will activate
*/
if (rx_len > 0) {
spi_enable_rx_dma(SPI1);
}
spi_enable_tx_dma(SPI1);
return 0;
}
/* SPI receive completed with DMA */
void dma1_channel2_isr(void)
{
gpio_set(GPIOA,GPIO4);
if ((DMA1_ISR &DMA_ISR_TCIF2) != 0) {
DMA1_IFCR |= DMA_IFCR_CTCIF2;
}
dma_disable_transfer_complete_interrupt(DMA1, DMA_CHANNEL2);
spi_disable_rx_dma(SPI1);
dma_disable_channel(DMA1, DMA_CHANNEL2);
/* Increment the status to indicate one of the transfers is complete */
transceive_status++;
gpio_clear(GPIOA,GPIO4);
}
/* SPI transmit completed with DMA */
void dma1_channel3_isr(void)
{
gpio_set(GPIOB,GPIO1);
if ((DMA1_ISR &DMA_ISR_TCIF3) != 0) {
DMA1_IFCR |= DMA_IFCR_CTCIF3;
}
dma_disable_transfer_complete_interrupt(DMA1, DMA_CHANNEL3);
spi_disable_tx_dma(SPI1);
dma_disable_channel(DMA1, DMA_CHANNEL3);
/* If tx_len < rx_len, create a dummy transfer to clock in the remaining
* rx data
*/
if (rx_buf_remainder > 0) {
dma_channel_reset(DMA1, DMA_CHANNEL3);
dma_set_peripheral_address(DMA1, DMA_CHANNEL3, (u32)&SPI1_DR);
dma_set_memory_address(DMA1, DMA_CHANNEL3, (u32)(&dummy_tx_buf)); // Change here
dma_set_number_of_data(DMA1, DMA_CHANNEL3, rx_buf_remainder); // Change here
dma_set_read_from_memory(DMA1, DMA_CHANNEL3);
dma_disable_memory_increment_mode(DMA1, DMA_CHANNEL3); // Change here
#if USE_16BIT_TRANSFERS
dma_set_peripheral_size(DMA1, DMA_CHANNEL3, DMA_CCR_PSIZE_16BIT);
dma_set_memory_size(DMA1, DMA_CHANNEL3, DMA_CCR_MSIZE_16BIT);
#else
dma_set_peripheral_size(DMA1, DMA_CHANNEL3, DMA_CCR_PSIZE_8BIT);
dma_set_memory_size(DMA1, DMA_CHANNEL3, DMA_CCR_MSIZE_8BIT);
#endif
dma_set_priority(DMA1, DMA_CHANNEL3, DMA_CCR_PL_HIGH);
rx_buf_remainder = 0; // Clear the buffer remainder to disable this section later
dma_enable_transfer_complete_interrupt(DMA1, DMA_CHANNEL3);
dma_enable_channel(DMA1, DMA_CHANNEL3);
spi_enable_tx_dma(SPI1);
} else {
/* Increment the status to indicate one of the transfers is complete */
transceive_status++;
}
gpio_clear(GPIOB,GPIO1);
}
static void usart_setup(void)
{
/* Setup GPIO pin GPIO_USART2_TX and GPIO_USART2_RX. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART2_TX);
gpio_set_mode(GPIOA, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_FLOAT, GPIO_USART2_RX);
/* Setup UART parameters. */
usart_set_baudrate(USART2, 9600);
usart_set_databits(USART2, 8);
usart_set_stopbits(USART2, USART_STOPBITS_1);
usart_set_mode(USART2, USART_MODE_TX_RX);
usart_set_parity(USART2, USART_PARITY_NONE);
usart_set_flow_control(USART2, USART_FLOWCONTROL_NONE);
/* Finally enable the USART. */
usart_enable(USART2);
}
int _write(int file, char *ptr, int len)
{
int i;
if (file == 1) {
for (i = 0; i < len; i++)
usart_send_blocking(USART2, ptr[i]);
return i;
}
errno = EIO;
return -1;
}
static void gpio_setup(void)
{
/* Set GPIO8 (in GPIO port A) to 'output push-pull'. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO8);
/* Use the extra pins to signal when the ISRs are running */
/* First, SPI1 - SS pin on Lisa/M v2.0 */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO4);
/* Then, SPI1 - DRDY pin on Lisa/M v2.0 */
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO1);
}
int main(void)
{
int counter_tx = 0;
int counter_rx = 0;
cnt_state counter_state = TX_UP_RX_HOLD;
int i = 0;
/* Transmit and Receive packets, set transmit to index and receive to known unused value to aid in debugging */
#if USE_16BIT_TRANSFERS
u16 tx_packet[16] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15};
u16 rx_packet[16] = {0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42};
#else
u8 tx_packet[16] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15};
u8 rx_packet[16] = {0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42};
#endif
transceive_status = DONE;
clock_setup();
gpio_setup();
usart_setup();
spi_setup();
dma_setup();
printf("SPI with DMA Transfer Test (Use loopback)\r\n\r\n");
/* Blink the LED (PA8) on the board with every transmitted byte. */
while (1) {
/* LED on/off */
gpio_toggle(GPIOA, GPIO8);
/* Print what is going to be sent on the SPI bus */
printf("Sending packet (tx len %02i):", counter_tx);
for (i = 0; i < counter_tx; i++)
{
printf(" 0x%02x,", tx_packet[i]);
}
printf("\r\n");
/* Start a transceive */
if (spi_dma_transceive(tx_packet, counter_tx, rx_packet, counter_rx)) {
printf("Attempted 0 length tx and rx packets\r\n");
}
/* Wait until transceive complete.
* This checks the state flag as well as follows the
* procedure on the Reference Manual (RM0008 rev 14
* Section 25.3.9 page 692, the note.)
*/
while (transceive_status != DONE)
;
while (!(SPI_SR(SPI1) & SPI_SR_TXE))
;
while (SPI_SR(SPI1) & SPI_SR_BSY)
;
/* Print what was received on the SPI bus */
printf("Received Packet (rx len %02i):", counter_rx);
for (i = 0; i < 16; i++) {
printf(" 0x%02x,", rx_packet[i]);
}
printf("\r\n\r\n");
/* Update counters
* If we use the loopback method, we can not
* have a rx length longer than the tx length.
* Testing rx lengths longer than tx lengths
* requires an actual slave device that will
* return data.
*/
switch (counter_state) {
case TX_UP_RX_HOLD:
counter_tx++;
if (counter_tx > 15) {
counter_state = TX_HOLD_RX_UP;
}
break;
case TX_HOLD_RX_UP:
counter_rx++;
if (counter_rx > 15) {
counter_state = TX_DOWN_RX_HOLD;
}
break;
case TX_DOWN_RX_HOLD:
counter_tx--;
if (counter_tx < 1) {
counter_state = TX_HOLD_RX_DOWN;
}
break;
case TX_HOLD_RX_DOWN:
counter_rx--;
if (counter_rx < 1) {
counter_state = TX_UP_RX_HOLD;
}
break;
default:
;
}
/* Reset receive buffer for consistency */
for (i = 0; i < 16; i++) {
#if USE_16BIT_TRANSFERS
tx_packet[i] = (u16)i;
#else
tx_packet[i] = (u8)i;
#endif
rx_packet[i] = 0x42;
}
}
return 0;
}

View File

@@ -0,0 +1,28 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = usart
# Comment the following line if you _don't_ have luftboot flashed!
LDFLAGS += -Wl,-Ttext=0x8002000
CFLAGS += -std=c99
LDSCRIPT = ../lisa-m.ld
include ../../Makefile.include

View File

@@ -0,0 +1,12 @@
------------------------------------------------------------------------------
README
------------------------------------------------------------------------------
This example program sends some characters on USART2 on Lisa/M 2.0 board
(see http://paparazzi.enac.fr/wiki/LisaM for details).
The terminal settings for the receiving device/PC are 38400 8n1.
The sending is done in a blocking way in the code, see the usart_irq example
for a more elaborate USART example.

View File

@@ -0,0 +1,86 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/stm32/usart.h>
static void clock_setup(void)
{
rcc_clock_setup_in_hse_12mhz_out_72mhz();
/* Enable GPIOA, GPIOB, GPIOC clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR,
RCC_APB2ENR_IOPAEN | RCC_APB2ENR_IOPBEN |
RCC_APB2ENR_IOPCEN);
/* Enable clocks for GPIO port B (for GPIO_USART3_TX) and USART3. */
rcc_peripheral_enable_clock(&RCC_APB1ENR,
RCC_APB1ENR_USART2EN);
}
static void usart_setup(void)
{
/* Setup GPIO pin GPIO_USART2_TX. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART2_TX);
/* Setup UART parameters. */
usart_set_baudrate(USART2, 38400);
usart_set_databits(USART2, 8);
usart_set_stopbits(USART2, USART_STOPBITS_1);
usart_set_mode(USART2, USART_MODE_TX);
usart_set_parity(USART2, USART_PARITY_NONE);
usart_set_flow_control(USART2, USART_FLOWCONTROL_NONE);
/* Finally enable the USART. */
usart_enable(USART2);
}
static void gpio_setup(void)
{
/* Set GPIO8 (in GPIO port A) to 'output push-pull'. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO8);
}
int main(void)
{
int i, j = 0, c = 0;
clock_setup();
gpio_setup();
usart_setup();
/* Blink the LED (PA8) on the board with every transmitted byte. */
while (1) {
gpio_toggle(GPIOA, GPIO8); /* LED on/off */
usart_send_blocking(USART2, c + '0'); /* USART2: Send byte. */
c = (c == 9) ? 0 : c + 1; /* Increment c. */
if ((j++ % 80) == 0) { /* Newline after line full. */
usart_send_blocking(USART2, '\r');
usart_send_blocking(USART2, '\n');
}
for (i = 0; i < 800000; i++) /* Wait a bit. */
__asm__("nop");
}
return 0;
}

View File

@@ -0,0 +1,28 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = usart_dma
# Comment the following line if you _don't_ have luftboot flashed!
LDFLAGS += -Wl,-Ttext=0x8002000
CFLAGS += -std=c99
LDSCRIPT = ../lisa-m.ld
include ../../Makefile.include

View File

@@ -0,0 +1,199 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/stm32/usart.h>
#include <libopencm3/stm32/f1/dma.h>
#include <libopencm3/cm3/nvic.h>
static void clock_setup(void)
{
rcc_clock_setup_in_hse_12mhz_out_72mhz();
/* Enable GPIOA, GPIOB, GPIOC clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR,
RCC_APB2ENR_IOPAEN | RCC_APB2ENR_IOPBEN |
RCC_APB2ENR_IOPCEN);
/* Enable clocks for GPIO port B (for GPIO_USART3_TX) and USART3. */
rcc_peripheral_enable_clock(&RCC_APB1ENR,
RCC_APB1ENR_USART2EN);
/* Enable DMA1 clock */
rcc_peripheral_enable_clock(&RCC_AHBENR, RCC_AHBENR_DMA1EN);
}
static void usart_setup(void)
{
/* Setup GPIO pin GPIO_USART2_TX and GPIO_USART2_RX. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART2_TX);
gpio_set_mode(GPIOA, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_FLOAT, GPIO_USART2_RX);
/* Setup UART parameters. */
usart_set_baudrate(USART2, 38400);
usart_set_databits(USART2, 8);
usart_set_stopbits(USART2, USART_STOPBITS_1);
usart_set_mode(USART2, USART_MODE_TX_RX);
usart_set_parity(USART2, USART_PARITY_NONE);
usart_set_flow_control(USART2, USART_FLOWCONTROL_NONE);
/* Finally enable the USART. */
usart_enable(USART2);
nvic_set_priority(NVIC_DMA1_CHANNEL7_IRQ, 0);
nvic_enable_irq(NVIC_DMA1_CHANNEL7_IRQ);
nvic_set_priority(NVIC_DMA1_CHANNEL6_IRQ, 0);
nvic_enable_irq(NVIC_DMA1_CHANNEL6_IRQ);
}
static void dma_write(char *data, int size)
{
/*
* Using channel 7 for USART2_TX
*/
/* Reset DMA channel*/
dma_channel_reset(DMA1, DMA_CHANNEL7);
dma_set_peripheral_address(DMA1, DMA_CHANNEL7, (u32)&USART2_DR);
dma_set_memory_address(DMA1, DMA_CHANNEL7, (u32)data);
dma_set_number_of_data(DMA1, DMA_CHANNEL7, size);
dma_set_read_from_memory(DMA1, DMA_CHANNEL7);
dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL7);
dma_set_peripheral_size(DMA1, DMA_CHANNEL7, DMA_CCR_PSIZE_8BIT);
dma_set_memory_size(DMA1, DMA_CHANNEL7, DMA_CCR_MSIZE_8BIT);
dma_set_priority(DMA1, DMA_CHANNEL7, DMA_CCR_PL_VERY_HIGH);
dma_enable_transfer_complete_interrupt(DMA1, DMA_CHANNEL7);
dma_enable_channel(DMA1, DMA_CHANNEL7);
usart_enable_tx_dma(USART2);
}
volatile int transfered = 0;
void dma1_channel7_isr(void)
{
if ((DMA1_ISR &DMA_ISR_TCIF7) != 0) {
DMA1_IFCR |= DMA_IFCR_CTCIF7;
transfered = 1;
}
dma_disable_transfer_complete_interrupt(DMA1, DMA_CHANNEL7);
usart_disable_tx_dma(USART2);
dma_disable_channel(DMA1, DMA_CHANNEL7);
}
static void dma_read(char *data, int size)
{
/*
* Using channel 6 for USART2_RX
*/
/* Reset DMA channel*/
dma_channel_reset(DMA1, DMA_CHANNEL6);
dma_set_peripheral_address(DMA1, DMA_CHANNEL6, (u32)&USART2_DR);
dma_set_memory_address(DMA1, DMA_CHANNEL6, (u32)data);
dma_set_number_of_data(DMA1, DMA_CHANNEL6, size);
dma_set_read_from_peripheral(DMA1, DMA_CHANNEL6);
dma_enable_memory_increment_mode(DMA1, DMA_CHANNEL6);
dma_set_peripheral_size(DMA1, DMA_CHANNEL6, DMA_CCR_PSIZE_8BIT);
dma_set_memory_size(DMA1, DMA_CHANNEL6, DMA_CCR_MSIZE_8BIT);
dma_set_priority(DMA1, DMA_CHANNEL6, DMA_CCR_PL_HIGH);
dma_enable_transfer_complete_interrupt(DMA1, DMA_CHANNEL6);
dma_enable_channel(DMA1, DMA_CHANNEL6);
usart_enable_rx_dma(USART2);
}
volatile int received = 0;
void dma1_channel6_isr(void)
{
if ((DMA1_ISR &DMA_ISR_TCIF6) != 0) {
DMA1_IFCR |= DMA_IFCR_CTCIF6;
received = 1;
}
dma_disable_transfer_complete_interrupt(DMA1, DMA_CHANNEL6);
usart_disable_rx_dma(USART2);
dma_disable_channel(DMA1, DMA_CHANNEL6);
}
static void gpio_setup(void)
{
/* Set GPIO8 (in GPIO port A) to 'output push-pull'. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO8);
}
int main(void)
{
char tx[10] = "abcdefg\r\n";
int tx_len = 10;
char rx[7] = "bcdefg";
int rx_len = 6;
clock_setup();
gpio_setup();
usart_setup();
transfered = 0;
dma_write(tx, tx_len);
received = 0;
dma_read(rx, rx_len);
/* Blink the LED (PA8) on the board with every transmitted byte. */
while (1) {
gpio_toggle(GPIOA, GPIO8); /* LED on/off */
while ( transfered != 1) {
if (received == 1) {
tx[1] = rx[0];
tx[2] = rx[1];
tx[3] = rx[2];
tx[4] = rx[3];
tx[5] = rx[4];
tx[6] = rx[5];
received = 0;
dma_read(rx, rx_len);
}
}
tx[0]++;
if (tx[0] > 'z') tx[0] = 'a';
transfered = 0;
dma_write(tx, tx_len);
}
return 0;
}

View File

@@ -0,0 +1,86 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/stm32/usart.h>
void clock_setup(void)
{
rcc_clock_setup_in_hse_12mhz_out_72mhz();
/* Enable GPIOA, GPIOB, GPIOC clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR,
RCC_APB2ENR_IOPAEN | RCC_APB2ENR_IOPBEN |
RCC_APB2ENR_IOPCEN);
/* Enable clocks for GPIO port B (for GPIO_USART3_TX) and USART3. */
rcc_peripheral_enable_clock(&RCC_APB1ENR,
RCC_APB1ENR_USART2EN);
}
void usart_setup(void)
{
/* Setup GPIO pin GPIO_USART2_TX. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART2_TX);
/* Setup UART parameters. */
usart_set_baudrate(USART2, 38400);
usart_set_databits(USART2, 8);
usart_set_stopbits(USART2, USART_STOPBITS_1);
usart_set_mode(USART2, USART_MODE_TX);
usart_set_parity(USART2, USART_PARITY_NONE);
usart_set_flow_control(USART2, USART_FLOWCONTROL_NONE);
/* Finally enable the USART. */
usart_enable(USART2);
}
void gpio_setup(void)
{
/* Set GPIO8 (in GPIO port A) to 'output push-pull'. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO8);
}
int main(void)
{
int i, j = 0, c = 0;
clock_setup();
gpio_setup();
usart_setup();
/* Blink the LED (PA8) on the board with every transmitted byte. */
while (1) {
gpio_toggle(GPIOA, GPIO8); /* LED on/off */
usart_send_blocking(USART2, c + '0'); /* USART2: Send byte. */
c = (c == 9) ? 0 : c + 1; /* Increment c. */
if ((j++ % 80) == 0) { /* Newline after line full. */
usart_send_blocking(USART2, '\r');
usart_send_blocking(USART2, '\n');
}
for (i = 0; i < 800000; i++) /* Wait a bit. */
__asm__("nop");
}
return 0;
}

View File

@@ -0,0 +1,28 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = usart_irq
# Comment the following line if you _don't_ have luftboot flashed!
LDFLAGS += -Wl,-Ttext=0x8002000
CFLAGS += -std=c99
LDSCRIPT = ../lisa-m.ld
include ../../Makefile.include

View File

@@ -0,0 +1,126 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/stm32/usart.h>
#include <libopencm3/cm3/nvic.h>
static void clock_setup(void)
{
rcc_clock_setup_in_hse_12mhz_out_72mhz();
/* Enable GPIOA clock (for LED GPIOs). */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN | RCC_APB2ENR_IOPCEN);
/* Enable clocks for GPIO port A (for GPIO_USART2_TX) and USART2. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN |
RCC_APB2ENR_AFIOEN);
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USART2EN);
}
static void usart_setup(void)
{
/* Enable the USART2 interrupt. */
nvic_enable_irq(NVIC_USART2_IRQ);
/* Setup GPIO pin GPIO_USART2_TX on GPIO port A for transmit. */
gpio_set_mode(GPIO_BANK_USART2_TX, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART2_TX);
/* Setup GPIO pin GPIO_USART2_RX on GPIO port A for receive. */
gpio_set_mode(GPIO_BANK_USART2_RX, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_FLOAT, GPIO_USART2_RX);
/* Setup UART parameters. */
usart_set_baudrate(USART2, 230400);
usart_set_databits(USART2, 8);
usart_set_stopbits(USART2, USART_STOPBITS_1);
usart_set_parity(USART2, USART_PARITY_NONE);
usart_set_flow_control(USART2, USART_FLOWCONTROL_NONE);
usart_set_mode(USART2, USART_MODE_TX_RX);
/* Enable USART2 Receive interrupt. */
USART_CR1(USART2) |= USART_CR1_RXNEIE;
/* Finally enable the USART. */
usart_enable(USART2);
}
static void gpio_setup(void)
{
gpio_set(GPIOA, GPIO8);
/* Setup GPIO8 (in GPIO port A) for LED use. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO8);
gpio_set(GPIOC, GPIO15);
/* Setup GPIO15 (in GPIO port C) for LED use. */
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO15);
}
void usart2_isr(void)
{
static u8 data = 'A';
/* Check if we were called because of RXNE. */
if (((USART_CR1(USART2) & USART_CR1_RXNEIE) != 0) &&
((USART_SR(USART2) & USART_SR_RXNE) != 0)) {
/* Indicate that we got data. */
gpio_toggle(GPIOA, GPIO8);
/* Retrieve the data from the peripheral. */
data = usart_recv(USART2);
/* Enable transmit interrupt so it sends back the data. */
USART_CR1(USART2) |= USART_CR1_TXEIE;
}
/* Check if we were called because of TXE. */
if (((USART_CR1(USART2) & USART_CR1_TXEIE) != 0) &&
((USART_SR(USART2) & USART_SR_TXE) != 0)) {
/* Indicate that we are sending out data. */
gpio_toggle(GPIOC, GPIO15);
/* Put data into the transmit register. */
usart_send(USART2, data);
/* Disable the TXE interrupt as we don't need it anymore. */
USART_CR1(USART2) &= ~USART_CR1_TXEIE;
}
}
int main(void)
{
clock_setup();
gpio_setup();
usart_setup();
/* Wait forever and do nothing. */
while (1)
__asm__("nop");
return 0;
}

View File

@@ -0,0 +1,28 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = usart_irq_printf
# Comment the following line if you _don't_ have luftboot flashed!
LDFLAGS += -Wl,-Ttext=0x8002000
CFLAGS += -std=c99
LDSCRIPT = ../lisa-m.ld
include ../../Makefile.include

View File

@@ -0,0 +1,274 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>,
* Copyright (C) 2011 Piotr Esden-Tempski <piotr@esden.net>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/stm32/usart.h>
#include <libopencm3/cm3/nvic.h>
#include <libopencm3/cm3/systick.h>
#include <stdio.h>
#include <errno.h>
/******************************************************************************
* Simple ringbuffer implementation from open-bldc's libgovernor that
* you can find at:
* https://github.com/open-bldc/open-bldc/tree/master/source/libgovernor
*****************************************************************************/
typedef s32 ring_size_t;
struct ring {
u8 *data;
ring_size_t size;
u32 begin;
u32 end;
};
#define RING_SIZE(RING) ((RING)->size - 1)
#define RING_DATA(RING) (RING)->data
#define RING_EMPTY(RING) ((RING)->begin == (RING)->end)
int _write(int file, char *ptr, int len);
static void ring_init(struct ring *ring, u8 *buf, ring_size_t size)
{
ring->data = buf;
ring->size = size;
ring->begin = 0;
ring->end = 0;
}
static s32 ring_write_ch(struct ring *ring, u8 ch)
{
if (((ring->end + 1) % ring->size) != ring->begin) {
ring->data[ring->end++] = ch;
ring->end %= ring->size;
return (u32)ch;
}
return -1;
}
static s32 ring_write(struct ring *ring, u8 *data, ring_size_t size)
{
s32 i;
for (i = 0; i < size; i++) {
if (ring_write_ch(ring, data[i]) < 0)
return -i;
}
return i;
}
static s32 ring_read_ch(struct ring *ring, u8 *ch)
{
s32 ret = -1;
if (ring->begin != ring->end) {
ret = ring->data[ring->begin++];
ring->begin %= ring->size;
if (ch)
*ch = ret;
}
return ret;
}
/* Not used!
static s32 ring_read(struct ring *ring, u8 *data, ring_size_t size)
{
s32 i;
for (i = 0; i < size; i++) {
if (ring_read_ch(ring, data + i) < 0)
return i;
}
return -i;
}
*/
/******************************************************************************
* The example implementation
*****************************************************************************/
#define BUFFER_SIZE 1024
struct ring output_ring;
u8 output_ring_buffer[BUFFER_SIZE];
static void clock_setup(void)
{
rcc_clock_setup_in_hse_12mhz_out_72mhz();
/* Enable GPIOA clock (for LED GPIOs). */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
/* Enable clocks for GPIO port A (for GPIO_USART2_TX) and USART2. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN |
RCC_APB2ENR_AFIOEN);
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USART2EN);
}
static void usart_setup(void)
{
/* Initialize output ring buffer. */
ring_init(&output_ring, output_ring_buffer, BUFFER_SIZE);
/* Enable the USART2 interrupt. */
nvic_enable_irq(NVIC_USART2_IRQ);
/* Setup GPIO pin GPIO_USART2_TX on GPIO port A for transmit. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART2_TX);
/* Setup GPIO pin GPIO_USART2_RX on GPIO port A for receive. */
gpio_set_mode(GPIOA, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_FLOAT, GPIO_USART2_RX);
/* Setup UART parameters. */
usart_set_baudrate(USART2, 230400);
usart_set_databits(USART2, 8);
usart_set_stopbits(USART2, USART_STOPBITS_1);
usart_set_parity(USART2, USART_PARITY_NONE);
usart_set_flow_control(USART2, USART_FLOWCONTROL_NONE);
usart_set_mode(USART2, USART_MODE_TX_RX);
/* Enable USART2 Receive interrupt. */
USART_CR1(USART2) |= USART_CR1_RXNEIE;
/* Finally enable the USART. */
usart_enable(USART2);
}
static void gpio_setup(void)
{
gpio_set(GPIOA, GPIO8);
/* Setup GPIO8 (in GPIO port A) for LED use. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO8);
}
void usart2_isr(void)
{
/* Check if we were called because of RXNE. */
if (((USART_CR1(USART2) & USART_CR1_RXNEIE) != 0) &&
((USART_SR(USART2) & USART_SR_RXNE) != 0)) {
/* Indicate that we got data. */
gpio_toggle(GPIOA, GPIO8);
/* Retrieve the data from the peripheral. */
ring_write_ch(&output_ring, usart_recv(USART2));
/* Enable transmit interrupt so it sends back the data. */
USART_CR1(USART2) |= USART_CR1_TXEIE;
}
/* Check if we were called because of TXE. */
if (((USART_CR1(USART2) & USART_CR1_TXEIE) != 0) &&
((USART_SR(USART2) & USART_SR_TXE) != 0)) {
s32 data;
data = ring_read_ch(&output_ring, NULL);
if (data == -1) {
/* Disable the TXE interrupt, it's no longer needed. */
USART_CR1(USART2) &= ~USART_CR1_TXEIE;
} else {
/* Put data into the transmit register. */
usart_send(USART2, data);
}
}
}
int _write(int file, char *ptr, int len)
{
int ret;
if (file == 1) {
ret = ring_write(&output_ring, (u8 *)ptr, len);
if (ret < 0)
ret = -ret;
USART_CR1(USART2) |= USART_CR1_TXEIE;
return ret;
}
errno = EIO;
return -1;
}
static void systick_setup(void)
{
/* 72MHz / 8 => 9000000 counts per second. */
systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
/* 9000000/9000 = 1000 overflows per second - every 1ms one interrupt */
/* SysTick interrupt every N clock pulses: set reload to N-1 */
systick_set_reload(8999);
systick_interrupt_enable();
/* Start counting. */
systick_counter_enable();
}
void sys_tick_handler(void)
{
static int counter = 0;
static float fcounter = 0.0;
static double dcounter = 0.0;
static u32 temp32 = 0;
temp32++;
/*
* We call this handler every 1ms so we are sending hello world
* every 10ms / 100Hz.
*/
if (temp32 == 10) {
printf("Hello World! %i %f %f\r\n", counter, fcounter,
dcounter);
counter++;
fcounter += 0.01;
dcounter += 0.01;
temp32 = 0;
}
}
int main(void)
{
clock_setup();
gpio_setup();
usart_setup();
systick_setup();
while (1)
__asm__("nop");
return 0;
}

View File

@@ -0,0 +1,28 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = usart_printf
# Comment the following line if you _don't_ have luftboot flashed!
LDFLAGS += -Wl,-Ttext=0x8002000
CFLAGS += -std=c99
LDSCRIPT = ../lisa-m.ld
include ../../Makefile.include

View File

@@ -0,0 +1,108 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>,
* Copyright (C) 2011-2012 Piotr Esden-Tempski <piotr@esden.net>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/stm32/usart.h>
#include <libopencm3/cm3/nvic.h>
#include <stdio.h>
#include <errno.h>
int _write(int file, char *ptr, int len);
static void clock_setup(void)
{
rcc_clock_setup_in_hse_12mhz_out_72mhz();
/* Enable GPIOA clock (for LED GPIOs). */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
/* Enable clocks for GPIO port A (for GPIO_USART2_TX) and USART2. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN |
RCC_APB2ENR_AFIOEN);
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USART2EN);
}
static void usart_setup(void)
{
/* Setup GPIO pin GPIO_USART2_RE_TX on GPIO port B for transmit. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART2_TX);
/* Setup UART parameters. */
usart_set_baudrate(USART2, 230400);
usart_set_databits(USART2, 8);
usart_set_stopbits(USART2, USART_STOPBITS_1);
usart_set_parity(USART2, USART_PARITY_NONE);
usart_set_flow_control(USART2, USART_FLOWCONTROL_NONE);
usart_set_mode(USART2, USART_MODE_TX);
/* Finally enable the USART. */
usart_enable(USART2);
}
static void gpio_setup(void)
{
gpio_set(GPIOA, GPIO8);
/* Setup GPIO8 (in GPIO port A) for LED use. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO8);
}
int _write(int file, char *ptr, int len)
{
int i;
if (file == 1) {
for (i = 0; i < len; i++)
usart_send_blocking(USART2, ptr[i]);
return i;
}
errno = EIO;
return -1;
}
int main(void)
{
int counter = 0;
float fcounter = 0.0;
double dcounter = 0.0;
clock_setup();
gpio_setup();
usart_setup();
/*
* Write Hello World, an integer, float and double all over
* again while incrementing the numbers.
*/
while (1) {
gpio_toggle(GPIOA, GPIO8);
printf("Hello World! %i %f %f\r\n", counter, fcounter,
dcounter);
counter++;
fcounter += 0.01;
dcounter += 0.01;
}
return 0;
}

View File

@@ -0,0 +1,25 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = fancyblink
LDSCRIPT = ../mb525.ld
include ../../Makefile.include

View File

@@ -0,0 +1,10 @@
------------------------------------------------------------------------------
README
------------------------------------------------------------------------------
This is a blink example program using libopencm3.
It's intended for the ST STM32-based MB525 eval board (see
http://www.st.com/stonline/products/literature/um/13472.htm for details).
It should blink the LEDs on the board.

View File

@@ -0,0 +1,76 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>,
* Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/gpio.h>
static void clock_setup(void)
{
rcc_clock_setup_in_hse_8mhz_out_72mhz();
/* Enable GPIOC clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
}
static void gpio_setup(void)
{
/* Set GPIO6/7/8/9 (in GPIO port C) to 'output push-pull'. */
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO6 | GPIO7 | GPIO8 | GPIO9);
}
int main(void)
{
int i;
clock_setup();
gpio_setup();
/* Blink the LEDs on the board. */
gpio_set(GPIOC, GPIO6);
while (1) {
gpio_toggle(GPIOC, GPIO6); /* LED on/off */
gpio_toggle(GPIOC, GPIO7); /* LED on/off */
for (i = 0; i < 4000000; i++) /* Wait a bit. */
__asm__("nop");
gpio_toggle(GPIOC, GPIO7); /* LED on/off */
gpio_toggle(GPIOC, GPIO8); /* LED on/off */
for (i = 0; i < 4000000; i++) /* Wait a bit. */
__asm__("nop");
gpio_toggle(GPIOC, GPIO8); /* LED on/off */
gpio_toggle(GPIOC, GPIO9); /* LED on/off */
for (i = 0; i < 4000000; i++) /* Wait a bit. */
__asm__("nop");
gpio_toggle(GPIOC, GPIO8); /* LED on/off */
gpio_toggle(GPIOC, GPIO9); /* LED on/off */
for (i = 0; i < 4000000; i++) /* Wait a bit. */
__asm__("nop");
gpio_toggle(GPIOC, GPIO7); /* LED on/off */
gpio_toggle(GPIOC, GPIO8); /* LED on/off */
for (i = 0; i < 4000000; i++) /* Wait a bit. */
__asm__("nop");
gpio_toggle(GPIOC, GPIO6); /* LED on/off */
gpio_toggle(GPIOC, GPIO7); /* LED on/off */
for (i = 0; i < 4000000; i++) /* Wait a bit. */
__asm__("nop");
}
return 0;
}

View File

@@ -0,0 +1,32 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
/* TODO: Fix description and sizes. */
/* Linker script for Olimex STM32-H103 (STM32F103RBT6, 128K flash, 20K RAM). */
/* Define memory regions. */
MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
}
/* Include the common ld script. */
INCLUDE libopencm3_stm32f1.ld

View File

@@ -0,0 +1,25 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = pwmleds
LDSCRIPT = ../mb525.ld
include ../../Makefile.include

View File

@@ -0,0 +1,9 @@
------------------------------------------------------------------------------
README
------------------------------------------------------------------------------
This is a PWM based LED fading example using libopencm3.
It's intended for the ST STM32-based MB525 eval board (see
http://www.st.com/stonline/products/literature/um/13472.htm for details).

View File

@@ -0,0 +1,497 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/stm32/timer.h>
// #define COMPARE
// #define MOVING_FADE
#define KITT
#ifdef COMPARE
#define GAMMA_LINEAR
#define GAMMA_1_3
#define GAMMA_2_5
#define GAMMA_3_0
#endif
#ifdef MOVING_FADE
#define GAMMA_2_2
#define GAMMA_TABLE gamma_table_2_2
#endif
#ifdef KITT
#define GAMMA_2_5
#define GAMMA_TABLE gamma_table_2_5
#endif
/*
* Gamma correction table
*
* The nonlinear tables are calculating with the function:
* Iout = Iin ** gamma
*/
#ifdef GAMMA_LINEAR
static const u16 gamma_table_linear[] = {
1, 4, 9, 17, 26, 37, 51, 67,
84, 104, 126, 149, 175, 203, 233, 265,
299, 334, 372, 412, 454, 499, 545, 593,
643, 695, 749, 805, 864, 924, 986, 1050,
1116, 1185, 1255, 1327, 1402, 1478, 1556, 1637,
1719, 1803, 1890, 1978, 2068, 2161, 2255, 2352,
2450, 2550, 2653, 2757, 2864, 2972, 3082, 3195,
3309, 3426, 3544, 3664, 3787, 3911, 4038, 4166,
4296, 4429, 4563, 4700, 4838, 4978, 5121, 5265,
5411, 5560, 5710, 5862, 6017, 6173, 6331, 6492,
6654, 6818, 6985, 7153, 7323, 7495, 7670, 7846,
8024, 8204, 8387, 8571, 8757, 8945, 9135, 9327,
9521, 9718, 9916, 10116, 10318, 10522, 10728, 10936,
11146, 11358, 11572, 11788, 12006, 12226, 12448, 12672,
12897, 13125, 13355, 13587, 13821, 14057, 14294, 14534,
14776, 15020, 15265, 15513, 15763, 16014, 16268, 16524,
16781, 17041, 17302, 17566, 17831, 18099, 18368, 18640,
18913, 19189, 19466, 19745, 20027, 20310, 20595, 20883,
21172, 21463, 21756, 22051, 22349, 22648, 22949, 23252,
23557, 23864, 24173, 24484, 24797, 25112, 25429, 25748,
26069, 26391, 26716, 27043, 27372, 27702, 28035, 28370,
28707, 29045, 29386, 29728, 30073, 30419, 30768, 31118,
31471, 31825, 32182, 32540, 32900, 33263, 33627, 33993,
34361, 34731, 35104, 35478, 35854, 36232, 36612, 36994,
37378, 37764, 38152, 38542, 38933, 39327, 39723, 40121,
40521, 40922, 41326, 41732, 42139, 42549, 42960, 43374,
43789, 44207, 44626, 45048, 45471, 45896, 46324, 46753,
47184, 47617, 48052, 48490, 48929, 49370, 49813, 50258,
50705, 51154, 51604, 52057, 52512, 52969, 53428, 53888,
54351, 54816, 55282, 55751, 56222, 56694, 57169, 57645,
58123, 58604, 59086, 59570, 60057, 60545, 61035, 61527,
62021, 62517, 63016, 63516, 64018, 64521, 65027, 65535,
};
#endif
#ifdef GAMMA_1_3
static const u16 gamma_table_1_3[] = {
/* Gamma 1.3 */
0, 49, 120, 203, 296, 395, 501, 612,
728, 848, 973, 1101, 1233, 1368, 1506, 1648,
1792, 1939, 2088, 2241, 2395, 2552, 2711, 2872,
3036, 3201, 3369, 3538, 3709, 3882, 4057, 4234,
4412, 4592, 4774, 4957, 5142, 5329, 5517, 5706,
5897, 6090, 6283, 6479, 6675, 6873, 7072, 7273,
7475, 7678, 7882, 8088, 8294, 8502, 8711, 8922,
9133, 9346, 9559, 9774, 9990, 10207, 10425, 10644,
10864, 11086, 11308, 11531, 11755, 11981, 12207, 12434,
12662, 12891, 13121, 13352, 13584, 13817, 14051, 14285,
14521, 14757, 14994, 15233, 15472, 15712, 15952, 16194,
16436, 16679, 16923, 17168, 17414, 17660, 17908, 18156,
18405, 18654, 18905, 19156, 19408, 19660, 19914, 20168,
20423, 20679, 20935, 21192, 21450, 21708, 21968, 22228,
22488, 22750, 23012, 23275, 23538, 23802, 24067, 24332,
24599, 24865, 25133, 25401, 25670, 25939, 26209, 26480,
26751, 27023, 27296, 27569, 27843, 28118, 28393, 28669,
28945, 29222, 29500, 29778, 30057, 30336, 30616, 30897,
31178, 31460, 31742, 32025, 32308, 32592, 32877, 33162,
33448, 33734, 34021, 34309, 34597, 34885, 35175, 35464,
35754, 36045, 36337, 36628, 36921, 37214, 37507, 37801,
38096, 38391, 38686, 38982, 39279, 39576, 39874, 40172,
40471, 40770, 41070, 41370, 41670, 41972, 42273, 42576,
42878, 43181, 43485, 43789, 44094, 44399, 44705, 45011,
45317, 45625, 45932, 46240, 46549, 46858, 47167, 47477,
47787, 48098, 48409, 48721, 49034, 49346, 49659, 49973,
50287, 50602, 50917, 51232, 51548, 51864, 52181, 52498,
52816, 53134, 53452, 53771, 54091, 54411, 54731, 55052,
55373, 55694, 56016, 56339, 56662, 56985, 57309, 57633,
57957, 58282, 58608, 58933, 59260, 59586, 59913, 60241,
60569, 60897, 61226, 61555, 61884, 62214, 62545, 62875,
63206, 63538, 63870, 64202, 64535, 64868, 65201, 65535,
};
#endif
#ifdef GAMMA_2_2
static const u16 gamma_table_2_2[] = {
0, 0, 2, 4, 7, 11, 17, 24,
32, 42, 53, 65, 79, 94, 111, 129,
148, 169, 192, 216, 242, 270, 299, 330,
362, 396, 432, 469, 508, 549, 591, 635,
681, 729, 779, 830, 883, 938, 995, 1053,
1113, 1175, 1239, 1305, 1373, 1443, 1514, 1587,
1663, 1740, 1819, 1900, 1983, 2068, 2155, 2243,
2334, 2427, 2521, 2618, 2717, 2817, 2920, 3024,
3131, 3240, 3350, 3463, 3578, 3694, 3813, 3934,
4057, 4182, 4309, 4438, 4570, 4703, 4838, 4976,
5115, 5257, 5401, 5547, 5695, 5845, 5998, 6152,
6309, 6468, 6629, 6792, 6957, 7124, 7294, 7466,
7640, 7816, 7994, 8175, 8358, 8543, 8730, 8919,
9111, 9305, 9501, 9699, 9900, 10102, 10307, 10515,
10724, 10936, 11150, 11366, 11585, 11806, 12029, 12254,
12482, 12712, 12944, 13179, 13416, 13655, 13896, 14140,
14386, 14635, 14885, 15138, 15394, 15652, 15912, 16174,
16439, 16706, 16975, 17247, 17521, 17798, 18077, 18358,
18642, 18928, 19216, 19507, 19800, 20095, 20393, 20694,
20996, 21301, 21609, 21919, 22231, 22546, 22863, 23182,
23504, 23829, 24156, 24485, 24817, 25151, 25487, 25826,
26168, 26512, 26858, 27207, 27558, 27912, 28268, 28627,
28988, 29351, 29717, 30086, 30457, 30830, 31206, 31585,
31966, 32349, 32735, 33124, 33514, 33908, 34304, 34702,
35103, 35507, 35913, 36321, 36732, 37146, 37562, 37981,
38402, 38825, 39252, 39680, 40112, 40546, 40982, 41421,
41862, 42306, 42753, 43202, 43654, 44108, 44565, 45025,
45487, 45951, 46418, 46888, 47360, 47835, 48313, 48793,
49275, 49761, 50249, 50739, 51232, 51728, 52226, 52727,
53230, 53736, 54245, 54756, 55270, 55787, 56306, 56828,
57352, 57879, 58409, 58941, 59476, 60014, 60554, 61097,
61642, 62190, 62741, 63295, 63851, 64410, 64971, 65535,
};
#endif
#ifdef GAMMA_2_5
static const u16 gamma_table_2_5[] = {
/* gamma = 2.5 */
0, 0, 0, 1, 2, 4, 6, 8,
11, 15, 20, 25, 31, 38, 46, 55,
65, 75, 87, 99, 113, 128, 143, 160,
178, 197, 218, 239, 262, 286, 311, 338,
366, 395, 425, 457, 491, 526, 562, 599,
639, 679, 722, 765, 811, 857, 906, 956,
1007, 1061, 1116, 1172, 1231, 1291, 1352, 1416,
1481, 1548, 1617, 1688, 1760, 1834, 1910, 1988,
2068, 2150, 2233, 2319, 2407, 2496, 2587, 2681,
2776, 2874, 2973, 3075, 3178, 3284, 3391, 3501,
3613, 3727, 3843, 3961, 4082, 4204, 4329, 4456,
4585, 4716, 4850, 4986, 5124, 5264, 5407, 5552,
5699, 5849, 6001, 6155, 6311, 6470, 6632, 6795,
6962, 7130, 7301, 7475, 7650, 7829, 8009, 8193,
8379, 8567, 8758, 8951, 9147, 9345, 9546, 9750,
9956, 10165, 10376, 10590, 10806, 11025, 11247, 11472,
11699, 11929, 12161, 12397, 12634, 12875, 13119, 13365,
13614, 13865, 14120, 14377, 14637, 14899, 15165, 15433,
15705, 15979, 16256, 16535, 16818, 17104, 17392, 17683,
17978, 18275, 18575, 18878, 19184, 19493, 19805, 20119,
20437, 20758, 21082, 21409, 21739, 22072, 22407, 22746,
23089, 23434, 23782, 24133, 24487, 24845, 25206, 25569,
25936, 26306, 26679, 27055, 27435, 27818, 28203, 28592,
28985, 29380, 29779, 30181, 30586, 30994, 31406, 31820,
32239, 32660, 33085, 33513, 33944, 34379, 34817, 35258,
35702, 36150, 36602, 37056, 37514, 37976, 38441, 38909,
39380, 39856, 40334, 40816, 41301, 41790, 42282, 42778,
43277, 43780, 44286, 44795, 45308, 45825, 46345, 46869,
47396, 47927, 48461, 48999, 49540, 50085, 50634, 51186,
51742, 52301, 52864, 53431, 54001, 54575, 55153, 55734,
56318, 56907, 57499, 58095, 58695, 59298, 59905, 60515,
61130, 61748, 62370, 62995, 63624, 64258, 64894, 65535,
};
#endif
#ifdef GAMMA_3_0
static const u16 gamma_table_3_0[] = {
/* gamma = 3.0 */
0, 0, 0, 0, 0, 0, 1, 1,
2, 3, 4, 5, 7, 9, 11, 13,
16, 19, 23, 27, 32, 37, 42, 48,
55, 62, 69, 78, 87, 96, 107, 118,
130, 142, 155, 169, 184, 200, 217, 234,
253, 272, 293, 314, 337, 360, 385, 410,
437, 465, 494, 524, 556, 588, 622, 658,
694, 732, 771, 812, 854, 897, 942, 988,
1036, 1085, 1136, 1189, 1243, 1298, 1356, 1415,
1475, 1538, 1602, 1667, 1735, 1804, 1876, 1949,
2024, 2100, 2179, 2260, 2343, 2427, 2514, 2603,
2693, 2786, 2881, 2978, 3078, 3179, 3283, 3389,
3497, 3607, 3720, 3835, 3952, 4072, 4194, 4319,
4446, 4575, 4707, 4842, 4979, 5118, 5261, 5405,
5553, 5703, 5856, 6011, 6169, 6330, 6494, 6660,
6830, 7002, 7177, 7355, 7536, 7719, 7906, 8096,
8289, 8484, 8683, 8885, 9090, 9298, 9510, 9724,
9942, 10163, 10387, 10614, 10845, 11079, 11317, 11557,
11802, 12049, 12300, 12555, 12813, 13074, 13339, 13608,
13880, 14156, 14435, 14718, 15005, 15295, 15589, 15887,
16189, 16494, 16803, 17117, 17433, 17754, 18079, 18408,
18740, 19077, 19418, 19762, 20111, 20464, 20821, 21182,
21547, 21917, 22290, 22668, 23050, 23436, 23827, 24222,
24621, 25025, 25433, 25845, 26262, 26683, 27109, 27539,
27974, 28413, 28857, 29306, 29759, 30217, 30680, 31147,
31619, 32095, 32577, 33063, 33554, 34050, 34551, 35056,
35567, 36082, 36602, 37128, 37658, 38194, 38734, 39280,
39830, 40386, 40947, 41513, 42084, 42661, 43243, 43830,
44422, 45019, 45622, 46231, 46844, 47463, 48088, 48718,
49353, 49994, 50641, 51293, 51950, 52614, 53282, 53957,
54637, 55323, 56014, 56712, 57415, 58123, 58838, 59558,
60285, 61017, 61755, 62499, 63249, 64005, 64767, 65535,
};
#endif
static void clock_setup(void)
{
rcc_clock_setup_in_hse_8mhz_out_72mhz();
/* Enable TIM1 clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_TIM1EN);
/* Enable GPIOC, Alternate Function clocks. */
rcc_peripheral_enable_clock(&RCC_APB2ENR,
RCC_APB2ENR_IOPAEN | RCC_APB2ENR_AFIOEN);
}
static void gpio_setup(void)
{
/*
* Set GPIO_TIM1_CH1/2/3/4 (in GPIO port A) to
* 'output alternate function push-pull'.
*/
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL,
GPIO_TIM1_CH1 | GPIO_TIM1_CH2 |
GPIO_TIM1_CH3 | GPIO_TIM1_CH4);
/*
* Remap TIM1:
* CH1 -> PC6
* CH2 -> PC7
* CH3 -> PC8
* CH4 -> PC9
*/
// AFIO_MAPR |= AFIO_MAPR_TIM3_REMAP_FULL_REMAP;
}
static void tim_setup(void)
{
#if 0
TIM1_CR1 = TIM_CR1_CMS_CENTER_1 | TIM_CR1_ARPE;
TIM1_CCMR1 = TIM_CCMR1_OC1M_PWM1 | TIM_CCMR1_OC1PE |
TIM_CCMR1_OC2M_PWM1 | TIM_CCMR1_OC2PE;
TIM1_CCMR2 = TIM_CCMR2_OC3M_PWM1 | TIM_CCMR2_OC3PE;
TIM1_CCER &= ~TIM_CCER_CC1P;
#endif
#if 1
TIM1_SMCR &= ~TIM_SMCR_SMS_MASK;
TIM1_CR1 &= ~TIM_CR1_CEN;
/* Clock division and mode */
TIM1_CR1 = TIM_CR1_CKD_CK_INT | TIM_CR1_CMS_EDGE;
/* Period */
TIM1_ARR = 65535;
/* Prescaler */
TIM1_PSC = 2;
TIM1_EGR = TIM_EGR_UG;
/* ---- */
/* Output compare 1 mode and preload */
TIM1_CCMR1 |= TIM_CCMR1_OC1M_PWM1 | TIM_CCMR1_OC1PE;
/* Polarity and state */
// TIM1_CCER = TIM_CCER_CC1P | TIM_CCER_CC1E;
TIM1_CCER |= TIM_CCER_CC1E;
/* Capture compare value */
TIM1_CCR1 = 1000;
/* ---- */
/* Output compare 2 mode and preload */
TIM1_CCMR1 |= TIM_CCMR1_OC2M_PWM1 | TIM_CCMR1_OC2PE;
/* Polarity and state */
// TIM1_CCER = TIM_CCER_CC1P | TIM_CCER_CC1E;
TIM1_CCER |= TIM_CCER_CC2E;
/* Capture compare value */
TIM1_CCR2 = 1000;
/* ---- */
/* Output compare 3 mode and preload */
TIM1_CCMR2 |= TIM_CCMR2_OC3M_PWM1 | TIM_CCMR2_OC3PE;
/* Polarity and state */
// TIM1_CCER = TIM_CCER_CC1P | TIM_CCER_CC1E;
TIM1_CCER |= TIM_CCER_CC3E;
/* Capture compare value */
TIM1_CCR3 = 1000;
/* ---- */
/* Output compare 4 mode and preload */
TIM1_CCMR2 |= TIM_CCMR2_OC4M_PWM1 | TIM_CCMR2_OC4PE;
/* Polarity and state */
// TIM1_CCER = TIM_CCER_CC1P | TIM_CCER_CC1E;
TIM1_CCER |= TIM_CCER_CC4E;
/* Capture compare value */
TIM1_CCR4 = 1000;
/* ---- */
/* ARR reload enable */
TIM1_CR1 |= TIM_CR1_ARPE;
TIM1_BDTR |= TIM_BDTR_MOE;
/* Counter enable */
TIM1_CR1 |= TIM_CR1_CEN;
#endif
}
int main(void)
{
int i, j0, j1, j2, j3, d0, d1, d2, d3, j, k, kd;
clock_setup();
gpio_setup();
tim_setup();
#ifdef COMPARE
j0 = 0;
d0 = 1;
j1 = 0;
d1 = 1;
j2 = 0;
d2 = 1;
j3 = 0;
d3 = 1;
while (1) {
TIM1_CCR1 = gamma_table_linear[j0];
j0 += d0;
if (j0 == 255)
d0 = -1;
if (j0 == 0)
d0 = 1;
TIM1_CCR2 = gamma_table_1_3[j1];
j1 += d1;
if (j1 == 255)
d1 = -1;
if (j1 == 0)
d1 = 1;
TIM1_CCR3 = gamma_table_2_5[j2];
j2 += d2;
if (j2 == 255)
d2 = -1;
if (j2 == 0)
d2 = 1;
TIM1_CCR4 = gamma_table_3_0[j3];
j3 += d3;
if (j3 == 255)
d3 = -1;
if (j3 == 0)
d3 = 1;
for (i = 0; i < 50000; i++);
}
#endif
#ifdef MOVING_FADE
j0 = 0;
d0 = 1;
j1 = 128;
d1 = 1;
j2 = 255;
d2 = -1;
j3 = 128;
d3 = -1;
while (1) {
TIM1_CCR1 = GAMMA_TABLE[j0];
j0 += d0;
if (j0 == 255)
d0 = -1;
if (j0 == 0)
d0 = 1;
TIM1_CCR2 = GAMMA_TABLE[j1];
j1 += d1;
if (j1 == 255)
d1 = - 1;
if (j1 == 0)
d1 = 1;
TIM1_CCR3 = GAMMA_TABLE[j2];
j2 += d2;
if (j2 == 255)
d2 = -1;
if (j2 == 0)
d2 = 1;
TIM1_CCR4 = GAMMA_TABLE[j3];
j3 += d3;
if (j3 == 255)
d3 = -1;
if (j3 == 0)
d3 = 1;
for (i = 0; i < 10000; i++);
}
#endif
#ifdef KITT
j0 = 255;
d0 = -1;
j1 = 20;
d1 = -1;
j2 = 20;
d2 = -1;
j3 = 20;
d3 = -1;
j = 0;
k = 0;
kd = 1;
while (1) {
TIM1_CCR1 = GAMMA_TABLE[j0];
j0 += d0;
if (j0 == 255)
d0 = -1;
if (j0 == 19)
j0 = 20;
TIM1_CCR2 = GAMMA_TABLE[j1];
j1 += d1;
if (j1 == 255)
d1 = -1;
if (j1 == 19)
j1 = 20;
TIM1_CCR3 = GAMMA_TABLE[j2];
j2 += d2;
if (j2 == 255)
d2 = -1;
if (j2 == 19)
j2 = 20;
TIM1_CCR4 = GAMMA_TABLE[j3];
j3 += d3;
if (j3 == 255)
d3 = -1;
if (j3 == 19)
j3 = 20;
for (i = 0; i < 5000; i++);
j++;
if (j == 100) {
j = 0;
switch (k += kd) {
case 0:
j0 = 255;
break;
case 1:
j1 = 255;
break;
case 2:
j2 = 255;
break;
case 3:
j3 = 255;
break;
}
if (k == 3)
kd = -1;
if (k == 0)
kd = 1;
}
}
#endif
return 0;
}

View File

@@ -0,0 +1,25 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = can
LDSCRIPT = ../obldc-strip.ld
include ../../Makefile.include

View File

@@ -0,0 +1,4 @@
This test sets up the CAN interface on Lisa/M and transmits 8 bites every
100ms. The first byte is being incremented in each cycle. The demo also
receives messages and is displaing the first 4 bits of the first byte on the
board LEDs.

View File

@@ -0,0 +1,205 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2012 Piotr Esden-Tempski <piotr@esden.net>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/flash.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/cm3/nvic.h>
#include <libopencm3/cm3/systick.h>
#include <libopencm3/stm32/can.h>
struct can_tx_msg {
u32 std_id;
u32 ext_id;
u8 ide;
u8 rtr;
u8 dlc;
u8 data[8];
};
struct can_rx_msg {
u32 std_id;
u32 ext_id;
u8 ide;
u8 rtr;
u8 dlc;
u8 data[8];
u8 fmi;
};
struct can_tx_msg can_tx_msg;
struct can_rx_msg can_rx_msg;
static void gpio_setup(void)
{
/* Enable Alternate Function clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
/* Enable GPIOB clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
/* Preconfigure LEDs. */
gpio_set(GPIOB, GPIO4); /* LED green off */
gpio_set(GPIOB, GPIO5); /* LED red off */
/* Configure LED GPIOs. */
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO4);
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO5);
/* Configure PB4 as GPIO. */
AFIO_MAPR |= AFIO_MAPR_SWJ_CFG_FULL_SWJ_NO_JNTRST;
}
static void systick_setup(void)
{
/* 64MHz / 8 => 8000000 counts per second */
systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
/* 8000000/8000 = 1000 overflows per second - every 1ms one interrupt */
/* SysTick interrupt every N clock pulses: set reload to N-1 */
systick_set_reload(7999);
systick_interrupt_enable();
/* Start counting. */
systick_counter_enable();
}
static void can_setup(void)
{
/* Enable peripheral clocks. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_CAN1EN);
AFIO_MAPR |= AFIO_MAPR_CAN1_REMAP_PORTB;
/* Configure CAN pin: RX (input pull-up). */
gpio_set_mode(GPIO_BANK_CAN1_PB_RX, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_PULL_UPDOWN, GPIO_CAN1_PB_RX);
gpio_set(GPIO_BANK_CAN1_PB_RX, GPIO_CAN1_PB_RX);
/* Configure CAN pin: TX. */
gpio_set_mode(GPIO_BANK_CAN1_PB_TX, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_CAN1_PB_TX);
/* NVIC setup. */
nvic_enable_irq(NVIC_USB_LP_CAN_RX0_IRQ);
nvic_set_priority(NVIC_USB_LP_CAN_RX0_IRQ, 1);
/* Reset CAN. */
can_reset(CAN1);
/* CAN cell init.
* Setting the bitrate to 1MBit. APB1 = 32MHz,
* prescaler = 2 -> 16MHz time quanta frequency.
* 1tq sync + 9tq bit segment1 (TS1) + 6tq bit segment2 (TS2) =
* 16time quanto per bit period, therefor 16MHz/16 = 1MHz
*/
if (can_init(CAN1,
false, /* TTCM: Time triggered comm mode? */
true, /* ABOM: Automatic bus-off management? */
false, /* AWUM: Automatic wakeup mode? */
false, /* NART: No automatic retransmission? */
false, /* RFLM: Receive FIFO locked mode? */
false, /* TXFP: Transmit FIFO priority? */
CAN_BTR_SJW_1TQ,
CAN_BTR_TS1_9TQ,
CAN_BTR_TS2_6TQ,
2,
false,
false)) /* BRP+1: Baud rate prescaler */
{
gpio_clear(GPIOB, GPIO4); /* LED green on */
gpio_set(GPIOB, GPIO5); /* LED red off */
/* Die because we failed to initialize. */
while (1)
__asm__("nop");
}
/* CAN filter 0 init. */
can_filter_id_mask_32bit_init(CAN1,
0, /* Filter ID */
0, /* CAN ID */
0, /* CAN ID mask */
0, /* FIFO assignment (here: FIFO0) */
true); /* Enable the filter. */
/* Enable CAN RX interrupt. */
can_enable_irq(CAN1, CAN_IER_FMPIE0);
}
void sys_tick_handler(void)
{
static u8 data[8] = {0, 1, 2, 0, 0, 0, 0, 0};
/* We call this handler every 1ms so every 1ms = 0.001s
* resulting in 1000Hz message rate.
*/
/* Transmit CAN frame. */
data[0]++;
if (can_transmit(CAN1,
0, /* (EX/ST)ID: CAN ID */
false, /* IDE: CAN ID extended? */
false, /* RTR: Request transmit? */
8, /* DLC: Data length */
data) == -1)
{
gpio_set(GPIOB, GPIO4); /* LED green off */
gpio_clear(GPIOB, GPIO5); /* LED red on */
}
}
void usb_lp_can_rx0_isr(void)
{
u32 id, fmi;
bool ext, rtr;
u8 length, data[8];
can_receive(CAN1, 0, false, &id, &ext, &rtr, &fmi, &length, data);
if (data[0] & 0x40)
gpio_clear(GPIOB, GPIO4);
else
gpio_set(GPIOB, GPIO4);
if (data[0] & 0x80)
gpio_clear(GPIOB, GPIO5);
else
gpio_set(GPIOB, GPIO5);
can_fifo_release(CAN1, 0);
}
int main(void)
{
rcc_clock_setup_in_hsi_out_64mhz();
gpio_setup();
can_setup();
systick_setup();
while (1); /* Halt. */
return 0;
}

View File

@@ -0,0 +1,232 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
* Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/flash.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/cm3/nvic.h>
#include <libopencm3/cm3/systick.h>
#include <libopencm3/stm32/can.h>
struct can_tx_msg {
u32 std_id;
u32 ext_id;
u8 ide;
u8 rtr;
u8 dlc;
u8 data[8];
};
struct can_rx_msg {
u32 std_id;
u32 ext_id;
u8 ide;
u8 rtr;
u8 dlc;
u8 data[8];
u8 fmi;
};
struct can_tx_msg can_tx_msg;
struct can_rx_msg can_rx_msg;
void gpio_setup(void)
{
/* Enable Alternate Function clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
/* Enable GPIOA clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
/* Enable GPIOB clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
/* Enable GPIOC clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
/* Preconfigure LEDs. */
gpio_set(GPIOA, GPIO8); /* LED0 off */
gpio_set(GPIOB, GPIO4); /* LED1 off */
gpio_set(GPIOC, GPIO15); /* LED2 off */
gpio_set(GPIOC, GPIO2); /* LED3 off */
gpio_set(GPIOC, GPIO5); /* LED4 off */
/* Configure LED GPIOOs. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO8);
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO4);
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO15);
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO2);
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO5);
/* Configure PB4 as GPIO. */
AFIO_MAPR |= AFIO_MAPR_SWJ_CFG_FULL_SWJ_NO_JNTRST;
}
void systick_setup(void)
{
/* 72MHz / 8 => 9000000 counts per second */
systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
/* 9000000/9000 = 1000 overflows per second - every 1ms one interrupt */
systick_set_reload(9000);
systick_interrupt_enable();
/* Start counting. */
systick_counter_enable();
}
void can_setup(void)
{
/* Enable peripheral clocks. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_CANEN);
AFIO_MAPR = AFIO_MAPR_CAN1_REMAP_PORTB;
/* Configure CAN pin: RX (input pull-up). */
gpio_set_mode(GPIOB, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_PULL_UPDOWN, GPIO_CAN1_PB_RX);
gpio_set(GPIOB, GPIO_CAN1_PB_RX);
/* Configure CAN pin: TX. */
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_CAN1_PB_TX);
/* NVIC setup. */
nvic_enable_irq(NVIC_USB_LP_CAN_RX0_IRQ);
nvic_set_priority(NVIC_USB_LP_CAN_RX0_IRQ, 1);
/* Reset CAN. */
can_reset(CAN1);
/* CAN cell init. */
if (can_init(CAN1,
false, /* TTCM: Time triggered comm mode? */
true, /* ABOM: Automatic bus-off management? */
false, /* AWUM: Automatic wakeup mode? */
false, /* NART: No automatic retransmission? */
false, /* RFLM: Receive FIFO locked mode? */
false, /* TXFP: Transmit FIFO priority? */
CAN_BTR_SJW_1TQ,
CAN_BTR_TS1_3TQ,
CAN_BTR_TS2_4TQ,
12)) /* BRP+1: Baud rate prescaler */
{
gpio_set(GPIOA, GPIO8); /* LED0 off */
gpio_set(GPIOB, GPIO4); /* LED1 off */
gpio_set(GPIOC, GPIO15); /* LED2 off */
gpio_clear(GPIOC, GPIO2); /* LED3 on */
gpio_set(GPIOC, GPIO5); /* LED4 off */
/* Die because we failed to initialize. */
while (1)
__asm__("nop");
}
/* CAN filter 0 init. */
can_filter_id_mask_32bit_init(CAN1,
0, /* Filter ID */
0, /* CAN ID */
0, /* CAN ID mask */
0, /* FIFO assignment (here: FIFO0) */
true); /* Enable the filter. */
/* Enable CAN RX interrupt. */
can_enable_irq(CAN1, CAN_IER_FMPIE0);
}
void sys_tick_handler(void)
{
static int temp32 = 0;
static u8 data[8] = {0, 1, 2, 0, 0, 0, 0, 0};
/* We call this handler every 1ms so 1000ms = 1s on/off. */
if (++temp32 != 1000)
return;
temp32 = 0;
/* Transmit CAN frame. */
data[0]++;
if (can_transmit(CAN1,
0, /* (EX/ST)ID: CAN ID */
false, /* IDE: CAN ID extended? */
false, /* RTR: Request transmit? */
8, /* DLC: Data length */
data) == -1)
{
gpio_set(GPIOA, GPIO8); /* LED0 off */
gpio_set(GPIOB, GPIO4); /* LED1 off */
gpio_set(GPIOC, GPIO15); /* LED2 off */
gpio_set(GPIOC, GPIO2); /* LED3 off */
gpio_clear(GPIOC, GPIO5); /* LED4 on */
}
}
void usb_lp_can_rx0_isr(void)
{
u32 id, fmi;
bool ext, rtr;
u8 length, data[8];
can_receive(CAN1, 0, false, &id, &ext, &rtr, &fmi, &length, data);
if (data[0] & 1)
gpio_clear(GPIOA, GPIO8);
else
gpio_set(GPIOA, GPIO8);
if (data[0] & 2)
gpio_clear(GPIOB, GPIO4);
else
gpio_set(GPIOB, GPIO4);
if (data[0] & 4)
gpio_clear(GPIOC, GPIO15);
else
gpio_set(GPIOC, GPIO15);
if (data[0] & 8)
gpio_clear(GPIOC, GPIO2);
else
gpio_set(GPIOC, GPIO2);
can_fifo_release(CAN1, 0);
}
int main(void)
{
rcc_clock_setup_in_hse_12mhz_out_72mhz();
gpio_setup();
can_setup();
systick_setup();
while (1); /* Halt. */
return 0;
}

View File

@@ -0,0 +1,25 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = led
LDSCRIPT = ../obldc-strip.ld
include ../../Makefile.include

View File

@@ -0,0 +1,65 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2012 Piotr Esden-Tempski <piotr@esden.net>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/gpio.h>
static void clock_setup(void)
{
/* Set STM32 to 64 MHz. */
rcc_clock_setup_in_hsi_out_64mhz();
/* Enable alternate function peripheral clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
/* Enable GPIOB clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
}
static void gpio_setup(void)
{
/* Configure PB4 as GPIO. */
AFIO_MAPR |= AFIO_MAPR_SWJ_CFG_FULL_SWJ_NO_JNTRST;
/* Set GPIO4 and 5 (in GPIO port B) to 'output push-pull'. */
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO4 | GPIO5);
}
int main(void)
{
int i;
clock_setup();
gpio_setup();
/* Blink the LEDs on the board. */
while (1) {
gpio_toggle(GPIOB, GPIO4); /* LED on/off */
for (i = 0; i < 8000000; i++) /* Wait a bit. */
__asm__("nop");
gpio_toggle(GPIOB, GPIO5); /* LED on/off */
for (i = 0; i < 8000000; i++) /* Wait a bit. */
__asm__("nop");
}
return 0;
}

View File

@@ -0,0 +1,31 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
/* Linker script for Open-BLDC (STM32F103CBT6, 128K flash, 20K RAM). */
/* Define memory regions. */
MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
}
/* Include the common ld script. */
INCLUDE libopencm3_stm32f1.ld

View File

@@ -0,0 +1,25 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = systick
LDSCRIPT = ../obldc-strip.ld
include ../../Makefile.include

View File

@@ -0,0 +1,82 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2012 Piotr Esden-Tempski <piotr@esden.net>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/flash.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/cm3/nvic.h>
#include <libopencm3/cm3/systick.h>
u32 temp32;
static void gpio_setup(void)
{
/* Enable alternate function peripheral clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
/* Enable GPIOB clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
gpio_clear(GPIOB, GPIO4); /* LED green on */
gpio_set(GPIOB, GPIO5); /* LED red off */
/* Set GPIO4/5 (in GPIO port B) to 'output push-pull' for the LEDs. */
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO4);
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO5);
AFIO_MAPR |= AFIO_MAPR_SWJ_CFG_FULL_SWJ_NO_JNTRST;
}
void sys_tick_handler(void)
{
temp32++;
/* We call this handler every 1ms so 1000ms = 1s on/off. */
if (temp32 == 1000) {
gpio_toggle(GPIOB, GPIO4); /* LED green on/off */
gpio_toggle(GPIOB, GPIO5); /* LED red on/off */
temp32 = 0;
}
}
int main(void)
{
rcc_clock_setup_in_hsi_out_64mhz();
gpio_setup();
temp32 = 0;
/* 64MHz / 8 => 8000000 counts per second */
systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
/* 8000000/8000 = 1000 overflows per second - every 1ms one interrupt */
/* SysTick interrupt every N clock pulses: set reload to N-1 */
systick_set_reload(7999);
systick_interrupt_enable();
/* Start counting. */
systick_counter_enable();
while (1); /* Halt. */
return 0;
}

View File

@@ -0,0 +1,25 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = usart
LDSCRIPT = ../obldc-strip.ld
include ../../Makefile.include

View File

@@ -0,0 +1,87 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2012 Piotr Esden-Tempski <piotr@esden.net>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/stm32/usart.h>
static void clock_setup(void)
{
rcc_clock_setup_in_hsi_out_64mhz();
/* Enable clocks for GPIO port B (for GPIO_USART1_TX and LED) and USART1. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_USART1EN);
}
static void usart_setup(void)
{
/* Setup GPIO6 (in GPIO port A) to 'output push-pull' for LED use. */
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO5);
AFIO_MAPR |= AFIO_MAPR_USART1_REMAP;
/* Setup GPIO pin GPIO_USART3_TX/GPIO10 on GPIO port B for transmit. */
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART1_RE_TX);
/* Setup UART parameters. */
usart_set_baudrate(USART1, 230400);
usart_set_databits(USART1, 8);
usart_set_stopbits(USART1, USART_STOPBITS_1);
usart_set_mode(USART1, USART_MODE_TX);
usart_set_parity(USART1, USART_PARITY_NONE);
usart_set_flow_control(USART1, USART_FLOWCONTROL_NONE);
/* Finally enable the USART. */
usart_enable(USART1);
}
static void gpio_setup(void)
{
/* Set GPIO5 (in GPIO port B) to 'output push-pull'. */
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO5);
}
int main(void)
{
int i, j = 0, c = 0;
clock_setup();
gpio_setup();
usart_setup();
/* Blink the LED (PA6) on the board with every transmitted byte. */
while (1) {
gpio_toggle(GPIOB, GPIO5); /* LED red on/off */
usart_send_blocking(USART1, c + '0'); /* Send a byte. */
c = (c == 9) ? 0 : c + 1; /* Increment c. */
if ((j++ % 80) == 0) { /* Newline after line full. */
usart_send_blocking(USART1, '\r');
usart_send_blocking(USART1, '\n');
}
for (i = 0; i < 800000; i++) /* Wait a bit. */
__asm__("nop");
}
return 0;
}

View File

@@ -0,0 +1,25 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = can
LDSCRIPT = ../obldc.ld
include ../../Makefile.include

View File

@@ -0,0 +1,219 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
* Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/flash.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/cm3/nvic.h>
#include <libopencm3/cm3/systick.h>
#include <libopencm3/stm32/can.h>
struct can_tx_msg {
u32 std_id;
u32 ext_id;
u8 ide;
u8 rtr;
u8 dlc;
u8 data[8];
};
struct can_rx_msg {
u32 std_id;
u32 ext_id;
u8 ide;
u8 rtr;
u8 dlc;
u8 data[8];
u8 fmi;
};
struct can_tx_msg can_tx_msg;
struct can_rx_msg can_rx_msg;
static void gpio_setup(void)
{
/* Enable GPIOA clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
/* Enable GPIOB clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
gpio_set(GPIOA, GPIO6); /* LED0 off */
gpio_set(GPIOA, GPIO7); /* LED1 off */
gpio_set(GPIOB, GPIO0); /* LED2 off */
gpio_set(GPIOB, GPIO1); /* LED3 off */
/* Set GPIO6/7 (in GPIO port A) to 'output push-pull' for the LEDs. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO6);
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO7);
/* Set GPIO0/1 (in GPIO port B) to 'output push-pull' for the LEDs. */
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO0);
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO1);
}
static void systick_setup(void)
{
/* 72MHz / 8 => 9000000 counts per second */
systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
/* 9000000/9000 = 1000 overflows per second - every 1ms one interrupt */
/* SysTick interrupt every N clock pulses: set reload to N-1 */
systick_set_reload(8999);
systick_interrupt_enable();
/* Start counting. */
systick_counter_enable();
}
static void can_setup(void)
{
/* Enable peripheral clocks. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_CANEN);
/* Configure CAN pin: RX (input pull-up). */
gpio_set_mode(GPIOA, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_PULL_UPDOWN, GPIO_CAN_RX);
gpio_set(GPIOA, GPIO_CAN_RX);
/* Configure CAN pin: TX. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_CAN_TX);
/* NVIC setup. */
nvic_enable_irq(NVIC_USB_LP_CAN_RX0_IRQ);
nvic_set_priority(NVIC_USB_LP_CAN_RX0_IRQ, 1);
/* Reset CAN. */
can_reset(CAN1);
/* CAN cell init. */
if (can_init(CAN1,
false, /* TTCM: Time triggered comm mode? */
true, /* ABOM: Automatic bus-off management? */
false, /* AWUM: Automatic wakeup mode? */
false, /* NART: No automatic retransmission? */
false, /* RFLM: Receive FIFO locked mode? */
false, /* TXFP: Transmit FIFO priority? */
CAN_BTR_SJW_1TQ,
CAN_BTR_TS1_3TQ,
CAN_BTR_TS2_4TQ,
12,
false,
false)) /* BRP+1: Baud rate prescaler */
{
gpio_set(GPIOA, GPIO6); /* LED0 off */
gpio_set(GPIOA, GPIO7); /* LED1 off */
gpio_set(GPIOB, GPIO0); /* LED2 off */
gpio_clear(GPIOB, GPIO1); /* LED3 on */
/* Die because we failed to initialize. */
while (1)
__asm__("nop");
}
/* CAN filter 0 init. */
can_filter_id_mask_32bit_init(CAN1,
0, /* Filter ID */
0, /* CAN ID */
0, /* CAN ID mask */
0, /* FIFO assignment (here: FIFO0) */
true); /* Enable the filter. */
/* Enable CAN RX interrupt. */
can_enable_irq(CAN1, CAN_IER_FMPIE0);
}
void sys_tick_handler(void)
{
static int temp32 = 0;
static u8 data[8] = {0, 1, 2, 0, 0, 0, 0, 0};
/* We call this handler every 1ms so 1000ms = 1s on/off. */
if (++temp32 != 1000)
return;
temp32 = 0;
/* Transmit CAN frame. */
data[0]++;
if (can_transmit(CAN1,
0, /* (EX/ST)ID: CAN ID */
false, /* IDE: CAN ID extended? */
false, /* RTR: Request transmit? */
8, /* DLC: Data length */
data) == -1)
{
gpio_set(GPIOA, GPIO6); /* LED0 off */
gpio_set(GPIOA, GPIO7); /* LED1 off */
gpio_clear(GPIOB, GPIO0); /* LED2 on */
gpio_set(GPIOB, GPIO1); /* LED3 off */
}
}
void usb_lp_can_rx0_isr(void)
{
u32 id, fmi;
bool ext, rtr;
u8 length, data[8];
can_receive(CAN1, 0, false, &id, &ext, &rtr, &fmi, &length, data);
if (data[0] & 1)
gpio_clear(GPIOA, GPIO6);
else
gpio_set(GPIOA, GPIO6);
if (data[0] & 2)
gpio_clear(GPIOA, GPIO7);
else
gpio_set(GPIOA, GPIO7);
if (data[0] & 4)
gpio_clear(GPIOB, GPIO0);
else
gpio_set(GPIOB, GPIO0);
if (data[0] & 8)
gpio_clear(GPIOB, GPIO1);
else
gpio_set(GPIOB, GPIO1);
can_fifo_release(CAN1, 0);
}
int main(void)
{
rcc_clock_setup_in_hse_8mhz_out_72mhz();
gpio_setup();
can_setup();
systick_setup();
while (1); /* Halt. */
return 0;
}

View File

@@ -0,0 +1,232 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
* Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/flash.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/cm3/nvic.h>
#include <libopencm3/cm3/systick.h>
#include <libopencm3/stm32/can.h>
struct can_tx_msg {
u32 std_id;
u32 ext_id;
u8 ide;
u8 rtr;
u8 dlc;
u8 data[8];
};
struct can_rx_msg {
u32 std_id;
u32 ext_id;
u8 ide;
u8 rtr;
u8 dlc;
u8 data[8];
u8 fmi;
};
struct can_tx_msg can_tx_msg;
struct can_rx_msg can_rx_msg;
void gpio_setup(void)
{
/* Enable Alternate Function clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
/* Enable GPIOA clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
/* Enable GPIOB clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
/* Enable GPIOC clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
/* Preconfigure LEDs. */
gpio_set(GPIOA, GPIO8); /* LED0 off */
gpio_set(GPIOB, GPIO4); /* LED1 off */
gpio_set(GPIOC, GPIO15); /* LED2 off */
gpio_set(GPIOC, GPIO2); /* LED3 off */
gpio_set(GPIOC, GPIO5); /* LED4 off */
/* Configure LED GPIOOs. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO8);
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO4);
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO15);
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO2);
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO5);
/* Configure PB4 as GPIO. */
AFIO_MAPR |= AFIO_MAPR_SWJ_CFG_FULL_SWJ_NO_JNTRST;
}
void systick_setup(void)
{
/* 72MHz / 8 => 9000000 counts per second */
systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
/* 9000000/9000 = 1000 overflows per second - every 1ms one interrupt */
systick_set_reload(9000);
systick_interrupt_enable();
/* Start counting. */
systick_counter_enable();
}
void can_setup(void)
{
/* Enable peripheral clocks. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_CANEN);
AFIO_MAPR = AFIO_MAPR_CAN1_REMAP_PORTB;
/* Configure CAN pin: RX (input pull-up). */
gpio_set_mode(GPIOB, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_PULL_UPDOWN, GPIO_CAN1_PB_RX);
gpio_set(GPIOB, GPIO_CAN1_PB_RX);
/* Configure CAN pin: TX. */
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_CAN1_PB_TX);
/* NVIC setup. */
nvic_enable_irq(NVIC_USB_LP_CAN_RX0_IRQ);
nvic_set_priority(NVIC_USB_LP_CAN_RX0_IRQ, 1);
/* Reset CAN. */
can_reset(CAN1);
/* CAN cell init. */
if (can_init(CAN1,
false, /* TTCM: Time triggered comm mode? */
true, /* ABOM: Automatic bus-off management? */
false, /* AWUM: Automatic wakeup mode? */
false, /* NART: No automatic retransmission? */
false, /* RFLM: Receive FIFO locked mode? */
false, /* TXFP: Transmit FIFO priority? */
CAN_BTR_SJW_1TQ,
CAN_BTR_TS1_3TQ,
CAN_BTR_TS2_4TQ,
12)) /* BRP+1: Baud rate prescaler */
{
gpio_set(GPIOA, GPIO8); /* LED0 off */
gpio_set(GPIOB, GPIO4); /* LED1 off */
gpio_set(GPIOC, GPIO15); /* LED2 off */
gpio_clear(GPIOC, GPIO2); /* LED3 on */
gpio_set(GPIOC, GPIO5); /* LED4 off */
/* Die because we failed to initialize. */
while (1)
__asm__("nop");
}
/* CAN filter 0 init. */
can_filter_id_mask_32bit_init(CAN1,
0, /* Filter ID */
0, /* CAN ID */
0, /* CAN ID mask */
0, /* FIFO assignment (here: FIFO0) */
true); /* Enable the filter. */
/* Enable CAN RX interrupt. */
can_enable_irq(CAN1, CAN_IER_FMPIE0);
}
void sys_tick_handler(void)
{
static int temp32 = 0;
static u8 data[8] = {0, 1, 2, 0, 0, 0, 0, 0};
/* We call this handler every 1ms so 1000ms = 1s on/off. */
if (++temp32 != 1000)
return;
temp32 = 0;
/* Transmit CAN frame. */
data[0]++;
if (can_transmit(CAN1,
0, /* (EX/ST)ID: CAN ID */
false, /* IDE: CAN ID extended? */
false, /* RTR: Request transmit? */
8, /* DLC: Data length */
data) == -1)
{
gpio_set(GPIOA, GPIO8); /* LED0 off */
gpio_set(GPIOB, GPIO4); /* LED1 off */
gpio_set(GPIOC, GPIO15); /* LED2 off */
gpio_set(GPIOC, GPIO2); /* LED3 off */
gpio_clear(GPIOC, GPIO5); /* LED4 on */
}
}
void usb_lp_can_rx0_isr(void)
{
u32 id, fmi;
bool ext, rtr;
u8 length, data[8];
can_receive(CAN1, 0, false, &id, &ext, &rtr, &fmi, &length, data);
if (data[0] & 1)
gpio_clear(GPIOA, GPIO8);
else
gpio_set(GPIOA, GPIO8);
if (data[0] & 2)
gpio_clear(GPIOB, GPIO4);
else
gpio_set(GPIOB, GPIO4);
if (data[0] & 4)
gpio_clear(GPIOC, GPIO15);
else
gpio_set(GPIOC, GPIO15);
if (data[0] & 8)
gpio_clear(GPIOC, GPIO2);
else
gpio_set(GPIOC, GPIO2);
can_fifo_release(CAN1, 0);
}
int main(void)
{
rcc_clock_setup_in_hse_12mhz_out_72mhz();
gpio_setup();
can_setup();
systick_setup();
while (1); /* Halt. */
return 0;
}

View File

@@ -0,0 +1,25 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = led
LDSCRIPT = ../obldc.ld
include ../../Makefile.include

View File

@@ -0,0 +1,71 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
* Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/gpio.h>
static void clock_setup(void)
{
/* Set STM32 to 72 MHz. */
rcc_clock_setup_in_hse_8mhz_out_72mhz();
/* Enable GPIOA clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
/* Enable GPIOB clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
}
static void gpio_setup(void)
{
/* Set GPIO6 and 7 (in GPIO port A) to 'output push-pull'. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO6 | GPIO7);
/* Set GPIO0 and 1 (in GPIO port B) to 'output push-pull'. */
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO0 | GPIO1);
}
int main(void)
{
int i;
clock_setup();
gpio_setup();
/* Blink the LEDs on the board. */
while (1) {
gpio_toggle(GPIOA, GPIO6); /* LED on/off */
for (i = 0; i < 8000000; i++) /* Wait a bit. */
__asm__("nop");
gpio_toggle(GPIOA, GPIO7); /* LED on/off */
for (i = 0; i < 8000000; i++) /* Wait a bit. */
__asm__("nop");
gpio_toggle(GPIOB, GPIO0); /* LED on/off */
for (i = 0; i < 8000000; i++) /* Wait a bit. */
__asm__("nop");
gpio_toggle(GPIOB, GPIO1); /* LED on/off */
for (i = 0; i < 8000000; i++) /* Wait a bit. */
__asm__("nop");
}
return 0;
}

View File

@@ -0,0 +1,31 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
/* Linker script for Open-BLDC (STM32F103CBT6, 128K flash, 20K RAM). */
/* Define memory regions. */
MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
}
/* Include the common ld script. */
INCLUDE libopencm3_stm32f1.ld

View File

@@ -0,0 +1,25 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = pwmleds
LDSCRIPT = ../obldc.ld
include ../../Makefile.include

View File

@@ -0,0 +1,484 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/stm32/timer.h>
// #define COMPARE
// #define MOVING_FADE
#define KITT
#ifdef COMPARE
#define GAMMA_LINEAR
#define GAMMA_1_3
#define GAMMA_2_5
#define GAMMA_3_0
#endif
#ifdef MOVING_FADE
#define GAMMA_2_2
#define GAMMA_TABLE gamma_table_2_2
#endif
#ifdef KITT
#define GAMMA_2_5
#define GAMMA_TABLE gamma_table_2_5
#endif
/*
* Gamma correction table
*
* The nonlinear tables are calculating with the function:
* Iout = Iin ** gamma
*/
#ifdef GAMMA_LINEAR
static const u16 gamma_table_linear[] = {
1, 4, 9, 17, 26, 37, 51, 67,
84, 104, 126, 149, 175, 203, 233, 265,
299, 334, 372, 412, 454, 499, 545, 593,
643, 695, 749, 805, 864, 924, 986, 1050,
1116, 1185, 1255, 1327, 1402, 1478, 1556, 1637,
1719, 1803, 1890, 1978, 2068, 2161, 2255, 2352,
2450, 2550, 2653, 2757, 2864, 2972, 3082, 3195,
3309, 3426, 3544, 3664, 3787, 3911, 4038, 4166,
4296, 4429, 4563, 4700, 4838, 4978, 5121, 5265,
5411, 5560, 5710, 5862, 6017, 6173, 6331, 6492,
6654, 6818, 6985, 7153, 7323, 7495, 7670, 7846,
8024, 8204, 8387, 8571, 8757, 8945, 9135, 9327,
9521, 9718, 9916, 10116, 10318, 10522, 10728, 10936,
11146, 11358, 11572, 11788, 12006, 12226, 12448, 12672,
12897, 13125, 13355, 13587, 13821, 14057, 14294, 14534,
14776, 15020, 15265, 15513, 15763, 16014, 16268, 16524,
16781, 17041, 17302, 17566, 17831, 18099, 18368, 18640,
18913, 19189, 19466, 19745, 20027, 20310, 20595, 20883,
21172, 21463, 21756, 22051, 22349, 22648, 22949, 23252,
23557, 23864, 24173, 24484, 24797, 25112, 25429, 25748,
26069, 26391, 26716, 27043, 27372, 27702, 28035, 28370,
28707, 29045, 29386, 29728, 30073, 30419, 30768, 31118,
31471, 31825, 32182, 32540, 32900, 33263, 33627, 33993,
34361, 34731, 35104, 35478, 35854, 36232, 36612, 36994,
37378, 37764, 38152, 38542, 38933, 39327, 39723, 40121,
40521, 40922, 41326, 41732, 42139, 42549, 42960, 43374,
43789, 44207, 44626, 45048, 45471, 45896, 46324, 46753,
47184, 47617, 48052, 48490, 48929, 49370, 49813, 50258,
50705, 51154, 51604, 52057, 52512, 52969, 53428, 53888,
54351, 54816, 55282, 55751, 56222, 56694, 57169, 57645,
58123, 58604, 59086, 59570, 60057, 60545, 61035, 61527,
62021, 62517, 63016, 63516, 64018, 64521, 65027, 65535,
};
#endif
#ifdef GAMMA_1_3
static const u16 gamma_table_1_3[] = {
/* Gamma 1.3 */
0, 49, 120, 203, 296, 395, 501, 612,
728, 848, 973, 1101, 1233, 1368, 1506, 1648,
1792, 1939, 2088, 2241, 2395, 2552, 2711, 2872,
3036, 3201, 3369, 3538, 3709, 3882, 4057, 4234,
4412, 4592, 4774, 4957, 5142, 5329, 5517, 5706,
5897, 6090, 6283, 6479, 6675, 6873, 7072, 7273,
7475, 7678, 7882, 8088, 8294, 8502, 8711, 8922,
9133, 9346, 9559, 9774, 9990, 10207, 10425, 10644,
10864, 11086, 11308, 11531, 11755, 11981, 12207, 12434,
12662, 12891, 13121, 13352, 13584, 13817, 14051, 14285,
14521, 14757, 14994, 15233, 15472, 15712, 15952, 16194,
16436, 16679, 16923, 17168, 17414, 17660, 17908, 18156,
18405, 18654, 18905, 19156, 19408, 19660, 19914, 20168,
20423, 20679, 20935, 21192, 21450, 21708, 21968, 22228,
22488, 22750, 23012, 23275, 23538, 23802, 24067, 24332,
24599, 24865, 25133, 25401, 25670, 25939, 26209, 26480,
26751, 27023, 27296, 27569, 27843, 28118, 28393, 28669,
28945, 29222, 29500, 29778, 30057, 30336, 30616, 30897,
31178, 31460, 31742, 32025, 32308, 32592, 32877, 33162,
33448, 33734, 34021, 34309, 34597, 34885, 35175, 35464,
35754, 36045, 36337, 36628, 36921, 37214, 37507, 37801,
38096, 38391, 38686, 38982, 39279, 39576, 39874, 40172,
40471, 40770, 41070, 41370, 41670, 41972, 42273, 42576,
42878, 43181, 43485, 43789, 44094, 44399, 44705, 45011,
45317, 45625, 45932, 46240, 46549, 46858, 47167, 47477,
47787, 48098, 48409, 48721, 49034, 49346, 49659, 49973,
50287, 50602, 50917, 51232, 51548, 51864, 52181, 52498,
52816, 53134, 53452, 53771, 54091, 54411, 54731, 55052,
55373, 55694, 56016, 56339, 56662, 56985, 57309, 57633,
57957, 58282, 58608, 58933, 59260, 59586, 59913, 60241,
60569, 60897, 61226, 61555, 61884, 62214, 62545, 62875,
63206, 63538, 63870, 64202, 64535, 64868, 65201, 65535,
};
#endif
#ifdef GAMMA_2_2
static const u16 gamma_table_2_2[] = {
0, 0, 2, 4, 7, 11, 17, 24,
32, 42, 53, 65, 79, 94, 111, 129,
148, 169, 192, 216, 242, 270, 299, 330,
362, 396, 432, 469, 508, 549, 591, 635,
681, 729, 779, 830, 883, 938, 995, 1053,
1113, 1175, 1239, 1305, 1373, 1443, 1514, 1587,
1663, 1740, 1819, 1900, 1983, 2068, 2155, 2243,
2334, 2427, 2521, 2618, 2717, 2817, 2920, 3024,
3131, 3240, 3350, 3463, 3578, 3694, 3813, 3934,
4057, 4182, 4309, 4438, 4570, 4703, 4838, 4976,
5115, 5257, 5401, 5547, 5695, 5845, 5998, 6152,
6309, 6468, 6629, 6792, 6957, 7124, 7294, 7466,
7640, 7816, 7994, 8175, 8358, 8543, 8730, 8919,
9111, 9305, 9501, 9699, 9900, 10102, 10307, 10515,
10724, 10936, 11150, 11366, 11585, 11806, 12029, 12254,
12482, 12712, 12944, 13179, 13416, 13655, 13896, 14140,
14386, 14635, 14885, 15138, 15394, 15652, 15912, 16174,
16439, 16706, 16975, 17247, 17521, 17798, 18077, 18358,
18642, 18928, 19216, 19507, 19800, 20095, 20393, 20694,
20996, 21301, 21609, 21919, 22231, 22546, 22863, 23182,
23504, 23829, 24156, 24485, 24817, 25151, 25487, 25826,
26168, 26512, 26858, 27207, 27558, 27912, 28268, 28627,
28988, 29351, 29717, 30086, 30457, 30830, 31206, 31585,
31966, 32349, 32735, 33124, 33514, 33908, 34304, 34702,
35103, 35507, 35913, 36321, 36732, 37146, 37562, 37981,
38402, 38825, 39252, 39680, 40112, 40546, 40982, 41421,
41862, 42306, 42753, 43202, 43654, 44108, 44565, 45025,
45487, 45951, 46418, 46888, 47360, 47835, 48313, 48793,
49275, 49761, 50249, 50739, 51232, 51728, 52226, 52727,
53230, 53736, 54245, 54756, 55270, 55787, 56306, 56828,
57352, 57879, 58409, 58941, 59476, 60014, 60554, 61097,
61642, 62190, 62741, 63295, 63851, 64410, 64971, 65535,
};
#endif
#ifdef GAMMA_2_5
static const u16 gamma_table_2_5[] = {
/* gamma = 2.5 */
0, 0, 0, 1, 2, 4, 6, 8,
11, 15, 20, 25, 31, 38, 46, 55,
65, 75, 87, 99, 113, 128, 143, 160,
178, 197, 218, 239, 262, 286, 311, 338,
366, 395, 425, 457, 491, 526, 562, 599,
639, 679, 722, 765, 811, 857, 906, 956,
1007, 1061, 1116, 1172, 1231, 1291, 1352, 1416,
1481, 1548, 1617, 1688, 1760, 1834, 1910, 1988,
2068, 2150, 2233, 2319, 2407, 2496, 2587, 2681,
2776, 2874, 2973, 3075, 3178, 3284, 3391, 3501,
3613, 3727, 3843, 3961, 4082, 4204, 4329, 4456,
4585, 4716, 4850, 4986, 5124, 5264, 5407, 5552,
5699, 5849, 6001, 6155, 6311, 6470, 6632, 6795,
6962, 7130, 7301, 7475, 7650, 7829, 8009, 8193,
8379, 8567, 8758, 8951, 9147, 9345, 9546, 9750,
9956, 10165, 10376, 10590, 10806, 11025, 11247, 11472,
11699, 11929, 12161, 12397, 12634, 12875, 13119, 13365,
13614, 13865, 14120, 14377, 14637, 14899, 15165, 15433,
15705, 15979, 16256, 16535, 16818, 17104, 17392, 17683,
17978, 18275, 18575, 18878, 19184, 19493, 19805, 20119,
20437, 20758, 21082, 21409, 21739, 22072, 22407, 22746,
23089, 23434, 23782, 24133, 24487, 24845, 25206, 25569,
25936, 26306, 26679, 27055, 27435, 27818, 28203, 28592,
28985, 29380, 29779, 30181, 30586, 30994, 31406, 31820,
32239, 32660, 33085, 33513, 33944, 34379, 34817, 35258,
35702, 36150, 36602, 37056, 37514, 37976, 38441, 38909,
39380, 39856, 40334, 40816, 41301, 41790, 42282, 42778,
43277, 43780, 44286, 44795, 45308, 45825, 46345, 46869,
47396, 47927, 48461, 48999, 49540, 50085, 50634, 51186,
51742, 52301, 52864, 53431, 54001, 54575, 55153, 55734,
56318, 56907, 57499, 58095, 58695, 59298, 59905, 60515,
61130, 61748, 62370, 62995, 63624, 64258, 64894, 65535,
};
#endif
#ifdef GAMMA_3_0
static const u16 gamma_table_3_0[] = {
/* gamma = 3.0 */
0, 0, 0, 0, 0, 0, 1, 1,
2, 3, 4, 5, 7, 9, 11, 13,
16, 19, 23, 27, 32, 37, 42, 48,
55, 62, 69, 78, 87, 96, 107, 118,
130, 142, 155, 169, 184, 200, 217, 234,
253, 272, 293, 314, 337, 360, 385, 410,
437, 465, 494, 524, 556, 588, 622, 658,
694, 732, 771, 812, 854, 897, 942, 988,
1036, 1085, 1136, 1189, 1243, 1298, 1356, 1415,
1475, 1538, 1602, 1667, 1735, 1804, 1876, 1949,
2024, 2100, 2179, 2260, 2343, 2427, 2514, 2603,
2693, 2786, 2881, 2978, 3078, 3179, 3283, 3389,
3497, 3607, 3720, 3835, 3952, 4072, 4194, 4319,
4446, 4575, 4707, 4842, 4979, 5118, 5261, 5405,
5553, 5703, 5856, 6011, 6169, 6330, 6494, 6660,
6830, 7002, 7177, 7355, 7536, 7719, 7906, 8096,
8289, 8484, 8683, 8885, 9090, 9298, 9510, 9724,
9942, 10163, 10387, 10614, 10845, 11079, 11317, 11557,
11802, 12049, 12300, 12555, 12813, 13074, 13339, 13608,
13880, 14156, 14435, 14718, 15005, 15295, 15589, 15887,
16189, 16494, 16803, 17117, 17433, 17754, 18079, 18408,
18740, 19077, 19418, 19762, 20111, 20464, 20821, 21182,
21547, 21917, 22290, 22668, 23050, 23436, 23827, 24222,
24621, 25025, 25433, 25845, 26262, 26683, 27109, 27539,
27974, 28413, 28857, 29306, 29759, 30217, 30680, 31147,
31619, 32095, 32577, 33063, 33554, 34050, 34551, 35056,
35567, 36082, 36602, 37128, 37658, 38194, 38734, 39280,
39830, 40386, 40947, 41513, 42084, 42661, 43243, 43830,
44422, 45019, 45622, 46231, 46844, 47463, 48088, 48718,
49353, 49994, 50641, 51293, 51950, 52614, 53282, 53957,
54637, 55323, 56014, 56712, 57415, 58123, 58838, 59558,
60285, 61017, 61755, 62499, 63249, 64005, 64767, 65535,
};
#endif
static void clock_setup(void)
{
rcc_clock_setup_in_hse_8mhz_out_72mhz();
/* Enable TIM3 clock. */
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_TIM3EN);
/* Enable GPIOC, Alternate Function clocks. */
rcc_peripheral_enable_clock(&RCC_APB2ENR,
RCC_APB2ENR_IOPAEN |
RCC_APB2ENR_IOPBEN |
RCC_APB2ENR_AFIOEN);
}
static void gpio_setup(void)
{
/*
* Set GPIO6 and 7 (in GPIO port A) to
* 'output alternate function push-pull'.
*/
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL,
GPIO_TIM3_CH1 | GPIO_TIM3_CH2);
/*
* Set GPIO0 and 1 (in GPIO port B) to
* 'output alternate function push-pull'.
*/
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL,
GPIO_TIM3_CH3 | GPIO_TIM3_CH4);
}
static void tim_setup(void)
{
/* Clock division and mode */
TIM3_CR1 = TIM_CR1_CKD_CK_INT | TIM_CR1_CMS_EDGE;
/* Period */
TIM3_ARR = 65535;
/* Prescaler */
TIM3_PSC = 0;
TIM3_EGR = TIM_EGR_UG;
/* ---- */
/* Output compare 1 mode and preload */
TIM3_CCMR1 |= TIM_CCMR1_OC1M_PWM1 | TIM_CCMR1_OC1PE;
/* Polarity and state */
TIM3_CCER |= TIM_CCER_CC1P | TIM_CCER_CC1E;
//TIM3_CCER |= TIM_CCER_CC1E;
/* Capture compare value */
TIM3_CCR1 = 0;
/* ---- */
/* Output compare 2 mode and preload */
TIM3_CCMR1 |= TIM_CCMR1_OC2M_PWM1 | TIM_CCMR1_OC2PE;
/* Polarity and state */
TIM3_CCER |= TIM_CCER_CC2P | TIM_CCER_CC2E;
//TIM3_CCER |= TIM_CCER_CC2E;
/* Capture compare value */
TIM3_CCR2 = 0;
/* ---- */
/* Output compare 3 mode and preload */
TIM3_CCMR2 |= TIM_CCMR2_OC3M_PWM1 | TIM_CCMR2_OC3PE;
/* Polarity and state */
TIM3_CCER |= TIM_CCER_CC3P | TIM_CCER_CC3E;
//TIM3_CCER |= TIM_CCER_CC3E;
/* Capture compare value */
TIM3_CCR3 = 0;
/* ---- */
/* Output compare 4 mode and preload */
TIM3_CCMR2 |= TIM_CCMR2_OC4M_PWM1 | TIM_CCMR2_OC4PE;
/* Polarity and state */
TIM3_CCER |= TIM_CCER_CC4P | TIM_CCER_CC4E;
//TIM3_CCER |= TIM_CCER_CC4E;
/* Capture compare value */
TIM3_CCR4 = 0;
/* ---- */
/* ARR reload enable */
TIM3_CR1 |= TIM_CR1_ARPE;
/* Counter enable */
TIM3_CR1 |= TIM_CR1_CEN;
}
int main(void)
{
int i, j0, j1, j2, j3, d0, d1, d2, d3, j, k, kd;
clock_setup();
gpio_setup();
tim_setup();
#ifdef COMPARE
j0 = 0;
d0 = 1;
j1 = 0;
d1 = 1;
j2 = 0;
d2 = 1;
j3 = 0;
d3 = 1;
while (1) {
TIM3_CCR1 = gamma_table_linear[j0];
j0 += d0;
if (j0 == 255)
d0 = -1;
if (j0 == 0)
d0 = 1;
TIM3_CCR2 = gamma_table_1_3[j1];
j1 += d1;
if (j1 == 255)
d1 = -1;
if (j1 == 0)
d1 = 1;
TIM3_CCR3 = gamma_table_2_5[j2];
j2 += d2;
if (j2 == 255)
d2 = -1;
if (j2 == 0)
d2 = 1;
TIM3_CCR4 = gamma_table_3_0[j3];
j3 += d3;
if (j3 == 255)
d3 = -1;
if (j3 == 0)
d3 = 1;
for (i = 0; i < 50000; i++);
}
#endif
#ifdef MOVING_FADE
j0 = 0;
d0 = 1;
j1 = 128;
d1 = 1;
j2 = 255;
d2 = -1;
j3 = 128;
d3 = -1;
while (1) {
TIM3_CCR1 = GAMMA_TABLE[j0];
j0 += d0;
if (j0 == 255)
d0 = -1;
if (j0 == 0)
d0 = 1;
TIM3_CCR2 = GAMMA_TABLE[j1];
j1 += d1;
if (j1 == 255)
d1 = -1;
if (j1 == 0)
d1 = 1;
TIM3_CCR3 = GAMMA_TABLE[j2];
j2 += d2;
if (j2 == 255)
d2 = -1;
if (j2 == 0)
d2 = 1;
TIM3_CCR4 = GAMMA_TABLE[j3];
j3 += d3;
if (j3 == 255)
d3 = -1;
if (j3 == 0)
d3 = 1;
for (i = 0; i < 10000; i++);
}
#endif
#ifdef KITT
j0 = 255;
d0 = -1;
j1 = 20;
d1 = -1;
j2 = 20;
d2 = -1;
j3 = 20;
d3 = -1;
j = 0;
k = 0;
kd = 1;
while (1) {
TIM3_CCR1 = GAMMA_TABLE[j0];
j0 += d0;
if (j0 == 255)
d0 = -1;
if (j0 == 19)
j0 = 20;
TIM3_CCR2 = GAMMA_TABLE[j1];
j1 += d1;
if (j1 == 255)
d1 = -1;
if (j1 == 19)
j1 = 20;
TIM3_CCR3 = GAMMA_TABLE[j2];
j2 += d2;
if (j2 == 255)
d2 = -1;
if (j2 == 19)
j2 = 20;
TIM3_CCR4 = GAMMA_TABLE[j3];
j3 += d3;
if (j3 == 255)
d3 = -1;
if (j3 == 19)
j3 = 20;
for (i = 0; i < 15000; i++)
__asm__("nop");
j++;
if (j == 100) {
j = 0;
switch (k += kd) {
case 0:
j0 = 255;
break;
case 1:
j1 = 255;
break;
case 2:
j2 = 255;
break;
case 3:
j3 = 255;
break;
}
if (k == 3)
kd = -1;
if (k == 0)
kd = 1;
}
}
#endif
return 0;
}

View File

@@ -0,0 +1,25 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = systick
LDSCRIPT = ../obldc.ld
include ../../Makefile.include

View File

@@ -0,0 +1,91 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
* Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/flash.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/cm3/nvic.h>
#include <libopencm3/cm3/systick.h>
u32 temp32;
static void gpio_setup(void)
{
/* Enable GPIOA clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
/* Enable GPIOB clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
gpio_set(GPIOA, GPIO6); /* LED0 off */
gpio_set(GPIOA, GPIO7); /* LED1 off */
gpio_set(GPIOB, GPIO0); /* LED2 off */
gpio_set(GPIOB, GPIO1); /* LED3 off */
/* Set GPIO6/7 (in GPIO port A) to 'output push-pull' for the LEDs. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO6);
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO7);
/* Set GPIO0/1 (in GPIO port B) to 'output push-pull' for the LEDs. */
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO0);
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO1);
}
void sys_tick_handler(void)
{
temp32++;
/* We call this handler every 1ms so 1000ms = 1s on/off. */
if (temp32 == 1000) {
gpio_toggle(GPIOA, GPIO6); /* LED2 on/off */
temp32 = 0;
}
}
int main(void)
{
rcc_clock_setup_in_hse_8mhz_out_72mhz();
gpio_setup();
gpio_clear(GPIOA, GPIO7); /* LED1 on */
gpio_set(GPIOA, GPIO6); /* LED2 off */
temp32 = 0;
/* 72MHz / 8 => 9000000 counts per second */
systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
/* 9000000/9000 = 1000 overflows per second - every 1ms one interrupt */
/* SysTick interrupt every N clock pulses: set reload to N-1 */
systick_set_reload(8999);
systick_interrupt_enable();
/* Start counting. */
systick_counter_enable();
while (1); /* Halt. */
return 0;
}

View File

@@ -0,0 +1,25 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = usart
LDSCRIPT = ../obldc.ld
include ../../Makefile.include

View File

@@ -0,0 +1,90 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/stm32/usart.h>
static void clock_setup(void)
{
rcc_clock_setup_in_hse_8mhz_out_72mhz();
/* Enable GPIOA clock (for LED GPIOs). */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
/* Enable clocks for GPIO port B (for GPIO_USART1_TX) and USART1. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_USART1EN);
}
static void usart_setup(void)
{
/* Setup GPIO6 (in GPIO port A) to 'output push-pull' for LED use. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO6);
AFIO_MAPR |= AFIO_MAPR_USART1_REMAP;
/* Setup GPIO pin GPIO_USART3_TX/GPIO10 on GPIO port B for transmit. */
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART1_RE_TX);
/* Setup UART parameters. */
usart_set_baudrate(USART1, 230400);
usart_set_databits(USART1, 8);
usart_set_stopbits(USART1, USART_STOPBITS_1);
usart_set_mode(USART1, USART_MODE_TX);
usart_set_parity(USART1, USART_PARITY_NONE);
usart_set_flow_control(USART1, USART_FLOWCONTROL_NONE);
/* Finally enable the USART. */
usart_enable(USART1);
}
static void gpio_setup(void)
{
/* Set GPIO6 (in GPIO port A) to 'output push-pull'. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO6);
}
int main(void)
{
int i, j = 0, c = 0;
clock_setup();
gpio_setup();
usart_setup();
/* Blink the LED (PA6) on the board with every transmitted byte. */
while (1) {
gpio_toggle(GPIOA, GPIO6); /* LED on/off */
usart_send_blocking(USART1, c + '0'); /* Send a byte. */
c = (c == 9) ? 0 : c + 1; /* Increment c. */
if ((j++ % 80) == 0) { /* Newline after line full. */
usart_send_blocking(USART1, '\r');
usart_send_blocking(USART1, '\n');
}
for (i = 0; i < 800000; i++) /* Wait a bit. */
__asm__("nop");
}
return 0;
}

View File

@@ -0,0 +1,27 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = usart_irq
OOCD_BOARD = open-bldc
LDSCRIPT = ../obldc.ld
include ../../Makefile.include

View File

@@ -0,0 +1,120 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/stm32/usart.h>
#include <libopencm3/cm3/nvic.h>
static void clock_setup(void)
{
rcc_clock_setup_in_hse_8mhz_out_72mhz();
/* Enable GPIOA clock (for LED GPIOs). */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
/* Enable clocks for GPIO port B (for GPIO_USART1_TX) and USART1. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_USART1EN);
}
static void usart_setup(void)
{
/* Enable the USART1 interrupt. */
nvic_enable_irq(NVIC_USART1_IRQ);
/* Enable USART1 pin software remapping. */
AFIO_MAPR |= AFIO_MAPR_USART1_REMAP;
/* Setup GPIO pin GPIO_USART1_RE_TX on GPIO port B for transmit. */
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART1_RE_TX);
/* Setup GPIO pin GPIO_USART1_RE_RX on GPIO port B for receive. */
gpio_set_mode(GPIOB, GPIO_MODE_INPUT,
GPIO_CNF_INPUT_FLOAT, GPIO_USART1_RE_RX);
/* Setup UART parameters. */
usart_set_baudrate(USART1, 230400);
usart_set_databits(USART1, 8);
usart_set_stopbits(USART1, USART_STOPBITS_1);
usart_set_parity(USART1, USART_PARITY_NONE);
usart_set_flow_control(USART1, USART_FLOWCONTROL_NONE);
usart_set_mode(USART1, USART_MODE_TX_RX);
/* Enable USART1 Receive interrupt. */
USART_CR1(USART1) |= USART_CR1_RXNEIE;
/* Finally enable the USART. */
usart_enable(USART1);
}
static void gpio_setup(void)
{
gpio_set(GPIOA, GPIO6 | GPIO7);
/* Setup GPIO6 and 7 (in GPIO port A) for LED use. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO6 | GPIO7);
}
void usart1_isr(void)
{
static u8 data = 'A';
/* Check if we were called because of RXNE. */
if (((USART_CR1(USART1) & USART_CR1_RXNEIE) != 0) &&
((USART_SR(USART1) & USART_SR_RXNE) != 0)) {
/* Indicate that we got data. */
gpio_toggle(GPIOA, GPIO6);
/* Retrieve the data from the peripheral. */
data = usart_recv(USART1);
/* Enable transmit interrupt so it sends back the data. */
USART_CR1(USART1) |= USART_CR1_TXEIE;
}
/* Check if we were called because of TXE. */
if (((USART_CR1(USART1) & USART_CR1_TXEIE) != 0) &&
((USART_SR(USART1) & USART_SR_TXE) != 0)) {
/* Indicate that we are sending out data. */
gpio_toggle(GPIOA, GPIO7);
/* Put data into the transmit register. */
usart_send(USART1, data);
/* Disable the TXE interrupt as we don't need it anymore. */
USART_CR1(USART1) &= ~USART_CR1_TXEIE;
}
}
int main(void)
{
clock_setup();
gpio_setup();
usart_setup();
/* Wait forever and do nothing. */
while (1)
__asm__("nop");
return 0;
}

View File

@@ -0,0 +1,23 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = adc
include ../../Makefile.include

View File

@@ -0,0 +1,10 @@
------------------------------------------------------------------------------
README
------------------------------------------------------------------------------
This example program sends some characters on USART1.
Afterwards it read out the internal temperature sensor of the STM32 and
sends the value read out from the ADC to the USART1.
The terminal settings for the receiving device/PC are 115200 8n1.

View File

@@ -0,0 +1,153 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
*
* This library is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
#include <libopencm3/stm32/f1/rcc.h>
#include <libopencm3/stm32/f1/flash.h>
#include <libopencm3/stm32/f1/gpio.h>
#include <libopencm3/stm32/f1/adc.h>
#include <libopencm3/stm32/usart.h>
static void usart_setup(void)
{
/* Enable clocks for GPIO port A (for GPIO_USART1_TX) and USART1. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_USART1EN);
/* Setup GPIO pin GPIO_USART1_TX/GPIO9 on GPIO port A for transmit. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART1_TX);
/* Setup UART parameters. */
usart_set_baudrate(USART1, 115200);
usart_set_databits(USART1, 8);
usart_set_stopbits(USART1, USART_STOPBITS_1);
usart_set_mode(USART1, USART_MODE_TX_RX);
usart_set_parity(USART1, USART_PARITY_NONE);
usart_set_flow_control(USART1, USART_FLOWCONTROL_NONE);
/* Finally enable the USART. */
usart_enable(USART1);
}
static void gpio_setup(void)
{
/* Enable GPIOB clock. */
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
/* Set GPIO6/7 (in GPIO port B) to 'output push-pull' for the LEDs. */
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO6);
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO7);
}
static void adc_setup(void)
{
int i;
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_ADC1EN);
/* Make sure the ADC doesn't run during config. */
adc_off(ADC1);
/* We configure everything for one single conversion. */
adc_disable_scan_mode(ADC1);
adc_set_single_conversion_mode(ADC1);
adc_disable_external_trigger_regular(ADC1);
adc_set_right_aligned(ADC1);
/* We want to read the temperature sensor, so we have to enable it. */
adc_enable_temperature_sensor(ADC1);
adc_set_sample_time_on_all_channels(ADC1, ADC_SMPR_SMP_28DOT5CYC);
adc_power_on(ADC1);
/* Wait for ADC starting up. */
for (i = 0; i < 800000; i++) /* Wait a bit. */
__asm__("nop");
adc_reset_calibration(ADC1);
adc_calibration(ADC1);
}
static void my_usart_print_int(u32 usart, int value)
{
s8 i;
u8 nr_digits = 0;
char buffer[25];
if (value < 0) {
usart_send(usart, '-');
value = value * -1;
}
while (value > 0) {
buffer[nr_digits++] = "0123456789"[value % 10];
value /= 10;
}
for (i = nr_digits; i >= 0; i--)
usart_send(usart, buffer[i]);
}
int main(void)
{
u8 channel_array[16];
u16 temperature;
rcc_clock_setup_in_hse_16mhz_out_72mhz();
gpio_setup();
usart_setup();
adc_setup();
gpio_clear(GPIOB, GPIO7); /* LED1 on */
gpio_set(GPIOB, GPIO6); /* LED2 off */
/* Send a message on USART1. */
usart_send(USART1, 's');
usart_send(USART1, 't');
usart_send(USART1, 'm');
usart_send(USART1, '\r');
usart_send(USART1, '\n');
/* Select the channel we want to convert. 16=temperature_sensor. */
channel_array[0] = 16;
adc_set_regular_sequence(ADC1, 1, channel_array);
/*
* Start the conversion directly (not trigger mode).
*/
adc_start_conversion_direct(ADC1);
/* Wait for end of conversion. */
while (!(ADC_SR(ADC1) & ADC_SR_EOC));
temperature = ADC_DR(ADC1);
/*
* That's actually not the real temperature - you have to compute it
* as described in the datasheet.
*/
my_usart_print_int(USART1, temperature);
gpio_clear(GPIOB, GPIO6); /* LED2 on */
while(1); /* Halt. */
return 0;
}

View File

@@ -0,0 +1,31 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
*
* 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/>.
*/
/* Linker script for an STM32F103RBT6 board (128K flash, 20K RAM). */
/* Define memory regions. */
MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
}
/* Include the common ld script. */
INCLUDE libopencm3_stm32f1.ld

View File

@@ -0,0 +1,23 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
BINARY = dma
include ../../Makefile.include

View File

@@ -0,0 +1,11 @@
------------------------------------------------------------------------------
README
------------------------------------------------------------------------------
This program demonstrates a little DMA MEM2MEM transfer. A string is sent out
to USART1 and afterwards copied by DMA to another memory location. To check
if the transfer was successful we send the destination string also out to
USART1.
The terminal settings for the receiving device/PC are 115200 8n1.

Some files were not shown because too many files have changed in this diff Show More