aboutsummaryrefslogtreecommitdiffstats
path: root/src/fsm
diff options
context:
space:
mode:
Diffstat (limited to 'src/fsm')
l---------src/fsm/FreeRTOS1
-rw-r--r--src/fsm/FreeRTOSConfig.h165
-rw-r--r--src/fsm/Makefile119
-rw-r--r--src/fsm/README.md16
-rw-r--r--src/fsm/audio.c285
-rw-r--r--src/fsm/audio.h50
-rw-r--r--src/fsm/bin/.git_keep0
l---------src/fsm/bsp1
-rw-r--r--src/fsm/common.h (renamed from src/fsm/src/common.h)0
-rw-r--r--src/fsm/cw.c294
-rw-r--r--src/fsm/cw.h41
-rw-r--r--src/fsm/debug.c77
-rw-r--r--src/fsm/debug.h47
-rw-r--r--src/fsm/fsm.c (renamed from src/fsm/src/fsm.c)0
-rw-r--r--src/fsm/fsm.h (renamed from src/fsm/src/fsm.h)0
-rw-r--r--src/fsm/main.c215
16 files changed, 1310 insertions, 1 deletions
diff --git a/src/fsm/FreeRTOS b/src/fsm/FreeRTOS
new file mode 120000
index 0000000..51f4e96
--- /dev/null
+++ b/src/fsm/FreeRTOS
@@ -0,0 +1 @@
+../FreeRTOS \ No newline at end of file
diff --git a/src/fsm/FreeRTOSConfig.h b/src/fsm/FreeRTOSConfig.h
new file mode 100644
index 0000000..11427d8
--- /dev/null
+++ b/src/fsm/FreeRTOSConfig.h
@@ -0,0 +1,165 @@
+/*
+ FreeRTOS V8.0.0:rc2 - Copyright (C) 2014 Real Time Engineers Ltd.
+ All rights reserved
+
+ VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+ ***************************************************************************
+ * *
+ * FreeRTOS provides completely free yet professionally developed, *
+ * robust, strictly quality controlled, supported, and cross *
+ * platform software that has become a de facto standard. *
+ * *
+ * Help yourself get started quickly and support the FreeRTOS *
+ * project by purchasing a FreeRTOS tutorial book, reference *
+ * manual, or both from: http://www.FreeRTOS.org/Documentation *
+ * *
+ * Thank you! *
+ * *
+ ***************************************************************************
+
+ This file is part of the FreeRTOS distribution.
+
+ FreeRTOS is free software; you can redistribute it and/or modify it under
+ the terms of the GNU General Public License (version 2) as published by the
+ Free Software Foundation >>!AND MODIFIED BY!<< the FreeRTOS exception.
+
+ >>! NOTE: The modification to the GPL is included to allow you to distribute
+ >>! a combined work that includes FreeRTOS without being obliged to provide
+ >>! the source code for proprietary components outside of the FreeRTOS
+ >>! kernel.
+
+ FreeRTOS 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. Full license text is available from the following
+ link: http://www.freertos.org/a00114.html
+
+ 1 tab == 4 spaces!
+
+ ***************************************************************************
+ * *
+ * Having a problem? Start by reading the FAQ "My application does *
+ * not run, what could be wrong?" *
+ * *
+ * http://www.FreeRTOS.org/FAQHelp.html *
+ * *
+ ***************************************************************************
+
+ http://www.FreeRTOS.org - Documentation, books, training, latest versions,
+ license and Real Time Engineers Ltd. contact details.
+
+ http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+ including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+ compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+ http://www.OpenRTOS.com - Real Time Engineers ltd license FreeRTOS to High
+ Integrity Systems to sell under the OpenRTOS brand. Low cost OpenRTOS
+ licenses offer ticketed support, indemnification and middleware.
+
+ http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+ engineered and independently SIL3 certified version for use in safety and
+ mission critical applications that require provable dependability.
+
+ 1 tab == 4 spaces!
+*/
+
+
+#ifndef FREERTOS_CONFIG_H
+#define FREERTOS_CONFIG_H
+
+/*-----------------------------------------------------------
+ * Application specific definitions.
+ *
+ * These definitions should be adjusted for your particular hardware and
+ * application requirements.
+ *
+ * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE
+ * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE.
+ *
+ * See http://www.freertos.org/a00110.html.
+ *----------------------------------------------------------*/
+
+/* Ensure stdint is only used by the compiler, and not the assembler. */
+//#ifdef __ICCARM__
+ #include <stdint.h>
+ extern uint32_t SystemCoreClock;
+//#endif
+
+#define configUSE_PREEMPTION 1
+#define configUSE_IDLE_HOOK 0 // Default: 1
+#define configUSE_TICK_HOOK 0 // Default: 1
+#define configCPU_CLOCK_HZ ( SystemCoreClock )
+#define configTICK_RATE_HZ ( ( portTickType ) 1000 )
+#define configMAX_PRIORITIES ( 5 )
+#define configMINIMAL_STACK_SIZE ( ( unsigned short ) 130 )
+#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 75 * 1024 ) )
+#define configMAX_TASK_NAME_LEN ( 10 )
+#define configUSE_TRACE_FACILITY 1
+#define configUSE_16_BIT_TICKS 0
+#define configIDLE_SHOULD_YIELD 1
+#define configUSE_MUTEXES 1
+#define configQUEUE_REGISTRY_SIZE 8
+#define configCHECK_FOR_STACK_OVERFLOW 2 // Default: 2
+#define configUSE_RECURSIVE_MUTEXES 1
+#define configUSE_MALLOC_FAILED_HOOK 0 // Default: 1
+#define configUSE_APPLICATION_TASK_TAG 0
+#define configUSE_COUNTING_SEMAPHORES 1
+#define configGENERATE_RUN_TIME_STATS 0
+
+/* Co-routine definitions. */
+#define configUSE_CO_ROUTINES 0
+#define configMAX_CO_ROUTINE_PRIORITIES ( 2 )
+
+/* Software timer definitions. */
+#define configUSE_TIMERS 1
+#define configTIMER_TASK_PRIORITY ( 2 )
+#define configTIMER_QUEUE_LENGTH 10
+#define configTIMER_TASK_STACK_DEPTH ( configMINIMAL_STACK_SIZE * 2 )
+
+/* Set the following definitions to 1 to include the API function, or zero
+to exclude the API function. */
+#define INCLUDE_vTaskPrioritySet 1
+#define INCLUDE_uxTaskPriorityGet 1
+#define INCLUDE_vTaskDelete 1
+#define INCLUDE_vTaskCleanUpResources 1
+#define INCLUDE_vTaskSuspend 1
+#define INCLUDE_vTaskDelayUntil 1
+#define INCLUDE_vTaskDelay 1
+
+/* Cortex-M specific definitions. */
+#ifdef __NVIC_PRIO_BITS
+ /* __BVIC_PRIO_BITS will be specified when CMSIS is being used. */
+ #define configPRIO_BITS __NVIC_PRIO_BITS
+#else
+ #define configPRIO_BITS 4 /* 15 priority levels */
+#endif
+
+/* The lowest interrupt priority that can be used in a call to a "set priority"
+function. */
+#define configLIBRARY_LOWEST_INTERRUPT_PRIORITY 0xf
+
+/* The highest interrupt priority that can be used by any interrupt service
+routine that makes calls to interrupt safe FreeRTOS API functions. DO NOT CALL
+INTERRUPT SAFE FREERTOS API FUNCTIONS FROM ANY INTERRUPT THAT HAS A HIGHER
+PRIORITY THAN THIS! (higher priorities are lower numeric values. */
+#define configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY 5
+
+/* Interrupt priorities used by the kernel port layer itself. These are generic
+to all Cortex-M ports, and do not rely on any particular library functions. */
+#define configKERNEL_INTERRUPT_PRIORITY ( configLIBRARY_LOWEST_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) )
+/* !!!! configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to zero !!!!
+See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html. */
+#define configMAX_SYSCALL_INTERRUPT_PRIORITY ( configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) )
+
+/* Normal assert() semantics without relying on the provision of an assert.h
+header file. */
+#define configASSERT( x ) if( ( x ) == 0 ) { taskDISABLE_INTERRUPTS(); for( ;; ); }
+
+/* Definitions that map the FreeRTOS port interrupt handlers to their CMSIS
+standard names. */
+#define vPortSVCHandler SVC_Handler
+#define xPortPendSVHandler PendSV_Handler
+#define xPortSysTickHandler SysTick_Handler
+
+#endif /* FREERTOS_CONFIG_H */
+
diff --git a/src/fsm/Makefile b/src/fsm/Makefile
new file mode 100644
index 0000000..8a6e463
--- /dev/null
+++ b/src/fsm/Makefile
@@ -0,0 +1,119 @@
+###
+# GNU ARM Embedded Toolchain
+CC=arm-none-eabi-gcc
+LD=arm-none-eabi-ld
+AR=arm-none-eabi-ar
+AS=arm-none-eabi-as
+CP=arm-none-eabi-objcopy
+OD=arm-none-eabi-objdump
+SIZE=arm-none-eabi-size
+
+###
+# Directory Structure
+BINDIR=bin
+SRCDIR=.
+
+###
+# Find source files
+ASOURCES=$(shell find -L $(SRCDIR) -name '*.s')
+CSOURCES+=$(shell find -L $(SRCDIR) -name '*.c')
+# Find header directories
+INC=$(shell find -L . -name '*.h' -exec dirname {} \; | uniq)
+INCLUDES=$(INC:%=-I%)
+# Create object list
+OBJECTS=$(ASOURCES:%.s=%.o)
+OBJECTS+=$(CSOURCES:%.c=%.o)
+# Define output files ELF & IHEX
+BINELF=outp.elf
+BINHEX=outp.hex
+
+###
+# MCU FLAGS
+MCFLAGS=-mcpu=cortex-m4 -mthumb -mlittle-endian \
+-mfpu=fpv4-sp-d16 -mfloat-abi=softfp -mthumb-interwork
+# COMPILE FLAGS
+DEFS=-DUSE_STDPERIPH_DRIVER -DSTM32F4XX -DARM_MATH_CM4 -D__FPU_PRESENT=1
+CFLAGS =-Wall -ggdb -std=c99 -c $(MCFLAGS) $(DEFS) $(INCLUDES)
+# LINKER FLAGS
+LDSCRIPT= bsp/stm32_flash.ld
+LDFLAGS =-T $(LDSCRIPT) --specs=nosys.specs $(MCFLAGS)
+
+###
+# Optimizations
+OPT?='O1 O2 O3 O4 O6 O7' # O5 disabled by default, because it breaks code
+
+ifneq ($(findstring release-memopt,$(MAKECMDGOALS)),)
+ifneq ($(filter O1,$(OPT)),)
+CXXFLAGS+=-fno-exceptions # Uncomment to disable exception handling
+DEFS+=-DNO_EXCEPTIONS # The source code has to comply with this rule
+endif
+
+ifneq ($(filter O2,$(OPT)),)
+CFLAGS+=-Os # Optimize for size https://gcc.gnu.org/onlinedocs/gcc/Optimize-Options.html
+CXXFLAGS+=-Os
+LDFLAGS+=-Os # Optimize for size https://gcc.gnu.org/onlinedocs/gcc/Optimize-Options.html
+endif
+
+ifneq ($(filter O3,$(OPT)),)
+CFLAGS+=-ffunction-sections -fdata-sections # Place each function or data item into its own section in the output file
+CXXFLAGS+=-ffunction-sections -fdata-sections # -||-
+LDFLAGS+=-Wl,-gc-sections # Remove isolated unused sections
+endif
+
+ifneq ($(filter O4,$(OPT)),)
+CFLAGS+=-fno-builtin # Disable C++ exception handling
+CXXFLAGS+=-fno-builtin # Disable C++ exception handling
+endif
+
+ifneq ($(filter O5,$(OPT)),)
+CFLAGS+=-flto # Enable link time optimization
+CXXFLAGS+=-flto # Enable link time optimization
+LDFLAGS+=-flto # Enable link time optimization
+endif
+
+ifneq ($(filter O6,$(OPT)),)
+CXXFLAGS+=-fno-rtti # Disable type introspection
+endif
+
+ifneq ($(findstring O7,$(OPT)),)
+LDFLAGS+=--specs=nano.specs # Use size optimized newlib
+endif
+endif
+
+###
+# Build Rules
+.PHONY: all release release-memopt debug clean
+
+all: release
+
+release: $(BINDIR)/$(BINHEX)
+
+release-memopt: release
+
+debug: CFLAGS+=-g
+debug: LDFLAGS+=-g
+debug: release
+
+$(BINDIR)/$(BINHEX): $(BINDIR)/$(BINELF)
+ $(CP) -O ihex $< $@
+
+$(BINDIR)/$(BINELF): $(OBJECTS)
+ $(CC) $(LDFLAGS) $(OBJECTS) -o $@
+ $(SIZE) $(BINDIR)/$(BINELF)
+
+%.o: %.c
+ $(CC) $(CFLAGS) $< -o $@
+
+%.o: %.s
+ $(CC) $(CFLAGS) $< -o $@
+
+clean:
+ rm -f $(OBJECTS) $(BINDIR)/$(BINELF) $(BINDIR)/$(BINHEX)
+
+# Connect to openocd's gdb server on port 3333
+deploy: $(BINDIR)/$(BINELF)
+ifeq ($(wildcard /opt/openocd/bin/openocd),)
+ /usr/bin/openocd -f /usr/share/openocd/scripts/board/stm32f4discovery.cfg -c "program bin/"$(BINELF)" verify reset" -c "init" -c "reset" -c "exit"
+else
+ /opt/openocd/bin/openocd -f /opt/openocd/share/openocd/scripts/board/stm32f4discovery.cfg -c "program bin/"$(BINELF)" verify reset" -c "init" -c "reset" -c "exit"
+endif
diff --git a/src/fsm/README.md b/src/fsm/README.md
index 4fe3d28..69f1f22 100644
--- a/src/fsm/README.md
+++ b/src/fsm/README.md
@@ -1 +1,15 @@
-First implementations of the FSM. Tests are coming...
+An example program that tries to output CW using
+the audio codec on the STM32F4DISCOVERY, using the FSM
+and switches.
+
+Connections as follows:
+
+Blue in QRP_n PC1
+Violet out LED red PC2
+Grey in 1750 PC4
+White out LED yel PC5
+Black - GND GND
+Brown in RX_n PC6
+Red in U_n PC8
+Orange out LED grn PC9
+Green in D_n PC11
diff --git a/src/fsm/audio.c b/src/fsm/audio.c
new file mode 100644
index 0000000..752ad12
--- /dev/null
+++ b/src/fsm/audio.c
@@ -0,0 +1,285 @@
+#include "audio.h"
+#include "stm32f4xx_conf.h"
+#include "stm32f4xx.h"
+
+#include <stdlib.h>
+
+static void WriteRegister(uint8_t address, uint8_t value);
+static void StartAudioDMAAndRequestBuffers();
+static void StopAudioDMA();
+
+static AudioCallbackFunction *CallbackFunction;
+static void *CallbackContext;
+static int16_t * volatile NextBufferSamples;
+static volatile int NextBufferLength;
+static volatile int BufferNumber;
+static volatile bool DMARunning;
+
+void InitializeAudio(int plln, int pllr, int i2sdiv, int i2sodd) {
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ // Intitialize state.
+ CallbackFunction = NULL;
+ CallbackContext = NULL;
+ NextBufferSamples = NULL;
+ NextBufferLength = 0;
+ BufferNumber = 0;
+ DMARunning = false;
+
+ // Turn on peripherals.
+ RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOA, ENABLE);
+ RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOB, ENABLE);
+ RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOC, ENABLE);
+ RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOD, ENABLE);
+ RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_DMA1, ENABLE);
+
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C1, ENABLE);
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI3, ENABLE);
+
+ // Configure reset pin.
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4;;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
+ GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
+ GPIO_Init(GPIOD, &GPIO_InitStructure);
+
+ // Configure I2C SCL and SDA pins.
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
+ GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
+ GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+ GPIO_PinAFConfig(GPIOB, GPIO_PinSource6, GPIO_AF_I2C1);
+ GPIO_PinAFConfig(GPIOB, GPIO_PinSource9, GPIO_AF_I2C1);
+
+ // Configure I2S MCK, SCK, SD pins.
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_7 | GPIO_Pin_10 | GPIO_Pin_12;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
+ GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+ GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
+ GPIO_Init(GPIOC, &GPIO_InitStructure);
+
+ GPIO_PinAFConfig(GPIOC, GPIO_PinSource7, GPIO_AF_SPI3);
+ GPIO_PinAFConfig(GPIOC, GPIO_PinSource10, GPIO_AF_SPI3);
+ GPIO_PinAFConfig(GPIOC, GPIO_PinSource12, GPIO_AF_SPI3);
+
+ // Configure I2S WS pin.
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
+ GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+ GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ GPIO_PinAFConfig(GPIOA, GPIO_PinSource4, GPIO_AF_SPI3);
+
+ // Reset the codec.
+ GPIOD ->BSRRH = 1 << 4;
+ for (volatile int i = 0; i < 0x4fff; i++) {
+ __asm__ volatile("nop");
+ }
+ GPIOD ->BSRRL = 1 << 4;
+
+ // Reset I2C.
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C1, ENABLE);
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C1, DISABLE);
+
+ // Configure I2C.
+ uint32_t pclk1 = 42000000;
+
+ I2C1 ->CR2 = pclk1 / 1000000; // Configure frequency and disable interrupts and DMA.
+ I2C1 ->OAR1 = I2C_OAR1_ADDMODE | 0x33;
+
+ // Configure I2C speed in standard mode.
+ const uint32_t i2c_speed = 100000;
+ int ccrspeed = pclk1 / (i2c_speed * 2);
+ if (ccrspeed < 4) {
+ ccrspeed = 4;
+ }
+ I2C1 ->CCR = ccrspeed;
+ I2C1 ->TRISE = pclk1 / 1000000 + 1;
+
+ I2C1 ->CR1 = I2C_CR1_ACK | I2C_CR1_PE; // Enable and configure the I2C peripheral.
+
+ // Configure codec.
+ WriteRegister(0x02, 0x01); // Keep codec powered off.
+ WriteRegister(0x04, 0xaf); // SPK always off and HP always on.
+
+ WriteRegister(0x05, 0x81); // Clock configuration: Auto detection.
+ WriteRegister(0x06, 0x04); // Set slave mode and Philips audio standard.
+
+ SetAudioVolume(0xff);
+
+ // Power on the codec.
+ WriteRegister(0x02, 0x9e);
+
+ // Configure codec for fast shutdown.
+ WriteRegister(0x0a, 0x00); // Disable the analog soft ramp.
+ WriteRegister(0x0e, 0x04); // Disable the digital soft ramp.
+
+ WriteRegister(0x27, 0x00); // Disable the limiter attack level.
+ WriteRegister(0x1f, 0x0f); // Adjust bass and treble levels.
+
+ WriteRegister(0x1a, 0x0a); // Adjust PCM volume level.
+ WriteRegister(0x1b, 0x0a);
+
+ // Disable I2S.
+ SPI3 ->I2SCFGR = 0;
+
+ // I2S clock configuration
+ RCC ->CFGR &= ~RCC_CFGR_I2SSRC; // PLLI2S clock used as I2S clock source.
+ RCC ->PLLI2SCFGR = (pllr << 28) | (plln << 6);
+
+ // Enable PLLI2S and wait until it is ready.
+ RCC ->CR |= RCC_CR_PLLI2SON;
+ while (!(RCC ->CR & RCC_CR_PLLI2SRDY ))
+ ;
+
+ // Configure I2S.
+ SPI3 ->I2SPR = i2sdiv | (i2sodd << 8) | SPI_I2SPR_MCKOE;
+ SPI3 ->I2SCFGR = SPI_I2SCFGR_I2SMOD | SPI_I2SCFGR_I2SCFG_1
+ | SPI_I2SCFGR_I2SE; // Master transmitter, Phillips mode, 16 bit values, clock polarity low, enable.
+
+}
+
+void AudioOn() {
+ WriteRegister(0x02, 0x9e);
+ SPI3 ->I2SCFGR = SPI_I2SCFGR_I2SMOD | SPI_I2SCFGR_I2SCFG_1
+ | SPI_I2SCFGR_I2SE; // Master transmitter, Phillips mode, 16 bit values, clock polarity low, enable.
+}
+
+void AudioOff() {
+ WriteRegister(0x02, 0x01);
+ SPI3 ->I2SCFGR = 0;
+}
+
+void SetAudioVolume(int volume) {
+ WriteRegister(0x20, (volume + 0x19) & 0xff);
+ WriteRegister(0x21, (volume + 0x19) & 0xff);
+}
+
+void OutputAudioSample(int16_t sample) {
+ while (!(SPI3 ->SR & SPI_SR_TXE ))
+ ;
+ SPI3 ->DR = sample;
+}
+
+void OutputAudioSampleWithoutBlocking(int16_t sample) {
+ SPI3 ->DR = sample;
+}
+
+void PlayAudioWithCallback(AudioCallbackFunction *callback, void *context) {
+ StopAudioDMA();
+
+ NVIC_EnableIRQ(DMA1_Stream7_IRQn);
+ NVIC_SetPriority(DMA1_Stream7_IRQn, 5);
+
+ SPI3 ->CR2 |= SPI_CR2_TXDMAEN; // Enable I2S TX DMA request.
+
+ CallbackFunction = callback;
+ CallbackContext = context;
+ BufferNumber = 0;
+
+ if (CallbackFunction)
+ CallbackFunction(CallbackContext, BufferNumber);
+}
+
+void StopAudio() {
+ StopAudioDMA();
+ SPI3 ->CR2 &= ~SPI_CR2_TXDMAEN; // Disable I2S TX DMA request.
+ NVIC_DisableIRQ(DMA1_Stream7_IRQn);
+ CallbackFunction = NULL;
+}
+
+void ProvideAudioBuffer(void *samples, int numsamples) {
+ while (!ProvideAudioBufferWithoutBlocking(samples, numsamples))
+ __asm__ volatile ("wfi");
+}
+
+bool ProvideAudioBufferWithoutBlocking(void *samples, int numsamples) {
+ if (NextBufferSamples)
+ return false;
+
+ NVIC_DisableIRQ(DMA1_Stream7_IRQn);
+
+ NextBufferSamples = samples;
+ NextBufferLength = numsamples;
+
+ if (!DMARunning)
+ StartAudioDMAAndRequestBuffers();
+
+ NVIC_EnableIRQ(DMA1_Stream7_IRQn);
+
+ return true;
+}
+
+static void WriteRegister(uint8_t address, uint8_t value) {
+ while (I2C1 ->SR2 & I2C_SR2_BUSY )
+ ;
+
+ I2C1 ->CR1 |= I2C_CR1_START; // Start the transfer sequence.
+ while (!(I2C1 ->SR1 & I2C_SR1_SB ))
+ ; // Wait for start bit.
+
+ I2C1 ->DR = 0x94;
+ while (!(I2C1 ->SR1 & I2C_SR1_ADDR ))
+ ; // Wait for master transmitter mode.
+ I2C1 ->SR2;
+
+ I2C1 ->DR = address; // Transmit the address to write to.
+ while (!(I2C1 ->SR1 & I2C_SR1_TXE ))
+ ; // Wait for byte to move to shift register.
+
+ I2C1 ->DR = value; // Transmit the value.
+
+ while (!(I2C1 ->SR1 & I2C_SR1_BTF ))
+ ; // Wait for all bytes to finish.
+ I2C1 ->CR1 |= I2C_CR1_STOP; // End the transfer sequence.
+}
+
+static void StartAudioDMAAndRequestBuffers() {
+ // Configure DMA stream.
+ DMA1_Stream7 ->CR = (0 * DMA_SxCR_CHSEL_0 ) | // Channel 0
+ (1 * DMA_SxCR_PL_0 ) | // Priority 1
+ (1 * DMA_SxCR_PSIZE_0 ) | // PSIZE = 16 bit
+ (1 * DMA_SxCR_MSIZE_0 ) | // MSIZE = 16 bit
+ DMA_SxCR_MINC | // Increase memory address
+ (1 * DMA_SxCR_DIR_0 ) | // Memory to peripheral
+ DMA_SxCR_TCIE; // Transfer complete interrupt
+ DMA1_Stream7 ->NDTR = NextBufferLength;
+ DMA1_Stream7 ->PAR = (uint32_t) &SPI3 ->DR;
+ DMA1_Stream7 ->M0AR = (uint32_t) NextBufferSamples;
+ DMA1_Stream7 ->FCR = DMA_SxFCR_DMDIS;
+ DMA1_Stream7 ->CR |= DMA_SxCR_EN;
+
+ // Update state.
+ NextBufferSamples = NULL;
+ BufferNumber ^= 1;
+ DMARunning = true;
+
+ // Invoke callback if it exists to queue up another buffer.
+ if (CallbackFunction)
+ CallbackFunction(CallbackContext, BufferNumber);
+}
+
+static void StopAudioDMA() {
+ DMA1_Stream7 ->CR &= ~DMA_SxCR_EN; // Disable DMA stream.
+ while (DMA1_Stream7 ->CR & DMA_SxCR_EN )
+ ; // Wait for DMA stream to stop.
+
+ DMARunning = false;
+}
+
+void DMA1_Stream7_IRQHandler() {
+ DMA1 ->HIFCR |= DMA_HIFCR_CTCIF7; // Clear interrupt flag.
+
+ if (NextBufferSamples) {
+ StartAudioDMAAndRequestBuffers();
+ } else {
+ DMARunning = false;
+ }
+}
diff --git a/src/fsm/audio.h b/src/fsm/audio.h
new file mode 100644
index 0000000..35f3f65
--- /dev/null
+++ b/src/fsm/audio.h
@@ -0,0 +1,50 @@
+#ifndef __AUDIO_H__
+#define __AUDIO_H__
+
+#include <stdint.h>
+#include <stdbool.h>
+
+typedef void AudioCallbackFunction(void *context,int buffer);
+
+#define Audio8000HzSettings 256,5,12,1
+#define Audio16000HzSettings 213,2,13,0
+#define Audio32000HzSettings 213,2,6,1
+#define Audio48000HzSettings 258,3,3,1
+#define Audio96000HzSettings 344,2,3,1
+#define Audio22050HzSettings 429,4,9,1
+#define Audio44100HzSettings 271,2,6,0
+#define AudioVGAHSyncSettings 419,2,13,0 // 31475.3606. Actual VGA timer is 31472.4616.
+
+#define AUDIO_BUF_LEN 4096
+
+
+// Initialize and power up audio hardware. Use the above defines for the parameters.
+// Can probably only be called once.
+void InitializeAudio(int plln,int pllr,int i2sdiv,int i2sodd);
+
+// Power up and down the audio hardware.
+void AudioOn();
+void AudioOff();
+
+// Set audio volume in steps of 0.5 dB. 0xff is +12 dB.
+void SetAudioVolume(int volume);
+
+// Output one audio sample directly to the hardware without using DMA.
+void OutputAudioSample(int16_t sample);
+void OutputAudioSampleWithoutBlocking(int16_t sample);
+
+// Start and stop audio playback using DMA.
+// Callback is optional, and called whenever a new buffer is needed.
+void PlayAudioWithCallback(AudioCallbackFunction *callback,void *context);
+void StopAudio();
+
+// Provide a new buffer to the audio DMA. Output is double buffered, so
+// at least two buffers must be maintained by the program. It is not allowed
+// to overwrite the previously provided buffer until after the next callback
+// invocation.
+// Buffers must reside in DMA1-accessible memory, that is, the 128k RAM bank,
+// or flash.
+void ProvideAudioBuffer(void *samples,int numsamples);
+bool ProvideAudioBufferWithoutBlocking(void *samples,int numsamples);
+
+#endif
diff --git a/src/fsm/bin/.git_keep b/src/fsm/bin/.git_keep
new file mode 100644
index 0000000..e69de29
--- /dev/null
+++ b/src/fsm/bin/.git_keep
diff --git a/src/fsm/bsp b/src/fsm/bsp
new file mode 120000
index 0000000..5d9120a
--- /dev/null
+++ b/src/fsm/bsp
@@ -0,0 +1 @@
+../bsp \ No newline at end of file
diff --git a/src/fsm/src/common.h b/src/fsm/common.h
index 45ba854..45ba854 100644
--- a/src/fsm/src/common.h
+++ b/src/fsm/common.h
diff --git a/src/fsm/cw.c b/src/fsm/cw.c
new file mode 100644
index 0000000..a54a3ea
--- /dev/null
+++ b/src/fsm/cw.c
@@ -0,0 +1,294 @@
+/*
+ * The MIT License (MIT)
+ *
+ * Copyright (c) 2015 Matthias P. Braendli
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in all
+ * copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+ * SOFTWARE.
+*/
+
+/* CW generator
+ *
+ * Concept:
+ *
+ * +-------------------+ +-----------+
+ * | cw_push_message() | -> cw_msg_queue -> | cw_task() | -> cw_audio_queue
+ * +-------------------+ +-----------+
+ *
+ * The cw_fill_buffer() function can be called to fetch audio from the audio_queue
+ */
+
+#include "cw.h"
+#include "arm_math.h"
+#include "audio.h"
+#include "debug.h"
+
+/* Kernel includes. */
+#include "FreeRTOS.h"
+#include "task.h"
+#include "queue.h"
+#include "semphr.h"
+
+#define ON_BUFFER_SIZE 1024
+
+struct cw_out_message_s {
+ // Contains a sequence of ones and zeros corresponding to
+ // TX on/TX off CW data to be sent
+ uint8_t on_buffer[ON_BUFFER_SIZE];
+ size_t on_buffer_end;
+
+ int freq;
+ int dit_duration;
+};
+
+// The queue contains above structs
+QueueHandle_t cw_msg_queue;
+
+// Queue that contains audio data
+QueueHandle_t cw_audio_queue;
+static int cw_samplerate;
+
+static void cw_task(void *pvParameters);
+
+void cw_init(unsigned int samplerate)
+{
+ cw_samplerate = samplerate;
+
+ cw_msg_queue = xQueueCreate(15, sizeof(struct cw_out_message_s));
+ if (cw_msg_queue == 0) {
+ while(1); /* fatal error */
+ }
+
+ cw_audio_queue = xQueueCreate(2, AUDIO_BUF_LEN * sizeof(int16_t));
+ if (cw_audio_queue == 0) {
+ while(1); /* fatal error */
+ }
+
+ xTaskCreate(
+ cw_task,
+ "TaskCW",
+ 8*configMINIMAL_STACK_SIZE,
+ (void*) NULL,
+ tskIDLE_PRIORITY + 2UL,
+ NULL);
+}
+
+const uint8_t cw_mapping[60] = { // {{{
+ // Read bits from right to left
+
+ 0b110101, //+ ASCII 43
+ 0b110101, //, ASCII 44
+ 0b1011110, //- ASCII 45
+
+ 0b1010101, //., ASCII 46
+ 0b110110, // / ASCII 47
+
+ 0b100000, // 0, ASCII 48
+ 0b100001, // 1
+ 0b100011,
+ 0b100111,
+ 0b101111,
+ 0b111111,
+ 0b111110,
+ 0b111100,
+ 0b111000,
+ 0b110000, // 9, ASCII 57
+
+ // The following are mostly invalid, but
+ // required to fill the gap in ASCII between
+ // numerals and capital letters
+ 0b10, // :
+ 0b10, // ;
+ 0b10, // <
+ 0b10, // =
+ 0b10, // >
+ 0b1110011, // ?
+ 0b1101001, //@
+
+ 0b101, // A ASCII 65
+ 0b11110,
+ 0b11010,
+ 0b1110,
+ 0b11,
+ 0b11011,
+ 0b1100,
+ 0b11111,
+ 0b111,
+ 0b10001,
+ 0b1010,
+ 0b11101,
+ 0b100, //M
+ 0b110,
+ 0b1000,
+ 0b11001,
+ 0b10100,
+ 0b1101,
+ 0b1111,
+ 0b10,
+ 0b1011,
+ 0b10111,
+ 0b1001,
+ 0b10110,
+ 0b10010,
+ 0b11100, // Z
+
+ 0b101010, //Start, ASCII [
+ 0b1010111, // SK , ASCII '\'
+}; //}}}
+
+void cw_symbol(uint8_t sym, struct cw_out_message_s *msg)
+{
+ uint8_t p = 0;
+ uint8_t val = cw_mapping[sym];
+
+ while((val >> p) != 0b1) {
+
+ if (((val >> p) & 0b1) == 0b1) {
+ if (msg->on_buffer_end + 2 < ON_BUFFER_SIZE) {
+ // tone(1)
+ msg->on_buffer[msg->on_buffer_end++] = 1;
+
+ // silence(1)
+ msg->on_buffer[msg->on_buffer_end++] = 0;
+ }
+ }
+ else {
+ if (msg->on_buffer_end + 4 < ON_BUFFER_SIZE) {
+ // tone(3)
+ msg->on_buffer[msg->on_buffer_end++] = 1;
+ msg->on_buffer[msg->on_buffer_end++] = 1;
+ msg->on_buffer[msg->on_buffer_end++] = 1;
+
+ // silence(1)
+ msg->on_buffer[msg->on_buffer_end++] = 0;
+ }
+ }
+
+ p++;
+ }
+
+ // silence(2)
+ if (msg->on_buffer_end + 2 < ON_BUFFER_SIZE) {
+ for (int i = 0; i < 2; i++) {
+ msg->on_buffer[msg->on_buffer_end++] = 0;
+ }
+ }
+}
+
+// Transmit a string in morse code. Supported range:
+// All ASCII between '+' and '\', which includes
+// numerals and capital letters.
+void cw_push_message(const char* text, int dit_duration, int frequency)
+{
+ struct cw_out_message_s msg;
+ for (int i = 0; i < ON_BUFFER_SIZE; i++) {
+ msg.on_buffer[i] = 0;
+ }
+ msg.on_buffer_end = 0;
+ msg.freq = frequency;
+ msg.dit_duration = dit_duration;
+
+ const char* sym = text;
+ do {
+ if (*sym < '+' || *sym > '\\') {
+ if (msg.on_buffer_end + 3 < ON_BUFFER_SIZE) {
+ for (int i = 0; i < 3; i++) {
+ msg.on_buffer[msg.on_buffer_end++] = 0;
+ }
+ }
+ }
+ else {
+ cw_symbol(*sym - '+', &msg);
+ }
+ sym++;
+ } while (*sym != '\0');
+
+ xQueueSendToBack(cw_msg_queue, &msg, portMAX_DELAY); /* Send Message */
+}
+
+size_t cw_fill_buffer(int16_t *buf, size_t bufsize)
+{
+ if (xQueueReceiveFromISR(cw_audio_queue, buf, NULL)) {
+ return bufsize;
+ }
+ else {
+ return 0;
+ }
+}
+
+static int16_t cw_audio_buf[AUDIO_BUF_LEN];
+static void cw_task(void *pvParameters)
+{
+ struct cw_out_message_s cw_fill_msg_current;
+
+ float nco_phase = 0.0f;
+ float ampl = 0.0f;
+
+ int buf_pos = 0;
+
+ while (1) {
+ int status = xQueueReceive(cw_msg_queue, &cw_fill_msg_current, portMAX_DELAY);
+ if (status == pdTRUE) {
+
+ const int samples_per_dit = (cw_samplerate * 10) /
+ cw_fill_msg_current.dit_duration;
+
+ // Angular frequency of NCO
+ const float omega = 2.0f * FLOAT_PI * cw_fill_msg_current.freq /
+ (float)cw_samplerate;
+
+ for (int i = 0; i < cw_fill_msg_current.on_buffer_end; i++) {
+ for (int t = 0; t < samples_per_dit; t++) {
+ int16_t s = 0;
+
+ // Remove clicks from CW
+ if (cw_fill_msg_current.on_buffer[i]) {
+ const float remaining = 32768.0f - ampl;
+ ampl += remaining / 64.0f;
+ }
+ else {
+ ampl -= ampl / 64.0f;
+ }
+
+ nco_phase += omega;
+ if (nco_phase > FLOAT_PI) {
+ nco_phase -= 2.0f * FLOAT_PI;
+ }
+
+ s = ampl * arm_sin_f32(nco_phase);
+
+ if (buf_pos == AUDIO_BUF_LEN) {
+ xQueueSendToBack(cw_audio_queue, &cw_audio_buf, portMAX_DELAY);
+ buf_pos = 0;
+ }
+ cw_audio_buf[buf_pos++] = s;
+
+ // Stereo
+ if (buf_pos == AUDIO_BUF_LEN) {
+ xQueueSendToBack(cw_audio_queue, &cw_audio_buf, portMAX_DELAY);
+ buf_pos = 0;
+ }
+ cw_audio_buf[buf_pos++] = s;
+ }
+ }
+
+ // We have completed this message
+ }
+ }
+}
+
diff --git a/src/fsm/cw.h b/src/fsm/cw.h
new file mode 100644
index 0000000..b090a04
--- /dev/null
+++ b/src/fsm/cw.h
@@ -0,0 +1,41 @@
+/*
+ * The MIT License (MIT)
+ *
+ * Copyright (c) 2015 Matthias P. Braendli
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in all
+ * copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+ * SOFTWARE.
+*/
+
+#include <stdint.h>
+#include <stddef.h>
+
+#define FLOAT_PI 3.1415926535897932384f
+
+// Setup the CW generator to create audio samples at the given
+// samplerate.
+void cw_init(unsigned int samplerate);
+
+// Append new CW text to transmit
+// dit_duration in ms
+// frequency in Hz
+void cw_push_message(const char* text, int dit_duration, int frequency);
+
+// Write the waveform into the buffer (stereo)
+size_t cw_fill_buffer(int16_t *buf, size_t bufsize);
+
diff --git a/src/fsm/debug.c b/src/fsm/debug.c
new file mode 100644
index 0000000..2e33a32
--- /dev/null
+++ b/src/fsm/debug.c
@@ -0,0 +1,77 @@
+/*
+ * The MIT License (MIT)
+ *
+ * Copyright (c) 2015 Matthias P. Braendli
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in all
+ * copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+ * SOFTWARE.
+*/
+
+#include <stddef.h>
+#include <stdint.h>
+
+#include "debug.h"
+
+#if _DEBUG
+
+void debug_send_command(int command, void *message)
+{
+ __asm__ volatile (
+ "mov r0, %[cmd];"
+ "mov r1, %[msg];"
+ "bkpt #0xAB"
+ :
+ : [cmd] "r" (command), [msg] "r" (message)
+ : "r0", "r1", "memory");
+}
+
+void put_char(char c)
+{
+ __asm__ volatile (
+ "mov r0, #0x03\n" /* SYS_WRITEC */
+ "mov r1, %[msg]\n"
+ "bkpt #0xAB\n"
+ :
+ : [msg] "r" (&c)
+ : "r0", "r1"
+ );
+}
+
+void debug_print(const char* str)
+{
+ const int std_err = 2;
+
+ int strlen = 0;
+ const char* s;
+ s = str;
+ while (*s) {
+ strlen++;
+ s++;
+ }
+
+ uint32_t m[] = { std_err, (uint32_t)str, strlen };
+ debug_send_command(0x05, m);
+}
+
+#else
+void debug_send_command(int command, void *message) { }
+void put_char(char c) { }
+void debug_print(const char* str) { }
+
+#endif
+
diff --git a/src/fsm/debug.h b/src/fsm/debug.h
new file mode 100644
index 0000000..6215e5f
--- /dev/null
+++ b/src/fsm/debug.h
@@ -0,0 +1,47 @@
+/*
+ * The MIT License (MIT)
+ *
+ * Copyright (c) 2015 Matthias P. Braendli
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in all
+ * copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+ * SOFTWARE.
+*/
+
+/* Debugging utilities using the ARM semihosting facilities. Warning, it's quite
+ * slow.
+ *
+ * when used with OpenOCD's gdb server, requires the gdb command
+ *
+ * monitor arm semihosting enable
+ */
+#ifndef __DEBUG_H_
+#define __DEBUG_H_
+
+/* Example usage for the send_command function
+const char *s = "Hello world\n";
+uint32_t m[] = { 2, (uint32_t)s, sizeof(s)/sizeof(char) };
+send_command(0x05, m);
+// some interrupt ID
+
+*/
+
+/* Print a string to the OpenOCD console */
+void debug_print(const char* str);
+
+#endif // __DEBUG_H_
+
diff --git a/src/fsm/src/fsm.c b/src/fsm/fsm.c
index ca6a753..ca6a753 100644
--- a/src/fsm/src/fsm.c
+++ b/src/fsm/fsm.c
diff --git a/src/fsm/src/fsm.h b/src/fsm/fsm.h
index db37fd2..db37fd2 100644
--- a/src/fsm/src/fsm.h
+++ b/src/fsm/fsm.h
diff --git a/src/fsm/main.c b/src/fsm/main.c
new file mode 100644
index 0000000..ba0e9c0
--- /dev/null
+++ b/src/fsm/main.c
@@ -0,0 +1,215 @@
+#include <stdio.h>
+#include <stdlib.h>
+#include <stdint.h>
+#include <math.h>
+#include "stm32f4xx_conf.h"
+#include "audio.h"
+
+/* Kernel includes. */
+#include "FreeRTOS.h"
+#include "task.h"
+#include "timers.h"
+#include "semphr.h"
+
+#include "cw.h"
+
+// Private variables
+volatile uint32_t time_var1, time_var2;
+
+// Private function prototypes
+void init();
+
+// Tasks
+static void detect_button_press(void *pvParameters);
+static void audio_task(void *pvParameters);
+
+struct cw_msg_s {
+ const char* msg;
+ int freq;
+ int dit_duration;
+};
+
+void vApplicationStackOverflowHook( TaskHandle_t xTask,
+ signed char *pcTaskName )
+{
+ while (1) {};
+}
+
+int main(void) {
+ init();
+
+ cw_init(16000);
+
+ InitializeAudio(Audio16000HzSettings);
+ SetAudioVolume(128);
+
+ xTaskCreate(
+ detect_button_press,
+ "TaskButton",
+ 4*configMINIMAL_STACK_SIZE,
+ (void*) NULL,
+ tskIDLE_PRIORITY + 2UL,
+ NULL);
+
+ xTaskCreate(
+ audio_task,
+ "TaskAudio",
+ configMINIMAL_STACK_SIZE,
+ (void*) NULL,
+ tskIDLE_PRIORITY + 2UL,
+ NULL);
+
+ /* Start the RTOS Scheduler */
+ vTaskStartScheduler();
+
+ /* HALT */
+ while(1);
+}
+
+
+static void detect_button_press(void *pvParameters)
+{
+ int message_select = 0;
+ struct cw_msg_s msg1 = { "HB9G 1628M", 400, 100 };
+ struct cw_msg_s msg2 = { "HB9G JN36BK", 500, 100 };
+ struct cw_msg_s msg3 = { "HB9G U 12.5 73", 400, 130 };
+
+ GPIO_SetBits(GPIOD, GPIO_Pin_12);
+
+ while (1) {
+ if (GPIO_ReadInputDataBit(GPIOA,GPIO_Pin_0)>0) {
+
+ while (GPIO_ReadInputDataBit(GPIOA,GPIO_Pin_0) > 0) {
+ vTaskDelay(100 / portTICK_RATE_MS); /* Button Debounce Delay */
+ }
+
+ if (message_select == 0) {
+ GPIO_ResetBits(GPIOD, GPIO_Pin_12);
+ GPIO_SetBits(GPIOD, GPIO_Pin_15);
+ cw_push_message(msg1.msg, msg1.dit_duration, msg1.freq);
+ message_select++;
+ }
+ else if (message_select == 1) {
+ GPIO_SetBits(GPIOD, GPIO_Pin_12);
+ cw_push_message(msg2.msg, msg2.dit_duration, msg2.freq);
+ message_select++;
+ }
+ else if (message_select == 2) {
+ GPIO_ResetBits(GPIOD, GPIO_Pin_15);
+ cw_push_message(msg3.msg, msg3.dit_duration, msg3.freq);
+ message_select = 0;
+ }
+
+ while (GPIO_ReadInputDataBit(GPIOA,GPIO_Pin_0) == 0) {
+ vTaskDelay(100 / portTICK_RATE_MS); /* Button Debounce Delay */
+ }
+ }
+ taskYIELD();
+ }
+}
+
+static void audio_callback(void* context, int select_buffer)
+{
+ static int16_t audio_buffer0[AUDIO_BUF_LEN];
+ static int16_t audio_buffer1[AUDIO_BUF_LEN];
+ int16_t *samples;
+
+ if (select_buffer == 0) {
+ samples = audio_buffer0;
+ GPIO_SetBits(GPIOD, GPIO_Pin_13);
+ GPIO_ResetBits(GPIOD, GPIO_Pin_14);
+ select_buffer = 1;
+ } else {
+ samples = audio_buffer1;
+ GPIO_SetBits(GPIOD, GPIO_Pin_14);
+ GPIO_ResetBits(GPIOD, GPIO_Pin_13);
+ select_buffer = 0;
+ }
+
+ size_t samples_len = cw_fill_buffer(samples, AUDIO_BUF_LEN);
+
+ if (samples_len == 0) {
+ for (int i = 0; i < AUDIO_BUF_LEN; i++) {
+ samples[i] = 0;
+ }
+
+ samples_len = AUDIO_BUF_LEN;
+ }
+
+ ProvideAudioBufferWithoutBlocking(samples, samples_len);
+}
+
+static void audio_task(void *pvParameters)
+{
+ int select_buffer = 0;
+
+ PlayAudioWithCallback(audio_callback, NULL);
+
+ while (1) {
+ taskYIELD();
+ }
+}
+
+
+void init() {
+ GPIO_InitTypeDef GPIO_InitStructure;
+ USART_InitTypeDef USART_InitStructure;
+ // ---------- SysTick timer -------- //
+ if (SysTick_Config(SystemCoreClock / 1000)) {
+ // Capture error
+ while (1){};
+ }
+
+ // Enable full access to FPU (Should be done automatically in system_stm32f4xx.c):
+ //SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); // set CP10 and CP11 Full Access
+
+ // GPIOD Periph clock enable
+ RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOD, ENABLE);
+
+ // Configure PD12, PD13, PD14 and PD15 in output pushpull mode
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12 | GPIO_Pin_13| GPIO_Pin_14| GPIO_Pin_15;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
+ GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;
+ GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
+ GPIO_Init(GPIOD, &GPIO_InitStructure);
+
+ // Init PushButton
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN;
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0;
+ GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;
+ GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+
+ // ------ UART ------ //
+
+ // Clock
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
+ RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOA, ENABLE);
+
+ // IO
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_5 | GPIO_Pin_6;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
+ GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+ GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
+ GPIO_Init(GPIOD, &GPIO_InitStructure);
+
+ GPIO_PinAFConfig(GPIOD, GPIO_PinSource5, GPIO_AF_USART1);
+ GPIO_PinAFConfig(GPIOD, GPIO_PinSource6, GPIO_AF_USART1);
+
+ // Conf
+ USART_InitStructure.USART_BaudRate = 115200;
+ USART_InitStructure.USART_WordLength = USART_WordLength_8b;
+ USART_InitStructure.USART_StopBits = USART_StopBits_1;
+ USART_InitStructure.USART_Parity = USART_Parity_No;
+ USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+ USART_InitStructure.USART_Mode = USART_Mode_Tx | USART_Mode_Rx;
+ USART_Init(USART2, &USART_InitStructure);
+
+ // Enable
+ USART_Cmd(USART2, ENABLE);
+}
+