diff options
Diffstat (limited to 'src/kernel')
-rw-r--r-- | src/kernel/Makefile | 22 | ||||
-rw-r--r-- | src/kernel/clock.c | 103 | ||||
-rw-r--r-- | src/kernel/clock.h | 43 | ||||
-rw-r--r-- | src/kernel/fault.c | 5 | ||||
-rw-r--r-- | src/kernel/gpio.c | 90 | ||||
-rw-r--r-- | src/kernel/gpio.h | 131 | ||||
-rw-r--r-- | src/kernel/heap.c | 136 | ||||
-rw-r--r-- | src/kernel/heap.h | 61 | ||||
-rw-r--r-- | src/kernel/init.c | 52 | ||||
-rw-r--r-- | src/kernel/startup_stm32l476xx.s | 520 | ||||
-rw-r--r-- | src/kernel/svc.c | 61 | ||||
-rw-r--r-- | src/kernel/task.c | 198 | ||||
-rw-r--r-- | src/kernel/task.h | 63 |
13 files changed, 1485 insertions, 0 deletions
diff --git a/src/kernel/Makefile b/src/kernel/Makefile new file mode 100644 index 0000000..d22fbf3 --- /dev/null +++ b/src/kernel/Makefile @@ -0,0 +1,22 @@ +CFILES = $(wildcard *.c) +AFILES = $(wildcard *.s) +OFILES = $(patsubst %.c, %.o, $(CFILES)) \ + $(patsubst %.s, %.asm.o, $(AFILES)) + +CFLAGS += -I.. -I../arch/cmsis + +all: $(OFILES) + +%.o: %.c + @echo " CC " $< + @$(CROSS)$(CC) $(CFLAGS) -c $< -o $@ + +%.asm.o: %.s + @echo " AS " $< + @$(CROSS)$(AS) $(AFLAGS) -c $< -o $@ + +clean: + @echo " CLEAN" + @rm -f $(OFILES) + + diff --git a/src/kernel/clock.c b/src/kernel/clock.c new file mode 100644 index 0000000..44b7722 --- /dev/null +++ b/src/kernel/clock.c @@ -0,0 +1,103 @@ +/** + * @file clock.c + * Basic clock utilities + * + * Copyright (C) 2018 Clyne Sullivan + * + * 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 <https://www.gnu.org/licenses/>. + */ + +#include "clock.h" +#include <arch/stm/stm32l476xx.h> + +// ticks since init +volatile uint32_t ticks = 0; + +volatile uint8_t tim2_finished = 1; + +void clock_svc(uint32_t *args) +{ + udelay(args[0]); +} + +void clock_init(void) +{ + // turn on HSI (16MHz) + RCC->CR |= RCC_CR_HSION; + while ((RCC->CR & RCC_CR_HSIRDY) != RCC_CR_HSIRDY); + + // get PLLR to 80MHz (max) + // VCO = C * (N/M) -> 16 * (10/1) = 160 + // SCLK = VCO / R = 160 / 2 = 80 MHz + RCC->PLLCFGR &= ~(RCC_PLLCFGR_PLLSRC); + RCC->PLLCFGR |= RCC_PLLCFGR_PLLSRC_HSI; + RCC->PLLCFGR &= ~(RCC_PLLCFGR_PLLN | RCC_PLLCFGR_PLLM); + RCC->PLLCFGR |= 10 << RCC_PLLCFGR_PLLN_Pos; + RCC->PLLCFGR &= ~(RCC_PLLCFGR_PLLR | RCC_PLLCFGR_PLLQ); // /2 + RCC->PLLCFGR |= RCC_PLLCFGR_PLLREN | RCC_PLLCFGR_PLLQEN; + + // start PLL + RCC->CR |= RCC_CR_PLLON; + while ((RCC->CR & RCC_CR_PLLRDY) != RCC_CR_PLLRDY); + + // set system clock to PLL + RCC->CFGR &= ~(RCC_CFGR_SW); + RCC->CFGR &= ~(RCC_CFGR_HPRE_Msk); + RCC->CFGR |= RCC_CFGR_SW_PLL; + while ((RCC->CFGR & RCC_CFGR_SWS_PLL) != RCC_CFGR_SWS_PLL); + + // SysTick init. 80MHz / 80000 = 1kHz, ms precision + SysTick->LOAD = 80000; + SysTick->CTRL |= 0x07; // no div, interrupt, enable + + // Prepare TIM2 for microsecond timing + NVIC_EnableIRQ(TIM2_IRQn); + + RCC->APB1ENR1 |= RCC_APB1ENR1_TIM2EN; + TIM2->DIER |= TIM_DIER_UIE; + TIM2->PSC = 40 - 1; + TIM2->ARR = 100; + TIM2->CR1 |= TIM_CR1_OPM | TIM_CR1_CEN; +} + +void delay(uint32_t count) +{ + uint32_t target = ticks + count; + while (ticks < target); +} + +void udelay(uint32_t count) +{ + tim2_finished = 0; + TIM2->ARR = count; + TIM2->CR1 |= TIM_CR1_CEN; + while (tim2_finished == 0); +} + +void SysTick_Handler(void) +{ + // just keep counting + ticks++; + + // task switch every four ticks (4ms) + if (!(ticks & 3)) + SCB->ICSR |= SCB_ICSR_PENDSVSET_Msk; +} + +void TIM2_IRQHandler(void) +{ + TIM2->SR &= ~(TIM_SR_UIF); + tim2_finished |= 1; +} + diff --git a/src/kernel/clock.h b/src/kernel/clock.h new file mode 100644 index 0000000..c3554f6 --- /dev/null +++ b/src/kernel/clock.h @@ -0,0 +1,43 @@ +/** + * @file clock.h + * Clock utilities + * + * Copyright (C) 2018 Clyne Sullivan + * + * 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 <https://www.gnu.org/licenses/>. + */ + +#ifndef CLOCK_H_ +#define CLOCK_H_ + +#include <stdint.h> + +/** + * Initializes clocks, setting HCLK (system clock) to 80MHz, the maximum. + */ +extern void clock_init(void); + +/** + * Sleeps for given amount of milliseconds. + * @param ms Number of milliseconds to sleep for + */ +void delay(uint32_t ms); + +/** + * Sleeps for the given amount of microseconds. + * @param count Number of microseconds to sleep for + */ +void udelay(uint32_t count); + +#endif // CLOCK_H_ diff --git a/src/kernel/fault.c b/src/kernel/fault.c new file mode 100644 index 0000000..dd491c4 --- /dev/null +++ b/src/kernel/fault.c @@ -0,0 +1,5 @@ +__attribute__ ((naked)) +void HardFault_Handler(void) +{ + while (1); +} diff --git a/src/kernel/gpio.c b/src/kernel/gpio.c new file mode 100644 index 0000000..1c81d11 --- /dev/null +++ b/src/kernel/gpio.c @@ -0,0 +1,90 @@ +/** + * @file gpio.c + * Abstracts gpio access, makes things easier + * + * Copyright (C) 2018 Clyne Sullivan + * + * 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 <https://www.gnu.org/licenses/>. + */ + +#include "gpio.h" + +static const GPIO_TypeDef *gpio_ports[8] = { + GPIOA, GPIOB, GPIOC, GPIOD, + GPIOE, GPIOF, GPIOG, GPIOH +}; + +void gpio_svc(uint32_t *args) +{ + GPIO_TypeDef *port = gpio_ports[args[1] / 16]; + uint32_t pin = args[1] & 0xF; + + switch (args[0]) { + case 0: + gpio_mode(port, pin, args[2]); + break; + case 1: + gpio_type(port, pin, args[2]); + break; + case 2: + gpio_pupd(port, pin, args[2]); + break; + case 3: + gpio_speed(port, pin, args[2]); + break; + case 4: + gpio_dout(port, pin, args[2]); + break; + } +} + +void gpio_init(void) +{ + // enable clocks + RCC->AHB2ENR |= 0x0F; +} + +void gpio_pupd(GPIO_TypeDef *port, uint32_t pin, uint32_t pupd) +{ + port->PUPDR &= ~(0x03 << (2 * pin)); + port->PUPDR |= pupd << (2 * pin); +} + +void gpio_speed(GPIO_TypeDef *port, uint32_t pin, uint32_t speed) +{ + port->OSPEEDR &= ~(0x03 << (2 * pin)); + port->OSPEEDR |= speed << (2 * pin); +} + +void gpio_type(GPIO_TypeDef *port, uint32_t pin, uint32_t type) +{ + port->OTYPER &= ~(1 << pin); + port->OTYPER |= type << pin; +} + +void gpio_mode(GPIO_TypeDef *port, uint32_t pin, uint32_t mode) +{ + port->MODER &= ~(0x03 << (2 * pin)); + port->MODER |= mode << (2 * pin); +} + +void gpio_dout(GPIO_TypeDef *port, uint32_t pin, uint32_t val) +{ + port->BSRR |= (1 << (val ? pin : pin + 16)); +} + +uint32_t gpio_din(GPIO_TypeDef *port, uint32_t pin) +{ + return port->IDR & (1 << pin); +} diff --git a/src/kernel/gpio.h b/src/kernel/gpio.h new file mode 100644 index 0000000..ea7e837 --- /dev/null +++ b/src/kernel/gpio.h @@ -0,0 +1,131 @@ +/** + * @file gpio.h + * GPIO Abstraction and access + * + * Copyright (C) 2018 Clyne Sullivan + * + * 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 <https://www.gnu.org/licenses/>. + */ + +#ifndef GPIO_H_ +#define GPIO_H_ + +#include <arch/stm/stm32l476xx.h> + +/** + * Helps simplify gpio calls. + * @param p Port, e.g. A + * @param b Pin, e.g. 4 + */ +#define GPIO_PORT(p, b) GPIO##p, b + +/** + * Defines possible modes for a gpio pin. + */ +enum GPIO_MODE +{ + INPUT = 0, /**< digital input */ + OUTPUT, /**< digital output */ + ALTERNATE, /**< alternate function */ + ANALOG /**< analog function */ +}; + +/** + * Defines whether to use push-pull or open drain. + */ +enum GPIO_TYPE +{ + PUSHPULL = 0, /**< push-pull */ + OPENDRAIN /**< open drain */ +}; + +/** + * Defines the pin's speed + */ +enum GPIO_SPEED +{ + LOW = 0, /**< low */ + MEDIUM, /**< medium */ + HIGH, /**< high */ + VERYHIGH /**< very high/maximum */ +}; + +/** + * Defines if a pullup or pulldown should be used. + */ +enum GPIO_PUPD +{ + NOPUPD, /**< no pullup/pulldown */ + PULLUP, /**< use pullup */ + PULLDOWN /**< use pulldown */ +}; + +/** + * Prepares for GPIO usage. + */ +void gpio_init(void); + +/** + * Enables or disables pullup/pulldown for the given pin. + * @param port The port, e.g. GPIOA + * @param pin The pin + * @param pupd Pullup/pulldown enable + * @see GPIO_PUPD + */ +void gpio_pupd(GPIO_TypeDef *port, uint32_t pin, uint32_t pupd); + +/** + * Sets whether to use push-pull or open drain for the given pin. + * @param port The port + * @param pin The pin + * @param type What type to use + * @see GPIO_TYPE + */ +void gpio_type(GPIO_TypeDef *port, uint32_t pin, uint32_t type); + +/** + * Sets the pin's speed. + * @param port The port + * @param pin The pin + * @param speed The speed to use + * @see GPIO_SPEED + */ +void gpio_speed(GPIO_TypeDef *port, uint32_t pin, uint32_t speed); + +/** + * Sets the pin's i/o mode. + * @param port The port + * @param pin The pin + * @param mode The mode to use + * @see GPIO_MODE + */ +void gpio_mode(GPIO_TypeDef *port, uint32_t pin, uint32_t mode); + +/** + * Sets the state of a digital output pin. + * @param port The port + * @param pin The pin + * @param val Non-zero for high, zero for low + */ +void gpio_dout(GPIO_TypeDef *port, uint32_t pin, uint32_t val); + +/** + * Reads a digital input pin. + * @param port The port + * @param pin The pin + * @return Non-zero for high, zero for low + */ +uint32_t gpio_din(GPIO_TypeDef *port, uint32_t pin); + +#endif // GPIO_H_ diff --git a/src/kernel/heap.c b/src/kernel/heap.c new file mode 100644 index 0000000..ff5dd9e --- /dev/null +++ b/src/kernel/heap.c @@ -0,0 +1,136 @@ +/** + * @file heap.c + * A basic memory manager + * + * Copyright (C) 2018 Clyne Sullivan + * + * 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 <https://www.gnu.org/licenses/>. + */ + +#include "heap.h" + +#define HEAP_ALIGN 4 + +typedef struct { + uint32_t size; + void *next; +} __attribute__ ((packed)) alloc_t; + +static alloc_t *free_blocks; +static void *heap_end; + +void heap_init(void *buf) +{ + heap_end = buf; + free_blocks = 0; +} + +uint32_t heap_free(void) +{ + uint32_t total = 0; + for (alloc_t *node = free_blocks; node != 0; node = node->next) + total += node->size; + return total + (0x20018000 - (uint32_t)heap_end); +} + +void *malloc(uint32_t size) +{ + if (size == 0) + return 0; + + size = (size + sizeof(alloc_t) + HEAP_ALIGN) & ~(HEAP_ALIGN - 1); + + alloc_t *node = free_blocks; + alloc_t *prev = 0; + while (node != 0) { + if (node->size >= size) { + // get out of the free chain + if (prev != 0) + prev->next = node->next; + else + free_blocks = node->next; + node->next = 0; + + // split alloc if too big + if (node->size > size + 64) { + alloc_t *leftover = (alloc_t *)((uint32_t)node + + sizeof(alloc_t) + size); + leftover->size = node->size - size - sizeof(alloc_t); + leftover->next = 0; + free((uint8_t *)leftover + sizeof(alloc_t)); + node->size = size; + return (void *)((uint8_t *)node + sizeof(alloc_t)); + } + + return (void *)((uint8_t *)node + sizeof(alloc_t)); + } + + prev = node; + node = node->next; + } + + node = (alloc_t *)heap_end; + node->size = size; + node->next = 0; + + heap_end = (void *)((uint8_t *)heap_end + size); + + return (void *)((uint8_t *)node + sizeof(alloc_t)); +} + +void *calloc(uint32_t count, uint32_t size) +{ + uint8_t *buf = malloc(count * size); + for (uint32_t i = 0; i < count * size; i++) + buf[i] = 0; + return buf; +} + +void free(void *buf) +{ + if (buf == 0) + return; + + alloc_t *alloc = (alloc_t *)((uint8_t *)buf - sizeof(alloc_t)); + if (alloc->next != 0) + return; + + // check for adjacent free'd blocks + int merged = 0; + for (alloc_t *prev = 0, *node = free_blocks; node != 0; prev = node, node = node->next) { + if ((uint32_t)node + sizeof(alloc_t) + node->size == (uint32_t)alloc) { + // block before + merged |= 1; + node->size += sizeof(alloc_t) + alloc->size; + break; + //alloc = node; + } else if ((uint32_t)buf + alloc->size == (uint32_t)node) { + // block after + merged |= 1; + alloc->size += sizeof(alloc_t) + node->size; + alloc->next = node->next; + if (prev != 0) + prev->next = alloc; + else + free_blocks = alloc; + break; + } + } + + if (merged == 0) { + alloc->next = free_blocks; + free_blocks = alloc; + } + +} diff --git a/src/kernel/heap.h b/src/kernel/heap.h new file mode 100644 index 0000000..c817e4d --- /dev/null +++ b/src/kernel/heap.h @@ -0,0 +1,61 @@ +/** + * @file heap.h + * A basic memory manager + * + * Copyright (C) 2018 Clyne Sullivan + * + * 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 <https://www.gnu.org/licenses/>. + */ + +#ifndef HEAP_H_ +#define HEAP_H_ + +#include <stdint.h> + +/** + * Initializes memory management of the given heap. + * No overflow stuff is done, so... be careful. + * @param buf The heap to use for allocations + */ +void heap_init(void *buf); + +/** + * Returns the amount of free, allocatable memory, in bytes. + * @return Amount of free memory in bytes + */ +uint32_t heap_free(void); + +/** + * Allocates a chunk of memory. + * @param size How many bytes to claim + * @return Pointer to the allocated buffer + */ +void *malloc(uint32_t size); + +/** + * Allocates and zeros a chunk of memory. + * @param count How many of whatever to allocate + * @param size Byte count of each whatever + * @return Pointer to the allocated buffer + */ +void *calloc(uint32_t count, uint32_t size); + +/** + * Frees the buffer allocated through malloc/calloc. + * Please don't double-free. + * @param The buffer to release + */ +void free(void *buf); + +#endif // HEAP_H_ diff --git a/src/kernel/init.c b/src/kernel/init.c new file mode 100644 index 0000000..e4ac115 --- /dev/null +++ b/src/kernel/init.c @@ -0,0 +1,52 @@ +/**
+ * @file init.c
+ * Kernel initialization procedure
+ *
+ * Copyright (C) 2018 Clyne Sullivan
+ *
+ * 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 <https://www.gnu.org/licenses/>.
+ */
+
+#include "clock.h"
+#include "gpio.h"
+#include "heap.h"
+#include "task.h"
+#include <arch/stm/stm32l476xx.h>
+
+extern uint8_t __bss_end__;
+
+extern void user_main(void);
+
+int main(void)
+{
+ asm("cpsid i");
+ // disable cached writes for precise debug info
+ //*((uint32_t *)0xE000E008) |= 2;
+
+ // prepare flash latency for 80MHz operation
+ FLASH->ACR &= ~(FLASH_ACR_LATENCY);
+ FLASH->ACR |= FLASH_ACR_LATENCY_4WS;
+
+ // init core components
+ clock_init();
+ heap_init(&__bss_end__);
+ gpio_init();
+
+ // enable FPU
+ //SCB->CPACR |= (0xF << 20);
+
+ task_init(user_main);
+ while (1);
+}
+
diff --git a/src/kernel/startup_stm32l476xx.s b/src/kernel/startup_stm32l476xx.s new file mode 100644 index 0000000..b26ced5 --- /dev/null +++ b/src/kernel/startup_stm32l476xx.s @@ -0,0 +1,520 @@ +/**
+ ******************************************************************************
+ * @file startup_stm32l476xx.s
+ * @author MCD Application Team
+ * @brief STM32L476xx devices vector table GCC toolchain.
+ * This module performs:
+ * - Set the initial SP
+ * - Set the initial PC == Reset_Handler,
+ * - Set the vector table entries with the exceptions ISR address,
+ * - Configure the clock system
+ * - Branches to main in the C library (which eventually
+ * calls main()).
+ * After Reset the Cortex-M4 processor is in Thread mode,
+ * priority is Privileged, and the Stack is set to Main.
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>© COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ ******************************************************************************
+ */
+
+ .syntax unified
+ .cpu cortex-m4
+ .fpu softvfp
+ .thumb
+
+.global g_pfnVectors
+.global Default_Handler
+
+/* start address for the initialization values of the .data section.
+defined in linker script */
+.word _sidata
+/* start address for the .data section. defined in linker script */
+.word _sdata
+/* end address for the .data section. defined in linker script */
+.word _edata
+
+.equ _estack, 0x20018000
+
+.equ BootRAM, 0xF1E0F85F
+/**
+ * @brief This is the code that gets called when the processor first
+ * starts execution following a reset event. Only the absolutely
+ * necessary set is performed, after which the application
+ * supplied main() routine is called.
+ * @param None
+ * @retval : None
+*/
+
+ .section .text.Reset_Handler
+ .weak Reset_Handler
+ .type Reset_Handler, %function
+Reset_Handler:
+ ldr sp, =_estack /* Atollic update: set stack pointer */
+
+/* Copy the data segment initializers from flash to SRAM */
+ movs r1, #0
+ b LoopCopyDataInit
+
+CopyDataInit:
+ ldr r3, =_sidata
+ ldr r3, [r3, r1]
+ str r3, [r0, r1]
+ adds r1, r1, #4
+
+LoopCopyDataInit:
+ ldr r0, =_sdata
+ ldr r3, =_edata
+ adds r2, r0, r1
+ cmp r2, r3
+ bcc CopyDataInit
+ ldr r2, =__bss_start__
+ b LoopFillZerobss
+/* Zero fill the bss segment. */
+FillZerobss:
+ movs r3, #0
+ str r3, [r2], #4
+
+LoopFillZerobss:
+ ldr r3, = __bss_end__
+ cmp r2, r3
+ bcc FillZerobss
+
+/* Call static constructors */
+ bl __libc_init_array
+/* Call the application's entry point.*/
+ bl main
+
+LoopForever:
+ b LoopForever
+
+.size Reset_Handler, .-Reset_Handler
+
+/**
+ * @brief This is the code that gets called when the processor receives an
+ * unexpected interrupt. This simply enters an infinite loop, preserving
+ * the system state for examination by a debugger.
+ *
+ * @param None
+ * @retval : None
+*/
+ .section .text.Default_Handler,"ax",%progbits
+Default_Handler:
+Infinite_Loop:
+ b Infinite_Loop
+ .size Default_Handler, .-Default_Handler
+/******************************************************************************
+*
+* The minimal vector table for a Cortex-M4. Note that the proper constructs
+* must be placed on this to ensure that it ends up at physical address
+* 0x0000.0000.
+*
+******************************************************************************/
+ .section .isr_vector,"a",%progbits
+ .type g_pfnVectors, %object
+ .size g_pfnVectors, .-g_pfnVectors
+
+
+g_pfnVectors:
+ .word _estack
+ .word Reset_Handler
+ .word NMI_Handler
+ .word HardFault_Handler
+ .word MemManage_Handler
+ .word BusFault_Handler
+ .word UsageFault_Handler
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word SVC_Handler
+ .word DebugMon_Handler
+ .word 0
+ .word PendSV_Handler
+ .word SysTick_Handler
+ .word WWDG_IRQHandler
+ .word PVD_PVM_IRQHandler
+ .word TAMP_STAMP_IRQHandler
+ .word RTC_WKUP_IRQHandler
+ .word FLASH_IRQHandler
+ .word RCC_IRQHandler
+ .word EXTI0_IRQHandler
+ .word EXTI1_IRQHandler
+ .word EXTI2_IRQHandler
+ .word EXTI3_IRQHandler
+ .word EXTI4_IRQHandler
+ .word DMA1_Channel1_IRQHandler
+ .word DMA1_Channel2_IRQHandler
+ .word DMA1_Channel3_IRQHandler
+ .word DMA1_Channel4_IRQHandler
+ .word DMA1_Channel5_IRQHandler
+ .word DMA1_Channel6_IRQHandler
+ .word DMA1_Channel7_IRQHandler
+ .word ADC1_2_IRQHandler
+ .word CAN1_TX_IRQHandler
+ .word CAN1_RX0_IRQHandler
+ .word CAN1_RX1_IRQHandler
+ .word CAN1_SCE_IRQHandler
+ .word EXTI9_5_IRQHandler
+ .word TIM1_BRK_TIM15_IRQHandler
+ .word TIM1_UP_TIM16_IRQHandler
+ .word TIM1_TRG_COM_TIM17_IRQHandler
+ .word TIM1_CC_IRQHandler
+ .word TIM2_IRQHandler
+ .word TIM3_IRQHandler
+ .word TIM4_IRQHandler
+ .word I2C1_EV_IRQHandler
+ .word I2C1_ER_IRQHandler
+ .word I2C2_EV_IRQHandler
+ .word I2C2_ER_IRQHandler
+ .word SPI1_IRQHandler
+ .word SPI2_IRQHandler
+ .word USART1_IRQHandler
+ .word USART2_IRQHandler
+ .word USART3_IRQHandler
+ .word EXTI15_10_IRQHandler
+ .word RTC_Alarm_IRQHandler
+ .word DFSDM1_FLT3_IRQHandler
+ .word TIM8_BRK_IRQHandler
+ .word TIM8_UP_IRQHandler
+ .word TIM8_TRG_COM_IRQHandler
+ .word TIM8_CC_IRQHandler
+ .word ADC3_IRQHandler
+ .word FMC_IRQHandler
+ .word SDMMC1_IRQHandler
+ .word TIM5_IRQHandler
+ .word SPI3_IRQHandler
+ .word UART4_IRQHandler
+ .word UART5_IRQHandler
+ .word TIM6_DAC_IRQHandler
+ .word TIM7_IRQHandler
+ .word DMA2_Channel1_IRQHandler
+ .word DMA2_Channel2_IRQHandler
+ .word DMA2_Channel3_IRQHandler
+ .word DMA2_Channel4_IRQHandler
+ .word DMA2_Channel5_IRQHandler
+ .word DFSDM1_FLT0_IRQHandler
+ .word DFSDM1_FLT1_IRQHandler
+ .word DFSDM1_FLT2_IRQHandler
+ .word COMP_IRQHandler
+ .word LPTIM1_IRQHandler
+ .word LPTIM2_IRQHandler
+ .word OTG_FS_IRQHandler
+ .word DMA2_Channel6_IRQHandler
+ .word DMA2_Channel7_IRQHandler
+ .word LPUART1_IRQHandler
+ .word QUADSPI_IRQHandler
+ .word I2C3_EV_IRQHandler
+ .word I2C3_ER_IRQHandler
+ .word SAI1_IRQHandler
+ .word SAI2_IRQHandler
+ .word SWPMI1_IRQHandler
+ .word TSC_IRQHandler
+ .word LCD_IRQHandler
+ .word 0
+ .word RNG_IRQHandler
+ .word FPU_IRQHandler
+
+
+/*******************************************************************************
+*
+* Provide weak aliases for each Exception handler to the Default_Handler.
+* As they are weak aliases, any function with the same name will override
+* this definition.
+*
+*******************************************************************************/
+
+ .weak NMI_Handler
+ .thumb_set NMI_Handler,Default_Handler
+
+ .weak HardFault_Handler
+ .thumb_set HardFault_Handler,Default_Handler
+
+ .weak MemManage_Handler
+ .thumb_set MemManage_Handler,Default_Handler
+
+ .weak BusFault_Handler
+ .thumb_set BusFault_Handler,Default_Handler
+
+ .weak UsageFault_Handler
+ .thumb_set UsageFault_Handler,Default_Handler
+
+ .weak SVC_Handler
+ .thumb_set SVC_Handler,Default_Handler
+
+ .weak DebugMon_Handler
+ .thumb_set DebugMon_Handler,Default_Handler
+
+ .weak PendSV_Handler
+ .thumb_set PendSV_Handler,Default_Handler
+
+ .weak SysTick_Handler
+ .thumb_set SysTick_Handler,Default_Handler
+
+ .weak WWDG_IRQHandler
+ .thumb_set WWDG_IRQHandler,Default_Handler
+
+ .weak PVD_PVM_IRQHandler
+ .thumb_set PVD_PVM_IRQHandler,Default_Handler
+
+ .weak TAMP_STAMP_IRQHandler
+ .thumb_set TAMP_STAMP_IRQHandler,Default_Handler
+
+ .weak RTC_WKUP_IRQHandler
+ .thumb_set RTC_WKUP_IRQHandler,Default_Handler
+
+ .weak FLASH_IRQHandler
+ .thumb_set FLASH_IRQHandler,Default_Handler
+
+ .weak RCC_IRQHandler
+ .thumb_set RCC_IRQHandler,Default_Handler
+
+ .weak EXTI0_IRQHandler
+ .thumb_set EXTI0_IRQHandler,Default_Handler
+
+ .weak EXTI1_IRQHandler
+ .thumb_set EXTI1_IRQHandler,Default_Handler
+
+ .weak EXTI2_IRQHandler
+ .thumb_set EXTI2_IRQHandler,Default_Handler
+
+ .weak EXTI3_IRQHandler
+ .thumb_set EXTI3_IRQHandler,Default_Handler
+
+ .weak EXTI4_IRQHandler
+ .thumb_set EXTI4_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel1_IRQHandler
+ .thumb_set DMA1_Channel1_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel2_IRQHandler
+ .thumb_set DMA1_Channel2_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel3_IRQHandler
+ .thumb_set DMA1_Channel3_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel4_IRQHandler
+ .thumb_set DMA1_Channel4_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel5_IRQHandler
+ .thumb_set DMA1_Channel5_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel6_IRQHandler
+ .thumb_set DMA1_Channel6_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel7_IRQHandler
+ .thumb_set DMA1_Channel7_IRQHandler,Default_Handler
+
+ .weak ADC1_2_IRQHandler
+ .thumb_set ADC1_2_IRQHandler,Default_Handler
+
+ .weak CAN1_TX_IRQHandler
+ .thumb_set CAN1_TX_IRQHandler,Default_Handler
+
+ .weak CAN1_RX0_IRQHandler
+ .thumb_set CAN1_RX0_IRQHandler,Default_Handler
+
+ .weak CAN1_RX1_IRQHandler
+ .thumb_set CAN1_RX1_IRQHandler,Default_Handler
+
+ .weak CAN1_SCE_IRQHandler
+ .thumb_set CAN1_SCE_IRQHandler,Default_Handler
+
+ .weak EXTI9_5_IRQHandler
+ .thumb_set EXTI9_5_IRQHandler,Default_Handler
+
+ .weak TIM1_BRK_TIM15_IRQHandler
+ .thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler
+
+ .weak TIM1_UP_TIM16_IRQHandler
+ .thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler
+
+ .weak TIM1_TRG_COM_TIM17_IRQHandler
+ .thumb_set TIM1_TRG_COM_TIM17_IRQHandler,Default_Handler
+
+ .weak TIM1_CC_IRQHandler
+ .thumb_set TIM1_CC_IRQHandler,Default_Handler
+
+ .weak TIM2_IRQHandler
+ .thumb_set TIM2_IRQHandler,Default_Handler
+
+ .weak TIM3_IRQHandler
+ .thumb_set TIM3_IRQHandler,Default_Handler
+
+ .weak TIM4_IRQHandler
+ .thumb_set TIM4_IRQHandler,Default_Handler
+
+ .weak I2C1_EV_IRQHandler
+ .thumb_set I2C1_EV_IRQHandler,Default_Handler
+
+ .weak I2C1_ER_IRQHandler
+ .thumb_set I2C1_ER_IRQHandler,Default_Handler
+
+ .weak I2C2_EV_IRQHandler
+ .thumb_set I2C2_EV_IRQHandler,Default_Handler
+
+ .weak I2C2_ER_IRQHandler
+ .thumb_set I2C2_ER_IRQHandler,Default_Handler
+
+ .weak SPI1_IRQHandler
+ .thumb_set SPI1_IRQHandler,Default_Handler
+
+ .weak SPI2_IRQHandler
+ .thumb_set SPI2_IRQHandler,Default_Handler
+
+ .weak USART1_IRQHandler
+ .thumb_set USART1_IRQHandler,Default_Handler
+
+ .weak USART2_IRQHandler
+ .thumb_set USART2_IRQHandler,Default_Handler
+
+ .weak USART3_IRQHandler
+ .thumb_set USART3_IRQHandler,Default_Handler
+
+ .weak EXTI15_10_IRQHandler
+ .thumb_set EXTI15_10_IRQHandler,Default_Handler
+
+ .weak RTC_Alarm_IRQHandler
+ .thumb_set RTC_Alarm_IRQHandler,Default_Handler
+
+ .weak DFSDM1_FLT3_IRQHandler
+ .thumb_set DFSDM1_FLT3_IRQHandler,Default_Handler
+
+ .weak TIM8_BRK_IRQHandler
+ .thumb_set TIM8_BRK_IRQHandler,Default_Handler
+
+ .weak TIM8_UP_IRQHandler
+ .thumb_set TIM8_UP_IRQHandler,Default_Handler
+
+ .weak TIM8_TRG_COM_IRQHandler
+ .thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler
+
+ .weak TIM8_CC_IRQHandler
+ .thumb_set TIM8_CC_IRQHandler,Default_Handler
+
+ .weak ADC3_IRQHandler
+ .thumb_set ADC3_IRQHandler,Default_Handler
+
+ .weak FMC_IRQHandler
+ .thumb_set FMC_IRQHandler,Default_Handler
+
+ .weak SDMMC1_IRQHandler
+ .thumb_set SDMMC1_IRQHandler,Default_Handler
+
+ .weak TIM5_IRQHandler
+ .thumb_set TIM5_IRQHandler,Default_Handler
+
+ .weak SPI3_IRQHandler
+ .thumb_set SPI3_IRQHandler,Default_Handler
+
+ .weak UART4_IRQHandler
+ .thumb_set UART4_IRQHandler,Default_Handler
+
+ .weak UART5_IRQHandler
+ .thumb_set UART5_IRQHandler,Default_Handler
+
+ .weak TIM6_DAC_IRQHandler
+ .thumb_set TIM6_DAC_IRQHandler,Default_Handler
+
+ .weak TIM7_IRQHandler
+ .thumb_set TIM7_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel1_IRQHandler
+ .thumb_set DMA2_Channel1_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel2_IRQHandler
+ .thumb_set DMA2_Channel2_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel3_IRQHandler
+ .thumb_set DMA2_Channel3_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel4_IRQHandler
+ .thumb_set DMA2_Channel4_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel5_IRQHandler
+ .thumb_set DMA2_Channel5_IRQHandler,Default_Handler
+
+ .weak DFSDM1_FLT0_IRQHandler
+ .thumb_set DFSDM1_FLT0_IRQHandler,Default_Handler
+
+ .weak DFSDM1_FLT1_IRQHandler
+ .thumb_set DFSDM1_FLT1_IRQHandler,Default_Handler
+
+ .weak DFSDM1_FLT2_IRQHandler
+ .thumb_set DFSDM1_FLT2_IRQHandler,Default_Handler
+
+ .weak COMP_IRQHandler
+ .thumb_set COMP_IRQHandler,Default_Handler
+
+ .weak LPTIM1_IRQHandler
+ .thumb_set LPTIM1_IRQHandler,Default_Handler
+
+ .weak LPTIM2_IRQHandler
+ .thumb_set LPTIM2_IRQHandler,Default_Handler
+
+ .weak OTG_FS_IRQHandler
+ .thumb_set OTG_FS_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel6_IRQHandler
+ .thumb_set DMA2_Channel6_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel7_IRQHandler
+ .thumb_set DMA2_Channel7_IRQHandler,Default_Handler
+
+ .weak LPUART1_IRQHandler
+ .thumb_set LPUART1_IRQHandler,Default_Handler
+
+ .weak QUADSPI_IRQHandler
+ .thumb_set QUADSPI_IRQHandler,Default_Handler
+
+ .weak I2C3_EV_IRQHandler
+ .thumb_set I2C3_EV_IRQHandler,Default_Handler
+
+ .weak I2C3_ER_IRQHandler
+ .thumb_set I2C3_ER_IRQHandler,Default_Handler
+
+ .weak SAI1_IRQHandler
+ .thumb_set SAI1_IRQHandler,Default_Handler
+
+ .weak SAI2_IRQHandler
+ .thumb_set SAI2_IRQHandler,Default_Handler
+
+ .weak SWPMI1_IRQHandler
+ .thumb_set SWPMI1_IRQHandler,Default_Handler
+
+ .weak TSC_IRQHandler
+ .thumb_set TSC_IRQHandler,Default_Handler
+
+ .weak LCD_IRQHandler
+ .thumb_set LCD_IRQHandler,Default_Handler
+
+ .weak RNG_IRQHandler
+ .thumb_set RNG_IRQHandler,Default_Handler
+
+ .weak FPU_IRQHandler
+ .thumb_set FPU_IRQHandler,Default_Handler
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/src/kernel/svc.c b/src/kernel/svc.c new file mode 100644 index 0000000..62324f7 --- /dev/null +++ b/src/kernel/svc.c @@ -0,0 +1,61 @@ +/** + * @file svc.c + * An unused handler for SVC calls + * TODO: use SVC calls, possibly allowing for switch to unprivileged mode? + * + * Copyright (C) 2018 Clyne Sullivan + * + * 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 <https://www.gnu.org/licenses/>. + */ + +#include <stdint.h> +#include "gpio.h" +#include "clock.h" +#include "task.h" + +extern void gpio_svc(uint32_t *); +extern void clock_svc(uint32_t *); + +void svc_handler(uint32_t *args) +{ + /*uint32_t*/int svc_number = ((char *)args[6])[-2]; + + switch (svc_number) { + case -1: + case 0: + _exit(args[0]); + break; + case 1: + gpio_svc(args); + break; + case 2: + clock_svc(args); + default: + break; + } +} + +void SVC_Handler(void) { + uint32_t *args; + + asm("\ + tst lr, #4; \ + ite eq; \ + mrseq %0, msp; \ + mrsne %0, psp; \ + " : "=r" (args)); + + svc_handler(args); +} + diff --git a/src/kernel/task.c b/src/kernel/task.c new file mode 100644 index 0000000..1a1c16b --- /dev/null +++ b/src/kernel/task.c @@ -0,0 +1,198 @@ +/** + * @file task.c + * Provides multitasking functionality + * + * Copyright (C) 2018 Clyne Sullivan + * + * 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 <https://www.gnu.org/licenses/>. + */ + +#include "task.h" +#include "heap.h" +#include <arch/stm/stm32l476xx.h> + +task_t *current, *prev; +static uint8_t task_disable = 0; + +void task_hold(uint8_t hold) +{ + if (hold != 0) + task_disable++; + else if (task_disable > 0) + task_disable--; +} + +void _exit(int code) +{ + (void)code; + + while (prev == 0); + + prev->next = current->next; + + // Free this thread's stack, and task data. + // Since we're single core, no one else can claim this memory until + // a task switch, after which we're done with this memory anyway. + free(current->stack); + free(current); + + SCB->ICSR |= SCB_ICSR_PENDSVSET_Msk; +} + +/** + * 'Prepares' task for running. + * Calls the task's main code, setting _exit() as the return point. + */ +__attribute__ ((naked)) +void task_doexit(void) +{ + asm("eor r0, r0; svc 0"); + while (1); +} + +__attribute__ ((naked)) +void task_crt0(void) +{ + asm("\ + mov r4, lr; \ + ldr lr, =task_doexit; \ + bx r4; \ + "); +} + +task_t *task_create(void (*code)(void), uint32_t stackSize) +{ + task_t *t = (task_t *)malloc(sizeof(task_t)); + t->next = 0; + t->stack = (uint32_t *)malloc(stackSize); + void *sp = (uint8_t *)t->stack + stackSize - 68; // excep. stack + regs + t->sp = sp; + + /* + sp[0-7] - r4-r11 + sp[8] - r14 (lr) + sp[9-12] - r0-r3 + sp[13] - r12 + sp[14] - LR + sp[15] - PC + sp[16] - xPSR + */ + + for (uint8_t i = 0; i < 14; i++) + t->sp[i] = 0; + t->sp[8] = 0xFFFFFFFD; + t->sp[14] = (uint32_t)code; + t->sp[15] = (uint32_t)task_crt0; + t->sp[16] = 0x01000000; + return t; +} + +void task_init(void (*init)(void)) +{ + current = (task_t *)malloc(sizeof(task_t)); + current->stack = 0; + + task_t *init_task = task_create(init, 4096); + + prev = init_task; + current->next = init_task; + init_task->next = init_task; + + task_disable = 0; + + // bit 0 - priv, bit 1 - psp/msp + asm("\ + mov r0, sp; \ + mov %0, r0; \ + msr psp, r0; \ + mrs r0, control; \ + orr r0, r0, #3; \ + cpsie i; \ + msr control, r0; \ + " : "=r" (current->sp)); + + task_doexit(); +} + +void task_start(void (*task)(void), uint16_t stackSize) +{ + task_hold(1); + task_t *t = task_create(task, stackSize); + t->next = current->next; + current->next = t; + task_hold(0); +} + +/*int fork_ret(void) +{ + return 1; +} + +int fork(void) +{ + void (*pc)(void) = (void (*)(void))((uint32_t)fork_ret & ~(3)); + task_hold(1); + + // duplicate task info + alloc_t *heapInfo = (alloc_t *)(current->stack - 2); + task_t *t = task_create(pc, heapInfo->size); + memcpy(t->stack, current->stack, heapInfo->size); + uint32_t *sp; + asm("mov %0, sp" : "=r" (sp)); + t->sp = t->stack + (sp - current->stack); + + t->next = current->next; + current->next = t; + current = t; + task_hold(0); + SCB->ICSR |= SCB_ICSR_PENDSVSET_Msk; + return 0; +}*/ + +__attribute__ ((naked)) +void PendSV_Handler(void) +{ + if (task_disable != 0) + asm("bx lr"); + + // TODO why, and what does this do + // TODO get back to c, implement task sleeping + asm("\ + mrs r0, psp; \ + isb; \ + ldr r1, =current; \ + ldr r2, [r1]; \ + stmdb r0!, {r4-r11, r14}; \ + str r0, [r2, #8]; \ + ldr r0, [r2, #0]; \ + ldr r3, =prev; \ + str r2, [r3]; \ + str r0, [r1]; \ + ldr r2, [r1]; \ + ldr r0, [r2, #8]; \ + ldmia r0!, {r4-r11, r14}; \ + msr psp, r0; \ + bx lr; \ + "); + // r1 = current + // r2 = *current + // r0 = sp + // *current.sp = sp + // r0 = current->next + // current = r0 + // r2 = *current + // r0 = *current.sp + // unpack +} + diff --git a/src/kernel/task.h b/src/kernel/task.h new file mode 100644 index 0000000..3d331ae --- /dev/null +++ b/src/kernel/task.h @@ -0,0 +1,63 @@ +/** + * @file task.h + * Provides multitasking functionality + * + * Copyright (C) 2018 Clyne Sullivan + * + * 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 <https://www.gnu.org/licenses/>. + */ + +#ifndef TASK_H_ +#define TASK_H_ + +#include <stdint.h> + +/** + * A structure to contain task data. + */ +typedef struct { + void *next; /**< pointer to the next task_t instance */ + uint32_t *stack; /**< pointer to the task's stack */ + uint32_t *sp; /**< pointer to the task's last sp register value */ +} task_t; + +/** + * Enters multitasking mode. The given function acts as the initial thread. + * This task is given a 4kb stack. + * @param init the initial thread to run + */ +void task_init(void (*init)(void)); + +/** + * Starts a new task. + * @param task the code to run + * @param stackSize how many bytes of stack to give the thread + */ +void task_start(void (*task)(void), uint16_t stackSize); + +/** + * Allows task switching to be disabled, for low-level actions. + * Multiple holds can be placed, and all must be removed to continue task + * switching. + * @param hold non-zero for hold, zero to remove hold + */ +void task_hold(uint8_t hold); + +/** + * Frees the task's resources and removes it from the running task list. + * @param code An unused exit code + */ +void _exit(int code); + +#endif // TASK_H_ |