From 618de224e004d5ea2a79e93571e4056ebf2cbaa1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?King=20K=C3=A9vin?= Date: Thu, 18 Feb 2016 10:39:08 +0100 Subject: [PATCH] add all common changes, files, and libraries from previous project --- .gitignore | 1 + .gitmodules | 2 + Makefile | 58 +++++++---- README.md | 11 +- global.h | 18 ++-- lib/bluetooth_hc-05.c | 235 ++++++++++++++++++++++++++++++++++++++++++ lib/bluetooth_hc-05.h | 36 +++++++ lib/flash_storage.c | 113 ++++++++++++++++++++ lib/flash_storage.h | 33 ++++++ lib/led_ws2812b.c | 175 +++++++++++++++++++++++++++++++ lib/led_ws2812b.h | 29 ++++++ lib/usart.c | 29 ++++-- lib/usart.h | 16 +-- lib/usart_ir.c | 175 +++++++++++++++++++++++++++++++ lib/usart_ir.h | 32 ++++++ lib/usart_irda.c | 152 +++++++++++++++++++++++++++ lib/usart_irda.h | 31 ++++++ lib/usb_cdcacm.c | 51 +++++---- lib/usb_cdcacm.h | 2 +- main.c | 21 +++- 20 files changed, 1144 insertions(+), 76 deletions(-) create mode 100644 lib/bluetooth_hc-05.c create mode 100644 lib/bluetooth_hc-05.h create mode 100644 lib/flash_storage.c create mode 100644 lib/flash_storage.h create mode 100644 lib/led_ws2812b.c create mode 100644 lib/led_ws2812b.h create mode 100644 lib/usart_ir.c create mode 100644 lib/usart_ir.h create mode 100644 lib/usart_irda.c create mode 100644 lib/usart_irda.h diff --git a/.gitignore b/.gitignore index 6e98e2e..352c2f3 100644 --- a/.gitignore +++ b/.gitignore @@ -1,5 +1,6 @@ *.o *.d +*.inc *.hex *.lst *.map diff --git a/.gitmodules b/.gitmodules index 58f51fb..ad0820c 100644 --- a/.gitmodules +++ b/.gitmodules @@ -1,6 +1,8 @@ [submodule "libopencm3"] path = libopencm3 url = https://github.com/libopencm3/libopencm3 + ignore = all [submodule "STM32duino-bootloader"] path = STM32duino-bootloader url = https://github.com/rogerclarkmelbourne/STM32duino-bootloader.git + ignore = all diff --git a/Makefile b/Makefile index 3f3890e..2f85639 100644 --- a/Makefile +++ b/Makefile @@ -25,14 +25,23 @@ endif BINARY = firmware # which development board is used -# supported are: SYSTEM_BOARD, MAPLE_MINI +# supported are: SYSTEM_BOARD, MAPLE_MINI, BLUE_PILL BOARD = MAPLE_MINI # source files -LIBS = lib CSRC = $(wildcard *.c) -CSRC += $(foreach LIB,$(LIBS),$(wildcard $(LIB)/*.c)) OBJ = $(patsubst %.c,%.o,$(CSRC)) +# figure out based on the includes which library files are used in the main CSRC files +DEPENDENCIES = $(patsubst %.c,%.inc,$(CSRC)) + +# my library collection +LIB = lib +# the library files to use +# this will be populated using includes based DEPENDENCIES +LIB_CSRC = +LIB_OBJ = $(patsubst %.c,%.o,$(LIB_CSRC)) +# populates LIB_CSRC based on the library files used +-include $(DEPENDENCIES) # executables PREFIX ?= arm-none-eabi @@ -63,16 +72,16 @@ DEFS += -DSTM32F1 -D$(BOARD) # C flags CFLAGS += -Os -g -CFLAGS += -Wall -Werror -Wundef -Wextra -Wshadow -Wimplicit-function-declaration -CFLAGS += -Wredundant-decls -Wmissing-prototypes -Wstrict-prototypes +CFLAGS += -Wall -Werror -Wundef -Wextra -Wshadow -Wimplicit-function-declaration -Wredundant-decls -Wmissing-prototypes -Wstrict-prototypes CFLAGS += -fno-common -ffunction-sections -fdata-sections -CFLAGS += -MD -CFLAGS += -I. -I$(INCLUDE_DIR) $(patsubst %,-I%,$(LIBS)) +CFLAGS += -I. -I$(INCLUDE_DIR) $(patsubst %,-I%,$(LIB)) CFLAGS += $(DEFS) # linker script ifeq ($(BOARD),SYSTEM_BOARD) LDSCRIPT = stm32f103x8-dfu.ld +else ifeq ($(BOARD),BLUE_PILL) +LDSCRIPT = stm32f103x8-dfu.ld else ifeq ($(BOARD),MAPLE_MINI) LDSCRIPT = stm32f103xb-dfu.ld endif @@ -80,7 +89,7 @@ endif # linker flags LDFLAGS += --static -nostartfiles LDFLAGS += -L$(LIB_DIR) -LDFLAGS += -I. $(patsubst %,-I%,$(LIBS)) +LDFLAGS += -I. $(patsubst %,-I%,$(LIB)) LDFLAGS += -T$(LDSCRIPT) LDFLAGS += -Wl,-Map=$(*).map LDFLAGS += -Wl,--gc-sections @@ -110,6 +119,8 @@ ACMPORT_EXISTS = $(shell [ -e $(ACMPORT) ] && echo 1 || echo 0 ) BOOTLOADERS = STM32duino-bootloader ifeq ($(BOARD),SYSTEM_BOARD) BOOTLOADER = $(BOOTLOADERS)/STM32F1/binaries/generic_boot20_pa1.bin +else ifeq ($(BOARD),BLUE_PILL) +BOOTLOADER = $(BOOTLOADERS)/STM32F1/binaries/generic_boot20_pc13.bin else ifeq ($(BOARD),MAPLE_MINI) BOOTLOADER = $(BOOTLOADERS)/STM32F1/binaries/maple_mini_boot20.bin endif @@ -131,30 +142,33 @@ srec: $(BINARY).srec list: $(BINARY).list %.bin: %.elf - $(Q)$(OBJCOPY) -Obinary $(<) $(@) - %.hex: %.elf - $(Q)$(OBJCOPY) -Oihex $(<) $(@) - %.srec: %.elf $(Q)$(OBJCOPY) -Osrec $(<) $(@) +%.map: %.elf %.list: %.elf $(Q)$(OBJDUMP) -S $(<) > $(@) -%.map: %.elf - @# it's generated along with the elf - -%.elf: $(LDSCRIPT) $(LIB_DIR)/lib$(LIBNAME).a $(OBJ) +%.elf: $(LDSCRIPT) $(LIB_DIR)/lib$(LIBNAME).a $(OBJ) $(LIB_OBJ) $(info compiling $(@)) - $(Q)$(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJ) $(LDLIBS) -o $(@) + $(Q)$(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJ) $(LIB_OBJ) $(LDLIBS) -o $(@) $(Q)size $(@) %.o: %.c $(Q)$(CC) $(CFLAGS) $(ARCH_FLAGS) -o $(@) -c $(<) +# generate dependencies +%.d: %.c + @# check which libraries are used + $(Q)$(CC) $(CFLAGS) $(ARCH_FLAGS) -MM -MF $(@) -o /dev/null -c $(<) + +# figure out which library source files are used for later inclusion +%.inc: %.d + $(Q)grep -o -e " ${LIB}\/[^ ]*\.h" $(<) | sed -e 's/\.h$$/.c/g' -e 's/^/LIB_CSRC +=/' > $(@) + clean: - $(Q)$(RM) *.o *.d *.elf *.bin *.hex *.srec *.list *.map + $(Q)$(RM) $(BINARY).elf $(BINARY).bin $(BINARY).hex $(BINARY).map $(OBJ) $(LIB_OBJ) $(LIB)/*.o $(DEPENDENCIES) # make libopencm3 if not done $(LIB_DIR)/lib$(LIBNAME).a: @@ -182,6 +196,8 @@ flash-dfu: $(BINARY).bin reset $(info flashing $(<) using DFU) $(Q)dfu-util --device 1eaf:0003 --cfg 1 --intf 0 --alt 2 --reset --download $(<) $(NULL) -.PHONY: clean elf bin hex srec list bootloader flash flash-swd flash-dfu -.SECONDARY: --include $(OBJ:.o=.d) +# debug using jtag (openOCB+GDB) +debug: $(BINARY).elf + $(Q)$(GDB) --eval-command="target remote | $(OOCD) --file interface/stlink-v2.cfg --file target/stm32f1x.cfg --command \"gdb_port pipe; log_output /dev/null; init\"" --eval-command="monitor reset halt" --eval-command="load" --eval-command="monitor reset init" $(<) + +.PHONY: clean elf bin hex srec list libraries bootloader $(BOOTLOADER) flash flash-swd reset flash-dfu diff --git a/README.md b/README.md index 55d6deb..d671115 100644 --- a/README.md +++ b/README.md @@ -19,6 +19,7 @@ board currently the following development boards are supported: - [Maple Mini](http://leaflabs.com/docs/hardware/maple-mini.html), based on a STM32F103CBT6 - [System Board](http://www.aliexpress.com/item/stm32f103c8t6-stm32f103-stm32f1-stm32-system-board-learning-board-evaluation-kit-development-board/2042654667.html), based on a STM32F103C8T6 +- [blue pill](http://www.aliexpress.com/item/1pcs-STM32F103C8T6-ARM-STM32-Minimum-System-Development-Board-Module-For-arduino/32478120209.html), based on a STM32F103C8T6 **you need to define which board you are using in the Makefile** @@ -40,16 +41,20 @@ SWD --- to flash over SWD you need an SWD adapter. -the `Makefile` uses a ST-Link V2 (clone), along with the OpenOCD software. +the `Makefile` uses a ST-Link V2, along with the OpenOCD software. the main firmware will be placed after the bootloader. thus you first need to flash the bootloader first (see below), else the main firmware will not be started. +to flash the bootloader run `make bootloader`. -SWD is nice because it will always work, even is USB is buggy, or the code on the board is stuck. +SWD is nice because it will always work, even if USB is buggy, or the code on the board is stuck. it also does not require to press on any reset button. to flash using SWD run `make flash-swd` +SWD also allows you to debug the code running on the micro-controller using GDB. +to start the debugging session use `make debug`. + DFU --- @@ -71,6 +76,8 @@ firmware the firmware provides basic example code for various peripherals. +to compile the firmware run `make` + button ------ diff --git a/global.h b/global.h index a25267c..e09e248 100644 --- a/global.h +++ b/global.h @@ -13,7 +13,7 @@ * */ /* Copyright (c) 2016 King Kévin */ - +#pragma once #include // GPIO defines #include // interrupt defines #include // external interrupt defines @@ -21,16 +21,18 @@ /* get the length of an array */ #define LENGTH(x) (sizeof(x) / sizeof((x)[0])) -/* system clock frequency in Hz */ -#define SYSTEM_CLOCK_FREQ 72000000 - /* LED pin */ -#ifdef SYSTEM_BOARD +#if defined(SYSTEM_BOARD) /* on system board LED is on pin 11/PA1 */ #define LED_RCC RCC_GPIOA #define LED_PORT GPIOA #define LED_PIN GPIO1 -#elif MAPLE_MINI +#elif defined(BLUE_PILL) +/* on minimum system LED is on pin 2/PC13 */ +#define LED_RCC RCC_GPIOC +#define LED_PORT GPIOC +#define LED_PIN GPIO13 +#elif defined (MAPLE_MINI) /* on maple mini LED is on pin 19/PB1 */ #define LED_RCC RCC_GPIOB #define LED_PORT GPIOB @@ -38,7 +40,7 @@ #endif /* user button */ -#ifdef MAPLE_MINI +#if defined(MAPLE_MINI) /* on maple mini button is on 32/PB8 */ #define BUTTON_RCC RCC_GPIOB #define BUTTON_PORT GPIOB @@ -56,4 +58,6 @@ void led_off(void); void led_toggle(void); /* default output (i.e. for printf) */ int _write(int file, char *ptr, int len); +/* print binary as string */ +char* b2s(uint32_t binary, uint8_t rjust); diff --git a/lib/bluetooth_hc-05.c b/lib/bluetooth_hc-05.c new file mode 100644 index 0000000..3a13503 --- /dev/null +++ b/lib/bluetooth_hc-05.c @@ -0,0 +1,235 @@ +/* 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 . + * + */ +/* Copyright (c) 2016 King Kévin */ +/* this library handles the communication with a HC-05 bluetooth module */ +/* peripherals used: USART (check source for details) */ + +/* standard libraries */ +#include // standard integer types +#include // standard I/O facilities +#include // general utilities +#include // string utilities + +/* STM32 (including CM3) libraries */ +#include // real-time control clock library +#include // general purpose input output library +#include // universal synchronous asynchronous receiver transmitter library +#include // interrupt handler +#include // Cortex M3 utilities + +#include "global.h" // common utilities +#include "bluetooth_hc-05.h" // USART header and definitions + +/* which USART to use to talk to the bluetooth module */ +#define USART USART2 +#define USART_RCC RCC_USART2 +#define USART_IRQ NVIC_USART2_IRQ +#define USART_PORT GPIOA +#define USART_PIN_TX GPIO_USART2_TX +#define USART_PIN_RX GPIO_USART3_RX +#define USART_BAUDRATE 9600 +/* AT mode pin + * to configure the HC-05 bluetooth module you need to put it in AT mode and use AT commands + * there are several ways to get into AT mode, and there are several AT modes + * - in full AT mode you can send all [defined] AT commands + * - in mini AT mode you can't send some AT commands, such as AT+NAME + * the AT mode is defined by the state of pin 34 of the module (top right) + * - high: full AT mode + * - low: mini AT mode + * this pin is often connect to a switch on the adapter board (connected to VCC) + * to enter AT mode: + * - set pin 34 high when powering up, the LED will blink slowly, the baudrate will be 38400, bluetooth will be off + * - set pin 34 high after powering up, the LED will keep blinking fast, the baudrate is user defined (AT+UART), bluetooth communication will keep working + * setting pin 34 low after setting it high will put it into mini AT mode, except when bluetooth is not connected + * when booting normally (fast blinking LED), the module will not respond to AT commands before setting pin 34 high + * connect pin 34 to a STM32 GPIO to be able to go into AT mode */ +#define AT_PORT GPIOB +#define AT_RCC RCC_GPIOB +#define AT_PIN GPIO5 + +/* input and output ring buffer, indexes, and available memory */ +static uint8_t rx_buffer[BT_BUFFER] = {0}; +static volatile uint8_t rx_i = 0; +static volatile uint8_t rx_used = 0; +static uint8_t tx_buffer[BT_BUFFER] = {0}; +static volatile uint8_t tx_i = 0; +static volatile uint8_t tx_used = 0; +/* show the user how much data received over bluetooth is ready */ +volatile uint8_t bt_received = 0; // same as rx_used, but since the user can write this variable we don't rely on it + +/* display configuration of bluetooth module */ +void bt_info(void) +{ + char* at_commands[] = {"AT+VERSION?","AT+ADDR?","AT+ROLE?","AT+UART?","AT+CMODE?","AT+STATE?","AT+NAME?"}; + char* ok = "OK\r\n"; + gpio_set(AT_PORT, AT_PIN); // enable AT mode + for (uint8_t i=0; i=sizeof(tx_buffer)) { // idle until buffer has some space + usart_enable_tx_interrupt(USART); // enable transmit interrupt + __WFI(); // sleep until something happened + } + tx_buffer[(tx_i+tx_used)%sizeof(tx_buffer)] = c; // put character in buffer + tx_used++; // update used buffer + usart_enable_tx_interrupt(USART); // enable transmit interrupt +} + +#if (USART==USART1) +void usart1_isr(void) +#elif (USART==USART2) +void usart2_isr(void) +#elif (USART==USART3) +void usart3_isr(void) +#endif +{ // USART interrupt + if (usart_get_interrupt_source(USART, USART_SR_TXE)) { // data has been transmitted + if (!tx_used) { // no data in the buffer to transmit + usart_disable_tx_interrupt(USART); // disable transmit interrupt + } else { + usart_send(USART,tx_buffer[tx_i]); // put data in transmit register + tx_i = (tx_i+1)%sizeof(rx_buffer); // update location on buffer + tx_used--; // update used size + } + } + if (usart_get_interrupt_source(USART, USART_SR_RXNE)) { // data has been received + // only save data if there is space in the buffer + if (rx_used>=sizeof(rx_buffer)) { + usart_recv(USART); // read to clear interrupt + } else { + rx_buffer[(rx_i+rx_used)%sizeof(rx_buffer)] = usart_recv(USART); // put character in buffer + rx_used++; // update used buffer + bt_received = rx_used; // update available data + } + } +} diff --git a/lib/bluetooth_hc-05.h b/lib/bluetooth_hc-05.h new file mode 100644 index 0000000..a4d8fc7 --- /dev/null +++ b/lib/bluetooth_hc-05.h @@ -0,0 +1,36 @@ +/* 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 . + * + */ +/* Copyright (c) 2016 King Kévin */ +/* this library handles the communication with a HC-05 bluetooth module */ +/* peripherals used: USART (check source for details) */ +#pragma once + +/* RX and TX buffer sizes */ +#define BT_BUFFER 128 +/* show the user how much received is available */ +extern volatile uint8_t bt_received; + +/* display configuration of bluetooth module */ +void bt_info(void); +/* setup communication to bluetooth module */ +void bt_setup(void); +/* send character over bluetooth (blocking) */ +void bt_putchar_blocking(char c); +/* ensure all data has been transmitted (blocking) */ +void bt_flush(void); +/* get character received over bluetooth (blocking) */ +char bt_getchar(void); +/* send character over bluetooth (non-blocking until buffer is full) */ +void bt_putchar_nonblocking(char c); diff --git a/lib/flash_storage.c b/lib/flash_storage.c new file mode 100644 index 0000000..b7df97e --- /dev/null +++ b/lib/flash_storage.c @@ -0,0 +1,113 @@ +/* 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 . + * + */ +/* Copyright (c) 2016 King Kévin */ +/* this library is used to store (read and write) data in flash */ +/* peripherals used: none */ + +/* standard libraries */ +#include // standard integer types +#include // general utilities + +/* STM32 (including CM3) libraries */ +#include // device signature utilities +#include // flash utilities + +#include "flash_storage.h" // flash storage library API +#include "global.h" // global definitions + +// the flash page size (medium-density devices have 1KiB page size) +#define PAGE_SIZE 1024 + +/* read data from address
into + * returns if read succeeded */ +bool storage_read(uint32_t address, uint8_t *buffer, size_t size) +{ + // verify it's in the storage area + if (addressSTORAGE_END) { + return false; + } + if (buffer==NULL || size==0) { + return false; + } + + // copy data byte per byte + // a more efficient way would be to copy words, than the remaining bytes + for (size_t i=0; i data from to address
+ * returns if write succeeded */ +bool storage_write(uint32_t address, uint8_t *buffer, size_t size) +{ + // verify it's in the storage area + if (addressSTORAGE_END) { + return false; + } + if (buffer==NULL || size==0) { + return false; + } + + uint8_t page[PAGE_SIZE]; // the complete page to write + + flash_unlock(); // unlock flash to be able to write it + // go through memory + while (size) { + uint32_t page_pre = address%PAGE_SIZE; // the beginning data size in the page + address -= page_pre; // go to beginning of the page + storage_read(address, &page[0], page_pre); // copy existing data + if (size>=PAGE_SIZE-page_pre) { // no need to read tailing page data + for (uint16_t i=0; i. + * + */ +/* Copyright (c) 2016 King Kévin */ +/* this library is used to store (read and write) data in flash */ +/* peripherals used: none */ +#include // device signature utilities + +// how much data (in bytes) should we be able to store (be sure it's available and does not overlap the firmware) +#define STORAGE_SIZE 2048 +// the end of the flash area where to store data +#define STORAGE_END FLASH_BASE+DESIG_FLASH_SIZE +// the start of the flash area where to store data (be sure it's after the firmware data) +// we will only use the last kilobytes +#define STORAGE_START STORAGE_END-STORAGE_SIZE + +/* read data from address
into + * returns if read succeeded */ +bool storage_read(uint32_t address, uint8_t *buffer, size_t size); +/* write data from to address
+ * returns if write succeeded */ +bool storage_write(uint32_t address, uint8_t *buffer, size_t size); diff --git a/lib/led_ws2812b.c b/lib/led_ws2812b.c new file mode 100644 index 0000000..12735ee --- /dev/null +++ b/lib/led_ws2812b.c @@ -0,0 +1,175 @@ +/* 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 . + * + */ +/* Copyright (c) 2016 King Kévin */ +/* this library is used to drive a WS2812b LED chain */ +/* peripherals used: SPI , timer, DMA (check source for details) */ + +/* standard libraries */ +#include // standard integer types +#include // general utilities + +/* STM32 (including CM3) libraries */ +#include // real-time control clock library +#include // general purpose input output library +#include // SPI library +#include // timer library +#include // DMA library +#include // interrupt handler +#include // Cortex M3 utilities + +#include "led_ws2812b.h" // LED WS2812b library API +#include "global.h" // global definitions + +/* WS2812b peripheral configuration */ +#define WS2812B_SPI SPI1 +#define WS2812B_SPI_DR SPI1_DR +#define WS2812B_SPI_RCC RCC_SPI1 +#define WS2812B_SPI_PORT GPIOA +#define WS2812B_SPI_CLK GPIO_SPI1_SCK +#define WS2812B_SPI_DOUT GPIO_SPI1_MISO +#define WS2812B_TIMER TIM3 +#define WS2812B_TIMER_RCC RCC_TIM3 +#define WS2812B_TIMER_OC TIM_OC3 +#define WS2812B_CLK_RCC RCC_GPIOB +#define WS2812B_CLK_PORT GPIOB +#define WS2812B_CLK_PIN GPIO_TIM3_CH3 +#define WS2812B_DMA DMA1 // DMA1 supports SPI1_TX interrupt +#define WS2812B_DMA_RCC RCC_DMA1 // follows previous definition +#define WS2812B_DMA_CH DMA_CHANNEL3 // only DMA1 channel 3 supports SPI1_TX interrupt +#define WS2812B_DMA_IRQ NVIC_DMA1_CHANNEL3_IRQ // follows previous definition +#define WS2812B_DMA_ISR dma1_channel3_isr // follows previous definition + +/* template to encode one byte + * for each WS2812b bit which needs to be transfered we require to transfer 3 SPI bits + * the first SPI bit is the high start of the WS2812b bit frame + * the second SPI bit determines if the WS2812b bit is a 0 or 1 + * the third SPI bit is the last part of the WS2812b bit frame, which is always low + * only the first 24 bits (3*8) are used */ +#define WS2812B_SPI_TEMPLATE 0b10010010010010010010010000000000 + +uint8_t ws2812b_data[WS2812B_LEDS*3*3+40*3/8] = {0}; // SPI encode data to be shifted out for WS2812b + the 50us reset +static volatile bool transmit_flag = false; // is transmission ongoing + +/* set color of a single LED + * transmission needs to be done separately */ +void ws2812b_set_rgb(uint16_t led, uint8_t red, uint8_t green, uint8_t blue) +{ + // verify the led exists + if (led>=WS2812B_LEDS) { + return; + } + // wait for transmission to complete before changing the color + while (transmit_flag) { + __WFI(); + } + + uint8_t colors[] = {green, red, blue}; + + // generate the pattern + for (uint8_t color=0; color>bit)&0b1)<<(bit*3+9); // encode the data bits in the pattern + } + // store pattern + ws2812b_data[led*3*3+color*3+0] = (bits_color>>24); + ws2812b_data[led*3*3+color*3+1] = (bits_color>>16); + ws2812b_data[led*3*3+color*3+2] = (bits_color>>8); + } +} + +/* transmit colors to LEDs */ +void ws2812b_transmit(void) +{ + while (transmit_flag) { // wait for previous transmission to complete + __WFI(); + } + transmit_flag = true; // remember transmission started + dma_set_memory_address(WS2812B_DMA, WS2812B_DMA_CH, (uint32_t)ws2812b_data); + dma_set_number_of_data(WS2812B_DMA, WS2812B_DMA_CH, LENGTH(ws2812b_data)); // set the size of the data to transmit + dma_enable_transfer_complete_interrupt(WS2812B_DMA, WS2812B_DMA_CH); // warm when transfer is complete to stop transmission + dma_enable_channel(WS2812B_DMA, WS2812B_DMA_CH); // enable DMA channel + + spi_enable_tx_dma(WS2812B_SPI); // use DMA to provide data stream to be transfered + + timer_set_counter(WS2812B_TIMER, 0); // reset timer counter fro clean clock + timer_enable_counter(WS2812B_TIMER); // start timer to generate clock +} + +/* setup WS2812b LED controller */ +void ws2812b_setup(void) +{ + /* setup timer to generate clock of (using PWM): 800kHz*3 */ + rcc_periph_clock_enable(WS2812B_CLK_RCC); // enable clock for GPIO peripheral + gpio_set_mode(WS2812B_CLK_PORT, GPIO_MODE_OUTPUT_10_MHZ, GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, WS2812B_CLK_PIN); // set pin a output + rcc_periph_clock_enable(RCC_AFIO); // enable clock for alternate function (PWM) + rcc_periph_clock_enable(WS2812B_TIMER_RCC); // enable clock for timer peripheral + timer_reset(WS2812B_TIMER); // reset timer state + timer_set_mode(WS2812B_TIMER, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP); // set timer mode, use undivided timer clock, edge alignment (simple count), and count up + timer_set_prescaler(WS2812B_TIMER, 0); // no prescaler to keep most precise timer (72MHz/2^16=1099<800kHz) + timer_set_period(WS2812B_TIMER, rcc_ahb_frequency/800000/3-1); // set the clock frequency to 800kHz*3bit since we need to send 3 bits to output a 800kbps stream + timer_set_oc_value(WS2812B_TIMER, WS2812B_TIMER_OC, rcc_ahb_frequency/800000/3/2); // duty cycle to 50% + timer_set_oc_mode(WS2812B_TIMER, WS2812B_TIMER_OC, TIM_OCM_PWM1); // set timer to generate PWM (used as clock) + timer_enable_oc_output(WS2812B_TIMER, WS2812B_TIMER_OC); // enable output to generate the clock + + /* setup SPI to transmit data (we are slave and the clock comes from the above PWM): 3 SPI bits for 1 WS2812b bit */ + rcc_periph_clock_enable(WS2812B_SPI_RCC); // enable clock for SPI peripheral + gpio_set_mode(WS2812B_SPI_PORT, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, WS2812B_SPI_CLK); // set clock as input + gpio_set_mode(WS2812B_SPI_PORT, GPIO_MODE_OUTPUT_10_MHZ, GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, WS2812B_SPI_DOUT); // set MISO as output + spi_reset(WS2812B_SPI); // clear SPI values to default + spi_set_slave_mode(WS2812B_SPI); // set SPI as slave (since we use the clock as input) + spi_set_bidirectional_transmit_only_mode(WS2812B_SPI); // we won't receive data + spi_set_unidirectional_mode(WS2812B_SPI); // we only need to transmit data + spi_set_dff_8bit(WS2812B_SPI); // use 8 bits for simpler encoding (but there will be more interrupts) + spi_set_clock_polarity_1(WS2812B_SPI); // clock is high when idle + spi_set_clock_phase_1(WS2812B_SPI); // output data on second edge (rising) + spi_send_msb_first(WS2812B_SPI); // send least significant bit first + spi_enable_software_slave_management(WS2812B_SPI); // control the slave select in software (since there is no master) + spi_set_nss_low(WS2812B_SPI); // set NSS low so we can output + spi_enable(WS2812B_SPI); // enable SPI + // do not disable SPI or set NSS high since it will put MISO high, breaking the beginning of the next transmission + + /* configure DMA to provide the pattern to be shifted out from SPI to the WS2812b LEDs */ + rcc_periph_clock_enable(WS2812B_DMA_RCC); // enable clock for DMA peripheral + dma_channel_reset(WS2812B_DMA, WS2812B_DMA_CH); // start with fresh channel configuration + dma_set_memory_address(WS2812B_DMA, WS2812B_DMA_CH, (uint32_t)ws2812b_data); // set bit pattern as source address + dma_set_peripheral_address(WS2812B_DMA, WS2812B_DMA_CH, (uint32_t)&WS2812B_SPI_DR); // set SPI as peripheral destination address + dma_set_read_from_memory(WS2812B_DMA, WS2812B_DMA_CH); // set direction from memory to peripheral + dma_enable_memory_increment_mode(WS2812B_DMA, WS2812B_DMA_CH); // go through bit pattern + dma_set_memory_size(WS2812B_DMA, WS2812B_DMA_CH, DMA_CCR_MSIZE_8BIT); // read 8 bits from memory + dma_set_peripheral_size(WS2812B_DMA, WS2812B_DMA_CH, DMA_CCR_PSIZE_8BIT); // write 8 bits to peripheral + dma_set_priority(WS2812B_DMA, WS2812B_DMA_CH, DMA_CCR_PL_HIGH); // set priority to high since time is crucial for the peripheral + nvic_enable_irq(WS2812B_DMA_IRQ); // enable interrupts for this DMA channel + + // reset color + for (uint16_t led=0; led. + * + */ +/* Copyright (c) 2016 King Kévin */ +/* this library is used to drive a WS2812b LED chain */ +/* peripherals used: SPI , timer, DMA (check source for details) */ +#pragma once + +/* number of LEDs */ +#define WS2812B_LEDS 60 + +/* set color of a single LED + * transmission needs to be done separately */ +void ws2812b_set_rgb(uint16_t led, uint8_t red, uint8_t green, uint8_t blue); +/* transmit colors to LEDs */ +void ws2812b_transmit(void); +/* setup WS2812b LED controller */ +void ws2812b_setup(void); diff --git a/lib/usart.c b/lib/usart.c index 72bfcb9..6a7abcf 100644 --- a/lib/usart.c +++ b/lib/usart.c @@ -13,7 +13,8 @@ * */ /* Copyright (c) 2016 King Kévin */ -/* this library handles the USART */ +/* this library handles USART communication */ +/* peripherals used: USART (check source for details) */ /* standard libraries */ #include // standard integer types @@ -29,6 +30,19 @@ #include "usart.h" // USART header and definitions +/* which USART to use */ +#define USART USART1 +#define USART_RCC RCC_USART1 +#define USART_IRQ NVIC_USART1_IRQ +#define USART_PORT GPIOA +#define USART_PIN_TX GPIO_USART1_TX +#define USART_PIN_RX GPIO_USART1_RX + +/* serial baudrate, in bits per second (with 8N1 8 bits, no parity bit, 1 stop bit settings) */ +#define USART_BAUDRATE 115200 +/* RX and TX buffer sizes */ +#define USART_BUFFER 128 + /* input and output ring buffer, indexes, and available memory */ static uint8_t rx_buffer[USART_BUFFER] = {0}; static volatile uint8_t rx_i = 0; @@ -42,13 +56,14 @@ volatile uint8_t usart_received = 0; // same as rx_used, but since the user can /* setup USART port */ void usart_setup(void) { - rcc_periph_clock_enable(USART_RCC); // enable USART1 clock + /* enable USART I/O peripheral */ + rcc_periph_clock_enable(USART_RCC); // enable clock for USART peripheral gpio_set_mode(USART_PORT, GPIO_MODE_OUTPUT_10_MHZ, GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, USART_PIN_TX); // setup GPIO pin USART transmit gpio_set_mode(USART_PORT, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, USART_PIN_RX); // setup GPIO pin USART receive gpio_set(USART_PORT, USART_PIN_RX); // pull up to avoid noise when not connected - /* setup UART parameters */ - usart_set_baudrate(USART, 115200); + /* setup USART parameters */ + usart_set_baudrate(USART, USART_BAUDRATE); usart_set_databits(USART, 8); usart_set_stopbits(USART, USART_STOPBITS_1); usart_set_mode(USART, USART_MODE_TX_RX); @@ -70,9 +85,6 @@ void usart_setup(void) /* put character on USART (blocking) */ void usart_putchar_blocking(char c) { - if (c == '\n') { // add carrier return before line feed. this is recommended for most UART terminals - usart_putchar_blocking('\r'); // a second carrier return doesn't influence the terminal - } usart_flush(); // empty buffer first usart_send_blocking(USART, c); // send character } @@ -103,7 +115,8 @@ char usart_getchar(void) void usart_putchar_nonblocking(char c) { while (tx_used>=sizeof(tx_buffer)) { // idle until buffer has some space - __WFI(); + usart_enable_tx_interrupt(USART); // enable transmit interrupt + __WFI(); // sleep until something happened } tx_buffer[(tx_i+tx_used)%sizeof(tx_buffer)] = c; // put character in buffer tx_used++; // update used buffer diff --git a/lib/usart.h b/lib/usart.h index 8911e59..644827c 100644 --- a/lib/usart.h +++ b/lib/usart.h @@ -13,20 +13,10 @@ * */ /* Copyright (c) 2016 King Kévin */ -/* this library handles the USART */ +/* this library handles USART communication */ +/* peripherals used: USART (check source for details) */ +#pragma once -/* which USART to use */ -#define USART USART1 -#define USART_RCC RCC_USART1 -#define USART_IRQ NVIC_USART1_IRQ -#define USART_PORT GPIOA -#define USART_PIN_TX GPIO_USART1_TX -#define USART_PIN_RX GPIO_USART1_RX - -/* serial baudrate, in bits per second (with 8N1 8 bits, no parity bit, 1 stop bit settings) */ -#define BAUD 115200 -/* RX and TX buffer sizes */ -#define USART_BUFFER 128 /* show the user how much received is available */ extern volatile uint8_t usart_received; diff --git a/lib/usart_ir.c b/lib/usart_ir.c new file mode 100644 index 0000000..68859dd --- /dev/null +++ b/lib/usart_ir.c @@ -0,0 +1,175 @@ +/* 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 . + * + */ +/* Copyright (c) 2016 King Kévin */ +/* this library handles USART communication over pulse coded InfraRed transmission */ +/* peripherals used: USART, timer (check source for details) */ + +/* standard libraries */ +#include // standard integer types +#include // standard I/O facilities +#include // general utilities + +/* STM32 (including CM3) libraries */ +#include // real-time control clock library +#include // general purpose input output library +#include // universal synchronous asynchronous receiver transmitter library +#include // timer library +#include // interrupt handler +#include // Cortex M3 utilities + +#include "usart_ir.h" // USART InfraRed header and definitions + +/* which USART to use */ +#define USART USART3 +#define USART_RCC RCC_USART3 +#define USART_IRQ NVIC_USART3_IRQ +#define USART_PORT GPIOB +#define USART_PIN_TX GPIO_USART3_TX +#define USART_PIN_RX GPIO_USART3_RX + +/* which timer to use to create PWM for IR modulation */ +#define TIMER TIM2 +#define TIMER_RCC RCC_TIM2 +#define TIMER_OC TIM_OC2 +#define TIMER_PORT GPIOA +#define TIMER_PORT_RCC RCC_GPIOA +#define TIMER_PIN GPIO_TIM2_CH2 + +#define USART_BAUDRATE 2400 // serial baudrate (in bits per second, with 8N1 configuration) +#define USART_BUFFER 128 // RX and TX buffer sizes +#define IR_MODULATION 38000 // infra-red modulation frequency + +/* input and output ring buffer, indexes, and available memory */ +static uint8_t rx_buffer[USART_BUFFER] = {0}; +static volatile uint8_t rx_i = 0; +static volatile uint8_t rx_used = 0; +static uint8_t tx_buffer[USART_BUFFER] = {0}; +static volatile uint8_t tx_i = 0; +static volatile uint8_t tx_used = 0; +/* show the user how much data received over USART is ready */ +volatile uint8_t usart_ir_received = 0; // same as rx_used, but since the user can write this variable we don't rely on it + +/* setup USART/IR peripheral */ +void usart_ir_setup(void) +{ + /* setup timer to generate infra-red pulse modulation (using PWM) */ + rcc_periph_clock_enable(TIMER_PORT_RCC); // enable clock for GPIO peripheral + gpio_set_mode(TIMER_PORT, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, TIMER_PIN); // set pin a output + rcc_periph_clock_enable(RCC_AFIO); // enable clock for alternate function (PWM) + rcc_periph_clock_enable(TIMER_RCC); // enable clock for timer peripheral + timer_reset(TIMER); // reset timer state + timer_set_mode(TIMER, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP); // set timer mode, use undivided timer clock, edge alignment (simple count), and count up + timer_set_prescaler(TIMER, 0); // no pre-scaler to keep most precise timer (72MHz/2^16=1099Hz) + timer_set_period(TIMER, rcc_ahb_frequency/IR_MODULATION-1+15); // set the infra-red modulation frequency (plus hand tuning) + timer_set_oc_value(TIMER, TIMER_OC, rcc_ahb_frequency/IR_MODULATION/2-1); // duty cycle to 50% + timer_set_oc_mode(TIMER, TIMER_OC, TIM_OCM_PWM1); // set timer to generate PWM + timer_enable_oc_output(TIMER, TIMER_OC); // enable output to provide the modulation + timer_enable_counter(TIMER); // start timer to generate modulation + + /* enable USART I/O peripheral */ + rcc_periph_clock_enable(USART_RCC); // enable clock for USART peripheral + gpio_set_mode(USART_PORT, GPIO_MODE_OUTPUT_10_MHZ, GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, USART_PIN_TX); // setup GPIO pin USART transmit + gpio_set_mode(USART_PORT, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, USART_PIN_RX); // setup GPIO pin USART receive + gpio_set(USART_PORT, USART_PIN_RX); // pull up to avoid noise when not connected + + /* setup UART parameters */ + usart_set_baudrate(USART, USART_BAUDRATE); + usart_set_databits(USART, 8); + usart_set_stopbits(USART, USART_STOPBITS_1); + usart_set_mode(USART, USART_MODE_TX_RX); + usart_set_parity(USART, USART_PARITY_NONE); + usart_set_flow_control(USART, USART_FLOWCONTROL_NONE); + + nvic_enable_irq(USART_IRQ); // enable the USART interrupt + usart_enable_rx_interrupt(USART); // enable receive interrupt + usart_enable(USART); // enable USART + + /* reset buffer states */ + tx_i = 0; + tx_used = 0; + rx_i = 0; + rx_used = 0; + usart_ir_received = 0; +} + +/* put character on USART/IR (blocking) */ +void usart_ir_putchar_blocking(char c) +{ + usart_ir_flush(); // empty buffer first + usart_send_blocking(USART, c); // send character +} + +/* ensure all data has been transmitted (blocking) */ +void usart_ir_flush(void) +{ + while (tx_used) { // idle until buffer is empty + __WFI(); // sleep until interrupt + } + usart_wait_send_ready(USART); // wait until transmit register is empty (transmission might not be complete) +} + +/* get character from USART/IR (blocking) */ +char usart_ir_getchar(void) +{ + while (!rx_used) { // idle until data is available + __WFI(); // sleep until interrupt; + } + char to_return = rx_buffer[rx_i]; // get the next available character + rx_i = (rx_i+1)%sizeof(rx_buffer); // update used buffer + rx_used--; // update used buffer + usart_ir_received = rx_used; // update available data + return to_return; +} + +/* put character on USART/IR (non-blocking until buffer is full) */ +void usart_ir_putchar_nonblocking(char c) +{ + while (tx_used>=sizeof(tx_buffer)) { // idle until buffer has some space + usart_enable_tx_interrupt(USART); // enable transmit interrupt + __WFI(); // sleep until something happened + } + tx_buffer[(tx_i+tx_used)%sizeof(tx_buffer)] = c; // put character in buffer + tx_used++; // update used buffer + usart_enable_tx_interrupt(USART); // enable transmit interrupt +} + +#if (USART==USART1) +void usart1_isr(void) +#elif (USART==USART2) +void usart2_isr(void) +#elif (USART==USART3) +void usart3_isr(void) +#endif +{ // USART interrupt + if (usart_get_interrupt_source(USART, USART_SR_TXE)) { // data has been transmitted + if (!tx_used) { // no data in the buffer to transmit + usart_disable_tx_interrupt(USART); // disable transmit interrupt + } else { + usart_send(USART,tx_buffer[tx_i]); // put data in transmit register + tx_i = (tx_i+1)%sizeof(rx_buffer); // update location on buffer + tx_used--; // update used size + } + } + if (usart_get_interrupt_source(USART, USART_SR_RXNE)) { // data has been received + // only save data if there is space in the buffer + if (rx_used>=sizeof(rx_buffer)) { + usart_recv(USART); // read to clear interrupt + } else { + rx_buffer[(rx_i+rx_used)%sizeof(rx_buffer)] = usart_recv(USART); // put character in buffer + rx_used++; // update used buffer + usart_ir_received = rx_used; // update available data + } + } +} diff --git a/lib/usart_ir.h b/lib/usart_ir.h new file mode 100644 index 0000000..59bd915 --- /dev/null +++ b/lib/usart_ir.h @@ -0,0 +1,32 @@ +/* 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 . + * + */ +/* Copyright (c) 2016 King Kévin */ +/* this library handles USART communication over pulse coded InfraRed transmission */ +/* peripherals used: USART, timer (check source for details) */ +#pragma once + +/* show the user how much data has been received and is available */ +extern volatile uint8_t usart_ir_received; + +/* setup USART/IR peripheral */ +void usart_ir_setup(void); +/* put character on USART/IR (blocking) */ +void usart_ir_putchar_blocking(char c); +/* ensure all data has been transmitted (blocking) */ +void usart_ir_flush(void); +/* get character from USART/IR (blocking) */ +char usart_ir_getchar(void); +/* put character on USART/IR (non-blocking until buffer is full) */ +void usart_ir_putchar_nonblocking(char c); diff --git a/lib/usart_irda.c b/lib/usart_irda.c new file mode 100644 index 0000000..ed18def --- /dev/null +++ b/lib/usart_irda.c @@ -0,0 +1,152 @@ +/* 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 . + * + */ +/* Copyright (c) 2016 King Kévin */ +/* this library handles IrDA SIR (USART based) communication */ +/* this library handles IrDA communication */ + +/* standard libraries */ +#include // standard integer types +#include // standard I/O facilities +#include // general utilities + +/* STM32 (including CM3) libraries */ +#include // real-time control clock library +#include // general purpose input output library +#include // universal synchronous asynchronous receiver transmitter library +#include // interrupt handler +#include // Cortex M3 utilities + +#include "usart_irda.h" // IrDA header and definitions + +/* which USART to use for IrDA */ +#define IRDA USART3 +#define IRDA_RCC RCC_USART3 +#define IRDA_IRQ NVIC_USART3_IRQ +#define IRDA_PORT GPIOB +#define IRDA_PIN_TX GPIO_USART3_TX +#define IRDA_PIN_RX GPIO_USART3_RX +/* serial baudrate, in bits per second (with 8N1 8 bits, no parity bit, 1 stop bit settings) */ +#define IRDA_BAUDRATE 9600 +/* RX and TX buffer sizes */ +#define IRDA_BUFFER 128 + +/* input and output ring buffer, indexes, and available memory */ +static uint8_t rx_buffer[IRDA_BUFFER] = {0}; +static volatile uint8_t rx_i = 0; +static volatile uint8_t rx_used = 0; +static uint8_t tx_buffer[IRDA_BUFFER] = {0}; +static volatile uint8_t tx_i = 0; +static volatile uint8_t tx_used = 0; +/* show the user how much data received over IrDA is ready */ +volatile uint8_t irda_received = 0; // same as rx_used, but since the user can write this variable we don't rely on it + +/* setup IrDA peripheral */ +void irda_setup(void) +{ + rcc_periph_clock_enable(IRDA_RCC); // enable clock for USART/IrDA block + gpio_set_mode(IRDA_PORT, GPIO_MODE_OUTPUT_10_MHZ, GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, IRDA_PIN_TX); // setup GPIO pin USART/IrDA transmit + gpio_set_mode(IRDA_PORT, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, IRDA_PIN_RX); // setup GPIO pin USART/IrDA receive + gpio_set(IRDA_PORT, IRDA_PIN_RX); // pull up to avoid noise when not connected + + /* setup UART/IrDA parameters */ + usart_set_baudrate(IRDA, IRDA_BAUDRATE); + usart_set_databits(IRDA, 8); + usart_set_stopbits(IRDA, USART_STOPBITS_1); + usart_set_mode(IRDA, USART_MODE_TX_RX); + usart_set_parity(IRDA, USART_PARITY_NONE); + usart_set_flow_control(IRDA, USART_FLOWCONTROL_NONE); + USART_CR3(IRDA) |= USART_CR3_IREN; // enable IrDA SIR ENDEC block (using IREN) + + nvic_enable_irq(IRDA_IRQ); // enable the USART/IrDA interrupt + usart_enable_rx_interrupt(IRDA); // enable receive interrupt + usart_enable(IRDA); // enable USART/IrDA + + /* reset buffer states */ + tx_i = 0; + tx_used = 0; + rx_i = 0; + rx_used = 0; + irda_received = 0; +} + +/* put character on IrDA (blocking) */ +void irda_putchar_blocking(char c) +{ + irda_flush(); // empty buffer first + usart_send_blocking(IRDA, c); // send character +} + +/* ensure all data has been transmitted (blocking) */ +void irda_flush(void) +{ + while (tx_used) { // idle until buffer is empty + __WFI(); // sleep until interrupt + } + usart_wait_send_ready(IRDA); // wait until transmit register is empty (transmission might not be complete) +} + +/* get character from IrDA (blocking) */ +char irda_getchar(void) +{ + while (!rx_used) { // idle until data is available + __WFI(); // sleep until interrupt; + } + char to_return = rx_buffer[rx_i]; // get the next available character + rx_i = (rx_i+1)%sizeof(rx_buffer); // update used buffer + rx_used--; // update used buffer + irda_received = rx_used; // update available data + return to_return; +} + +/* put character on IrDA (non-blocking until buffer is full) */ +void irda_putchar_nonblocking(char c) +{ + while (tx_used>=sizeof(tx_buffer)) { // idle until buffer has some space + usart_enable_tx_interrupt(IRDA); // enable transmit interrupt + __WFI(); // sleep until something happened + } + tx_buffer[(tx_i+tx_used)%sizeof(tx_buffer)] = c; // put character in buffer + tx_used++; // update used buffer + usart_enable_tx_interrupt(IRDA); // enable transmit interrupt +} + +#if (IRDA==USART1) +void usart1_isr(void) +#elif (IRDA==USART2) +void usart2_isr(void) +#elif (IRDA==USART3) +void usart3_isr(void) +#endif +{ // USART interrupt + if (usart_get_interrupt_source(IRDA, USART_SR_TXE)) { // data has been transmitted + if (!tx_used) { // no data in the buffer to transmit + usart_disable_tx_interrupt(IRDA); // disable transmit interrupt + } else { + usart_send(IRDA,tx_buffer[tx_i]); // put data in transmit register + tx_i = (tx_i+1)%sizeof(rx_buffer); // update location on buffer + tx_used--; // update used size + } + } + if (usart_get_interrupt_source(IRDA, USART_SR_RXNE)) { // data has been received + // only save data if there is space in the buffer + if (rx_used>=sizeof(rx_buffer)) { + usart_recv(IRDA); // read to clear interrupt + } else { + rx_buffer[(rx_i+rx_used)%sizeof(rx_buffer)] = usart_recv(IRDA); // put character in buffer + rx_used++; // update used buffer + irda_received = rx_used; // update available data + } + } +} diff --git a/lib/usart_irda.h b/lib/usart_irda.h new file mode 100644 index 0000000..b5e1a77 --- /dev/null +++ b/lib/usart_irda.h @@ -0,0 +1,31 @@ +/* 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 . + * + */ +/* Copyright (c) 2016 King Kévin */ +/* this library handles IrDA SIR (USART based) communication */ +/* peripherals used: USART (check source for details) */ + +/* show the user how much received is available */ +extern volatile uint8_t irda_received; + +/* setup IrDA peripheral */ +void irda_setup(void); +/* put character on IrDA (blocking) */ +void irda_putchar_blocking(char c); +/* ensure all data has been transmitted (blocking) */ +void irda_flush(void); +/* get character from IrDA (blocking) */ +char irda_getchar(void); +/* put character on IrDA (non-blocking until buffer is full) */ +void irda_putchar_nonblocking(char c); diff --git a/lib/usb_cdcacm.c b/lib/usb_cdcacm.c index 91d16cf..03ff37e 100644 --- a/lib/usb_cdcacm.c +++ b/lib/usb_cdcacm.c @@ -198,6 +198,30 @@ static volatile uint8_t tx_used = 0; /* show the user how much data received over USB is ready */ volatile uint8_t cdcacm_received = 0; // same as rx_used, but since the user can write this variable we don't rely on it +/* disconnect USB by pulling down D+ to for re-enumerate */ +static void usb_disconnect(void) +{ + /* short USB disconnect to force re-enumerate */ +#if defined(SYSTEM_BOARD) || defined(BLUE_PILL) + // pull USB D+ low for a short while + rcc_periph_clock_enable(RCC_GPIOA); + gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_PUSHPULL, GPIO12); + gpio_clear(GPIOA, GPIO12); + for (uint32_t i = 0; i < 0x2000; i++) { + __asm__("nop"); + } +#elif defined(MAPLE_MINI) + // disconnect USB D+ using dedicated DISC line/circuit on PB9 + rcc_periph_clock_enable(RCC_GPIOB); + gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_PUSHPULL, GPIO9); + gpio_set(GPIOB, GPIO9); + for (uint32_t i = 0; i < 0x2000; i++) { + __asm__("nop"); + } + gpio_clear(GPIOB, GPIO9); +#endif +} + static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf, uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)) { (void)complete; @@ -229,6 +253,7 @@ static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data * * to reset the device from the host you can use stty --file /dev/ttyACM0 115200 raw cs5 */ if (coding->bDataBits==5) { + usb_disconnect(); // force re-enumerate after reset scb_reset_system(); // reset device while (true); // wait for the reset to happen } @@ -291,29 +316,11 @@ static void cdcacm_set_config(usbd_device *usbd_dev, uint16_t wValue) 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); } - + void cdcacm_setup(void) { - /* short USB disconnect to force re-enumerate */ -#ifdef SYSTEM_BOARD - // pull USB D+ low for a short while - rcc_periph_clock_enable(RCC_GPIOA); - gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_PUSHPULL, GPIO12); - gpio_clear(GPIOA, GPIO12); - for (uint32_t i = 0; i < 0xa00; i++) { - __asm__("nop"); - } -#elif MAPLE_MINI - // disconnect USB D+ using dedicated DISC line/circuit on PB9 - rcc_periph_clock_enable(RCC_GPIOB); - gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_PUSHPULL, GPIO9); - gpio_set(GPIOB, GPIO9); - for (uint32_t i = 0; i < 0xa00; i++) { - __asm__("nop"); - } - gpio_clear(GPIOB, GPIO9); -#endif - + usb_disconnect(); // force re-enumerate + /* initialize USB */ usb_device = usbd_init(&st_usbfs_v1_usb_driver, &device_descriptor, &config, usb_strings, 3, usbd_control_buffer, sizeof(usbd_control_buffer)); usbd_register_set_config_callback(usb_device, cdcacm_set_config); @@ -335,7 +342,7 @@ void cdcacm_setup(void) char cdcacm_getchar(void) { while (!rx_used) { // idle until data is available - __WFI(); // sleep until interrupt (not sure if it's a good idea here + __WFI(); // sleep until interrupt (not sure if it's a good idea here) } char to_return = rx_buffer[rx_i]; // get the next available character rx_i = (rx_i+1)%sizeof(rx_buffer); // update used buffer diff --git a/lib/usb_cdcacm.h b/lib/usb_cdcacm.h index b82a417..43263dc 100644 --- a/lib/usb_cdcacm.h +++ b/lib/usb_cdcacm.h @@ -14,7 +14,7 @@ */ /* Copyright (c) 2016 King Kévin */ /* this library handles the USB CDC ACM */ - +#pragma once /* RX buffer size */ #define CDCACM_BUFFER 128 diff --git a/main.c b/main.c index 0e2ae03..2ccc554 100644 --- a/main.c +++ b/main.c @@ -34,6 +34,9 @@ #include "usart.h" // USART utilities #include "usb_cdcacm.h" // USB CDC ACM utilities +/* flag set in interrupts to be processed in main taks */ +volatile bool button_flag = false; // button has been presse + /* default output (i.e. for printf) */ int _write(int file, char *ptr, int len) { @@ -109,17 +112,31 @@ int main(void) printf("welcome to the STM32F1 CuVoodoo example code\n"); // print welcome message led_on(); // switch on LED to indicate setup completed + bool action = false; // if an action has been performed don't go to sleep + button_flag = false; // reset button flag /* toggle the LED with every transmitted character */ while (true) { // infinite loop while (usart_received) { // echo every received character + action = true; // action has been performed led_toggle(); // toggle LED printf("%c",usart_getchar()); // transmit receive character } while (cdcacm_received) { // echo every received character + action = true; // action has been performed led_toggle(); // toggle LED printf("%c",cdcacm_getchar()); // transmit receive character } - __WFI(); // go to sleep + while (button_flag) { + button_flag = false; // reset flag + action = true; // action has been performed + led_toggle(); // toggle LED + } + // go to sleep if nothing had to be done, else recheck for activity + if (action) { + action = false; + } else { + __WFI(); // go to sleep + } } return 0; @@ -129,6 +146,6 @@ int main(void) void BUTTON_ISR(void) { exti_reset_request(BUTTON_EXTI); // reset interrupt - led_toggle(); // toggle LED to show the button press has been detected + button_flag = true; // perform button action } #endif