Merge pull request from sandtler/iothread

Move serial stuff to separate I/O thread
This commit is contained in:
Felix 2020-12-01 23:44:58 +01:00 committed by GitHub
commit e98382dde2
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
30 changed files with 876 additions and 228 deletions

View file

@ -26,9 +26,11 @@
ARDIX_ARCH_PWD = $(PWD)/arch/at91sam3x8e
ARDIX_SOURCES += \
$(ARDIX_ARCH_PWD)/atomic.c \
$(ARDIX_ARCH_PWD)/interrupt.c \
$(ARDIX_ARCH_PWD)/sched.c \
$(ARDIX_ARCH_PWD)/serial.c \
$(ARDIX_ARCH_PWD)/spinlock.c \
$(ARDIX_ARCH_PWD)/startup.c \
$(ARDIX_ARCH_PWD)/sys.c

47
arch/at91sam3x8e/atomic.c Normal file
View file

@ -0,0 +1,47 @@
/* SPDX-License-Identifier: BSD-3-Clause */
/* See the end of this file for copyright, licensing, and warranty information. */
#include <arch/at91sam3x8e/spinlock.h>
#include <ardix/atomic.h>
static SPINLOCK_DEFINE(atomic_context);
void atomic_enter(void)
{
arch_spin_lock(&atomic_context);
}
void atomic_leave(void)
{
arch_spin_unlock(&atomic_context);
}
int is_atomic_context(void)
{
return arch_spinlock_count(&atomic_context);
}
/*
* Copyright (c) 2020 Felix Kopp <sandtler@sandtler.club>
*
* 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 the copyright holder 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.
*/

View file

@ -6,12 +6,35 @@
void arch_irq_enable(enum irqno irqno)
{
REG_NVIC_ISER((uint32_t)irqno >> 5) = 1 << ( ((uint32_t)irqno) & 0x1F );
if (irqno >= 0)
REG_NVIC_ISER((uint32_t)irqno >> 5) = 1 << ( ((uint32_t)irqno) & 0x1F );
}
void arch_irq_disable(enum irqno irqno)
{
REG_NVIC_ICER((uint32_t)irqno >> 5) = 1 << ( ((uint32_t)irqno) & 0x1F );
if (irqno >= 0)
REG_NVIC_ICER((uint32_t)irqno >> 5) = 1 << ( ((uint32_t)irqno) & 0x1F );
}
void arch_irq_invoke(enum irqno irqno)
{
if (irqno < 0) {
switch (irqno) {
case IRQNO_PEND_SV:
REG_SCB_ICSR = REG_SCB_ICSR_PENDSVSET_BIT;
break;
case IRQNO_SYS_TICK:
REG_SCB_ICSR = REG_SCB_ICSR_PENDSTSET_BIT;
break;
default:
/* TODO: Implement the rest of interrupts < 0 */
break;
}
} else {
REG_NVIC_ISPR((uint32_t)irqno >> 5) = 1 << ( ((uint32_t)irqno) & 0x1F );
}
}
/*

View file

@ -3,23 +3,16 @@
#include <arch/sched.h>
#include <arch/at91sam3x8e/hardware.h>
#include <arch/at91sam3x8e/interrupt.h>
#include <ardix/atomic.h>
#include <ardix/string.h>
#include <ardix/sched.h>
#include <stdbool.h>
#include <toolchain.h>
#ifdef __cplusplus
extern "C"
{
#endif /* __cplusplus */
/**
* Set the PENDSV bit in the system control block.
*/
static __always_inline void sched_pendsv_req(void)
{
REG_SCB_ICSR |= REG_SCB_ICSR_PENDSVSET_BIT;
}
#include <ardix/spinlock.h>
void irq_sys_tick(void)
{
@ -27,16 +20,8 @@ void irq_sys_tick(void)
* fire a PendSV interrupt and do the actual context switching there
* because it is faster that way (according to the docs, at least)
*/
sched_pendsv_req();
}
void sched_init_process_regs(struct reg_snapshot *reg_snap, void (*entry)(void))
{
memset(reg_snap, 0, sizeof(*reg_snap));
reg_snap->hw.lr = (void *)0xFFFFFFF9U;
reg_snap->hw.pc = entry;
reg_snap->hw.psr = 0x01000000U;
if (!is_atomic_context())
arch_irq_invoke(IRQNO_PEND_SV);
}
/**
@ -57,7 +42,7 @@ static inline void sched_nvic_set_prio_group(uint32_t prio_group)
REG_SCB_AIRCR = reg_val;
}
int sched_hwtimer_init(unsigned int freq)
int arch_sched_hwtimer_init(unsigned int freq)
{
uint32_t ticks = sys_core_clock / freq;
if (ticks > REG_SYSTICK_LOAD_RELOAD_MASK)
@ -75,26 +60,24 @@ int sched_hwtimer_init(unsigned int freq)
return 0;
}
inline void sched_atomic_enter(void)
void arch_sched_process_init(struct process *process, void (*entry)(void))
{
REG_SYSTICK_CTRL &= ~REG_SYSTICK_CTRL_ENABLE_BIT;
struct reg_snapshot *regs = process->stack_bottom - sizeof(*regs);
process->sp = regs;
memset(regs, 0, sizeof(*regs));
regs->hw.pc = entry;
regs->hw.psr = 0x01000000U;
regs->sw.lr = (void *)0xFFFFFFF9U;
}
inline void sched_atomic_leave(bool resched)
{
REG_SYSTICK_CTRL |= REG_SYSTICK_CTRL_ENABLE_BIT;
}
void sched_exec_early(void)
void sched_yield(enum proc_state state)
{
REG_SYSTICK_VAL = 0U; /* Reset timer */
sched_pendsv_req();
_current_process->state = state;
arch_irq_invoke(IRQNO_PEND_SV);
}
#ifdef __cplusplus
} /* extern "C" */
#endif /* __cplusplus */
/*
* Copyright (c) 2020 Felix Kopp <sandtler@sandtler.club>
*

View file

@ -1,37 +1,48 @@
/* SPDX-License-Identifier: BSD-3-Clause */
/* See the end of this file for copyright, licensing, and warranty information. */
#include <ardix/serial.h>
#include <ardix/types.h>
#include <ardix/atomic.h>
#include <ardix/io.h>
#include <ardix/ringbuf.h>
#include <ardix/serial.h>
#include <ardix/string.h>
#include <ardix/types.h>
#include <arch/at91sam3x8e/hardware.h>
#include <arch/at91sam3x8e/interrupt.h>
#include <arch/serial.h>
#include <errno.h>
#include <stddef.h>
struct serial_interface arch_serial_default_interface = {
.tx = NULL,
.rx = NULL,
.id = 0,
.baud = 0,
struct arch_serial_interface arch_serial_default_interface = {
.interface = {
.tx = NULL,
.rx = NULL,
.id = 0,
.baud = 0,
},
.hw_txrdy = false,
};
struct serial_interface *serial_default_interface = &arch_serial_default_interface;
struct serial_interface *serial_default_interface = &arch_serial_default_interface.interface;
int arch_serial_init(struct serial_interface *interface)
{
struct arch_serial_interface *arch_iface = to_arch_serial_interface(interface);
if (interface->baud <= 0 || interface->id != 0)
return -1;
memset(&arch_iface->txbuf[0], 0, CONFIG_ARCH_SERIAL_BUFSZ);
/* enable peripheral clock for UART (which has peripheral id 8) */
REG_PMC_PCER0 |= REG_PMC_PCER0_PID(8);
/* ensure the PIO controller is turned off on the serial pins */
REG_PIO_PDR(PIOA) = (1 << 8) | (1 << 9);
/* turn off PDC channel (we are manually writing byte-by-byte here) */
REG_UART_PDC_PTCR = REG_UART_PDC_PTCR_RXTDIS_MASK | REG_UART_PDC_PTCR_TXTDIS_MASK;
/* configure peripheral DMA controller */
REG_UART_PDC_PTCR = REG_UART_PDC_PTCR_RXTDIS_MASK | REG_UART_PDC_PTCR_TXTEN_MASK;
/* reset & disable rx and tx */
REG_UART_CR = REG_UART_CR_RXDIS_MASK | REG_UART_CR_RSTRX_MASK
@ -45,8 +56,10 @@ int arch_serial_init(struct serial_interface *interface)
/* choose the events we want an interrupt on */
REG_UART_IDR = 0xFFFFFFFF; /* make sure all interrupts are disabled first */
/* TXRDY is not selected because the output buffer is initially empty anyway */
REG_UART_IER = REG_UART_IER_RXRDY_MASK | REG_UART_IER_OVRE_MASK | REG_UART_IER_FRAME_MASK | REG_UART_IER_TXRDY_MASK;
REG_UART_IER = REG_UART_IER_RXRDY_MASK
| REG_UART_IER_TXBUFE_MASK
| REG_UART_IER_OVRE_MASK
| REG_UART_IER_FRAME_MASK;
arch_irq_enable(IRQNO_UART);
@ -72,38 +85,46 @@ void arch_serial_exit(struct serial_interface *interface)
interface->id = -1;
}
void arch_serial_notify(struct serial_interface *interface)
void io_serial_buf_update(struct serial_interface *interface)
{
/* if the TXRDY event is masked ... */
if ((REG_UART_IMR & REG_UART_IMR_TXRDY_MASK) == 0) {
/* ... unmask it */
REG_UART_IER = REG_UART_IER_TXRDY_MASK;
uint16_t len;
struct arch_serial_interface *arch_iface = to_arch_serial_interface(interface);
if (arch_iface->hw_txrdy) {
atomic_enter();
len = (uint16_t)ringbuf_read(&arch_iface->txbuf[0], interface->tx,
CONFIG_ARCH_SERIAL_BUFSZ);
atomic_leave();
if (len) {
arch_iface->hw_txrdy = false;
REG_UART_IER = REG_UART_IER_TXBUFE_MASK;
REG_UART_PDC_TPR = (uint32_t)&arch_iface->txbuf[0];
REG_UART_PDC_TCR = len;
}
}
}
void irq_uart(void)
{
uint8_t tmp;
size_t len;
uint32_t state = REG_UART_SR;
/* RX has received a byte, store it into the ring buffer */
if (state & REG_UART_SR_RXRDY_MASK) {
tmp = REG_UART_RHR;
ringbuf_write(serial_default_interface->rx, &tmp, sizeof(tmp));
ringbuf_write(arch_serial_default_interface.interface.rx, &tmp, sizeof(tmp));
}
/* TX is ready to transmit the next byte */
if (state & REG_UART_SR_TXRDY_MASK) {
len = ringbuf_read(&tmp, serial_default_interface->tx, sizeof(tmp));
if (len) {
/* there is data in the queue, so write it to TX holding register */
REG_UART_THR = tmp;
} else {
/* TX queue is empty, mask the TXRDY event */
REG_UART_IDR = REG_UART_IDR_TXRDY_MASK;
}
/* TX buffer has been sent */
if (state & REG_UART_SR_TXBUFE_MASK) {
/*
* this is picked up by the I/O thread, which will copy the next
* chunk of data from the ring buffer to the hardware buffer and
* resume transmission
*/
arch_serial_default_interface.hw_txrdy = true;
REG_UART_IDR = REG_UART_IDR_TXBUFE_MASK;
}
/* check for error conditions */

View file

@ -0,0 +1,81 @@
/* SPDX-License-Identifier: BSD-3-Clause */
/* See the end of this file for copyright, licensing, and warranty information. */
#include <arch/at91sam3x8e/spinlock.h>
/* This code is basically stolen from arch/arm/include/asm/spinlock.h in Linux 5.9 */
void arch_spinlock_init(spinlock_t *lock)
{
lock->lock = 0;
}
int arch_spin_lock(spinlock_t *lock)
{
int tmp;
int newval;
spinlock_t lockval;
__asm__ volatile(
"1: ldrex %0, [%3] \n" /* lockval = *lock */
" add %1, %0, #1 \n" /* newval = lockval.lock + 1 */
" strex %2, %1, [%3] \n" /* *lock = newval */
" teq %2, #0 \n" /* store successful? */
" bne 1b \n" /* -> goto 1 if not */
" dmb " /* memory barrier */
: "=&r" (lockval), "=&r" (newval), "=&r" (tmp)
: "r" (lock)
: "cc");
return newval;
}
int arch_spin_unlock(spinlock_t *lock)
{
int tmp;
int newval;
spinlock_t lockval;
__asm__ volatile(
"1: ldrex %0, [%3] \n"
" sub %1, %0, #1 \n"
" strex %2, %1, [%3] \n"
" teq %2, #0 \n"
" bne 1b \n"
" dmb "
: "=&r" (lockval), "=&r" (newval), "=&r" (tmp)
: "r" (lock)
: "cc");
return newval;
}
int arch_spinlock_count(spinlock_t *lock)
{
return lock->lock;
}
/*
* Copyright (c) 2020 Felix Kopp <sandtler@sandtler.club>
*
* 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 the copyright holder 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.
*/

View file

@ -23,9 +23,13 @@ extern uint32_t _eheap; /* heap end */
/* implementation in init/main.c */
void do_bootstrap(void);
/* implementation in sys.c */
void sys_init();
void irq_reset(void)
__naked void irq_reset(void)
{
sys_init();
memmove(
&_srelocate,
&_etext,

View file

@ -0,0 +1,35 @@
/* SPDX-License-Identifier: BSD-3-Clause */
/* See the end of this file for copyright, licensing, and warranty information. */
#pragma once
#ifdef ARCH_AT91SAM3X8E
#define ARCH_INCLUDE(file) <arch/at91sam3x8e/file>
#else
#error "Unsupported architecture"
#endif
/*
* Copyright (c) 2020 Felix Kopp <sandtler@sandtler.club>
*
* 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 the copyright holder 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.
*/

View file

@ -347,11 +347,11 @@ struct reg_snapshot {
/** UART PDC Receive Pointer Register */
#define REG_UART_PDC_RPR (*(uint32_t *)0x400E0900U)
/** UART PDC Receive Counter Register */
#define REG_UART_PDC_RCR (*(uint32_t *)0x400E0904U)
#define REG_UART_PDC_RCR (*(uint16_t *)0x400E0904U)
/** UART PDC Transmit Pointer Register */
#define REG_UART_PDC_TPR (*(uint32_t *)0x400E0908U)
/** UART PDC Transmit Counter Register */
#define REG_UART_PDC_TCR (*(uint32_t *)0x400E090CU)
#define REG_UART_PDC_TCR (*(uint16_t *)0x400E090CU)
/** UART PDC Receive Next Pointer Register */
#define REG_UART_PDC_RNPR (*(uint32_t *)0x400E0910U)
/** UART PDC Receive Next Counter Register */

View file

@ -20,7 +20,7 @@ void irq_svc(void);
/** Debug handler (reserved) */
void irq_debug_mon(void);
/** Pending SV interrupt handler */
extern void irq_pend_sv(void);
void irq_pend_sv(void);
/** SysTick interrupt handler */
void irq_sys_tick(void);
@ -167,6 +167,8 @@ void arch_irq_enable(enum irqno irqno);
void arch_irq_disable(enum irqno irqno);
void arch_irq_invoke(enum irqno irqno);
/*
* Copyright (c) 2020 Felix Kopp <sandtler@sandtler.club>
*

View file

@ -4,6 +4,38 @@
#pragma once
#include <ardix/serial.h>
#include <ardix/types.h>
#include <ardix/util.h>
#include <stdbool.h>
#ifndef CONFIG_ARCH_SERIAL_BUFSZ
#define CONFIG_ARCH_SERIAL_BUFSZ 32
#endif /* CONFIG_ARCH_SERIAL_BUFSZ */
/** Architecture-specific extension of `struct serial_interface` */
struct arch_serial_interface {
struct serial_interface interface;
/*
* two hardware buffers; one is for being written to while the other one can be read from
* by the hardware w/out interfering with each other. `arch_serial_hwbuf_rotate()` is
* responsible for writing this to the respective hardware register and swapping them out.
* The platform's buffer length registers only allow 16-byte numbers, so we can save some
* memory by not using `size_t`
*/
uint8_t txbuf[CONFIG_ARCH_SERIAL_BUFSZ];
/** hardware has finished sending the current buffer and ready for a swap */
bool hw_txrdy;
};
/**
* Cast a `struct serial_interface` out to a `struct arch_serial_interface`.
*
* @param ptr: The `struct serial_interface *` to cast out from.
* @returns The containing `struct arch_serial_interface *`.
*/
#define to_arch_serial_interface(ptr) container_of(ptr, struct arch_serial_interface, interface)
/*
* Copyright (c) 2020 Felix Kopp <sandtler@sandtler.club>

View file

@ -0,0 +1,67 @@
/* SPDX-License-Identifier: BSD-3-Clause */
/* See the end of this file for copyright, licensing, and warranty information. */
#pragma once
#include <arch/at91sam3x8e/spinlock_type.h>
#include <toolchain.h>
/* This code is basically stolen from arch/arm/include/asm/spinlock.h in Linux 5.9 */
#define SPINLOCK_DEFINE(name) spinlock_t name = { .lock = 0 }
/**
* Initialize a spinlock.
*
* @param lock: Pointer to the spinlock.
*/
void arch_spinlock_init(spinlock_t *lock);
/**
* Increment the lock count on a spinlock.
*
* @param lock: Pointer to the spinlock.
* @returns The new lock count.
*/
int arch_spin_lock(spinlock_t *lock);
/**
* Decrement the lock count on a spinlock.
*
* @param lock: Pointer to the spinlock.
* @returns The new lock count.
*/
int arch_spin_unlock(spinlock_t *lock);
/**
* Get the lock count on a spinlock.
*
* @param lock: Pointer to the spinlock.
*/
int arch_spinlock_count(spinlock_t *lock);
/*
* Copyright (c) 2020 Felix Kopp <sandtler@sandtler.club>
*
* 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 the copyright holder 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.
*/

View file

@ -0,0 +1,33 @@
/* SPDX-License-Identifier: BSD-3-Clause */
/* See the end of this file for copyright, licensing, and warranty information. */
#pragma once
typedef struct spinlock {
int lock;
} spinlock_t;
/*
* Copyright (c) 2020 Felix Kopp <sandtler@sandtler.club>
*
* 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 the copyright holder 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.
*/

View file

@ -3,6 +3,8 @@
#pragma once
#include <arch/arch_include.h>
/**
* Block the CPU by continuously checking the same expression in an
* infinite loop, until the condition is true. Useful for polling.
@ -38,13 +40,7 @@ int sys_init(void);
#define STACK_SIZE 2048U
#endif
#if defined(ARCH_ATMEGA328P)
#error "ATmega328p is not implemented (yet?)"
#elif defined(ARCH_AT91SAM3X8E)
#include <arch/at91sam3x8e/hardware.h>
#else
#error "Unsupported architecture"
#endif
#include ARCH_INCLUDE(hardware.h)
/*
* Copyright (c) 2020 Felix Kopp <sandtler@sandtler.club>

View file

@ -4,43 +4,28 @@
#pragma once
#include <arch/hardware.h>
#include <stdbool.h>
#include <toolchain.h>
struct process; /* see include/ardix/sched.h */
/**
* Initialize a hardware timer for schduling.
*
* @param freq: The timer frequency in Hertz.
*/
int sched_hwtimer_init(unsigned int freq);
int arch_sched_hwtimer_init(unsigned int freq);
/**
* Disable all scheduling interrupts in order to enter atomic context.
*/
void sched_atomic_enter(void);
/**
* Re-enable scheduling interrupts, i.e. leave atomic context.
* Initialize a new process.
* This requires the process' `stack_base` field to be initialized as the
* initial register values are written to the stack.
*
* @param resched: If `true`, request the scheduler to proceed to the next
* process ASAP. Until then, put the CPU to sleep if required.
*/
void sched_atomic_leave(bool resched);
/**
* Infinite loop of sleep instructions.
*/
void sched_idle_process_loop(void);
/**
* Initialize the register values of a newly allocated process image.
* Called by the scheduling subsystem when a process is being created.
*
* @param reg_snap: The stack memory location where the initial register values
* are to be loaded from.
* @param process: The process.
* @param entry: The process entry point.
*/
void sched_init_process_regs(struct reg_snapshot *reg_snap,
void (*entry)(void));
void arch_sched_process_init(struct process *process, void (*entry)(void));
/*
* Copyright (c) 2020 Felix Kopp <sandtler@sandtler.club>

View file

@ -3,25 +3,14 @@
#pragma once
#include <arch/arch_include.h>
#include <ardix/serial.h>
int arch_serial_init(struct serial_interface *interface);
void arch_serial_exit(struct serial_interface *interface);
/**
* Notify the serial interface about new data in the TX buffer.
* This is required because if the transmitter is sleeping due to the TX queue being empty,
* we need some way to tell it to turn on and fire interrupts again.
*
* @param interface: The serial interface to notify about new data.
*/
void arch_serial_notify(struct serial_interface *interface);
#ifdef ARCH_AT91SAM3X8E
#include <arch/at91sam3x8e/serial.h>
#else
#error "Unsupported architecture"
#endif
#include ARCH_INCLUDE(serial.h)
/*
* Copyright (c) 2020 Felix Kopp <sandtler@sandtler.club>

33
include/arch/spinlock.h Normal file
View file

@ -0,0 +1,33 @@
/* SPDX-License-Identifier: BSD-3-Clause */
/* See the end of this file for copyright, licensing, and warranty information. */
#pragma once
#include <arch/arch_include.h>
#include ARCH_INCLUDE(spinlock.h)
/*
* Copyright (c) 2020 Felix Kopp <sandtler@sandtler.club>
*
* 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 the copyright holder 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.
*/

View file

@ -0,0 +1,32 @@
/* SPDX-License-Identifier: BSD-3-Clause */
/* See the end of this file for copyright, licensing, and warranty information. */
#pragma once
#include <arch/arch_include.h>
#include ARCH_INCLUDE(spinlock_type.h)
/*
* Copyright (c) 2020 Felix Kopp <sandtler@sandtler.club>
*
* 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 the copyright holder 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.
*/

38
include/ardix/atomic.h Normal file
View file

@ -0,0 +1,38 @@
/* SPDX-License-Identifier: BSD-3-Clause */
/* See the end of this file for copyright, licensing, and warranty information. */
#pragma once
/** Enter atomic context. */
void atomic_enter(void);
/** Leave atomic context. */
void atomic_leave(void);
/** Return a nonzero value if the current process is in atomic context. */
int is_atomic_context(void);
/*
* Copyright (c) 2020 Felix Kopp <sandtler@sandtler.club>
*
* 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 the copyright holder 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.
*/

47
include/ardix/io.h Normal file
View file

@ -0,0 +1,47 @@
/* SPDX-License-Identifier: BSD-3-Clause */
/* See the end of this file for copyright, licensing, and warranty information. */
#pragma once
#include <ardix/serial.h>
/**
* Initialize the I/O thread and subsystems.
* Must be called after all I/O components have been initialized.
*
* @returns 0 on success, or a negative number on failure.
*/
int io_init(void);
/**
* Update the hardware serial buffers if necessary.
* This includes copying to and from the main ring buffers.
*
* @param interface: The serial interface.
*/
void io_serial_buf_update(struct serial_interface *interface);
/*
* Copyright (c) 2020 Felix Kopp <sandtler@sandtler.club>
*
* 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 the copyright holder 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.
*/

View file

@ -3,12 +3,16 @@
#pragma once
#include <ardix/list.h>
#include <ardix/spinlock.h>
#include <ardix/types.h>
#include <arch/hardware.h>
#include <stdbool.h>
#ifndef CONFIG_SCHED_MAXPROC
/** The maximum number of processes. */
#define CONFIG_SCHED_MAXPROC 16
#define CONFIG_SCHED_MAXPROC 8
#endif /* SCHED_MAXPROC */
#if CONFIG_SCHED_MAXPROC > 64
@ -20,6 +24,11 @@
#define CONFIG_SCHED_INTR_FREQ 10000U
#endif
#ifndef CONFIG_STACKSZ
/** Per-process stack size in bytes */
#define CONFIG_STACKSZ 4096U
#endif /* CONFIG_STACKSZ */
enum proc_state {
/** Process is dead / doesn't exist */
PROC_DEAD,
@ -29,12 +38,12 @@ enum proc_state {
PROC_QUEUE,
/** Process is sleeping, `sleep_until` specifies when to wake it up. */
PROC_SLEEP,
/** Process is waiting for I/O to flush buffers. */
PROC_IOWAIT,
};
/** Stores an entire process image. */
struct process {
/** Next process in the (circular) list. */
struct process *next;
/** Stack pointer. */
void *sp;
/** Bottom of the stack (i.e. the highest address). */
@ -79,44 +88,21 @@ void *sched_process_switch(void *curr_sp);
/**
* Create a new process.
*
* @param exec: The process executor.
* @param entry: The process entry point.
* @returns A pointer to the new process, or `NULL` if something went wrong.
*
* TODO: make something like errno to tell what *exactly* went wrong
*/
struct process *sched_process_create(void (*exec)(void));
struct process *sched_process_create(void (*entry)(void));
/**
* Suspend the current process for the specified amount of milliseconds.
* Note that there are slight deviations from this time interval because of the
* round-robin scheduling algorithm.
* If the sleep time is required to be exactly accurate, use `atomic_udelay()`.
* Note, however, that this will block *all* other processes, even including
* I/O, for the entire time period.
* Request the scheduler be invoked early, resulting in the current process to
* be suspended.
*
* @param msecs: The amount of milliseconds to (approximately) sleep for.
* @param state The state the process should enter.
* Allowed values are `PROC_SLEEP` and `PROC_IOWAIT`.
*/
void msleep(unsigned long int msecs);
/**
* Block the entire CPU from execution for the specified amount of microseconds.
* Note that this will temporarily disable the scheduler, meaning that *nothing*
* (not even I/O) will be executed. The only reason you would ever want to use
* this is for mission-critical, very short (<= 100 us) periods of time.
*
* @param usecs: The amount of microseconds to halt the CPU for.
*/
void atomic_udelay(unsigned long int usecs);
/**
* Attempt to acquire an atomic lock.
*
* @param mutex: The pointer to the mutex.
* @returns `0` if the lock could be acquired, and `-EAGAIN` if not.
*/
int atomic_lock(atomic_t *mutex);
void atomic_unlock(atomic_t *mutex);
void sched_yield(enum proc_state state);
/*
* Copyright (c) 2020 Felix Kopp <sandtler@sandtler.club>

View file

@ -7,9 +7,14 @@
#include <ardix/ringbuf.h>
#include <toolchain.h>
#ifndef CONFIG_SERIAL_BAUD
/** serial baud rate */
#define CONFIG_SERIAL_BAUD 115200
#endif
#ifndef SERIAL_BUFSZ
/** size of a serial I/O buffer in bytes */
#define SERIAL_BUFSZ 64
#define SERIAL_BUFSZ 256
#endif
struct serial_interface {

83
include/ardix/spinlock.h Normal file
View file

@ -0,0 +1,83 @@
/* SPDX-License-Identifier: BSD-3-Clause */
/* See the end of this file for copyright, licensing, and warranty information. */
#pragma once
/*
* Spinlocks in Ardix work pretty much the same as they do on Linux
* (this is basically just a ripoff). See The Linux Kernel documentation
* for details.
*/
#include <arch/spinlock.h>
#include <toolchain.h>
/**
* Initialize a spinlock.
*
* @param lock: Pointer to the spinlock.
*/
__always_inline void spinlock_init(spinlock_t *lock)
{
arch_spinlock_init(lock);
}
/**
* Increment the lock count on a spinlock.
* If required, block until we have exclusive access to the memory.
*
* @param lock: Pointer to the spinlock.
* @returns The new lock count.
*/
__always_inline int spin_lock(spinlock_t *lock)
{
return arch_spin_lock(lock);
}
/**
* Decrement the lock count on a spinlock.
* If required, block until we have exclusive access to the memory.
*
* @param lock: Pointer to the spinlock.
* @returns The new lock count.
*/
__always_inline int spin_unlock(spinlock_t *lock)
{
return arch_spin_unlock(lock);
}
/**
* Get the lock count of a spinlock.
*
* @param lock: Pointer to the spinlock.
* @returns The current lock count.
*/
__always_inline int spinlock_count(spinlock_t *lock)
{
return arch_spinlock_count(lock);
}
/*
* Copyright (c) 2020 Felix Kopp <sandtler@sandtler.club>
*
* 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 the copyright holder 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.
*/

View file

@ -2,7 +2,13 @@
/* See the end of this file for copyright, licensing, and warranty information. */
#include <arch/hardware.h>
#include <ardix/spinlock.h>
#include <ardix/io.h>
#include <ardix/printk.h>
#include <ardix/sched.h>
#include <ardix/serial.h>
#include <stdint.h>
#include <stddef.h>
@ -21,30 +27,28 @@
*/
void do_bootstrap(void)
{
bool on = true;
uint32_t state = (1 << 27);
uint32_t count = 0;
unsigned int print_count = 0;
sys_init();
REG_PIOB_OER = 1 << 27;
REG_PIOB_PER = 1 << 27;
REG_PIOB_CODR = 1 << 27;
sched_init();
io_init();
REG_PIOB_OER |= state;
REG_PIOB_PER |= state;
/* we'll only let the LED flash for now */
printk("hello, world\n");
while (true) {
if (count++ != 100000)
if (count++ != 1000000)
continue;
if (on) {
REG_PIOB_SODR |= state;
on = false;
} else {
REG_PIOB_CODR |= state;
on = true;
}
print_count++;
if (print_count % 2)
REG_PIOB_CODR = 1 << 27;
else
REG_PIOB_SODR = 1 << 27;
printk("endless loop iteration #%u\n", print_count);
count = 0;
}

View file

@ -25,6 +25,8 @@
ARDIX_KERNEL_PWD = $(PWD)/kernel
include $(ARDIX_KERNEL_PWD)/io/Makefile
ARDIX_SOURCES += \
$(ARDIX_KERNEL_PWD)/printk.c \
$(ARDIX_KERNEL_PWD)/ringbuf.c \

29
kernel/io/Makefile Normal file
View file

@ -0,0 +1,29 @@
#
# Copyright (c) 2020 Felix Kopp <sandtler@sandtler.club>
#
# 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 the copyright holder 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.
#
ARDIX_KERNEL_IO_PWD = $(ARDIX_KERNEL_PWD)/io
ARDIX_SOURCES += \
$(ARDIX_KERNEL_IO_PWD)/io.c

60
kernel/io/io.c Normal file
View file

@ -0,0 +1,60 @@
/* SPDX-License-Identifier: BSD-3-Clause */
/* See the end of this file for copyright, licensing, and warranty information. */
#include <arch/serial.h>
#include <ardix/io.h>
#include <ardix/sched.h>
#include <ardix/serial.h>
#include <toolchain.h>
static __naked void io_thread_entry(void)
{
while (1) {
io_serial_buf_update(serial_default_interface);
sched_yield(PROC_QUEUE);
}
}
int io_init(void)
{
int ret;
struct process *proc;
ret = serial_init(serial_default_interface, CONFIG_SERIAL_BAUD);
if (ret)
return ret;
proc = sched_process_create(&io_thread_entry);
if (proc == NULL)
ret = -1;
return ret;
}
/*
* Copyright (c) 2020 Felix Kopp <sandtler@sandtler.club>
*
* 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 the copyright holder 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.
*/

View file

@ -31,7 +31,7 @@ size_t ringbuf_read(void *dest, struct ringbuf *buf, size_t len)
{
uint8_t *tmp = dest;
while (len-- > 0 && buf->len > 0) {
while (len-- && buf->len) {
*tmp++ = buf->data[buf->rpos++];
buf->len--;
@ -46,7 +46,7 @@ size_t ringbuf_write(struct ringbuf *buf, const void *src, size_t len)
{
const uint8_t *tmp = src;
while (len-- > 0 && buf->len < buf->capacity) {
while (len-- && buf->len != buf->capacity) {
buf->data[buf->wpos++] = *tmp++;
buf->len++;

View file

@ -1,71 +1,41 @@
/* SPDX-License-Identifier: BSD-3-Clause */
/* See the end of this file for copyright, licensing, and warranty information. */
#include <arch/hardware.h>
#include <arch/sched.h>
#include <ardix/atomic.h>
#include <ardix/malloc.h>
#include <ardix/sched.h>
#include <ardix/string.h>
#include <ardix/types.h>
#include <errno.h>
#include <stddef.h>
extern uint32_t _sstack;
extern uint32_t _estack;
struct process *proc_table[CONFIG_SCHED_MAXPROC];
struct process *_current_process;
/**
* An array of all processes.
* The `pid` not only identifies each process, it is also the index of the
* struct in this array. Unused slots have a `pid` of `-1`, however.
*/
static struct process procs[CONFIG_SCHED_MAXPROC + 1];
/**
* Find an unused process slot in the `procs` array, insert that process into
* the scheduler's ring queue and return it. Must run in atomic context.
*
* @returns A pointer to the new process slot, or `NULL` if none are available.
*/
static struct process *sched_find_free_slot_and_link(void)
{
pid_t i;
struct process *newproc = NULL;
for (i = 1; i < CONFIG_SCHED_MAXPROC + 1; i++) {
if (procs[i].pid == -1 && procs[i].state == PROC_DEAD) {
newproc = &procs[i];
newproc->next = procs[i - 1].next;
procs[i - 1].next = newproc;
newproc->pid = i;
break;
}
}
return newproc;
}
int sched_init(void)
{
int i;
_current_process = &procs[0];
_current_process->next = _current_process;
_current_process = malloc(sizeof(*_current_process));
if (_current_process == NULL)
return -ENOMEM;
_current_process->sp = &_sstack;
_current_process->stack_bottom = &_estack;
_current_process->pid = 0;
_current_process->state = PROC_READY;
proc_table[0] = _current_process;
for (i = 1; i < CONFIG_SCHED_MAXPROC + 1; i++) {
procs[i].next = NULL;
procs[i].sp = NULL;
procs[i].stack_bottom = NULL;
procs[i].pid = -1;
procs[i].state = PROC_DEAD;
}
for (i = 1; i < CONFIG_SCHED_MAXPROC; i++)
proc_table[i] = NULL;
i = sched_hwtimer_init(CONFIG_SCHED_INTR_FREQ);
return i;
return arch_sched_hwtimer_init(CONFIG_SCHED_INTR_FREQ);
}
/**
@ -78,7 +48,7 @@ static inline bool sched_proc_should_run(const struct process *proc)
{
enum proc_state state = proc->state;
if (state == PROC_QUEUE || state == PROC_READY)
if (state == PROC_QUEUE || state == PROC_READY || state == PROC_IOWAIT)
return true;
return false;
@ -86,26 +56,62 @@ static inline bool sched_proc_should_run(const struct process *proc)
void *sched_process_switch(void *curr_sp)
{
struct process *nextproc = _current_process;
pid_t nextpid = _current_process->pid;
_current_process->sp = curr_sp;
if (_current_process->state != PROC_SLEEP)
if (_current_process->state != PROC_SLEEP && _current_process->state != PROC_IOWAIT)
_current_process->state = PROC_QUEUE;
while (true) {
nextproc = nextproc->next;
if (sched_proc_should_run(nextproc)) {
nextproc->state = PROC_READY;
_current_process = nextproc;
while (1) {
nextpid++;
nextpid %= CONFIG_SCHED_MAXPROC;
if (proc_table[nextpid] != NULL && sched_proc_should_run(proc_table[nextpid])) {
_current_process = proc_table[nextpid];
break;
}
/* TODO: Let the CPU sleep if there is nothing to do */
/* TODO: Add idle thread */
}
_current_process->state = PROC_READY;
return _current_process->sp;
}
struct process *sched_process_create(void (*entry)(void))
{
pid_t pid;
struct process *proc = malloc(sizeof(*proc));
if (proc == NULL)
return NULL;
atomic_enter();
for (pid = 1; pid < CONFIG_SCHED_MAXPROC; pid++) {
if (proc_table[pid] == NULL)
break;
}
if (pid == CONFIG_SCHED_MAXPROC) {
/* max number of processess exceeded */
free(proc);
atomic_leave();
return NULL;
}
proc->pid = pid;
proc->stack_bottom = &_estack - (pid * (signed)CONFIG_STACKSZ);
proc->lastexec = 0;
proc->sleep_usecs = 0;
proc->state = PROC_QUEUE;
arch_sched_process_init(proc, entry);
proc_table[pid] = proc;
atomic_leave();
return proc;
}
/*
* Copyright (c) 2020 Felix Kopp <sandtler@sandtler.club>
*

View file

@ -1,7 +1,9 @@
/* SPDX-License-Identifier: BSD-3-Clause */
/* See the end of this file for copyright, licensing, and warranty information. */
#include <ardix/atomic.h>
#include <ardix/ringbuf.h>
#include <ardix/sched.h>
#include <ardix/serial.h>
#include <arch/serial.h>
@ -46,15 +48,36 @@ void serial_exit(struct serial_interface *interface)
ssize_t serial_read(void *dest, struct serial_interface *interface, size_t len)
{
return (ssize_t)ringbuf_read(dest, interface->rx, len);
ssize_t ret;
atomic_enter();
ret = (ssize_t)ringbuf_read(dest, interface->rx, len);
atomic_leave();
return ret;
}
ssize_t serial_write(struct serial_interface *interface, const void *data, size_t len)
{
ssize_t ret = (ssize_t)ringbuf_write(interface->tx, data, len);
if (ret > 0)
arch_serial_notify(interface);
return ret;
size_t ret = 0;
size_t tmp;
while (1) {
atomic_enter();
tmp = ringbuf_write(interface->tx, data, len);
atomic_leave();
ret += tmp;
if (ret != len) { /* buffer full, suspend until I/O is ready */
len -= tmp;
data += tmp;
sched_yield(PROC_IOWAIT);
} else {
break;
}
}
return (ssize_t)ret;
}
/*