This commit is contained in:
lr 2024-05-29 15:37:20 +08:00
commit a9309fa1b4
139 changed files with 4951 additions and 486 deletions

View File

@ -4,7 +4,7 @@ MAKEFLAGS += --no-print-directory
.PHONY:COMPILE_APP COMPILE_KERNEL
riscv_support :=
arm_support += imx6q-sabrelite zynq7000-zc702
arm_support += imx6q-sabrelite zynq7000-zc702 ok1028a-c
emulator_support +=
support := $(riscv_support) $(arm_support) $(emulator_support)
SRC_DIR :=
@ -34,6 +34,9 @@ export UBIQUITOUS_ROOT ?= ..
ifneq ($(findstring $(BOARD), imx6q-sabrelite zynq7000-zc702), )
include $(KERNEL_ROOT)/hardkernel/arch/arm/armv7-a/cortex-a9/preboot_for_$(BOARD)/config.mk
endif
ifneq ($(findstring $(BOARD), ok1028a-c), )
include $(KERNEL_ROOT)/hardkernel/arch/arm/armv8-a/cortex-a72/preboot_for_$(BOARD)/config.mk
endif
export BSP_BUILD_DIR := $(KERNEL_ROOT)
export HOSTTOOLS_DIR ?= $(KERNEL_ROOT)/services/tools/hosttools
export CONFIG2H_EXE ?= $(HOSTTOOLS_DIR)/xsconfig.sh
@ -126,6 +129,7 @@ clean:
@rm -rf build
@rm -rf temp.txt
@rm -rf services/app/bin
@rm -f services/app/*.o
@rm -rf services/tools/mkfs/mkfs
@rm -rf services/app/fs.img
@rm -rf services/app/user.map

View File

@ -1,4 +1,10 @@
# The following three platforms support compatiable instructions.
ifneq ($(findstring $(BOARD), ok1028a-c), )
SRC_DIR := armv8-a
endif
ifneq ($(findstring $(BOARD), imx6q-sabrelite zynq7000-zc702), )
SRC_DIR := armv7-a
endif
include $(KERNEL_ROOT)/compiler.mk

View File

@ -32,8 +32,8 @@ Modification:
.global _boot_start
.global CpuInitCrit
.global primary_cpu_init
.global primary_cpu_init
_boot_start:
@ save r0 for cores 1-3, r0 arg field passed by ROM
@ r0 is a function pointer for secondary cpus

View File

@ -0,0 +1,7 @@
# The following three platforms support compatiable instructions.
ifneq ($(findstring $(BOARD), ok1028a-c), )
SRC_DIR := cortex-a72
endif
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,4 @@
SRC_DIR := preboot_for_$(BOARD)
SRC_FILES := context_switch.S core.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,56 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
/**
* @file context_switch.S
* @brief task context switch functions
* @version 1.0
* @author AIIT XUOS Lab
* @date 2024.4.10
*/
/*************************************************
File name: context_switch.S
Description: task context switch functions
Others:
History:
*************************************************/
.global context_switch
context_switch:
mov x9, sp
mov x10, sp
sub x9, x9, #16 * 7
stp x10/*sp*/, x18, [x9, #16 * 0]
stp x19, x20, [x9, #16 * 1]
stp x21, x22, [x9, #16 * 2]
stp x23, x24, [x9, #16 * 3]
stp x25, x26, [x9, #16 * 4]
stp x27, x28, [x9, #16 * 5]
stp x29, x30, [x9, #16 * 6]
str x9, [x0]
mov x9, x1
ldp x10/*sp*/, x18, [x9, #16 * 0]
ldp x19, x20, [x9, #16 * 1]
ldp x21, x22, [x9, #16 * 2]
ldp x23, x24, [x9, #16 * 3]
ldp x25, x26, [x9, #16 * 4]
ldp x27, x28, [x9, #16 * 5]
ldp x29, x30, [x9, #16 * 6]
add x9, x9, #16 * 7
mov sp, x9
ret

View File

@ -0,0 +1,74 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
/**
* @file core.c
* @brief spl boot function
* @version 1.0
* @author AIIT XUOS Lab
* @date 2024.04.23
*/
/*************************************************
File name: core.c
Description: cortex-a9 core function, include cpu registers operationscore boot
Others:
History:
1. Date: 2024-04-23
Author: AIIT XUOS Lab
Modification:
1. first version
*************************************************/
/*********cortex-a72 general register************
EL0 | EL1 | EL2 | EL3
x0;
x1;
x2;
x3;
x4;
x5;
x6;
x7;
x8;
x9;
x10;
x11;
x12;
x13;
x14;
x15;
x16;
x17;
x18;
x19;
x20;
x21;
x22;
x23;
x24;
x25;
x26;
x27;
x28;
x29;
x30;
*********cortex-a72 special register************
XZR
PC
SP_EL0 SP_EL1 SP_EL2 SP_EL3
SPSR_EL1 SPSR_EL2 SPSR_EL3
ELR_EL1 ELR_EL2 ELR_EL3
************************************************/
#include "core.h"

View File

@ -0,0 +1,227 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
/**
* @file core.h
* @brief cortex-a72 core function
* @version 1.0
* @author AIIT XUOS Lab
* @date 2024.04.11
*/
/*************************************************
File name: core.h
Description: cortex-a72 core function
Others:
History:
Author: AIIT XUOS Lab
Modification:
*************************************************/
#pragma once
// Interrupt control bits
#define NO_INT 0x80 // disable IRQ.
#define DIS_INT 0xc0 // disable both IRQ and FIQ.
#define MODE_STACK_SIZE 0x1000
//! @name SPSR fields
//@{
#define SPSR_EL1_N (1 << 31) //!< Negative
#define SPSR_EL1_Z (1 << 30) //!< Zero
#define SPSR_EL1_C (1 << 29) //!< Carry
#define SPSR_EL1_V (1 << 28) //!< Overflow
#define SPSR_EL1_SS (1 << 21) //!< Software Step
#define SPSR_EL1_IL (1 << 20) //!< Illegal Exception
#define SPSR_EL1_D (1 << 9) //!< Debug mask
#define SPSR_EL1_A (1 << 8) //!< SError mask
#define SPSR_EL1_I (1 << 7) //!< IRQ mask
#define SPSR_EL1_F (1 << 6) //!< FIQ mask
#define SPSR_EL1_M (1 << 4) //!< Execution state 0=64-bit 1=32-bit
#define SPSR_EL1_MODE (0x7) //!< Current processor mode
//@}
//! @name Interrupt enable bits in SPSR
//@{
#define I_BIT 0x80 //!< When I bit is set, IRQ is disabled
#define F_BIT 0x40 //!< When F bit is set, FIQ is disabled
//@}
// ARM Modes t indicates selecting sp_el0 pointer, h indicates selecting sp_eln pointer
#define SPSR_MODE_MASK 0x0f
#define ARM_MODE_EL0_t 0x00
#define ARM_MODE_EL1_t 0x04
#define ARM_MODE_EL1_h 0x05
#define ARM_MODE_EL2_t 0x08
#define ARM_MODE_EL2_h 0x09
#define ARM_MODE_EL3_t 0x0c
#define ARM_MODE_EL3_h 0x0d
#ifndef __ASSEMBLER__
#include <stdint.h>
#include <string.h>
#include "cortex_a72.h"
#define NR_CPU 4 // maximum number of CPUs
__attribute__((always_inline)) static inline uint64_t EL0_mode() // Set ARM mode to EL0
{
uint64_t val = 0;
__asm__ __volatile__(
"mrs %0, spsr_el1"
: "=r"(val)
:
:);
val &= ~DIS_INT;
val &= ~SPSR_MODE_MASK;
val |= ARM_MODE_EL0_t;
return val;
}
__attribute__((always_inline, optimize("O0"))) static inline void cpu_into_low_power()
{
WFE();
}
__attribute__((always_inline, optimize("O0"))) static inline void cpu_leave_low_power()
{
SEV();
}
struct context {
uint64_t sp;
/* callee register */
uint64_t x18;
uint64_t x19;
uint64_t x20;
uint64_t x21;
uint64_t x22;
uint64_t x23;
uint64_t x24;
uint64_t x25;
uint64_t x26;
uint64_t x27;
uint64_t x28;
uint64_t x29;
uint64_t x30;
};
/// @brief init task context, set return address to trap return
/// @param ctx
extern void task_prepare_enter(void);
__attribute__((__always_inline__)) static inline void arch_init_context(struct context* ctx)
{
memset(ctx, 0, sizeof(*ctx));
ctx->x30 = (uintptr_t)(task_prepare_enter + 4);
}
struct trapframe {
uint64_t x0;
uint64_t x1;
uint64_t x2;
uint64_t x3;
uint64_t x4;
uint64_t x5;
uint64_t x6;
uint64_t x7;
uint64_t x8;
uint64_t x9;
uint64_t x10;
uint64_t x11;
uint64_t x12;
uint64_t x13;
uint64_t x14;
uint64_t x15;
uint64_t x16;
uint64_t x17;
uint64_t x18;
uint64_t x19;
uint64_t x20;
uint64_t x21;
uint64_t x22;
uint64_t x23;
uint64_t x24;
uint64_t x25;
uint64_t x26;
uint64_t x27;
uint64_t x28;
uint64_t x29;
uint64_t x30;
uint64_t pc;
uint64_t spsr;
uint64_t sp;
};
/// @brief init task trapframe
/// @param tf
/// @param sp
/// @param pc
__attribute__((__always_inline__)) static inline void arch_init_trapframe(struct trapframe* tf, uintptr_t sp, uintptr_t pc)
{
memset(tf, 0, sizeof(*tf));
tf->sp = sp;
tf->spsr = EL0_mode();
tf->pc = pc;
}
/// @brief set pc and sp to trapframe
/// @param tf
/// @param sp
/// @param pc
__attribute__((__always_inline__)) static inline void arch_trapframe_set_sp_pc(struct trapframe* tf, uintptr_t sp, uintptr_t pc)
{
tf->sp = sp;
tf->pc = pc;
}
/// @brief set params of main(int argc, char** argv) to trapframe (argc, argv)
/// @param tf
/// @param argc
/// @param argv
__attribute__((__always_inline__)) static inline void arch_set_main_params(struct trapframe* tf, int argc, uintptr_t argv)
{
tf->x0 = (uint64_t)argc;
tf->x1 = (uint64_t)argv;
}
/// @brief retrieve params to trapframe (up to max number of 6) and pass it to syscall()
/// @param sys_num
/// @param param1
/// @param param2
/// @param param3
/// @param param4
/// @param param5
/// @return
extern int syscall(int sys_num, uintptr_t param1, uintptr_t param2, uintptr_t param3, uintptr_t param4);
__attribute__((__always_inline__)) static inline int arch_syscall(struct trapframe* tf, int* syscall_num)
{
// call syscall
*syscall_num = tf->x0;
return syscall(*syscall_num, tf->x1, tf->x2, tf->x3, tf->x4);
}
/// @brief set return reg to trapframe
/// @param tf
/// @param ret
__attribute__((__always_inline__)) static inline void arch_set_return(struct trapframe* tf, int ret)
{
tf->x0 = (uint64_t)ret;
}
void cpu_start_secondary(uint8_t cpu_id);
void start_smp_cache_broadcast(int cpu_id);
#endif

View File

@ -0,0 +1,5 @@
SRC_FILES := boot.S \
smp.c \
cortexA72.S
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,81 @@
// #include "memlayout.h"
#include "core.h"
// #include "registers.h"
// #include "cortex_a72.h"
// qemu -kernel loads the kernel at 0x40000000
// and causes each CPU to jump there.
// kernel.ld causes the following code to
// be placed at 0x40000000.
.section ".text"
//.global _entry
.global _boot_start
.global primary_cpu_init
_boot_start:
// set up a stack for C.
// stack0 is declared in start.c,
// with a 4096-byte stack per CPU.
// sp = stack0 + ((cpuid+1) * 4096)
// cpuid = mpidr_el1 & 0xff
// save r0 for cores 1-3, r0 arg field passed by ROM
// r0 is a function pointer for secondary cpus
// mov x4, x0
mrs x0, spsr_el1 /* Enter EL1 (Exception Level 1) */
bic x0, x0, #0x1f
MOV x1, #0xC5
ORR x0, x0, x1
msr spsr_el1, x0
/* set NSACR, both Secure and Non-secure access are allowed to NEON */
MRS X1, CPACR_EL1
ORR X1, X1, #(0X3 << 20)
MSR CPACR_EL1, X1
ISB
// clear some registers
msr elr_el1, XZR
ldr x0, =stacks_top
mov x1, #MODE_STACK_SIZE
// get cpu id, and subtract the offset from the stacks base address
mrs x2, mpidr_el1
and x2, x2, #0x3
mov x5, x2
mul x3, x2, x1
sub x0, x0, x3
MOV X2, #ARM_MODE_EL1_h | DIS_INT
MSR SPSR_EL1, X2
mov sp, x0
SUB x0, x0,x1
// check cpu id - cpu0 is primary cpu
cmp x5, #0
beq primary_cpu_init
bl bootmain // for secondary cpus, jump to argument function pointer passed in by ROM
bl .
primary_cpu_init:
/* init .bss */
/* clear the .bss section (zero init) */
ldr x1, =boot_start_addr
ldr x2, =boot_end_addr
mov x3, #0
1:
cmp x1, x2
stp x3, x3, [x1], #16
b.lt 1b
// branch to c library entry point
mov x0, #0 // argc
mov x1, #0 // argv
mov x2, #0 // env
bl bootmain
.end

View File

@ -0,0 +1,11 @@
export CROSS_COMPILE ?= aarch64-none-elf-
export DEVICE = -mtune=cortex-a72 -ffreestanding -fno-common -fno-stack-protector -fno-pie -no-pie
export CFLAGS := $(DEVICE) -Wall -Werror -O2 -g -fno-omit-frame-pointer -fPIC
# export AFLAGS := -c $(DEVICE) -x assembler-with-cpp -D__ASSEMBLY__ -gdwarf-2
export LFLAGS := $(DEVICE) -Wl,-T -Wl,$(KERNEL_ROOT)/hardkernel/arch/arm/armv8-a/cortex-a72/preboot_for_ok1028a-c/nxp_ls1028.lds -Wl,--start-group,-lgcc,-lc,--end-group
export CXXFLAGS :=
export DEFINES := -DHAVE_CCONFIG_H -DCHIP_LS1028
export ARCH = arm
export ARCH_ARMV = armv8-a

View File

@ -0,0 +1,37 @@
/*!
* @file cortexA72.s
* @brief This file contains cortexA72 functions
*
*/
/*************************************************
File name: cortexA72.S
Description: This file contains cortexA9 functions
Others:
History:
1. Date: 202-05-08
Author: AIIT XUOS Lab
Modification:
1. No modifications
*************************************************/
.section ".text","ax"
.global cpu_get_current
# int cpu_get_current(void)@
# get current CPU ID
.func cpu_get_current
cpu_get_current:
mrs x0, mpidr_el1
and x0, x0, #3
ret
.endfunc
.global psci_call
psci_call:
hvc #0
ret
# ------------------------------------------------------------
# End of cortexA72.s
# ------------------------------------------------------------
.end

View File

@ -0,0 +1,234 @@
/*
* Copyright (c) 2012, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o 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.
*
* o Neither the name of Freescale Semiconductor, Inc. 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.
*/
/**
* @file cortex_a72.h
* @brief some cortex A72 core functions
* @version 1.0
* @author AIIT XUOS Lab
* @date 2024.04.24
*/
/*************************************************
File name: cortex_a72.h
Description: some cortex A72 core functions
Others:
History:
Author: AIIT XUOS Lab
Modification:
1. No modifications
*************************************************/
#if !defined(__CORTEX_A72_H__)
#define __CORTEX_A72_H__
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
//! @name Instruction macros
//@{
#define NOP() __asm__ volatile("nop\n\t")
#define WFI() __asm__ volatile("wfi\n\t")
#define WFE() __asm__ volatile("wfe\n\t")
#define SEV() __asm__ volatile("sev\n\t")
#define DMB() __asm__ volatile("dmb ish\n\t")
#define DSB() __asm__ volatile("dsb ish\n\t")
#define ISB() __asm__ volatile("isb\n\t")
#define _ARM_MRS(coproc, opcode1, Rt, CRn, CRm, opcode2) \
__asm__ volatile("mrc p" #coproc ", " #opcode1 ", %[output], c" #CRn ", c" #CRm ", " #opcode2 "\n" : [output] "=r"(Rt))
#define _ARM_MSR(coproc, opcode1, Rt, CRn, CRm, opcode2) \
__asm__ volatile("mcr p" #coproc ", " #opcode1 ", %[input], c" #CRn ", c" #CRm ", " #opcode2 "\n" ::[input] "r"(Rt))
// #define WriteReg(value, address) (*(volatile unsigned int*)(address) = (value))
// #define ReadReg(address) (*(volatile unsigned int*)(address))
#if defined(__cplusplus)
extern "C" {
#endif
//! @name Misc
//@{
//! @brief Enable or disable the IRQ and FIQ state.
bool arm_set_interrupt_state(bool enable);
//! @brief Get current CPU ID.
int cpu_get_current(void);
//! @brief Enable the NEON MPE.
void enable_neon_fpu(void);
//! @brief Disable aborts on unaligned accesses.
void disable_strict_align_check(void);
//! @brief Get base address of private perpherial space.
//!
//! @return The address of the ARM CPU's private peripherals.
// uint32_t get_arm_private_peripheral_base(void);
//@}
//! @name Data cache operations
//@{
//! @brief Check if dcache is enabled or disabled.
int arm_dcache_state_query();
//! @brief Enables data cache at any available cache level.
//!
//! Works only if MMU is enabled!
void arm_dcache_enable();
//! @brief Disables the data cache at any available cache level.
void arm_dcache_disable();
//! @brief Invalidates the entire data cache.
void arm_dcache_invalidate();
//! @brief Invalidate a line of data cache.
void arm_dcache_invalidate_line(const void* addr);
//! @brief Invalidate a number of lines of data cache.
//!
//! Number of lines depends on length parameter and size of line.
//! Size of line for A9 L1 cache is 32B.
void arm_dcache_invalidate_mlines(const void* addr, size_t length);
//! @brief Flush (clean) all lines of cache (all sets in all ways).
void arm_dcache_flush();
//! @brief Flush (clean) one line of cache.
void arm_dcache_flush_line(const void* addr);
// @brief Flush (clean) multiple lines of cache.
//!
//! Number of lines depends on length parameter and size of line.
void arm_dcache_flush_mlines(const void* addr, size_t length);
//@}
//! @name Instrution cache operations
//@{
//! @brief Check if icache is enabled or disabled.
int arm_icache_state_query();
//! @brief Enables instruction cache at any available cache level.
//!
//! Works without enabled MMU too!
void arm_icache_enable();
//! @brief Disables the instruction cache at any available cache level.
void arm_icache_disable();
//! @brief Invalidates the entire instruction cache.
void arm_icache_invalidate();
//! @brief Invalidates the entire instruction cache inner shareable.
void arm_icache_invalidate_is();
//! @brief Invalidate a line of the instruction cache.
void arm_icache_invalidate_line(const void* addr);
//! @brief Invalidate a number of lines of instruction cache.
//!
//! Number of lines depends on length parameter and size of line.
void arm_icache_invalidate_mlines(const void* addr, size_t length);
//@}
//! @name TLB operations
//@{
//! @brief Invalidate entire unified TLB.
void arm_unified_tlb_invalidate(void);
//! @brief Invalidate entire unified TLB Inner Shareable.
void arm_unified_tlb_invalidate_is(void);
//@}
//! @name Branch predictor operations
//@{
//! @brief Enable branch prediction.
void arm_branch_prediction_enable(void);
//! @brief Disable branch prediction.
void arm_branch_prediction_disable(void);
//! @brief Invalidate entire branch predictor array.
void arm_branch_target_cache_invalidate(void);
//! @brief Invalidate entire branch predictor array Inner Shareable
void arm_branch_target_cache_invalidate_is(void);
//@}
//! @name SCU
//@{
//! @brief Enables the SCU.
void scu_enable(void);
//! @brief Set this CPU as participating in SMP.
void scu_join_smp(void);
//! @brief Set this CPU as not participating in SMP.
void scu_leave_smp(void);
//! @brief Determine which CPUs are participating in SMP.
//!
//! The return value is 1 bit per core:
//! - bit 0 - CPU 0
//! - bit 1 - CPU 1
//! - etc...
unsigned int scu_get_cpus_in_smp(void);
//! @brief Enable the broadcasting of cache & TLB maintenance operations.
//!
//! When enabled AND in SMP, broadcast all "inner sharable"
//! cache and TLM maintenance operations to other SMP cores
void scu_enable_maintenance_broadcast(void);
//! @brief Disable the broadcasting of cache & TLB maintenance operations.
void scu_disable_maintenance_broadcast(void);
//! @brief Invalidates the SCU copy of the tag rams for the specified core.
//!
//! Typically only done at start-up.
//! Possible flow:
//! - Invalidate L1 caches
//! - Invalidate SCU copy of TAG RAMs
//! - Join SMP
//!
//! @param cpu 0x0=CPU 0, 0x1=CPU 1, etc...
//! @param ways The ways to invalidate. Pass 0xf to invalidate all ways.
void scu_secure_invalidate(unsigned int cpu, unsigned int ways);
//@}
#if defined(__cplusplus)
}
#endif
#endif //__CORTEX_A72_H__

View File

@ -0,0 +1,110 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
#ifndef INC_SYSREGS_H_
#define INC_SYSREGS_H_
/* SCTLR_EL1, System Control Register (EL1). */
#define SCTLR_RESERVED \
((3 << 28) | (3 << 22) | (1 << 20) | (1 << 11) | (1 << 8) | (1 << 7))
#define SCTLR_EE_LITTLE_ENDIAN (0 << 25)
#define SCTLR_E0E_LITTLE_ENDIAN (0 << 24)
#define SCTLR_I_CACHE (1 << 12)
#define SCTLR_D_CACHE (1 << 2)
#define SCTLR_MMU_DISABLED (0 << 0)
#define SCTLR_MMU_ENABLED (1 << 0)
#define SCTLR_VALUE_MMU_DISABLED \
(SCTLR_RESERVED | SCTLR_EE_LITTLE_ENDIAN | SCTLR_E0E_LITTLE_ENDIAN \
| SCTLR_I_CACHE | SCTLR_D_CACHE | SCTLR_MMU_DISABLED)
/* HCR_EL2, Hypervisor Configuration Register (EL2). */
#define HCR_RW (1 << 31)
#define HCR_VALUE HCR_RW
/* CPACR_EL1, Architectural Feature Access Control Register. */
#define CPACR_FP_EN (3 << 20)
#define CPACR_TRACE_EN (0 << 28)
#define CPACR_VALUE (CPACR_FP_EN | CPACR_TRACE_EN)
/* SCR_EL3, Secure Configuration Register (EL3). */
#define SCR_RESERVED (3 << 4)
#define SCR_RW (1 << 10)
#define SCR_HCE (1 << 8)
#define SCR_SMD (1 << 7)
#define SCR_NS (1 << 0)
#define SCR_VALUE (SCR_RESERVED | SCR_RW | SCR_HCE | SCR_SMD | SCR_NS)
/* SPSR_EL1/2/3, Saved Program Status Register. */
#define SPSR_MASK_ALL (7 << 6)
#define SPSR_EL1h (5 << 0)
#define SPSR_EL2h (9 << 0)
#define SPSR_EL3_VALUE (SPSR_MASK_ALL | SPSR_EL2h)
#define SPSR_EL2_VALUE (SPSR_MASK_ALL | SPSR_EL1h)
/* Exception Class in ESR_EL1. */
#define EC_SHIFT 26
#define EC_UNKNOWN 0x00
#define EC_SVC64 0x15
#define EC_DABORT 0x24
#define EC_IABORT 0x20
#define PTE_VALID 1 // level 0,1,2 descriptor: valid
#define PTE_TABLE 2 // level 0,1,2 descriptor: table
#define PTE_V 3 // level 3 descriptor: valid
// PTE_AF(Access Flag)
//
// 0 -- this block entry has not yet.
// 1 -- this block entry has been used.
#define PTE_AF (1 << 10)
// PTE_AP(Access Permission) is 2bit field.
// EL0 EL1
// 00 -- x RW
// 01 -- RW RW
// 10 -- x RO
// 11 -- RO RO
#define PTE_AP(ap) (((ap) & 3) << 6)
#define PTE_U PTE_AP(1)
#define PTE_RO PTE_AP(2)
#define PTE_URO PTE_AP(3)
#define PTE_PXN (1UL << 53) // Privileged eXecute Never
#define PTE_UXN (1UL << 54) // Unprivileged(user) eXecute Never
#define PTE_XN (PTE_PXN | PTE_UXN) // eXecute Never
// attribute index
// index is set by mair_el1
#define AI_DEVICE_nGnRnE_IDX 0x0
#define AI_NORMAL_NC_IDX 0x1
// memory type
#define MT_DEVICE_nGnRnE 0x0
#define MT_NORMAL_NC 0x44
#define PTE_INDX(i) (((i) & 7) << 2)
#define PTE_DEVICE PTE_INDX(AI_DEVICE_nGnRnE_IDX)
#define PTE_NORMAL PTE_INDX(AI_NORMAL_NC_IDX)
// shift a physical address to the right place for a PTE.
#define PA2PTE(pa) ((uint64_t)(pa) & 0xfffffffff000)
#define PTE2PA(pte) ((uint64_t)(pte) & 0xfffffffff000)
#define PTE_FLAGS(pte) ((pte) & (0x600000000003ff))
// translation control register
// #define TCR_T0SZ(n) ((n) & 0x3f)
// #define TCR_TG0(n) (((n) & 0x3) << 14)
// #define TCR_T1SZ(n) (((n) & 0x3f) << 16)
// #define TCR_TG1(n) (((n) & 0x3) << 30)
// #define TCR_IPS(n) (((n) & 0x7) << 32)
#define ISS_MASK 0xFFFFFF
#endif // INC_SYSREGS_H_

View File

@ -0,0 +1,119 @@
/*
* Copyright (c) 2010-2012, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o 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.
*
* o Neither the name of Freescale Semiconductor, Inc. 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 OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/**
* @file nxp_ls1028.lds
* @brief nxp ls1028 lds function
* @version 1.0
* @author AIIT XUOS Lab
* @date 2024.04.10
*/
BOOT_STACK_SIZE = 0x4000;
OUTPUT_FORMAT("elf64-littleaarch64")
OUTPUT_ARCH( "aarch64" )
/**
ENTRY( _ENTRY )
*/
ENTRY( _boot_start )
MEMORY {
phy_ddr3 (rwx) : ORIGIN = 0x0000000040000000, LENGTH = 1024M
vir_ddr3 (rwx) : ORIGIN = 0x0000006040635000, LENGTH = 1024M
}
SECTIONS
{
.start_sec : {
. = ALIGN(0x1000);
/* initialization start checkpoint. */
boot.o(.text)
bootmmu.o(.text .text.*)
boot.o(.rodata .rodata.*)
bootmmu.o(.rodata .rodata.*)
boot.o(.data .data.*)
bootmmu.o(.data .data.*)
PROVIDE(boot_start_addr = .);
boot.o(.bss .bss.* COMMON)
bootmmu.o(.bss .bss.* COMMON)
/* stack for booting code. */
. = ALIGN(0x1000);
PROVIDE(stacks_start = .);
. += BOOT_STACK_SIZE;
PROVIDE(stacks_end = .);
PROVIDE(stacks_top = .);
/* initialization end checkpoint. */
PROVIDE(boot_end_addr = .);
} > phy_ddr3
.text : AT(0x40635000) {
. = ALIGN(0x1000);
*(.text .text.* .gnu.linkonce.t.*)
} > vir_ddr3
. = ALIGN(0x1000);
.data : {
*(.data .data.*)
. = ALIGN(0x1000);
PROVIDE(_binary_fs_img_start = .);
*(.rawdata_fs_img*)
PROVIDE(_binary_fs_img_end = .);
. = ALIGN(0x1000);
PROVIDE(_binary_init_start = .);
*(.rawdata_init*)
PROVIDE(_binary_init_end = .);
. = ALIGN(0x1000);
PROVIDE(_binary_default_fs_start = .);
*(.rawdata_memfs*)
PROVIDE(_binary_default_fs_end = .);
} > vir_ddr3
. = ALIGN(0x1000);
PROVIDE(kernel_data_begin = .);
_image_size = . - 0x0000006040000000;
.bss : {
PROVIDE(__bss_start__ = .);
*(.bss .bss.* COMMON)
PROVIDE(__bss_end__ = .);
} > vir_ddr3
. = ALIGN(0x1000);
PROVIDE(kernel_data_end = .);
}

View File

@ -0,0 +1,62 @@
/*
* Copyright (c) 2010-2012, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o 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.
*
* o Neither the name of Freescale Semiconductor, Inc. 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.
*/
/**
* @file smp.c
* @brief start multicore
* @version 1.0
* @author AIIT XUOS Lab
* @date 2024.04.10
*/
/*************************************************
File name: smp.c
Description:
Others:
History:
Author: AIIT XUOS Lab
Modification:
1. No modifications
*************************************************/
#include <stdint.h>
#define PSCI_CPUON 0xc4000003
extern void _boot_start();
void psci_call(uint64_t fn, uint8_t cpuid, uint64_t entry, uint64_t ctxid);
void cpu_start_secondary(uint8_t cpu_id)
{
psci_call(PSCI_CPUON, cpu_id, (uintptr_t)&_boot_start, 0);
}
void start_smp_cache_broadcast(int cpu_id)
{
return;
}

View File

@ -1,3 +1,8 @@
ifneq ($(findstring $(BOARD), imx6q-sabrelite zynq7000-zc702), )
SRC_DIR := cortex-a9
endif
ifneq ($(findstring $(BOARD), ok1028a-c), )
SRC_DIR := cortex-a72
endif
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,3 @@
SRC_FILES := l1_cache.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,281 @@
/**
* @file: l1_cache.c
* @brief: the general management of L1 cache
* @version: 1.0
* @author: AIIT XUOS Lab
* @date: 2024/04/23
*
*/
/*************************************************
File name: l1_cache.c
Description: the general management of L1 cache
Others:
History:
Author: AIIT XUOS Lab
Modification:
1. implement the l1 cache operations
2. function names are modified to apply softkernel developement
3. function implementations are from modifications of imx6 SDK package
*************************************************/
#include "l1_cache.h"
void InvalidateL1Dcache(uintptr_t start, uintptr_t end)
{
uint64_t length = end - start;
uint64_t addr = start;
uint64_t ccsidr_el1;
uint64_t line_size;
uint64_t va;
// get the cache line size
__asm__ __volatile__("mrs %0, ccsidr_el1" : "=r"(ccsidr_el1));
line_size = 1 << ((ccsidr_el1 & 0x7) + 4);
// align the address with line
const uintptr_t end_addr = (const uintptr_t)((uint64_t)addr + length);
do {
va = (uint64_t)((uint64_t)addr & (~(line_size - 1)));
// Invalidate data cache line to PoC (Point of Coherence) by va.
__asm__ __volatile__("dc ivac, %0 " : : "r"(va));
// increment addres to next line and decrement lenght
addr = (uintptr_t)((uint64_t)addr + line_size);
} while (addr < end_addr);
// All Cache, Branch predictor and TLB maintenance operations before followed instruction complete
DSB();
}
void InvalidateL1DcacheAll(void)
{
uint64_t ccsidr_el1; // Cache Size ID
int num_sets; // number of sets
int num_ways; // number of ways
uint32_t wayset; // wayset parameter
__asm__ __volatile__("mrs %0, ccsidr_el1" : "=r"(ccsidr_el1)); // Read Cache Size ID
// Fill number of sets and number of ways from ccsidr_el1 register
num_sets = ((ccsidr_el1 >> 32) & 0x7FFF) + 1;
num_ways = ((ccsidr_el1 >> 0) & 0x7FFF) + 1;
// Invalidation all lines (all Sets in all ways)
for (int way = 0; way < num_ways; way++) {
for (int set = 0; set < num_sets; set++) {
wayset = (way << 30) | (set << 5);
__asm__ __volatile__("dc isw, %0" : : "r"(wayset));
}
}
// All Cache, Branch predictor and TLB maintenance operations before followed instruction complete
DSB();
}
void CleanL1Dcache(uintptr_t start, uintptr_t end)
{
void* addr = (void*)start;
uintptr_t length = end - start;
const void* end_addr = (const void*)((uint64_t)addr + length);
uint64_t ccsidr_el1;
uint64_t line_size;
uint64_t va;
// get the cache line size
__asm__ __volatile__("mrs %0, ccsidr_el1" : "=r"(ccsidr_el1));
line_size = 1 << ((ccsidr_el1 & 0x7) + 4);
do {
va = (uint64_t)addr & (~(line_size - 1));
// Clean data cache line to PoC (Point of Coherence) by va.
__asm__ __volatile__("dc cvac, %0" : : "r"(va));
// increment addres to next line and decrement lenght
addr = (void*)((uint64_t)addr + line_size);
} while (addr < end_addr);
// All Cache, Branch predictor and TLB maintenance operations before followed instruction complete
DSB();
}
void CleanL1DcacheAll(void)
{
uint64_t ccsidr_el1; // Cache Size ID
int num_sets; // number of sets
int num_ways; // number of ways
uint32_t wayset; // wayset parameter
__asm__ __volatile__("mrs %0, ccsidr_el1" : "=r"(ccsidr_el1)); // Read Cache Size ID
// Fill number of sets and number of ways from ccsidr_el1 register This walues are decremented by 1
num_sets = ((ccsidr_el1 >> 32) & 0x7FFF) + 1;
num_ways = ((ccsidr_el1 >> 0) & 0x7FFF) + 1;
// clean all lines (all Sets in all ways)
for (int way = 0; way < num_ways; way++) {
for (int set = 0; set < num_sets; set++) {
wayset = (way << 30) | (set << 5);
__asm__ __volatile__("dc csw, %0" : : "r"(wayset));
}
}
// All Cache, Branch predictor and TLB maintenance operations before followed instruction complete
DSB();
}
void FlushL1Dcache(uintptr_t start, uintptr_t end)
{
void* addr = (void*)start;
// size_t length=end-start;
uint64_t va;
uint64_t ccsidr_el1 = 0, line_size = 0;
const void* end_addr = (const void*)((uint64_t)end);
// get the cache line size
__asm__ __volatile__("mrs %0, ccsidr_el1" : "=r"(ccsidr_el1));
line_size = 1 << ((ccsidr_el1 & 0x7) + 4);
do {
// Clean data cache line to PoC (Point of Coherence) by va.
va = (uint64_t)((uint64_t)addr & (~(line_size - 1))); // addr & va_VIRTUAL_ADDRESS_MASK
__asm__ __volatile__("dc civac, %0" : : "r"(va));
// increment addres to next line and decrement lenght
addr = (void*)((uint64_t)addr + line_size);
} while (addr < end_addr);
// All Cache, Branch predictor and TLB maintenance operations before followed instruction complete
DSB();
}
void FlushL1DcacheAll(void)
{
uint64_t ccsidr_el1; // Cache Size ID
int num_sets; // number of sets
int num_ways; // number of ways
uint32_t wayset; // wayset parameter
__asm__ __volatile__("mrs %0, ccsidr_el1" : "=r"(ccsidr_el1)); // Read Cache Size ID
// Fill number of sets and number of ways from ccsidr_el1 register This walues are decremented by 1
num_sets = ((ccsidr_el1 >> 32) & 0x7FFF) + 1;
num_ways = ((ccsidr_el1 >> 0) & 0x7FFF) + 1;
// clean and invalidate all lines (all Sets in all ways)
for (int way = 0; way < num_ways; way++) {
for (int set = 0; set < num_sets; set++) {
wayset = (way << 30) | (set << 5);
__asm__ __volatile__("dc cisw, %0" : : "r"(wayset));
}
}
// All Cache, Branch predictor and TLB maintenance operations before followed instruction complete
DSB();
}
void InvalidateL1IcacheAll()
{
__asm__ __volatile__("ic iallu\n\t");
// synchronize context on this processor
ISB();
}
void InvalidateL1Icache(uintptr_t start, uintptr_t end)
{
// uintptr_t length = end - start;
uintptr_t addr = start;
uint64_t ccsidr_el1;
uint64_t line_size;
uint64_t va;
const uintptr_t end_addr = (const uintptr_t)((uint64_t)end);
// get the cache line size
__asm__ __volatile__("mrs %0, ccsidr_el1" : "=r"(ccsidr_el1));
line_size = 1 << ((ccsidr_el1 & 0x7) + 4);
do {
va = (uint64_t)((uint64_t)addr & (~(line_size - 1)));
// Invalidate data cache line to PoC (Point of Coherence) by va.
__asm__ __volatile__("ic ivau, %0 " : : "r"(va));
// increment addres to next line and decrement lenght
addr = (uintptr_t)((uint64_t)addr + line_size);
} while (addr < end_addr);
// synchronize context on this processor
ISB();
}
void EnableL1Dcache()
{
uint64_t sctlr_el1; // System Control Register
// read sctlr_el1
__asm__ __volatile__("mrs %0, sctlr_el1" : "=r"(sctlr_el1));
if (!(sctlr_el1 & SCTLR_EL1_DCACHE_ENABLE)) {
// set C bit (data caching enable)
sctlr_el1 |= SCTLR_EL1_DCACHE_ENABLE;
// write modified sctlr_el1
__asm__ __volatile__("msr sctlr_el1, %0" : : "r"(sctlr_el1));
// data synchronization barrier
DSB();
}
}
void DisableL1Dcache()
{
uint64_t sctlr_el1; // System Control Register
// read sctlr_el1
__asm__ __volatile__("mrs %0, sctlr_el1" : "=r"(sctlr_el1));
// set C bit (data caching enable)
sctlr_el1 &= ~SCTLR_EL1_DCACHE_ENABLE;
// write modified sctlr_el1
__asm__ __volatile__("msr sctlr_el1, %0" : "=r"(sctlr_el1));
// data synchronization barrier
DSB();
}
void EnableL1Icache()
{
uint64_t sctlr_el1; // System Control Register
// read sctlr_el1
__asm__ __volatile__("mrs %0, sctlr_el1" : "=r"(sctlr_el1));
if (!(sctlr_el1 & SCTLR_EL1_ICACHE_ENABLE)) {
// set I bit (data caching enable)
sctlr_el1 |= SCTLR_EL1_ICACHE_ENABLE;
// write modified sctlr_el1
__asm__ __volatile__("msr sctlr_el1, %0" : "=r"(sctlr_el1));
// Instruction synchronization barrier
ISB();
}
}
void DisableL1Icache()
{
uint64_t sctlr_el1; // System Control Register
// read sctlr_el1
__asm__ __volatile__("mrs %0, sctlr_el1" : "=r"(sctlr_el1));
// set I bit (data caching enable)
sctlr_el1 &= ~SCTLR_EL1_ICACHE_ENABLE;
// write modified sctlr_el1
__asm__ __volatile__("msr sctlr_el1, %0" : : "r"(sctlr_el1));
// Instruction synchronization barrier
ISB();
}

View File

@ -0,0 +1,76 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
/**
* @file: l1_cache.h
* @brief: the general management of L1 cache
* @version: 1.0
* @author: AIIT XUOS Lab
* @date: 2024/4/23
*
*/
/*************************************************
File name: l1_cache.h
Description: the general management of L1 cache
Others:
History:
Author: AIIT XUOS Lab
Modification:
1define the l1 cache operations
*************************************************/
#include "core.h"
#include <stdint.h>
/*
* L1 Cache Operation:
*
* IVAC -Invalidate by Virtual Address, to Point of Coherency AArch32Equivalent :DCIMVAC
*
* ISW -Invalidate by Set/Way AArch32Equivalent :DCISW
*
*CVAC -Clean by Virtual Address to Point of Coherency AArch32Equivalent :DCCMVAC
*
*CSW -Clean by Set/Way AArch32Equivalent :DCCSW
*
*CVAU -Clean by Virtual Address to Point of Unification AArch32Equivalent :DCCMVAU
*
*CIVAC -Clean and invalidate data cache line by VA to PoC. AArch32Equivalent :DCCIMVAC
*
*ISW -Clean and invalidate data cache line by Set/Way. AArch32Equivalent :DCCISW
*/
#define SCTLR_EL1_ICACHE_ENABLE (1 << 12) //!< Instruction cache enable
#define SCTLR_EL1_DCACHE_ENABLE (1 << 2) //!< Data cache enable
void InvalidateL1Dcache(uintptr_t start, uintptr_t end);
void InvalidateL1DcacheAll(void);
void CleanL1Dcache(uintptr_t start, uintptr_t end);
void CleanL1DcacheAll(void);
void FlushL1Dcache(uintptr_t start, uintptr_t end);
void FlushL1DcacheAll(void);
void InvalidateL1IcacheAll(void);
void InvalidateL1Icache(uintptr_t start, uintptr_t end);
void EnableL1Icache(void);
void DisableL1Icache();
void EnableL1Dcache();
void DisableL1Dcache();

View File

@ -1,23 +1,23 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
/**
* @file: cache_common_ope.c
* @brief: the general management of cache
* @version: 3.0
* @author: AIIT XUOS Lab
* @date: 2023/11/06
*
*/
* @file: cache_common_ope.c
* @brief: the general management of cache
* @version: 3.0
* @author: AIIT XUOS Lab
* @date: 2023/11/06
*
*/
/*************************************************
File name: cache_common_ope.c
@ -31,7 +31,7 @@ Modification:
*************************************************/
#include "cache_common_ope.h"
#include "l1_cache.h"
#include "l2_cache.h"
// #include "l2_cache.h"
/****************************************************************************
* Public Functions
@ -48,7 +48,7 @@ Modification:
static inline void invalidate_dcache(uintptr_t start, uintptr_t end)
{
InvalidateL1Dcache(start, end);
// InvalidateL1Dcache(start, end);
// InvalidateL2Cache(start, end);
}
@ -65,7 +65,7 @@ static inline void invalidate_dcache(uintptr_t start, uintptr_t end)
static inline void invalidate_dcache_all(void)
{
InvalidateL1DcacheAll();
// InvalidateL1DcacheAll();
// InvalidateL2CacheAll();
}
@ -78,7 +78,7 @@ static inline void invalidate_dcache_all(void)
****************************************************************************/
static inline void invalidate_icache(uintptr_t start, uintptr_t end)
{
InvalidateL1Icache(start, end);
// InvalidateL1Icache(start, end);
}
/****************************************************************************
@ -92,7 +92,7 @@ static inline void invalidate_icache(uintptr_t start, uintptr_t end)
static inline void invalidate_icache_all(void)
{
InvalidateL1IcacheAll();
// InvalidateL1IcacheAll();
}
/****************************************************************************
@ -106,7 +106,7 @@ static inline void invalidate_icache_all(void)
static inline void clean_dcache(uintptr_t start, uintptr_t end)
{
CleanL1Dcache(start, end);
// CleanL1Dcache(start, end);
// CleanL2Cache(start, end);
}
@ -121,7 +121,7 @@ static inline void clean_dcache(uintptr_t start, uintptr_t end)
static inline void clean_dcache_all(void)
{
CleanL1DcacheAll();
// CleanL1DcacheAll();
// CleanL2CacheAll();
}
@ -137,7 +137,7 @@ static inline void clean_dcache_all(void)
static inline void flush_dcache(uintptr_t start, uintptr_t end)
{
FlushL1Dcache(start, end);
// FlushL1Dcache(start, end);
// FlushL2Cache(start, end);
}
@ -151,7 +151,7 @@ static inline void flush_dcache(uintptr_t start, uintptr_t end)
static inline void flush_dcache_all(void)
{
FlushL1DcacheAll();
// FlushL1DcacheAll();
// FlushL2CacheAll();
}
@ -165,7 +165,7 @@ static inline void flush_dcache_all(void)
static inline void enable_icache(void)
{
EnableL1Icache();
// EnableL1Icache();
}
/****************************************************************************
@ -178,7 +178,7 @@ static inline void enable_icache(void)
static inline void disable_icache(void)
{
DisableL1Icache();
// DisableL1Icache();
}
/****************************************************************************
@ -191,7 +191,7 @@ static inline void disable_icache(void)
static inline void enable_dcache(void)
{
EnableL1Dcache();
// EnableL1Dcache();
// EnableL2Cache();
}
@ -205,9 +205,9 @@ static inline void enable_dcache(void)
static inline void disable_dcache(void)
{
FlushL1DcacheAll();
// FlushL1DcacheAll();
// pl310_flush_all();
DisableL1Dcache();
// DisableL1Dcache();
// DisableL2Cache();
}

View File

@ -1,3 +1,3 @@
SRC_DIR:= arm/armv7-a/cortex-a9/$(BOARD)
SRC_DIR:= arm
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,9 @@
ifneq ($(findstring $(BOARD), ok1028a-c), )
SRC_DIR := armv8-a
endif
ifneq ($(findstring $(BOARD), imx6q-sabrelite zynq7000-zc702), )
SRC_DIR := armv7-a
endif
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,6 @@
ifneq ($(findstring $(BOARD), imx6q-sabrelite zynq7000-zc702), )
SRC_DIR := cortex-a9
endif
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,3 @@
SRC_DIR := $(BOARD)
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,6 @@
ifneq ($(findstring $(BOARD), ok1028a-c), )
SRC_DIR := cortex-a72
endif
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,3 @@
SRC_DIR := $(BOARD)
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,4 @@
SRC_FILES := clock.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,95 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
#include "actracer.h"
#include "core.h"
#include "generic_timer.h"
#include "clock_common_op.h"
// armv8 generic timer driver
#define CNTV_CTL_ENABLE (1 << 0)
#define CNTV_CTL_IMASK (1 << 1)
#define CNTV_CTL_ISTATUS (1 << 2)
static void enable_timer()
{
uint32_t c = r_cntv_ctl_el0();
c |= CNTV_CTL_ENABLE;
c &= ~CNTV_CTL_IMASK;
w_cntv_ctl_el0(c);
}
static void disable_timer()
{
uint32_t c = r_cntv_ctl_el0();
c |= CNTV_CTL_IMASK;
c &= ~CNTV_CTL_ENABLE;
w_cntv_ctl_el0(c);
}
static void reload_timer()
{
// interval 100ms
static uint32_t ms = 10;
uint32_t interval = ms * 1000;
uint32_t interval_clk = interval * (r_cntfrq_el0() / 1000000);
w_cntv_tval_el0(interval_clk);
}
void _sys_clock_init()
{
disable_timer();
reload_timer();
enable_timer();
}
static uint32_t _get_clock_int()
{
return 27;
}
static uint64_t _get_tick()
{
return r_cntvct_el0();
}
static uint64_t _get_second()
{
return 0;
}
static bool _is_timer_expired()
{
return true;
}
static void _clear_clock_intr()
{
disable_timer();
reload_timer();
enable_timer();
}
static struct XiziClockDriver hardkernel_clock_driver = {
.sys_clock_init = _sys_clock_init,
.get_clock_int = _get_clock_int,
.get_tick = _get_tick,
.get_second = _get_second,
.is_timer_expired = _is_timer_expired,
.clear_clock_intr = _clear_clock_intr,
};
struct XiziClockDriver* hardkernel_clock_init(struct TraceTag* hardkernel_tag)
{
hardkernel_clock_driver.sys_clock_init();
return &hardkernel_clock_driver;
}

View File

@ -0,0 +1,54 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
#pragma once
#include <stddef.h>
#include <stdint.h>
// armv8 generic timer
static inline uint32_t r_cntv_ctl_el0()
{
uint32_t x;
__asm__ volatile("mrs %0, cntv_ctl_el0" : "=r"(x));
return x;
}
static inline void w_cntv_ctl_el0(uint32_t x)
{
__asm__ volatile("msr cntv_ctl_el0, %0" : : "r"(x));
}
static inline uint32_t r_cntv_tval_el0()
{
uint32_t x;
__asm__ volatile("mrs %0, cntv_tval_el0" : "=r"(x));
return x;
}
static inline void w_cntv_tval_el0(uint32_t x)
{
__asm__ volatile("msr cntv_tval_el0, %0" : : "r"(x));
}
static inline uint64_t r_cntvct_el0()
{
uint64_t x;
__asm__ volatile("mrs %0, cntvct_el0" : "=r"(x));
return x;
}
static inline uint32_t r_cntfrq_el0()
{
uint32_t x;
__asm__ volatile("mrs %0, cntfrq_el0" : "=r"(x));
return x;
}

View File

@ -1,4 +1,4 @@
SRC_DIR := arm/armv7-a/cortex-a9
SRC_DIR := arm
SRC_FILES := spinlock.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,9 @@
ifneq ($(findstring $(BOARD), ok1028a-c), )
SRC_DIR := armv8-a
endif
ifneq ($(findstring $(BOARD), imx6q-sabrelite zynq7000-zc702), )
SRC_DIR := armv7-a
endif
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,6 @@
ifneq ($(findstring $(BOARD), imx6q-sabrelite zynq7000-zc702), )
SRC_DIR := cortex-a9
endif
include $(KERNEL_ROOT)/compiler.mk

View File

@ -89,7 +89,7 @@ static void _sys_irq_init(int cpu_id)
gic_init();
}
/* active hardware irq responser */
xizi_trap_driver.switch_hw_irqtbl((uint32_t*)&_vector_jumper);
xizi_trap_driver.switch_hw_irqtbl((uintptr_t*)&_vector_jumper);
}
static void _cpu_irq_enable(void)
@ -117,7 +117,7 @@ static void _single_irq_disable(int irq, int cpu)
}
#define VBAR
static inline uint32_t* _switch_hw_irqtbl(uint32_t* new_tbl_base)
static inline uintptr_t* _switch_hw_irqtbl(uintptr_t* new_tbl_base)
{
// get old irq table base addr
uint32_t old_tbl_base = 0;
@ -132,7 +132,7 @@ static inline uint32_t* _switch_hw_irqtbl(uint32_t* new_tbl_base)
sctlr &= ~(1 << 13);
_ARM_MCR(15, 0, sctlr, 1, 0, 0);
return (uint32_t*)old_tbl_base;
return (uintptr_t*)old_tbl_base;
}
static void _bind_irq_handler(int irq, irq_handler_t handler)

View File

@ -0,0 +1,3 @@
SRC_DIR := cortex-a72
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,9 @@
SRC_FILES := trampoline.S $(BOARD)/trap_common.c $(BOARD)/trap.c error_debug.c hard_spinlock.S
ifeq ($(BOARD), ok1028a-c)
SRC_DIR := gicv3
SRC_FILES += $(BOARD)/
endif
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,167 @@
/* Copyright (c) 2006-2018 Frans Kaashoek, Robert Morris, Russ Cox,
* Massachusetts Institute of Technology
*
* 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.
*/
/**
* @file error_debug.c
* @brief handle program abort
* @version 1.0
* @author AIIT XUOS Lab
* @date 2024.4.25
*/
/*************************************************
File name: error_debug.c
Description: handle program abort
Others:
History:
Author: AIIT XUOS Lab
Modification:
1. Take only armv8 abort reason part(_abort_reason).
2. Modify iabort and dabort handler(in dabort_handler() and iabort_handler())
*************************************************/
#include <stddef.h>
#include "assert.h"
#include "core.h"
#include "log.h"
#include "multicores.h"
#include "spinlock.h"
#include "task.h"
#include "trap_common.h"
void dump_tf(struct trapframe* tf)
{
KPrintf(" sp: 0x%x\n", tf->sp);
KPrintf(" pc: 0x%x\n", tf->pc);
KPrintf(" spsr: 0x%x\n", tf->spsr);
KPrintf(" x0: 0x%x\n", tf->x0);
KPrintf(" x1: 0x%x\n", tf->x1);
KPrintf(" x2: 0x%x\n", tf->x2);
KPrintf(" x3: 0x%x\n", tf->x3);
KPrintf(" x4: 0x%x\n", tf->x4);
KPrintf(" x5: 0x%x\n", tf->x5);
KPrintf(" x6: 0x%x\n", tf->x6);
KPrintf(" x7: 0x%x\n", tf->x7);
KPrintf(" x8: 0x%x\n", tf->x8);
KPrintf(" x9: 0x%x\n", tf->x9);
KPrintf(" x10: 0x%x\n", tf->x10);
KPrintf(" x11: 0x%x\n", tf->x11);
KPrintf(" x12: 0x%x\n", tf->x12);
KPrintf(" x13: 0x%x\n", tf->x13);
KPrintf(" x14: 0x%x\n", tf->x14);
KPrintf(" x15: 0x%x\n", tf->x15);
KPrintf(" x16: 0x%x\n", tf->x16);
KPrintf(" x17: 0x%x\n", tf->x17);
KPrintf(" x18: 0x%x\n", tf->x18);
KPrintf(" x19: 0x%x\n", tf->x19);
KPrintf(" x20: 0x%x\n", tf->x20);
KPrintf(" x21: 0x%x\n", tf->x21);
KPrintf(" x22: 0x%x\n", tf->x22);
KPrintf(" x23: 0x%x\n", tf->x23);
KPrintf(" x24: 0x%x\n", tf->x24);
KPrintf(" x25: 0x%x\n", tf->x25);
KPrintf(" x26: 0x%x\n", tf->x26);
KPrintf(" x27: 0x%x\n", tf->x27);
KPrintf(" x28: 0x%x\n", tf->x28);
KPrintf(" x29: 0x%x\n", tf->x29);
KPrintf(" x30: 0x%x\n", tf->x30);
}
void dabort_reason(struct trapframe* r)
{
uint32_t fault_status, fault_address;
__asm__ __volatile__("mrs %0, esr_el1" : "=r"(fault_status));
__asm__ __volatile__("mrs %0, far_el1" : "=r"(fault_address));
LOG("program counter: 0x%x caused\n", r->pc);
LOG("data abort at 0x%x, status 0x%x\n", fault_address, fault_status);
if ((fault_status & 0x3f) == 0x21) // Alignment failure
KPrintf("reason: alignment\n");
else if ((fault_status & 0x3f) == 0x4) // Translation fault, level 0
KPrintf("reason: sect. translation level 0\n");
else if ((fault_status & 0x3f) == 0x5) // Translation fault, level 1
KPrintf("reason: sect. translation level 1\n");
else if ((fault_status & 0x3f) == 0x6) // Translation fault, level 2
KPrintf("reason: sect. translation level 2\n");
else if ((fault_status & 0x3f) == 0x7) // Translation fault, level 3
KPrintf("reason: sect. translation level 3\n");
else if ((fault_status & 0x3f) == 0x3d) // Section Domain fault
KPrintf("reason: sect. domain\n");
else if ((fault_status & 0x3f) == 0xd) // Permission level 1
KPrintf("reason: sect. permission level 1\n");
else if ((fault_status & 0x3f) == 0xe) // Permission level 2
KPrintf("reason: sect. permission level 2\n");
else if ((fault_status & 0x3f) == 0xf) // Permission level 3
KPrintf("reason: sect. permission level 3\n");
else if ((fault_status & 0x3f) == 0x14) // External abort
KPrintf("reason: ext. abort\n");
else if ((fault_status & 0x3f) == 0x9) // Access flag fault, level 1
KPrintf("reason: sect. Access flag fault level 1\n");
else if ((fault_status & 0x3f) == 0xa) // Access flag fault, level 2
KPrintf("reason: sect. Access flag fault level 2\n");
else if ((fault_status & 0x3f) == 0xb) // Access flag fault, level 3
KPrintf("reason: sect. Access flag fault level 3\n");
else
KPrintf("reason: unknown???\n");
dump_tf(r);
return;
}
void iabort_reason(struct trapframe* r)
{
uint32_t fault_status, fault_address;
__asm__ __volatile__("mrs %0, esr_el1" : "=r"(fault_status));
__asm__ __volatile__("mrs %0, far_el1" : "=r"(fault_address));
LOG("program counter: 0x%x caused\n", r->pc);
LOG("data abort at 0x%x, status 0x%x\n", fault_address, fault_status);
if ((fault_status & 0x3f) == 0x21) // Alignment failure
KPrintf("reason: alignment\n");
else if ((fault_status & 0x3f) == 0x4) // Translation fault, level 0
KPrintf("reason: sect. translation level 0\n");
else if ((fault_status & 0x3f) == 0x5) // Translation fault, level 1
KPrintf("reason: sect. translation level 1\n");
else if ((fault_status & 0x3f) == 0x6) // Translation fault, level 2
KPrintf("reason: sect. translation level 2\n");
else if ((fault_status & 0x3f) == 0x7) // Translation fault, level 3
KPrintf("reason: sect. translation level 3\n");
else if ((fault_status & 0x3f) == 0x3d) // Section Domain fault
KPrintf("reason: sect. domain\n");
else if ((fault_status & 0x3f) == 0xd) // Permission level 1
KPrintf("reason: sect. permission level 1\n");
else if ((fault_status & 0x3f) == 0xe) // Permission level 2
KPrintf("reason: sect. permission level 2\n");
else if ((fault_status & 0x3f) == 0xf) // Permission level 3
KPrintf("reason: sect. permission level 3\n");
else if ((fault_status & 0x3f) == 0x14) // External abort
KPrintf("reason: ext. abort\n");
else if ((fault_status & 0x3f) == 0x9) // Access flag fault, level 1
KPrintf("reason: sect. Access flag fault level 1\n");
else if ((fault_status & 0x3f) == 0xa) // Access flag fault, level 2
KPrintf("reason: sect. Access flag fault level 2\n");
else if ((fault_status & 0x3f) == 0xb) // Access flag fault, level 3
KPrintf("reason: sect. Access flag fault level 3\n");
else
KPrintf("reason: unknown???\n");
dump_tf(r);
return;
}

View File

@ -0,0 +1,3 @@
SRC_FILES := gicv3.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,258 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
/**
* @file gicv3.c
* @brief gicv3 operation
* @version 1.0
* @author AIIT XUOS Lab
* @date 2024.05.10
*/
/*************************************************
File name: gicv3.c
Description: gicv3 operation
Others:
History:
Author: AIIT XUOS Lab
Modification:
*************************************************/
#include <string.h>
#include "core.h"
#include "gicv3_common_opa.h"
#include "gicv3_registers.h"
static struct {
char* gicd;
char* rdist_addrs[NR_CPU];
} gicv3;
static inline uint32_t icc_igrpen1_el1()
{
uint32_t x;
__asm__ volatile("mrs %0, S3_0_C12_C12_7" : "=r"(x));
return x;
}
static inline void w_icc_igrpen1_el1(uint32_t x)
{
__asm__ volatile("msr S3_0_C12_C12_7, %0" : : "r"(x));
}
static inline uint32_t icc_pmr_el1()
{
uint32_t x;
__asm__ volatile("mrs %0, S3_0_C4_C6_0" : "=r"(x));
return x;
}
static inline void w_icc_pmr_el1(uint32_t x)
{
__asm__ volatile("msr S3_0_C4_C6_0, %0" : : "r"(x));
}
inline uint32_t gic_read_irq_ack()
{
uint32_t x;
__asm__ volatile("mrs %0, S3_0_C12_C12_0" : "=r"(x));
return x;
}
inline void
gic_write_end_of_irq(uint32_t x)
{
__asm__ volatile("msr S3_0_C12_C12_1, %0" : : "r"(x));
}
static inline uint32_t icc_sre_el1()
{
uint32_t x;
__asm__ volatile("mrs %0, S3_0_C12_C12_5" : "=r"(x));
return x;
}
static inline void w_icc_sre_el1(uint32_t x)
{
__asm__ volatile("msr S3_0_C12_C12_5, %0" : : "r"(x));
}
static void gicd_write(uint32_t off, uint32_t val)
{
*(volatile uint32_t*)(gicv3.gicd + off) = val;
}
static uint32_t gicd_read(uint32_t off)
{
return *(volatile uint32_t*)(gicv3.gicd + off);
}
static void gicr_write(uint32_t cpuid, uint32_t off, uint32_t val)
{
*(volatile uint32_t*)(gicv3.rdist_addrs[cpuid] + off) = val;
}
static uint32_t gicr_read(uint32_t cpuid, uint32_t off)
{
return *(volatile uint32_t*)(gicv3.rdist_addrs[cpuid] + off);
}
static void giccinit()
{
w_icc_igrpen1_el1(0);
w_icc_pmr_el1(0xff);
}
static void gicdinit()
{
gicd_write(D_CTLR, 0);
uint32_t typer = gicd_read(D_TYPER);
uint32_t lines = typer & 0x1f;
for (int i = 0; i < lines; i++)
gicd_write(D_IGROUPR(i), ~0);
}
static void gicrinit(uint32_t cpuid)
{
gicr_write(cpuid, R_CTLR, 0);
w_icc_sre_el1(icc_sre_el1() | 1);
gicr_write(cpuid, R_IGROUPR0, ~0);
gicr_write(cpuid, R_IGRPMODR0, 0);
uint32_t waker = gicr_read(cpuid, R_WAKER);
gicr_write(cpuid, R_WAKER, waker & ~(1 << 1));
while (gicr_read(cpuid, R_WAKER) & (1 << 2))
;
}
void gic_enable()
{
gicd_write(D_CTLR, (1 << 1));
w_icc_igrpen1_el1(1);
}
void gic_init()
{
gicv3.gicd = (char*)GICV3;
for (int i = 0; i < NR_CPU; i++) {
gicv3.rdist_addrs[i] = (char*)(GICV3_REDIST + (i) * 0x20000);
}
gicdinit();
}
void gicv3inithart(uint32_t cpu_id)
{
giccinit();
gicrinit(cpu_id);
gic_enable();
}
static void
gic_enable_int(uint32_t intid)
{
uint32_t is = gicd_read(D_ISENABLER(intid / 32));
is |= 1 << (intid % 32);
gicd_write(D_ISENABLER(intid / 32), is);
}
int gic_int_enabled(uint32_t intid)
{
uint32_t is = gicd_read(D_ISENABLER(intid / 32));
return is & (1 << (intid % 32));
}
static void
gic_clear_pending(uint32_t intid)
{
uint32_t ic = gicd_read(D_ICPENDR(intid / 32));
ic |= 1 << (intid % 32);
gicd_write(D_ICPENDR(intid / 32), ic);
}
static void
gic_set_prio0(uint32_t intid)
{
// set priority to 0
uint32_t p = gicd_read(D_IPRIORITYR(intid / 4));
p &= ~((uint32_t)0xff << (intid % 4 * 8)); // set prio 0
gicd_write(D_IPRIORITYR(intid / 4), p);
}
static void gic_set_target(uint32_t intid, uint32_t cpuid)
{
uint32_t itargetsr = gicd_read(D_ITARGETSR(intid / 4));
itargetsr &= ~((uint32_t)0xff << (intid % 4 * 8));
gicd_write(D_ITARGETSR(intid / 4), itargetsr | ((uint32_t)(1 << cpuid) << (intid % 4 * 8)));
}
static void
gicr_enable_int(uint32_t cpuid, uint32_t intid)
{
uint32_t is = gicr_read(cpuid, R_ISENABLER0);
is |= 1 << (intid % 32);
gicr_write(cpuid, R_ISENABLER0, is);
}
static void
gicr_clear_pending(uint32_t cpuid, uint32_t intid)
{
uint32_t ic = gicr_read(cpuid, R_ICPENDR0);
ic |= 1 << (intid % 32);
gicr_write(cpuid, R_ICPENDR0, ic);
}
static void
gicr_set_prio0(uint32_t cpuid, uint32_t intid)
{
uint32_t p = gicr_read(cpuid, R_IPRIORITYR(intid / 4));
p &= ~((uint32_t)0xff << (intid % 4 * 8)); // set prio 0
gicr_write(cpuid, R_IPRIORITYR(intid / 4), p);
}
void gic_setup_ppi(uint32_t cpuid, uint32_t intid)
{
gicr_set_prio0(cpuid, intid);
gicr_clear_pending(cpuid, intid);
gicr_enable_int(cpuid, intid);
}
void gic_setup_spi(uint32_t cpuid, uint32_t intid)
{
gic_set_prio0(intid);
gic_set_target(intid, cpuid);
gic_clear_pending(intid);
gic_enable_int(intid);
}
// irq from iar
int gic_iar_irq(uint32_t iar)
{
return iar & 0x3ff;
}
// interrupt acknowledge register:
// ask GIC what interrupt we should serve.
uint32_t gic_iar()
{
return gic_read_irq_ack();
}
// tell GIC we've served this IRQ.
void gic_eoi(uint32_t iar)
{
gic_write_end_of_irq(iar);
}

View File

@ -0,0 +1,140 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
/**
* @file gicv3_common_opa.h
* @brief gicv3 operation
* @version 1.0
* @author AIIT XUOS Lab
* @date 2024.05.07
*/
/*************************************************
File name: gicv3_common_opa.h
Description: gicv3 operation
Others:
History:
Author: AIIT XUOS Lab
Modification:
1. Rename file
*************************************************/
#pragma once
#include <stdbool.h>
#include <stdint.h>
#include <mmio_access.h>
//! @name Initialization
//@{
//! @brief Init interrupt handling.
//!
//! This function is intended to be called only by the primary CPU init code, so it will
//! only be called once during system bootup.
//!
//! Also inits the current CPU. You don't need to call gic_init_cpu() separately.
//!
//! @post The interrupt distributor and the current CPU interface are enabled. All interrupts
//! that were pending are cleared, and all interrupts are made secure (group 0).
void gic_init(void);
//! @name GIC Interrupt Distributor Functions
//@{
//! @brief Enable or disable the GIC Distributor.
//!
//! Enables or disables the GIC distributor passing both secure (group 0) and non-secure
//! (group 1) interrupts to the CPU interfaces.
//!
//! @param enableIt Pass true to enable or false to disable.
void gic_enable();
//! @brief Set the security mode for an interrupt.
//!
//! @param irqID The interrupt number.
//! @param isSecure Whether the interrupt is taken to secure mode.
void gic_set_irq_security(uint32_t irqID, bool isSecure);
//! @brief Enable or disable an interrupt.
//!
//! @param irqID The number of the interrupt to control.
//! @param isEnabled Pass true to enable or false to disable.
void gic_enable_irq(uint32_t irqID, bool isEnabled);
//! @brief Set whether a CPU will receive a particular interrupt.
//!
//! @param irqID The interrupt number.
//! @param cpuNumber The CPU number. The first CPU core is 0.
//! @param enableIt Whether to send the interrupt to the specified CPU. Pass true to enable
//! or false to disable.
void gic_set_cpu_target(uint32_t irqID, unsigned cpuNumber, bool enableIt);
//! @brief Set an interrupt's priority.
//!
//! @param irq_id The interrupt number.
//! @param priority The priority for the interrupt. In the range of 0 through 0xff, with
//! 0 being the highest priority.
void gic_set_irq_priority(uint32_t irq_id, uint32_t priority);
void gic_setup_spi(uint32_t cpuid, uint32_t intid);
void gic_setup_ppi(uint32_t cpuid, uint32_t intid);
void gicv3inithart(uint32_t cpu_id);
//! @brief Send a software generated interrupt to a specific CPU.
//!
//! @param irq_id The interrupt number to send.
//! @param target_list Each bit indicates a CPU to which the interrupt will be forwarded.
//! Bit 0 is CPU 0, bit 1 is CPU 1, and so on. If the value is 0, then the interrupt
//! will not be forwarded to any CPUs. This parameter is only used if @a filter_list
//! is set to #kGicSgiFilter_UseTargetList.
//! @param filter_list One of the enums of the #_gicd_sgi_filter enumeration. The selected
//! option determines which CPUs the interrupt will be sent to. If the value
//! is #kGicSgiFilter_UseTargetList, then the @a target_list parameter is used.
void gic_send_sgi(uint32_t irq_id, uint32_t target_list, uint32_t filter_list);
//@}
//! @name GIC CPU Interface Functions
//@{
//! @brief Enable or disable the interface to the GIC for the current CPU.
//!
//! @param enableIt Pass true to enable or false to disable.
void gic_cpu_enable(bool enableIt);
//! @brief Set the mask of which interrupt priorities the CPU will receive.
//!
//! @param priority The lowest priority that will be passed to the current CPU. Pass 0xff to
//! allow all priority interrupts to signal the CPU.
void gic_set_cpu_priority_mask(uint32_t priority);
//! @brief Acknowledge starting of interrupt handling and get the interrupt number.
//!
//! Normally, this function is called at the beginning of the IRQ handler. It tells the GIC
//! that you are starting to handle an interupt, and returns the number of the interrupt you
//! need to handle. After the interrupt is handled, you should call gic_write_end_of_irq()
//! to signal that the interrupt is completely handled.
//!
//! In some cases, a spurious interrupt might happen. One possibility is if another CPU handles
//! the interrupt. When a spurious interrupt occurs, the end of the interrupt should be indicated
//! but nothing else.
//!
//! @return The number for the highest priority interrupt available for the calling CPU. If
//! the return value is 1022 or 1023, a spurious interrupt has occurred.
uint32_t gic_read_irq_ack(void);
//! @brief Signal the end of handling an interrupt.
//!
//! @param irq_id The number of the interrupt for which handling has finished.
void gic_write_end_of_irq(uint32_t irq_id);
//@}
//! @}
////////////////////////////////////////////////////////////////////////////////
// EOF
////////////////////////////////////////////////////////////////////////////////

View File

@ -0,0 +1,59 @@
/*
*
* Copyright (C) 2002 ARM Limited, All Rights Reserved.
*
* This program 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.
*/
/**
* @file gicv3_registers.h
* @brief gicv3 registers
* @version 1.0
* @author AIIT XUOS Lab
* @date 2024.05.09
*/
/*************************************************
File name: gicv3_registers.c
Description: gicv3 registers
Others:
History:
Author: AIIT XUOS Lab
Modification:
1. Rename the file
*************************************************/
#pragma once
#include "memlayout.h"
// clang-format off
// interrupt controller GICv3
#define GICV3 MMIO_P2V_WO(0x08000000ULL)
#define GICV3_REDIST MMIO_P2V_WO(0x080a0000ULL)
#define D_CTLR 0x0
#define D_TYPER 0x4
#define D_IGROUPR(n) (0x80 + (uint64_t)(n) * 4)
#define D_ISENABLER(n) (0x100 + (uint64_t)(n) * 4)
#define D_ICENABLER(n) (0x180 + (uint64_t)(n) * 4)
#define D_ISPENDR(n) (0x200 + (uint64_t)(n) * 4)
#define D_ICPENDR(n) (0x280 + (uint64_t)(n) * 4)
#define D_IPRIORITYR(n) (0x400 + (uint64_t)(n) * 4)
#define D_ITARGETSR(n) (0x800 + (uint64_t)(n) * 4)
#define D_ICFGR(n) (0xc00 + (uint64_t)(n) * 4)
#define R_CTLR 0x0
#define R_WAKER 0x14
#define SGI_BASE 0x10000
#define R_IGROUPR0 (SGI_BASE + 0x80)
#define R_ISENABLER0 (SGI_BASE + 0x100)
#define R_ICENABLER0 (SGI_BASE + 0x180)
#define R_ICPENDR0 (SGI_BASE + 0x280)
#define R_IPRIORITYR(n) (SGI_BASE + 0x400 + (n) * 4)
#define R_ICFGR0 (SGI_BASE + 0xc00)
#define R_ICFGR1 (SGI_BASE + 0xc04)
#define R_IGRPMODR0 (SGI_BASE + 0xd00)
// clang-format on

View File

@ -0,0 +1,117 @@
/*
* Copyright (c) 2013, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o 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.
*
* o Neither the name of Freescale Semiconductor, Inc. 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.
*/
/*
* Portions Copyright (c) 2011-2012 ARM Ltd. All rights reserved.
*/
/**
* @file hard_spinlock.S
* @brief spinlock implementation
* @version 1.0
* @author AIIT XUOS Lab
* @date 2024.04.11
*/
/*************************************************
File name: hard_spinlock.S
Description: spinlock implementation
Others:
History:
Author: AIIT XUOS Lab
Modification:
*************************************************/
.arch armv8-a
.section ".text","ax"
.global cpu_get_current
#define UNLOCKED 0xFF
// int spinlock_lock(spinlock_t * lock, uint64_t timeout)
.global _spinlock_lock
.func _spinlock_lock
_spinlock_lock:
mov w2, #1
sevl
wfe
ldaxrb w1, [x0] // check if the spinlock is currently unlocked
cmp w1, #UNLOCKED
bne _spinlock_lock
mrs x1, mpidr_el1 // get our CPU ID
and x1, x1, #3
stxrb w2, w1, [x0]
cmp x2, #0
bne _spinlock_lock // check if the write was successful, if the write failed, start over
dmb ish // Ensure that accesses to shared resource have completed
mov x0, #0
ret
.endfunc
// void spinlock_unlock(spinlock_t * lock)
.global _spinlock_unlock
.func _spinlock_unlock
_spinlock_unlock:
mrs x1, mpidr_el1 // get our CPU ID
and x1, x1, #3
ldr w2, [x0]
cmp w1, w2
bne 1f //doesn't match,jump to 1
dmb ish
mov w1, #UNLOCKED
str w1, [x0]
dsb ish //Ensure that no instructions following the barrier execute until
// all memory accesses prior to the barrier have completed.
sevl // send event to wake up other cores waiting on spinlock
mov x0, #0 // return success
ret
1:
mov x0, #1 //doesn't match, so exit with failure
ret
.endfunc
.end

View File

@ -0,0 +1,68 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
/**
* @file exception_registers.h
* @brief exception registers
* @version 1.0
* @author AIIT XUOS Lab
* @date 2024.05.09
*/
static inline void w_vbar_el1(uint64_t x)
{
__asm__ volatile("msr vbar_el1, %0" : : "r"(x));
}
static inline uint64_t r_esr_el1()
{
uint64_t x;
__asm__ volatile("mrs %0, esr_el1" : "=r"(x));
return x;
}
static inline void w_esr_el1(uint64_t x)
{
__asm__ volatile("msr esr_el1, %0" : : "r"(x));
}
static inline uint64_t r_elr_el1()
{
uint64_t x;
__asm__ volatile("mrs %0, elr_el1" : "=r"(x));
return x;
}
static inline uint64_t r_far_el1()
{
uint64_t x;
__asm__ volatile("mrs %0, far_el1" : "=r"(x));
return x;
}
static inline uint64_t daif()
{
uint64_t x;
__asm__ volatile("mrs %0, daif" : "=r"(x));
return x;
}
// enable interrupts(irq)
static inline void intr_on()
{
__asm__ volatile("msr daifclr, #0xf" ::: "memory");
}
// disable interrupts(irq)
static inline void intr_off()
{
__asm__ volatile("msr daifset, #0xf" ::: "memory");
}

View File

@ -0,0 +1,110 @@
/**
* @file irq_numbers.c
* @brief irq numbers
* @version 3.0
* @author AIIT XUOS Lab
* @date 2023.08.25
*/
/*************************************************
File name: irq_numbers.c
Description: irq numbers
Others:
History:
1. Date: 2023-08-28
Author: AIIT XUOS Lab
Modification:
1. Add HW_NR_IRQS
*************************************************/
#if !defined(__IRQ_NUMBERS_H__)
#define __IRQ_NUMBERS_H__
#define HW_NR_IRQS NR_OK1028_INTRS
////////////////////////////////////////////////////////////////////////////////
// Definitions
////////////////////////////////////////////////////////////////////////////////
//! @brief i.MX6 interrupt numbers.
//!
//! This enumeration lists the numbers for all of the interrupts available on the i.MX6 series.
//! Use these numbers when specifying an interrupt to the GIC.
//!
//! The first 16 interrupts are special in that they are reserved for software interrupts generated
//! by the SWI instruction.
enum _ls_interrupts {
SW_INTERRUPT_0 = 0, //!< Software interrupt 0.
SW_INTERRUPT_1 = 1, //!< Software interrupt 1.
SW_INTERRUPT_2 = 2, //!< Software interrupt 2.
SW_INTERRUPT_3 = 3, //!< Software interrupt 3.
SW_INTERRUPT_4 = 4, //!< Software interrupt 4.
SW_INTERRUPT_5 = 5, //!< Software interrupt 5.
SW_INTERRUPT_6 = 6, //!< Software interrupt 6.
SW_INTERRUPT_7 = 7, //!< Software interrupt 7.
SW_INTERRUPT_8 = 8, //!< Software interrupt 8.
SW_INTERRUPT_9 = 9, //!< Software interrupt 9.
SW_INTERRUPT_10 = 10, //!< Software interrupt 10.
SW_INTERRUPT_11 = 11, //!< Software interrupt 11.
SW_INTERRUPT_12 = 12, //!< Software interrupt 12.
SW_INTERRUPT_13 = 13, //!< Software interrupt 13.
SW_INTERRUPT_14 = 14, //!< Software interrupt 14.
SW_INTERRUPT_15 = 15, //!< Software interrupt 15.
RSVD_INTERRUPT_16 = 16, //!< Reserved.
RSVD_INTERRUPT_17 = 17, //!< Reserved.
RSVD_INTERRUPT_18 = 18, //!< Reserved.
RSVD_INTERRUPT_19 = 19, //!< Reserved.
RSVD_INTERRUPT_20 = 20, //!< Reserved.
RSVD_INTERRUPT_21 = 21, //!< Reserved.
LS_INT_DEBUG_CC = 22, //!<(cluster-internal) COMMIRQ - Debug communications channel
LS_INT_PMU = 23, //!<(cluster-internal) PMUIRQ - Perfmon*
LS_INT_CTI = 24, //!<(cluster-internal) CTIIRQ - Cross-trigger interface*
LS_INT_VMI = 25, //!<(cluster-internal) VCPUMNTIRQ -Virtual maintenance interface*
LS_INT_WDOG = 28, //!< Watchdog timer
LS_INT_SEC_PHY_TIMER = 29, //!<(cluster-internal) CNTPSIRQ - EL1 Secure physical timer event*
LS_INT_NON_SEC_PHY_TIMER = 30, //!<(cluster-internal) CNTPNSIRQ - EL1 Non-secure physical timer event*
RSVD_INTERRUPT_31 = 31, //!< Reserved.
RSVD_INTERRUPT_32 = 32, //!< Reserved.
RSVD_INTERRUPT_33 = 33, //!< Reserved.
RSVD_INTERRUPT_34 = 34, //!< Reserved.
RSVD_INTERRUPT_35 = 35, //!< Reserved.
RSVD_INTERRUPT_36 = 36, //!< Reserved.
RSVD_INTERRUPT_37 = 37, //!< Reserved.
RSVD_INTERRUPT_38 = 38, //!< Reserved.
RSVD_INTERRUPT_39 = 39, //!< Reserved.
RSVD_INTERRUPT_40 = 40, //!< Reserved.
RSVD_INTERRUPT_41 = 41, //!< Reserved.
RSVD_INTERRUPT_42 = 42, //!< Reserved.
LS_INT_DUART1 = 64, // Logical OR of DUART1 interrupt requests.
LS_INT_I2C1_2 = 66, //!< I2C1 and I2C2 ORed
LS_INT_I2C3_4 = 67, //!< I2C3 and I2C4 ORed
LS_INT_GPIO1_2 = 68, //!< GPIO1 and GPIO2 ORed
LS_INT_GPIO3 = 69, //!< GPIO3
LS_INT_FLETIMER1 = 76, //!< ORed all Flextimer 1 interrupt signals
LS_INT_FLETIMER2 = 77, //!< ORed all Flextimer 2 interrupt signals
LS_INT_FLETIMER3 = 78, //!< ORed all Flextimer 3 interrupt signals
LS_INT_FLETIMER4 = 79, //!< ORed all Flextimer 4 interrupt signals
LS_INT_I2C5_6 = 106, //!< I2C5 and I2C6 ORed
LS_INT_I2C7_8 = 107, //!< I2C7 and I2C8 ORed
LS_INT_USB3_1 = 112, //!< USB1 ORed INT
LS_INT_USB3_2 = 113, //!< USB2 ORed INT
LS_INT_LPUART1 = 264, //!< LPUART1 interrupt request.
LS_INT_LPUART2 = 265, //!< LPUART1 interrupt request.
LS_INT_LPUART3 = 266, //!< LPUART1 interrupt request.
LS_INT_LPUART4 = 267, //!< LPUART1 interrupt request.
LS_INT_LPUART5 = 268, //!< LPUART1 interrupt request.
LS_INT_LPUART6 = 269, //!< LPUART1 interrupt request.
NR_OK1028_INTRS,
};
#endif //__IRQ_NUMBERS_H__

View File

@ -0,0 +1,100 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
/**
* @file trap.c
* @brief trap interface of hardkernel
* @version 1.0
* @author AIIT XUOS Lab
* @date 2023.05.06
*/
/*************************************************
File name: trap.c
Description: trap interface of hardkernel
Others:
History:
Author: AIIT XUOS Lab
Modification:
1. first version
*************************************************/
#include <stdint.h>
#include "assert.h"
#include "core.h"
#include "exception_registers.h"
#include "multicores.h"
#include "syscall.h"
#include "task.h"
extern void dabort_handler(struct trapframe* r);
extern void iabort_handler(struct trapframe* r);
void kernel_abort_handler(struct trapframe* tf)
{
uint64_t esr = r_esr_el1();
switch ((esr >> 0x1A) & 0x3F) {
case 0b100100:
case 0b100101:
dabort_handler(tf);
break;
case 0b100000:
case 0b100001:
iabort_handler(tf);
break;
default: {
uint64_t ec = (esr >> 26) & 0x3f;
uint64_t iss = esr & 0x1ffffff;
ERROR("esr: %016lx %016lx %016lx\n", esr, ec, iss);
ERROR("elr = %016lx far = %016lx\n", r_elr_el1(), r_far_el1());
ERROR("Current Task: %s.\n", cur_cpu()->task->name);
panic("Unimplemented Error Occured.\n");
}
}
panic("Return from abort handler.\n");
}
void kernel_intr_handler(struct trapframe* tf)
{
panic("Intr at kernel mode should never happen by design.\n");
}
extern void context_switch(struct context**, struct context*);
void syscall_arch_handler(struct trapframe* tf)
{
uint64_t esr = r_esr_el1();
uint64_t ec = (esr >> 0x1A) & 0x3F;
w_esr_el1(0);
switch (ec) {
case 0B010101:
software_irq_dispatch(tf);
break;
case 0b100100:
case 0b100101:
dabort_handler(tf);
break;
case 0b100000:
case 0b100001:
iabort_handler(tf);
break;
default: {
ERROR("USYSCALL: unexpected ec: %016lx", esr);
ERROR(" elr = %016lx far = %016lx\n", r_elr_el1(), r_far_el1());
// kill error task
xizi_enter_kernel();
assert(cur_cpu()->task != NULL);
sys_exit(cur_cpu()->task);
context_switch(&cur_cpu()->task->thread_context.context, cur_cpu()->scheduler);
panic("dabort end should never be reashed.\n");
}
}
}

View File

@ -0,0 +1,137 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
/**
* @file trap_common.c
* @brief trap interface of hardkernel
* @version 1.0
* @author AIIT XUOS Lab
* @date 2023.05.06
*/
/*************************************************
File name: trap_common.c
Description: trap interface of hardkernel
Others:
History:
Author: AIIT XUOS Lab
Modification:
1. first version
*************************************************/
#include <string.h>
#include "core.h"
#include "cortex_a72.h"
#include "exception_registers.h"
#include "gicv3_common_opa.h"
#include "trap_common.h"
#include "log.h"
#include "multicores.h"
static struct XiziTrapDriver xizi_trap_driver;
void panic(char* s)
{
KPrintf("panic: %s\n", s);
for (;;)
;
}
extern void alltraps();
static void _sys_irq_init(int cpu_id)
{
// primary core init intr
xizi_trap_driver.switch_hw_irqtbl((uintptr_t*)alltraps);
if (cpu_id == 0) {
gic_init();
}
gicv3inithart(cpu_id);
}
static void _cpu_irq_enable(void)
{
intr_on();
}
static void _cpu_irq_disable(void)
{
intr_off();
}
static void _single_irq_enable(int irq, int cpu, int prio)
{
gic_setup_ppi((uint32_t)cpu, (uint32_t)irq);
}
static void _single_irq_disable(int irq, int cpu)
{
return;
}
static inline uintptr_t* _switch_hw_irqtbl(uintptr_t* new_tbl_base)
{
w_vbar_el1((uint64_t)new_tbl_base);
return NULL;
}
static void _bind_irq_handler(int irq, irq_handler_t handler)
{
xizi_trap_driver.sw_irqtbl[irq].handler = handler;
}
static uint32_t _hw_before_irq()
{
uint32_t iar = gic_read_irq_ack();
return iar;
}
static uint32_t _hw_cur_int_num(uint32_t int_info)
{
return int_info & 0x3FF;
}
static void _hw_after_irq(uint32_t int_info)
{
gic_write_end_of_irq(int_info);
}
int _cur_cpu_id()
{
return cpu_get_current();
}
static struct XiziTrapDriver xizi_trap_driver = {
.sys_irq_init = _sys_irq_init,
.cur_cpu_id = _cur_cpu_id,
.cpu_irq_enable = _cpu_irq_enable,
.cpu_irq_disable = _cpu_irq_disable,
.single_irq_enable = _single_irq_enable,
.single_irq_disable = _single_irq_disable,
.switch_hw_irqtbl = _switch_hw_irqtbl,
.bind_irq_handler = _bind_irq_handler,
.hw_before_irq = _hw_before_irq,
.hw_cur_int_num = _hw_cur_int_num,
.hw_after_irq = _hw_after_irq,
};
struct XiziTrapDriver* hardkernel_intr_init(struct TraceTag* hardkernel_tag)
{
xizi_trap_driver.sys_irq_init(0);
xizi_trap_driver.cpu_irq_disable();
return &xizi_trap_driver;
}

View File

@ -0,0 +1,225 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
/**
* @file trampoline.S
* @brief trap in and out code
* @version 1.0
* @author AIIT XUOS Lab
* @date 2024-04-22
*/
/*************************************************
File name: trampoline.S
Description: trap in and out code
Others:
History:
1. Date: 2024-04-22
Author: AIIT XUOS Lab
Modification:
1. first version
*************************************************/
#include "memlayout.h"
#include "core.h"
.macro savereg
// make room to save registers.
sub sp, sp, #272
// save the registers.
stp x0, x1, [sp, #16 * 0]
stp x2, x3, [sp, #16 * 1]
stp x4, x5, [sp, #16 * 2]
stp x6, x7, [sp, #16 * 3]
stp x8, x9, [sp, #16 * 4]
stp x10, x11, [sp, #16 * 5]
stp x12, x13, [sp, #16 * 6]
stp x14, x15, [sp, #16 * 7]
stp x16, x17, [sp, #16 * 8]
stp x18, x19, [sp, #16 * 9]
stp x20, x21, [sp, #16 * 10]
stp x22, x23, [sp, #16 * 11]
stp x24, x25, [sp, #16 * 12]
stp x26, x27, [sp, #16 * 13]
stp x28, x29, [sp, #16 * 14]
mrs x9, elr_el1
mrs x10, spsr_el1
add x11, sp, #272
stp x30, x9, [sp, #16 * 15]
stp x10, x11, [sp, #16 * 16]
.endm
.macro restorereg
ldp x30, x9, [sp, #16 * 15]
ldp x10, x11, [sp, #16 * 16]
msr elr_el1, x9
msr spsr_el1, x10
ldp x0, x1, [sp, #16 * 0]
ldp x2, x3, [sp, #16 * 1]
ldp x4, x5, [sp, #16 * 2]
ldp x6, x7, [sp, #16 * 3]
ldp x8, x9, [sp, #16 * 4]
ldp x10, x11, [sp, #16 * 5]
ldp x12, x13, [sp, #16 * 6]
ldp x14, x15, [sp, #16 * 7]
ldp x16, x17, [sp, #16 * 8]
ldp x18, x19, [sp, #16 * 9]
ldp x20, x21, [sp, #16 * 10]
ldp x22, x23, [sp, #16 * 11]
ldp x24, x25, [sp, #16 * 12]
ldp x26, x27, [sp, #16 * 13]
ldp x28, x29, [sp, #16 * 14]
add sp, sp, #272
.endm
.macro usavereg
sub sp, sp, #272
stp x0, x1, [sp, #16 * 0]
stp x2, x3, [sp, #16 * 1]
stp x4, x5, [sp, #16 * 2]
stp x6, x7, [sp, #16 * 3]
stp x8, x9, [sp, #16 * 4]
stp x10, x11, [sp, #16 * 5]
stp x12, x13, [sp, #16 * 6]
stp x14, x15, [sp, #16 * 7]
stp x16, x17, [sp, #16 * 8]
stp x18, x19, [sp, #16 * 9]
stp x20, x21, [sp, #16 * 10]
stp x22, x23, [sp, #16 * 11]
stp x24, x25, [sp, #16 * 12]
stp x26, x27, [sp, #16 * 13]
stp x28, x29, [sp, #16 * 14]
mrs x9, elr_el1
mrs x10, spsr_el1
mrs x11, sp_el0
stp x30, x9, [sp, #16 * 15]
stp x10, x11, [sp, #16 * 16]
.endm
.macro urestorereg
ldp x30, x9, [sp, #16 * 15]
ldp x10, x11, [sp, #16 * 16]
msr elr_el1, x9
msr spsr_el1, x10
msr sp_el0, x11
ldp x0, x1, [sp, #16 * 0]
ldp x2, x3, [sp, #16 * 1]
ldp x4, x5, [sp, #16 * 2]
ldp x6, x7, [sp, #16 * 3]
ldp x8, x9, [sp, #16 * 4]
ldp x10, x11, [sp, #16 * 5]
ldp x12, x13, [sp, #16 * 6]
ldp x14, x15, [sp, #16 * 7]
ldp x16, x17, [sp, #16 * 8]
ldp x18, x19, [sp, #16 * 9]
ldp x20, x21, [sp, #16 * 10]
ldp x22, x23, [sp, #16 * 11]
ldp x24, x25, [sp, #16 * 12]
ldp x26, x27, [sp, #16 * 13]
ldp x28, x29, [sp, #16 * 14]
add sp, sp, #272
.endm
.global alltraps
.balign 0x800
alltraps:
// Current EL with sp0
b .
.balign 0x80
b .
.balign 0x80
b .
.balign 0x80
b .
// Current EL with spx
.balign 0x80
b el1sync
.balign 0x80
b el1irq
.balign 0x80
b .
.balign 0x80
b .
// Lower EL using aarch64
.balign 0x80
b el0sync
.balign 0x80
b el0irq
.balign 0x80
b .
.balign 0x80
b .
// Lower EL using aarch32
.balign 0x80
b .
.balign 0x80
b .
.balign 0x80
b .
.balign 0x80
b .
el1sync:
msr daifset, #0xf
savereg
mov x0, sp
bl kernel_abort_handler
b .
el1irq:
msr daifset, #0xf
usavereg
mov x0, sp
bl intr_irq_dispatch
urestorereg
eret
el0sync:
msr daifset, #0xf
usavereg
mov x0, sp
bl syscall_arch_handler
urestorereg
eret
el0irq:
msr daifset, #0xf
usavereg
mov x0, sp
bl intr_irq_dispatch
.global trap_return
trap_return:
urestorereg
eret

View File

@ -59,7 +59,7 @@ __attribute__((optimize("O0"))) void spinlock_init(struct spinlock* lock, char*
}
extern int _spinlock_lock(struct spinlock* lock, uint32_t timeout);
void _spinlock_unlock(struct spinlock* lock);
extern void _spinlock_unlock(struct spinlock* lock);
__attribute__((optimize("O0"))) void spinlock_lock(struct spinlock* lock)
{

View File

@ -32,12 +32,11 @@ Modification:
#include <stdbool.h>
#include <stdint.h>
#include "actracer.h"
#include "core.h"
#include "irq_numbers.h"
#include "memlayout.h"
#include "actracer.h"
#define NR_IRQS HW_NR_IRQS
#define NR_MODE_STACKS 4
@ -65,7 +64,7 @@ struct XiziTrapDriver {
void (*single_irq_enable)(int irq, int cpu, int prio);
void (*single_irq_disable)(int irq, int cpu);
uint32_t* (*switch_hw_irqtbl)(uint32_t*);
uintptr_t* (*switch_hw_irqtbl)(uintptr_t*);
void (*bind_irq_handler)(int, irq_handler_t);
/* check if no if interruptable */

View File

@ -1,4 +1,10 @@
ifneq ($(findstring $(BOARD), ok1028a-c), )
SRC_DIR := armv8-a
endif
ifneq ($(findstring $(BOARD), imx6q-sabrelite zynq7000-zc702), )
SRC_DIR := armv7-a
endif
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,3 @@
SRC_DIR := cortex-a72
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,3 @@
SRC_FILES := bootmmu.c mmu.c pagetable_attr.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,139 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
/**
* @file bootmmu.c
* @brief build pagetable and enable mmu in boot time
* @version 1.0
* @author AIIT XUOS Lab
* @date 2024.04.26
*/
/*************************************************
File name: bootmmu.c
Description: build pagetable and enable mmu in boot time
Others:
History:
Author: AIIT XUOS Lab
Modification:
1. first version
*************************************************/
#include "core.h"
#include "memlayout.h"
#include "mmio_access.h"
#include "mmu.h"
#include "pagetable.h"
#include "registers.h"
#include <stdint.h>
#include <string.h>
extern uint64_t kernel_data_end[];
extern uint64_t kernel_data_begin[];
// clang-format off
#define L2_TYPE_TAB 2
#define L2_PTE_VALID 1
#define L3_TYPE_TAB 2
#define L3_PTE_VALID 1
#define L4_TYPE_PAGE (3 << 0)
#define L4_PTE_DEV ((0b00) << 2) // Device memory
#define L4_PTE_NORMAL ((0b01) << 2) // Device memory
#define L4_PTE_AF (1 << 10) // Data Access Permissions
#define L4_PTE_PXN (1UL << 53) // Privileged eXecute Never
#define L4_PTE_UXN (1UL << 54) // Unprivileged(user) eXecute Never
#define L4_PTE_XN (PTE_PXN|PTE_UXN) // eXecute Never
#define IDX_MASK (0b111111111)
#define L3_PDE_INDEX(idx) ((idx << LEVEL3_PDE_SHIFT) & L3_IDX_MASK)
// clang-format on
uint64_t boot_l2pgdir[NUM_LEVEL2_PDE] __attribute__((aligned(0x1000))) = { 0 };
uint64_t boot_dev_l3pgdir[NUM_LEVEL3_PDE] __attribute__((aligned(0x1000))) = { 0 };
uint64_t boot_virt_dev_l3pgdir[NUM_LEVEL3_PDE] __attribute__((aligned(0x1000))) = { 0 };
uint64_t boot_kern_l3pgdir[NUM_LEVEL3_PDE] __attribute__((aligned(0x1000))) = { 0 };
uint64_t boot_virt_kern_l3pgdir[NUM_LEVEL3_PDE] __attribute__((aligned(0x1000))) = { 0 };
uint64_t boot_dev_l4pgdirs[NUM_LEVEL3_PDE][NUM_LEVEL4_PTE] __attribute__((aligned(0x1000))) = { 0 };
uint64_t boot_kern_l4pgdirs[NUM_LEVEL3_PDE][NUM_LEVEL4_PTE] __attribute__((aligned(0x1000))) = { 0 };
static void build_boot_pgdir()
{
uint64_t dev_phy_mem_base = DEV_PHYMEM_BASE;
// dev mem
boot_l2pgdir[(dev_phy_mem_base >> LEVEL2_PDE_SHIFT) & IDX_MASK] = (uint64_t)boot_dev_l3pgdir | L2_TYPE_TAB | L2_PTE_VALID;
boot_l2pgdir[(MMIO_P2V_WO(dev_phy_mem_base) >> LEVEL2_PDE_SHIFT) & IDX_MASK] = (uint64_t)boot_dev_l3pgdir | L2_TYPE_TAB | L2_PTE_VALID;
uint64_t cur_mem_paddr = ALIGNDOWN((uint64_t)DEV_PHYMEM_BASE, PAGE_SIZE);
for (size_t i = 0; i < NUM_LEVEL3_PDE; i++) {
boot_dev_l3pgdir[i] = (uint64_t)boot_dev_l4pgdirs[i] | L3_TYPE_TAB | L3_PTE_VALID;
for (size_t j = 0; j < NUM_LEVEL4_PTE; j++) {
boot_dev_l4pgdirs[i][j] = cur_mem_paddr | L4_TYPE_PAGE | L4_PTE_DEV | L4_PTE_AF | L4_PTE_XN;
cur_mem_paddr += PAGE_SIZE;
}
}
// identical mem
boot_l2pgdir[(PHY_MEM_BASE >> LEVEL2_PDE_SHIFT) & IDX_MASK] = (uint64_t)boot_kern_l3pgdir | L2_TYPE_TAB | L2_PTE_VALID;
boot_l2pgdir[(P2V_WO(PHY_MEM_BASE) >> LEVEL2_PDE_SHIFT) & IDX_MASK] = (uint64_t)boot_kern_l3pgdir | L2_TYPE_TAB | L2_PTE_VALID;
cur_mem_paddr = ALIGNDOWN((uint64_t)PHY_MEM_BASE, PAGE_SIZE);
for (size_t i = 0; i < NUM_LEVEL3_PDE; i++) {
boot_kern_l3pgdir[i] = (uint64_t)boot_kern_l4pgdirs[i] | L3_TYPE_TAB | L3_PTE_VALID;
for (size_t j = 0; j < NUM_LEVEL4_PTE; j++) {
boot_kern_l4pgdirs[i][j] = cur_mem_paddr | L4_TYPE_PAGE | L4_PTE_NORMAL | L4_PTE_AF;
cur_mem_paddr += PAGE_SIZE;
}
}
}
static void load_boot_pgdir()
{
uint64_t val;
TTBR0_W((uintptr_t)boot_l2pgdir);
TTBR1_W(0);
TCR_W(TCR_VALUE);
MAIR_W((MT_DEVICE_nGnRnE << (8 * AI_DEVICE_nGnRnE_IDX)) | (MT_NORMAL_NC << (8 * AI_NORMAL_NC_IDX)));
// Enable paging using read/modify/write
SCTLR_R(val);
val |= (1 << 0); // EL1 and EL0 stage 1 address translation enabled.
SCTLR_W(val);
// flush all TLB
DSB();
CLEARTLB(0);
ISB();
}
extern void main(void);
static bool _bss_inited = false;
void bootmain()
{
build_boot_pgdir();
load_boot_pgdir();
__asm__ __volatile__("add sp, sp, %0" ::"r"(KERN_MEM_BASE - PHY_MEM_BASE));
if (!_bss_inited) {
memset(&kernel_data_begin, 0x00, (size_t)((uint64_t)kernel_data_end - (uint64_t)kernel_data_begin));
_bss_inited = true;
}
main();
}

View File

@ -0,0 +1,105 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
/**
* @file mmu.h
* @brief mmu related configure and registers
* @version 1.0
* @author AIIT XUOS Lab
* @date 2024-04-26
*/
/*************************************************
File name: mmu.h
Description: mmu related configure and registers
Others:
History:
Author: AIIT XUOS Lab
Modification:
1. first version
*************************************************/
#pragma once
#include <stdint.h>
#include "memlayout.h"
// #define TCR_SH1_INNER (0b11 << 28)
// #define TCR_ORGN1_IRGN1_WRITEBACK_WRITEALLOC ((0b01 << 26) | (0b01 << 24))
// #define TCR_SH0_INNER (0b11 << 12)
// #define TCR_ORGN0_IRGN0_WRITEBACK_WRITEALLOC ((0b01 << 10) | (0b01 << 8))
#define TCR_IPS (0 << 0)
#define TCR_TG1_4K (0b10 << 30)
#define TCR_TOSZ (0b11001 << 0)
#define TCR_T1SZ (0b11001 << 16)
#define TCR_TG0_4K (0 << 14)
#define TCR_VALUE \
(TCR_IPS | TCR_TG1_4K | TCR_TG0_4K | TCR_TOSZ | TCR_T1SZ)
enum AccessPermission {
AccessPermission_NoAccess = 0,
AccessPermission_KernelOnly = 1, // EL1
AccessPermission_Reserved = 2,
AccessPermission_KernelUser = 3, // EL1&EL0
};
void GetDevPteAttr(uintptr_t* attr);
void GetUsrPteAttr(uintptr_t* attr);
void GetUsrDevPteAttr(uintptr_t* attr);
void GetKernPteAttr(uintptr_t* attr);
void GetPdeAttr(uintptr_t* attr);
/*
Enable MMU, cache, write buffer, etc.
*/
#define SCTLR_R(val) __asm__ volatile("mrs %0, sctlr_el1" : "=r"(val))
#define SCTLR_W(val) __asm__ volatile("msr sctlr_el1, %0" ::"r"(val))
/*
Read and write mmu pagetable register base addr
*/
#define TTBR0_R(val) __asm__ volatile("mrs %0, ttbr0_el1" : "=r"(val))
#define TTBR0_W(val) __asm__ volatile("msr ttbr0_el1, %0" ::"r"(val))
/*
Read and write mmu pagetable register base addr
*/
#define TTBR1_R(val) __asm__ volatile("mrs %0, ttbr1_el1" : "=r"(val))
#define TTBR1_W(val) __asm__ volatile("msr ttbr1_el1, %0" ::"r"(val))
/*
Translation Control RegisterTCR
*/
#define TCR_R(val) __asm__ volatile("mrs %0, tcr_el1" : "=r"(val))
#define TCR_W(val) __asm__ volatile("msr tcr_el1, %0" ::"r"(val))
#define MAIR_R(val) __asm__ volatile("mrs %0, mair_el1" : "=r"(val))
#define MAIR_W(val) __asm__ volatile("msr mair_el1, %0" ::"r"(val))
/*
Flush TLB when loading a new page table.
@note If nG is not set in the pte attribute, process switching need flush tlb.
*/
#define CLEARTLB(val) __asm__ volatile("tlbi vmalle1")
/*
When nG is set in the pte attribute, the process is assigned an ASID, which is stored in the lower 8 bits of the CONTEXTIDR register.
When the process switches, the flush TLB is no longer required anymore.
*/
#define CONTEXTIDR_R(val) __asm__ volatile("mrs %0, contextidr_el1" : "=r"(val))
#define CONTEXTIDR_W(val) __asm__ volatile("msr contextidr_el1, %0" ::"r"(val))
#ifndef __ASSEMBLER__
#include <stdint.h>
__attribute__((always_inline)) static inline uint64_t v2p(void* a) { return ((uint64_t)(a)) - KERN_MEM_BASE; }
__attribute__((always_inline)) static inline void* p2v(uint64_t a) { return (void*)((a) + KERN_MEM_BASE); }
#endif

View File

@ -0,0 +1,91 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
/**
* @file mmu.c
* @brief mmu operations
* @version 1.0
* @author AIIT XUOS Lab
* @date 2024.04.26
*/
/*************************************************
File name: mmu.c
Description: mmu operations
Others:
History:
Author: AIIT XUOS Lab
Modification:
1. first version
*************************************************/
#include <string.h>
#include "mmu.h"
#include "cache_common_ope.h"
#include "mmu_common.h"
#include "trap_common.h"
// extern struct MmuCommonDone mmu_common_done;
static struct MmuDriverRightGroup right_group;
void load_pgdir(uintptr_t pgdir_paddr)
{
/* get cache driver */
struct ICacheDone* p_icache_done = AchieveResource(&right_group.icache_driver_tag);
struct DCacheDone* p_dcache_done = AchieveResource(&right_group.dcache_driver_tag);
TTBR0_W((uint64_t)pgdir_paddr);
CLEARTLB(0);
p_icache_done->invalidateall();
p_dcache_done->flushall();
}
__attribute__((always_inline)) inline static void _tlb_flush(uintptr_t va)
{
__asm__ volatile("tlbi vae1is, %0" ::"r"(va));
}
static void tlb_flush_range(uintptr_t vstart, int len)
{
uintptr_t vaddr = vstart;
uintptr_t vend = vaddr + len;
for (; vaddr < vend; vaddr += PAGE_SIZE) {
_tlb_flush(vaddr);
}
}
static void tlb_flush_all()
{
CLEARTLB(0);
}
static struct MmuCommonDone mmu_common_done = {
.MmuDevPteAttr = GetDevPteAttr,
.MmuPdeAttr = GetPdeAttr,
.MmuUsrPteAttr = GetUsrPteAttr,
.MmuUsrDevPteAttr = GetUsrDevPteAttr,
.MmuKernPteAttr = GetKernPteAttr,
.LoadPgdir = load_pgdir,
.TlbFlushAll = tlb_flush_all,
.TlbFlush = tlb_flush_range,
};
struct MmuCommonDone* hardkernel_mmu_init(struct TraceTag* hardkernel_tag, char* icache_name, char* dcache_name)
{
/* init right group for mmu driver */
AchieveResourceTag(&right_group.icache_driver_tag, hardkernel_tag, icache_name);
AchieveResourceTag(&right_group.dcache_driver_tag, hardkernel_tag, dcache_name);
return &mmu_common_done;
}

View File

@ -0,0 +1,85 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
/**
* @file memlayout.h
* @brief virtual memory and physical memory layout
* @version 1.0
* @author AIIT XUOS Lab
* @date 2024-04-25
*/
/*************************************************
File name: memlayout.h
Description: virtual memory and physical memory layout
Others:
History:
Author: AIIT XUOS Lab
Modification:
1. first version
*************************************************/
#pragma once
// Memory layout
// clang-format off
#define ARCH_BIT 64
/* A72 physical memory layout */
#define PHY_MEM_BASE (0x0000000040000000ULL)
#define PHY_USER_FREEMEM_BASE (0x0000000046000000ULL)
#define PHY_USER_FREEMEM_TOP (0x0000000048000000ULL)
#define PHY_MEM_STOP (0x0000000048000000ULL)
/* PTE-PAGE_SIZE */
#define LEVEL4_PTE_SHIFT 12
#define LEVEL4_PTE_SIZE (1 << LEVEL4_PTE_SHIFT)
/* PDE-SECTION_SIZE */
#define LEVEL3_PDE_SHIFT 21
#define LEVEL3_PDE_SIZE (1 << LEVEL3_PDE_SHIFT)
#define LEVEL2_PDE_SHIFT 30
#define LEVEL2_PDE_SIZE (1 << LEVEL2_PDE_SHIFT)
#define LEVEL1_PTE_SHIFT 39
#define NUM_LEVEL2_PDE (1 << (LEVEL1_PTE_SHIFT - LEVEL2_PDE_SHIFT))
#define NUM_LEVEL3_PDE (1 << (LEVEL2_PDE_SHIFT - LEVEL3_PDE_SHIFT)) // how many PDE in a PT
#define NUM_LEVEL4_PTE (1 << (LEVEL3_PDE_SHIFT - LEVEL4_PTE_SHIFT)) // how many PTE in a PT
#define NUM_TOPLEVEL_PDE NUM_LEVEL2_PDE
#define PAGE_SIZE LEVEL4_PTE_SIZE
#define MAX_NR_FREE_PAGES ((PHY_MEM_STOP - PHY_MEM_BASE) >> LEVEL4_PTE_SHIFT)
/* Deivce memory layout */
#define DEV_PHYMEM_BASE (0x0000000000000000ULL)
#define DEV_VRTMEM_BASE (0x0000004000000000ULL)
#define DEV_MEM_SZ (0x0000000010000000ULL)
/* User memory layout */
#define USER_STACK_SIZE PAGE_SIZE
#define USER_MEM_BASE (0x0000000000000000ULL)
#define USER_MEM_TOP DEV_VRTMEM_BASE
#define USER_IPC_SPACE_BASE (0x0000003000000000ULL)
#define USER_IPC_USE_ALLOCATOR_WATERMARK (0x0000003000010000ULL)
#define USER_IPC_SPACE_TOP (USER_IPC_SPACE_BASE + 0x10000000ULL)
/* Kernel memory layout */
#define KERN_MEM_BASE (0x0000006040000000ULL) // First kernel virtual address
#define KERN_OFFSET (KERN_MEM_BASE - PHY_MEM_BASE)
#define V2P(a) (((uint64_t)(a)) - KERN_OFFSET)
#define P2V(a) ((void *)(((char *)(a)) + KERN_OFFSET))
#define V2P_WO(x) ((x) - KERN_OFFSET) // same as V2P, but without casts
#define P2V_WO(x) ((x) + KERN_OFFSET) // same as P2V, but without casts
// clang-format on

View File

@ -0,0 +1,76 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
/**
* @file pagetable_attr.c
* @brief mmu entry attributes
* @version 1.
* @author AIIT XUOS Lab
* @date 2023.04.26
*/
/*************************************************
File name: pagetable_attr.c
Description: mmu entry attributes
Others:
History:
Author: AIIT XUOS Lab
Modification:
1. first version
*************************************************/
#include "mmu.h"
#include "mmu_common.h"
// clang-format off
#define ARMV8_PTE_ATTR_MASK(attr) (((attr) & 0b111) << 2)
#define ARMV8_PTE_DEVICE ARMV8_PTE_ATTR_MASK(0x0)
#define ARMV8_PTE_NORMAL ARMV8_PTE_ATTR_MASK(0x1)
#define ARMV8_PTE_AP(ap) (((ap) & 0b11) << 6)
#define ARMV8_PTE_AP_U ARMV8_PTE_AP(0x01)
#define ARMV8_PTE_AP_K ARMV8_PTE_AP(0x00)
#define ARMV8_PTE_AP_RO ARMV8_PTE_AP(0b10)
#define ARMV8_PTE_AP_RW ARMV8_PTE_AP(0b00)
#define ARMV8_PTE_AF (0x1 << 10)
#define ARMV8_PTE_PXN (1ULL << 53) // Privileged eXecute Never
#define ARMV8_PTE_UXN (1ULL << 54) // Unprivileged(user) eXecute Never
#define ARMV8_PTE_XN (ARMV8_PTE_PXN | ARMV8_PTE_UXN)
#define ARMV8_PTE_VALID (0b11 << 0)
#define ARMV8_PDE_VALID (0b11 << 0)
// clang-format on
void GetUsrPteAttr(uintptr_t* attr)
{
*attr = ARMV8_PTE_AP_U | ARMV8_PTE_AP_RW | ARMV8_PTE_AF | ARMV8_PTE_NORMAL | ARMV8_PTE_VALID;
}
void GetUsrDevPteAttr(uintptr_t* attr)
{
*attr = ARMV8_PTE_AP_U | ARMV8_PTE_AP_RW | ARMV8_PTE_AF | ARMV8_PTE_DEVICE | ARMV8_PTE_XN | ARMV8_PTE_VALID;
}
void GetDevPteAttr(uintptr_t* attr)
{
*attr = ARMV8_PTE_AP_K | ARMV8_PTE_AP_RW | ARMV8_PTE_AF | ARMV8_PTE_DEVICE | ARMV8_PTE_XN | ARMV8_PTE_VALID;
}
void GetKernPteAttr(uintptr_t* attr)
{
*attr = ARMV8_PTE_AP_K | ARMV8_PTE_AP_RW | ARMV8_PTE_AF | ARMV8_PTE_NORMAL | ARMV8_PTE_VALID;
}
void GetPdeAttr(uintptr_t* attr)
{
*attr = ARMV8_PDE_VALID;
}

View File

@ -19,8 +19,7 @@ struct MmuDriverRightGroup {
struct TraceTag intr_driver_tag;
};
struct MmuCommonDone
{
struct MmuCommonDone {
void (*MmuDevPteAttr)(uintptr_t* attr);
void (*MmuPdeAttr)(uintptr_t* attr);
void (*MmuUsrPteAttr)(uintptr_t* attr);

View File

@ -1,4 +1,10 @@
# The following three platforms support compatiable instructions.
ifneq ($(findstring $(BOARD), ok1028a-c), )
SRC_DIR := armv8-a
endif
ifneq ($(findstring $(BOARD), imx6q-sabrelite zynq7000-zc702), )
SRC_DIR := armv7-a
endif
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,4 @@
# The following three platforms support compatiable instructions.
SRC_DIR := cortex-a72
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,3 @@
SRC_DIR := uart_io_for_$(BOARD)
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,3 @@
SRC_FILES := uart.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,29 @@
#pragma once
#include "memlayout.h"
#include "mmio_access.h"
#define UART0_BASE (0x09000000ULL)
#define UART0_REG(reg) ((volatile uint32_t*)(MMIO_P2V_WO(UART0_BASE + reg)))
// the UART control registers.
// pl011
#define DR 0x00
#define FR 0x18
#define FR_RXFE (1 << 4) // recieve fifo empty
#define FR_TXFF (1 << 5) // transmit fifo full
#define FR_RXFF (1 << 6) // recieve fifo full
#define FR_TXFE (1 << 7) // transmit fifo empty
#define IBRD 0x24
#define FBRD 0x28
#define LCRH 0x2c
#define LCRH_FEN (1 << 4)
#define LCRH_WLEN_8BIT (3 << 5)
#define CR 0x30
#define IMSC 0x38
#define INT_RX_ENABLE (1 << 4)
#define INT_TX_ENABLE (1 << 5)
#define ICR 0x44
#define UART_READ_REG(reg) (*(UART0_REG(reg)))
#define UART_WRITE_REG(reg, v) (*(UART0_REG(reg)) = (v))

View File

@ -0,0 +1,128 @@
//
// low-level driver routines for pl011 UART.
//
#include "uart.h"
#include "actracer.h"
#include "uart_common_ope.h"
// the UART control registers are memory-mapped
// at address UART0. this macro returns the
// address of one of the registers.
// the transmit output buffer.
#define UART_TX_BUF_SIZE 32
static char uart_tx_buf[UART_TX_BUF_SIZE];
uint64_t uart_tx_w; // write next to uart_tx_buf[uart_tx_w % UART_TX_BUF_SIZE]
uint64_t uart_tx_r; // read next from uart_tx_buf[uart_tx_r % UART_TX_BUF_SIZE]
void uartinit(void)
{
// disable uart
UART_WRITE_REG(CR, 0);
// disable interrupts.
UART_WRITE_REG(IMSC, 0);
// in qemu, it is not necessary to set baudrate.
// enable FIFOs.
// set word length to 8 bits, no parity.
UART_WRITE_REG(LCRH, LCRH_FEN | LCRH_WLEN_8BIT);
// enable RXE, TXE and enable uart.
UART_WRITE_REG(CR, 0x301);
// enable transmit and receive interrupts.
UART_WRITE_REG(IMSC, INT_RX_ENABLE | INT_TX_ENABLE);
}
// if the UART is idle, and a character is waiting
// in the transmit buffer, send it.
// caller must hold uart_tx_lock.
// called from both the top- and bottom-half.
void uartstart()
{
while (1) {
if (uart_tx_w == uart_tx_r) {
// transmit buffer is empty.
return;
}
if (UART_READ_REG(FR) & FR_TXFF) {
// the UART transmit holding register is full,
// so we cannot give it another byte.
// it will interrupt when it's ready for a new byte.
return;
}
int c = uart_tx_buf[uart_tx_r % UART_TX_BUF_SIZE];
uart_tx_r += 1;
// maybe uartputc() is waiting for space in the buffer.
UART_WRITE_REG(DR, c);
}
}
// add a character to the output buffer and tell the
// UART to start sending if it isn't already.
// blocks if the output buffer is full.
// because it may block, it can't be called
// from interrupts; it's only suitable for use
// by write().
void uartputc(uint8_t c)
{
while (uart_tx_w == uart_tx_r + UART_TX_BUF_SIZE)
;
uart_tx_buf[uart_tx_w % UART_TX_BUF_SIZE] = c;
uart_tx_w += 1;
uartstart();
return;
}
// read one input character from the UART.
// return -1 if none is waiting.
static uint8_t uartgetc(void)
{
if (UART_READ_REG(FR) & FR_RXFE)
return 0xFF;
else
return UART_READ_REG(DR);
}
// handle a uart interrupt, raised because input has
// arrived, or the uart is ready for more output, or
// both. called from trap.c.
void uartintr(void)
{
// read and process incoming characters.
while (1) {
int c = uartgetc();
if (c == 0xFF)
break;
}
// send buffered characters.
uartstart();
// clear transmit and receive interrupts.
UART_WRITE_REG(ICR, INT_RX_ENABLE | INT_TX_ENABLE);
}
static uint32_t UartGetIrqnum()
{
return 0;
}
static struct XiziSerialDriver hardkernel_serial_driver = {
.sys_serial_init = uartinit,
.get_serial_irqnum = UartGetIrqnum,
.putc = uartputc,
.getc = uartgetc,
};
struct XiziSerialDriver* hardkernel_uart_init(struct TraceTag* hardkernel_tag)
{
hardkernel_serial_driver.sys_serial_init();
return &hardkernel_serial_driver;
}

View File

@ -70,6 +70,6 @@ struct SysTracer {
void sys_tracer_init();
TraceTag* const RequireRootTag();
bool AchieveResourceTag(struct TraceTag* target, struct TraceTag* owner, char* name);
void* AchieveResource(struct TraceTag* target);
void* AchieveResource(struct TraceTag* tag);
bool CreateResourceTag(struct TraceTag* new_tag, struct TraceTag* owner, char* name, tracemeta_ac_type type, void* p_resource);
bool DeleteResource(struct TraceTag* target, struct TraceTag* owner);

View File

@ -38,6 +38,22 @@ KERNELPATHS += \
-I$(KERNEL_ROOT)/hardkernel/cache/L2/pl310/
endif
ifeq ($(BOARD), ok1028a-c)
KERNELPATHS += \
-I$(KERNEL_ROOT)/hardkernel/clock/arm/armv8-a/cortex-a72/$(BOARD)/include \
-I$(KERNEL_ROOT)/hardkernel/arch/arm/armv8-a/cortex-a72/preboot_for_$(BOARD)/include \
-I$(KERNEL_ROOT)/hardkernel/arch/arm/armv8-a/cortex-a72/ \
-I$(KERNEL_ROOT)/hardkernel/mmu/arm/armv8-a/cortex-a72/$(BOARD) \
-I$(KERNEL_ROOT)/hardkernel/mmu/arm/armv8-a/cortex-a72/include \
-I$(KERNEL_ROOT)/hardkernel/clock/arm/armv8-a/cortex-a72/include \
-I$(KERNEL_ROOT)/hardkernel/intr/arm/armv8-a/cortex-a72/ \
-I$(KERNEL_ROOT)/hardkernel/intr/arm/armv8-a/cortex-a72/$(BOARD) \
-I$(KERNEL_ROOT)/hardkernel/intr/arm/armv8-a/cortex-a72/gicv3 \
-I$(KERNEL_ROOT)/hardkernel/uart/arm/armv8-a/cortex-a72/uart_io_for_$(BOARD)/include \
-I$(KERNEL_ROOT)/hardkernel/uart/arm/armv8-a/cortex-a72/ \
-I$(KERNEL_ROOT)/hardkernel/cache/L1/arm/cortex-a72/
endif
KERNELPATHS += \
-I$(KERNEL_ROOT)/hardkernel \
-I$(KERNEL_ROOT)/hardkernel/clock/ \

View File

@ -1,5 +1,5 @@
SRC_DIR := fs shell lib boards drivers semaphore tools net app
SRC_DIR := fs shell lib boards drivers semaphore drivers tools net app
include $(KERNEL_ROOT)/compiler.mk

View File

@ -10,6 +10,12 @@ cflags = -std=c11 -O2 -march=armv7-a -mtune=cortex-a9 -nostdlib -nodefaultlibs -
board_specs = stub.o
#cflags = -Wall -g -std=c11
endif
ifeq ($(BOARD), ok1028a-c)
toolchain ?= aarch64-none-elf-
user_ldflags = -N -Ttext 0
cflags = -Wall -g -std=c11 -mtune=cortex-a72 -nostdlib -nodefaultlibs -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
board_specs = stub.o
endif
cc = ${toolchain}gcc
ld = ${toolchain}g++
@ -37,9 +43,9 @@ INC_DIR = -I$(KERNEL_ROOT)/services/shell/letter-shell \
-I$(KERNEL_ROOT)/services/app
ifeq ($(BOARD), imx6q-sabrelite)
all: init test_fs simple_client simple_server shell fs_server semaphore_server test_thread test_irq_hdlr test_irq_block test_irq_send eth_driver epit_server test_net lwip readme.txt | bin
all: init test_fault simple_client simple_server shell fs_server semaphore_server test_semaphore test_ipc_null test_thread test_irq_hdlr test_irq_block test_irq_send eth_driver epit_server readme.txt | bin
else
all: init test_fs simple_client simple_server shell fs_server test_irq_hdlr readme.txt | bin
all: init test_fault simple_client simple_server shell fs_server test_ipc_null test_thread test_semaphore readme.txt | bin
endif
../tools/mkfs/mkfs ./fs.img $^
@mv $(filter-out readme.txt, $^) bin
@ -63,6 +69,14 @@ epit_server: timer.o epit.o ccm_pll.o usyscall.o arch_usyscall.o libserial.o pri
@${objdump} -S $@ > $@.asm
endif
test_semaphore: test_semaphore.o libserial.o printf.o usyscall.o arch_usyscall.o
@${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs}
@${objdump} -S $@ > $@.asm
test_ipc_null: test_ipc_null.o libserial.o printf.o usyscall.o arch_usyscall.o libipc.o session.o
@${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs}
@${objdump} -S $@ > $@.asm
semaphore_server: semaphore_server.o libserial.o printf.o usyscall.o arch_usyscall.o libipc.o session.o
@${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs}
@${objdump} -S $@ > $@.asm
@ -87,7 +101,7 @@ init: init.o libfs.o libipc.o session.o libserial.o printf.o usyscall.o arch_usy
@${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs}
@${objdump} -S $@ > $@.asm
test_fs: test_fs.o libfs.o libipc.o session.o libserial.o printf.o usyscall.o arch_usyscall.o libmem.o
test_fault: test_fault.o libserial.o printf.o usyscall.o arch_usyscall.o
@${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs}
@${objdump} -S $@ > $@.asm

View File

@ -56,10 +56,10 @@ int main(void)
printf("session connect faield\n");
return -1;
}
shellTask(&shell);
free_session(&session_fs);
exit(0);
return 0;
}

View File

@ -85,7 +85,6 @@ int main(int argc, char** argv)
if (argc >= 2) {
id = string_to_integer(argv[1]);
}
// printf("This is Simple Client %d, size is 0x%x\n", id, task_heap_base());
struct Session session_wait;
struct Session session_nowait;
@ -94,37 +93,39 @@ int main(int argc, char** argv)
exit(1);
}
// test no wait ipc
char *buf1 = NULL, *buf2 = NULL;
struct IpcMsg* msg1 = hello_string_nowait(&session_nowait, &buf1, 32);
struct IpcMsg* msg2 = hello_string_nowait(&session_nowait, &buf2, 128);
int ret = add(&session_wait, 17, 22);
// test ipc add(wait version)
int ret = 0;
ret = add(&session_wait, 17, 22);
printf("ipc_add 17 + 22 = %d\n", ret);
char buf[32];
ret = add(&session_wait, 9, 9);
printf("ipc_add 9 + 9 = %d\n", ret);
struct Session session;
struct Session fs_session;
static char id_buf[33] = { 0 };
if (id > 1) {
if (connect_session(&session, "MemFS", 8092) < 0) {
printf("connect session failed\n");
if (connect_session(&fs_session, "MemFS", 8192) < 0) {
printf("connect fs_session failed\n");
} else {
int fd;
itoa(id - 1, id_buf, 10);
char* shell_task_param[3] = { "/simple_client", id_buf, 0 };
if ((fd = open(&session, shell_task_param[0])) >= 0) {
if (spawn(&session, fd, read, fsize, shell_task_param[0], shell_task_param) < 0) {
if ((fd = open(&fs_session, shell_task_param[0])) >= 0) {
if (spawn(&fs_session, fd, read, fsize, shell_task_param[0], shell_task_param) < 0) {
printf("Syscall Spawn simple_client failed\n");
}
if (spawn(&session, fd, read, fsize, shell_task_param[0], shell_task_param) < 0) {
if (spawn(&fs_session, fd, read, fsize, shell_task_param[0], shell_task_param) < 0) {
printf("Syscall Spawn simple_client failed\n");
}
close(&session, fd);
close(&fs_session, fd);
} else {
printf("Open %s failed\n", shell_task_param[0]);
}
free_session(&session);
free_session(&fs_session);
}
}

View File

@ -44,4 +44,5 @@ int main(int argc, char* argv[])
// never reached
exit(0);
return 0;
}

View File

@ -10,34 +10,18 @@
* See the Mulan PSL v2 for more details.
*/
// test_priority: Test the priority scheduler of task
// test_fs: Test the file io control of fs
#include <assert.h>
#include <stdbool.h>
#include <string.h>
#include "libserial.h"
#include "usyscall.h"
static void count_down()
{
int time = 500000000;
while (time >= 0) {
if (time % 10000000 == 0) {
printf("Priority-based preempting, time remained %d\n", time);
}
time--;
}
return;
}
int main(int argc, char* argv[])
{
// set priority
sys_state_info info;
info.priority = 0;
set_priority(&info);
// test function
count_down();
printf("Test memry error %s.\n", 0x50000000);
printf("After error computing.\n");
exit(0);
return 0;

View File

@ -1,53 +0,0 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
// test_fs: Test the file io control of fs
#include <assert.h>
#include <stdbool.h>
#include <string.h>
#include "libfs.h"
#include "libserial.h"
#include "usyscall.h"
#define BLOCK_SIZE 256
int main(int argc, char* argv[])
{
printf("file system test\n");
struct Session session;
connect_session(&session, "MemFS", 4096);
int fd;
char* fd_path = "/readme.txt";
fd = open(&session, fd_path);
/// @todo support malloc for user
char buffer[BLOCK_SIZE] = { 0 };
read(&session, fd, buffer, 0, BLOCK_SIZE);
printf("file content: %s\n", buffer);
char* write_data = "hello world\n";
write(&session, fd, write_data, 0, strlen(write_data) + 1);
memset(buffer, 0, BLOCK_SIZE);
read(&session, fd, buffer, 0, BLOCK_SIZE);
printf("file content: %s\n", buffer);
close(&session, fd);
free_session(&session);
printf("file test done.\n");
printf("Test memry error %s.\n", 0x50000000);
printf("After error computing.\n");
exit(0);
return 0;
}

View File

@ -0,0 +1,85 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
#include <stdbool.h>
#include <string.h>
#include "libipc.h"
#include "libserial.h"
#include "usyscall.h"
IPC_SERVICES(IpcTestNull, Ipc_test_null);
#define TEST_BUF_SIZE 32
static char test_null_server_name[] = "TestNullServer";
static char test_null_client_name[] = "TestNullClient";
// client side
static char buf[TEST_BUF_SIZE];
IPC_INTERFACE(Ipc_test_null, 1, ptr, sizeof(buf));
int test_null(struct Session* session, char* ptr)
{
return IPC_CALL(Ipc_test_null)(session, ptr);
}
// client thread
int server_thread(int argc, char** argv);
int main(int argc, char** argv)
{
struct Session session;
bool server_enabled = false;
while (connect_session(&session, test_null_server_name, 4096) < 0) {
if (!server_enabled) {
char* server_param[] = { test_null_server_name, NULL };
if (thread(server_thread, test_null_server_name, server_param) >= 0) {
server_enabled = true;
}
}
}
printf("[%s] Call using NULL ptr.\n", test_null_client_name);
test_null(&session, NULL);
printf("[%s] Call using non-NULL ptr.\n", test_null_client_name);
test_null(&session, buf);
exit(0);
return 0;
}
// server side
int IPC_DO_SERVE_FUNC(Ipc_test_null)(void* ptr)
{
if (ptr == NULL) {
printf("[%s]: A NULL ptr ipc call.\n", test_null_server_name);
} else {
printf("[%s]: A non-NULL ptr ipc call.\n", test_null_server_name);
}
return 0;
}
IPC_SERVER_INTERFACE(Ipc_test_null, 1);
IPC_SERVER_REGISTER_INTERFACES(IpcTestNull, 1, Ipc_test_null);
// server threads
int server_thread(int argc, char** argv)
{
if (register_server(test_null_server_name) < 0) {
printf("[%s] Register %s server failed.\n", test_null_server_name, test_null_server_name);
exit(1);
return 1;
}
ipc_server_loop(&IpcTestNull);
exit(0);
return 0;
}

View File

@ -52,4 +52,5 @@ int main()
ipc_server_loop(&IpcSwIntrHandler);
exit(0);
return 0;
}

View File

@ -0,0 +1,71 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
#include <stdint.h>
#include "libserial.h"
#include "usyscall.h"
enum {
NR_THREADS = 16,
LOOP_TIMES = 0x1000000,
};
static int sem_id = -1;
static uint32_t sum = 0;
static int nr_thds = NR_THREADS;
int do_calculation(int argc, char** argv)
{
for (uint32_t i = 0; i < LOOP_TIMES; i++) {
sum++;
}
printf("test semaphore thd signal.\n");
semaphore_signal(sem_id);
char* params[] = { "do_cal", NULL };
if (nr_thds != 0) {
int tid = thread(do_calculation, "test_sem_thd", params);
nr_thds--;
}
exit(0);
return 0;
}
int main(int argc, char** argv)
{
printf("Test Semaphore.\n");
sem_id = semaphore_new(0);
if (sem_id < 0) {
printf("new a kernel sem failed.\n");
exit(1);
}
sum = 0;
nr_thds = NR_THREADS;
char* params[] = { "do_cal", NULL };
if (nr_thds != 0) {
int tid = thread(do_calculation, "test_sem_thd", params);
nr_thds--;
}
for (int i = 0; i < NR_THREADS; i++) {
semaphore_wait(sem_id);
}
printf("test thread sum after %d signal: 0x%x\n", NR_THREADS, sum);
exit(0);
return 0;
}

View File

@ -25,6 +25,8 @@ int sub_thread_entry(int argc, char** argv)
global_value++;
}
/// @warning session is single threaded, so that each thread cannot share a common session.
// sub thread connect to semaphore server
struct Session sem_session;
while (connect_session(&sem_session, sem_server_name, 4096) < 0) {
yield(SYS_TASK_YIELD_NO_REASON);

View File

@ -1,15 +1,23 @@
ifeq ($(BOARD), imx6q-sabrelite)
toolchain ?= arm-none-eabi-
user_ldflags = -N -Ttext 0
cflags = -march=armv7-a -std=c11 -mtune=cortex-a9 -nostdlib -nodefaultlibs -mfloat-abi=soft -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
endif
ifeq ($(BOARD), zynq7000-zc702)
toolchain ?= arm-xilinx-eabi-
user_ldflags = -N -Ttext 0
cflags = -march=armv7-a -std=c11 -mtune=cortex-a9 -nostdlib -nodefaultlibs -mfloat-abi=soft -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
endif
ifeq ($(BOARD), ok1028a-c)
toolchain ?= aarch64-none-elf-
user_ldflags = -N -Ttext 0
cflags = -Wall -g -std=c11 -mtune=cortex-a72 -nostdlib -nodefaultlibs -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
endif
cc = ${toolchain}gcc
ld = ${toolchain}g++
objdump = ${toolchain}objdump
user_ldflags = -N -Ttext 0
cflags = -march=armv7-a -std=c11 -mtune=cortex-a9 -nostdlib -nodefaultlibs -mfloat-abi=soft -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
c_useropts = -O2
INC_DIR = -I$(KERNEL_ROOT)/services/fs/libfs \

View File

@ -0,0 +1,38 @@
ifeq ($(BOARD), imx6q-sabrelite)
toolchain ?= arm-none-eabi-
user_ldflags = -N -Ttext 0
cflags = -march=armv7-a -std=c11 -mtune=cortex-a9 -nostdlib -nodefaultlibs -mfloat-abi=soft -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
endif
ifeq ($(BOARD), zynq7000-zc702)
toolchain ?= arm-xilinx-eabi-
user_ldflags = -N -Ttext 0
cflags = -march=armv7-a -std=c11 -mtune=cortex-a9 -nostdlib -nodefaultlibs -mfloat-abi=soft -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
endif
ifeq ($(BOARD), ok1028a-c)
toolchain ?= aarch64-none-elf-
user_ldflags = -N -Ttext 0
cflags = -Wall -g -std=c11 -mtune=cortex-a72 -nostdlib -nodefaultlibs -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
endif
cc = ${toolchain}gcc
ld = ${toolchain}g++
objdump = ${toolchain}objdump
c_useropts = -O2
INC_DIR = -I$(KERNEL_ROOT)/services/fs/libfs \
-I$(KERNEL_ROOT)/services/lib/ipc \
-I$(KERNEL_ROOT)/services/lib/memory \
-I$(KERNEL_ROOT)/services/lib/serial \
-I$(KERNEL_ROOT)/services/lib/usyscall \
-I$(KERNEL_ROOT)/services/boards/$(BOARD) \
-I$(KERNEL_ROOT)/services/app
board: libserial.o arch_usyscall.o stub.o
@mv $^ $(KERNEL_ROOT)/services/app
%.o: %.c
@echo "cc $^"
@${cc} ${cflags} ${c_useropts} ${INC_DIR} -o $@ -c $^
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,33 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
#include "usyscall.h"
int syscall(int sys_num, intptr_t a1, intptr_t a2, intptr_t a3, intptr_t a4)
{
int ret = -1;
__asm__ volatile(
"mov x0, %1;\
mov x1, %2;\
mov x2, %3;\
mov x3, %4;\
mov x4, %5;\
svc #0;\
dsb ish;\
isb;\
mov %0, x0"
: "=r"(ret)
: "r"(sys_num), "r"(a1), "r"(a2), "r"(a3), "r"(a4)
: "memory", "r0", "r1", "r2", "r3", "r4");
return ret;
}

View File

@ -0,0 +1,113 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
/// this file is only used for debug
#include "libserial.h"
#include "usyscall.h"
#define USER_UART_BASE 0x6FFFF000
#define UART0_BASE (0x09000000ULL)
#define UART0_REG(reg) ((volatile uint32_t*)(USER_UART_BASE + reg))
// the UART control registers.
// pl011
#define DR 0x00
#define FR 0x18
#define FR_RXFE (1 << 4) // recieve fifo empty
#define FR_TXFF (1 << 5) // transmit fifo full
#define FR_RXFF (1 << 6) // recieve fifo full
#define FR_TXFE (1 << 7) // transmit fifo empty
#define IBRD 0x24
#define FBRD 0x28
#define LCRH 0x2c
#define LCRH_FEN (1 << 4)
#define LCRH_WLEN_8BIT (3 << 5)
#define CR 0x30
#define IMSC 0x38
#define INT_RX_ENABLE (1 << 4)
#define INT_TX_ENABLE (1 << 5)
#define ICR 0x44
#define UART_READ_REG(reg) (*(UART0_REG(reg)))
#define UART_WRITE_REG(reg, v) (*(UART0_REG(reg)) = (v))
#define UART_TX_BUF_SIZE 32
static char uart_tx_buf[UART_TX_BUF_SIZE];
uint64_t uart_tx_w; // write next to uart_tx_buf[uart_tx_w % UART_TX_BUF_SIZE]
uint64_t uart_tx_r; // read next from uart_tx_buf[uart_tx_r % UART_TX_BUF_SIZE]
bool init_uart_mmio()
{
static int mapped = 0;
if (mapped == 0) {
if (-1 == mmap(USER_UART_BASE, UART0_BASE, 4096, true)) {
return false;
}
mapped = 1;
}
return true;
}
// if the UART is idle, and a character is waiting
// in the transmit buffer, send it.
// caller must hold uart_tx_lock.
// called from both the top- and bottom-half.
void uartstart()
{
while (1) {
if (uart_tx_w == uart_tx_r) {
// transmit buffer is empty.
return;
}
if (UART_READ_REG(FR) & FR_TXFF) {
// the UART transmit holding register is full,
// so we cannot give it another byte.
// it will interrupt when it's ready for a new byte.
return;
}
int c = uart_tx_buf[uart_tx_r % UART_TX_BUF_SIZE];
uart_tx_r += 1;
// maybe uartputc() is waiting for space in the buffer.
UART_WRITE_REG(DR, c);
}
}
// add a character to the output buffer and tell the
// UART to start sending if it isn't already.
// blocks if the output buffer is full.
// because it may block, it can't be called
// from interrupts; it's only suitable for use
// by write().
void putc(char c)
{
while (uart_tx_w == uart_tx_r + UART_TX_BUF_SIZE)
;
uart_tx_buf[uart_tx_w % UART_TX_BUF_SIZE] = c;
uart_tx_w += 1;
uartstart();
return;
}
// read one input character from the UART.
// return -1 if none is waiting.
char getc(void)
{
if (UART_READ_REG(FR) & FR_RXFE)
return 0xFF;
else
return UART_READ_REG(DR);
}

View File

@ -0,0 +1,91 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
#include <stddef.h>
#include <sys/stat.h>
#include <sys/types.h>
// _exit: 用于退出程序
void _exit(int status)
{
while (1) { }
}
// _sbrk: 用于增加程序的数据空间
void* _sbrk(ptrdiff_t incr)
{
extern char end; /* Defined by the linker */
static char* heap_end;
char* prev_heap_end;
if (heap_end == 0) {
heap_end = &end;
}
prev_heap_end = heap_end;
// 在这里,你应该添加一些检查来确保堆不会与栈或其他内存区域冲突
// 例如,检查 incr 是否会导致堆超出预定的内存区域
heap_end += incr;
return (void*)prev_heap_end;
}
// _write: 用于将数据写入文件描述符
ssize_t _write(int file, const void* ptr, size_t len)
{
// 在这里,你需要实现将数据写入文件描述符的逻辑
// 如果你的系统不支持文件系统,你可以将数据发送到串口或其他输出
return len; // 假设所有数据都被写入
}
// _close: 用于关闭文件描述符
int _close(int file)
{
return -1; // 表示失败,因为没有实际关闭文件的功能
}
// _fstat: 用于获取文件状态
int _fstat(int file, struct stat* st)
{
return 0; // 表示成功
}
// _isatty: 检查文件描述符是否指向TTY设备
int _isatty(int file)
{
return 1; // 表示是TTY设备
}
// _lseek: 用于重新定位文件读/写的位置
off_t _lseek(int file, off_t offset, int whence)
{
return -1; // 表示失败,因为不支持文件定位
}
// _read: 用于从文件描述符读取数据
ssize_t _read(int file, void* ptr, size_t len)
{
return 0; // 表示没有数据被读取
}
// _kill: 发送信号给进程
int _kill(int pid, int sig)
{
return -1; // 表示失败,因为不支持信号
}
// _getpid: 获取进程ID
int _getpid()
{
return 1; // 返回假设的进程ID
}

View File

@ -9,6 +9,12 @@ user_ldflags = --start-group,-lgcc,-lc,--end-group
cflags = -std=c11 -march=armv7-a -mtune=cortex-a9 -nostdlib -nodefaultlibs -mfloat-abi=soft -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
#cflags = -Wall -g -std=c11
endif
ifeq ($(BOARD), ok1028a-c)
toolchain ?= aarch64-none-elf-
user_ldflags = -N -Ttext 0
cflags = -Wall -g -std=c11 -mtune=cortex-a72 -nostdlib -nodefaultlibs -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
endif
cc = ${toolchain}gcc
ld = ${toolchain}g++
objdump = ${toolchain}objdump

View File

@ -1,15 +1,23 @@
ifeq ($(BOARD), imx6q-sabrelite)
toolchain ?= arm-none-eabi-
cflags = -std=c11 -march=armv7-a -mtune=cortex-a9 -nostdlib -nodefaultlibs -mfloat-abi=soft -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
user_ldflags = -N -Ttext 0
endif
ifeq ($(BOARD), zynq7000-zc702)
toolchain ?= arm-xilinx-eabi-
cflags = -std=c11 -march=armv7-a -mtune=cortex-a9 -nostdlib -nodefaultlibs -mfloat-abi=soft -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
user_ldflags = -N -Ttext 0
endif
ifeq ($(BOARD), ok1028a-c)
toolchain ?= aarch64-none-elf-
user_ldflags = -N -Ttext 0
cflags = -Wall -g -std=c11 -mtune=cortex-a72 -nostdlib -nodefaultlibs -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
endif
cc = ${toolchain}gcc
ld = ${toolchain}g++
objdump = ${toolchain}objdump
user_ldflags = -N -Ttext 0
cflags = -std=c11 -march=armv7-a -mtune=cortex-a9 -nostdlib -nodefaultlibs -mfloat-abi=soft -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
c_useropts = -O2
INC_DIR = -I$(KERNEL_ROOT)/services/app \

View File

@ -1,15 +1,23 @@
ifeq ($(BOARD), imx6q-sabrelite)
toolchain ?= arm-none-eabi-
cflags = -std=c11 -march=armv7-a -mtune=cortex-a9 -nostdlib -nodefaultlibs -mfloat-abi=soft -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
user_ldflags = -N -Ttext 0
endif
ifeq ($(BOARD), zynq7000-zc702)
toolchain ?= arm-xilinx-eabi-
cflags = -std=c11 -march=armv7-a -mtune=cortex-a9 -nostdlib -nodefaultlibs -mfloat-abi=soft -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
user_ldflags = -N -Ttext 0
endif
ifeq ($(BOARD), ok1028a-c)
toolchain ?= aarch64-none-elf-
user_ldflags = -N -Ttext 0
cflags = -Wall -g -std=c11 -mtune=cortex-a72 -nostdlib -nodefaultlibs -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
endif
cc = ${toolchain}gcc
ld = ${toolchain}g++
objdump = ${toolchain}objdump
user_ldflags = -N -Ttext 0
cflags = -std=c11 -march=armv7-a -mtune=cortex-a9 -nostdlib -nodefaultlibs -mfloat-abi=soft -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
c_useropts = -O2
INC_DIR = -I$(KERNEL_ROOT)/services/app \

View File

@ -1,15 +1,22 @@
ifeq ($(BOARD), imx6q-sabrelite)
toolchain ?= arm-none-eabi-
cflags = -std=c11 -march=armv7-a -mtune=cortex-a9 -nostdlib -nodefaultlibs -mfloat-abi=soft -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
user_ldflags = -N -Ttext 0
endif
ifeq ($(BOARD), zynq7000-zc702)
toolchain ?= arm-xilinx-eabi-
cflags = -std=c11 -march=armv7-a -mtune=cortex-a9 -nostdlib -nodefaultlibs -mfloat-abi=soft -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
user_ldflags = -N -Ttext 0
endif
ifeq ($(BOARD), ok1028a-c)
toolchain ?= aarch64-none-elf-
user_ldflags = -N -Ttext 0
cflags = -Wall -g -std=c11 -mtune=cortex-a72 -nostdlib -nodefaultlibs -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
endif
cc = ${toolchain}gcc
ld = ${toolchain}g++
objdump = ${toolchain}objdump
user_ldflags = -N -Ttext 0
cflags = -std=c11 -march=armv7-a -mtune=cortex-a9 -nostdlib -nodefaultlibs -mfloat-abi=soft -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
c_useropts = -O2
INC_DIR = -I$(KERNEL_ROOT)/services/app \

View File

@ -0,0 +1,3 @@
SRC_DIR :=
include $(KERNEL_ROOT)/compiler.mk

View File

@ -9,6 +9,12 @@ user_ldflags = --start-group,-lgcc,-lc,--end-group
cflags = -std=c11 -march=armv7-a -mtune=cortex-a9 -nostdlib -nodefaultlibs -mfloat-abi=soft -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
#cflags = -Wall -g -std=c11
endif
ifeq ($(BOARD), ok1028a-c)
toolchain ?= aarch64-none-elf-
user_ldflags = -N -Ttext 0
cflags = -Wall -g -std=c11 -mtune=cortex-a72 -nostdlib -nodefaultlibs -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
endif
cc = ${toolchain}gcc
ld = ${toolchain}g++
objdump = ${toolchain}objdump

View File

@ -63,7 +63,8 @@ uint32_t BlockAlloc()
}
}
Error("BlockAlloc: out of blocks");
printf("BlockAlloc: out of blocks, bit idx: %d, total size: %d\n", bit_index, sb.size);
Error("");
return 0;
}

View File

@ -119,9 +119,7 @@ struct Inode* InodeCreate(struct Inode* parent_inode, char* name, int type)
/// @brief Delete a file Inode or a dir Inode
int InodeDelete(struct Inode* parent_inode, char* name)
{
uint32_t offset;
struct Inode* inode;
struct DirectEntry de;
if ((inode = DirInodeLookup(parent_inode, name)) == 0) {
printf("Inode delete failed, file not exsit");

View File

@ -63,11 +63,12 @@ int IPC_DO_SERVE_FUNC(Ipc_ls)(char* path)
}
if (!(ip = InodeSeek(dp, path))) {
printf("ls: find target Inode failed, ip: %x(%d), dp: %x(%d)\n", ip, ip->inum, dp, dp->inum);
printf("ls: find target Inode failed, dp: %p(%d), path: %s\n", dp, dp->inum, path);
return -1;
}
if (ip->type != FS_DIRECTORY) {
printf("ls: not a dir\n");
printf("ls: not a dir, ip: %d\n", ip->inum);
return -1;
}
@ -364,4 +365,5 @@ int main(int argc, char* argv[])
// never reached
exit(0);
return 0;
}

View File

@ -1,14 +1,19 @@
ifeq ($(BOARD), imx6q-sabrelite)
toolchain ?= arm-none-eabi-
user_ldflags = -N -Ttext 0
cflags = -std=c11 -march=armv7-a -mtune=cortex-a9 -nostdlib -nodefaultlibs -mfloat-abi=soft -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
user_ldflags = -N -Ttext 0
endif
ifeq ($(BOARD), zynq7000-zc702)
toolchain ?= arm-xilinx-eabi-
user_ldflags = --start-group,-lgcc,-lc,--end-group
cflags = -std=c11 -march=armv7-a -mtune=cortex-a9 -nostdlib -nodefaultlibs -mfloat-abi=soft -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
#cflags = -Wall -g -std=c11
user_ldflags = -N -Ttext 0
endif
ifeq ($(BOARD), ok1028a-c)
toolchain ?= aarch64-none-elf-
user_ldflags = -N
cflags = -Wall -g -std=c11 -mtune=cortex-a72 -nostdlib -nodefaultlibs -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
endif
cc = ${toolchain}gcc
ld = ${toolchain}g++
objdump = ${toolchain}objdump

View File

@ -9,6 +9,12 @@ user_ldflags = --start-group,-lgcc,-lc,--end-group
cflags = -std=c11 -march=armv7-a -mtune=cortex-a9 -nostdlib -nodefaultlibs -mfloat-abi=soft -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
#cflags = -Wall -g -std=c11
endif
ifeq ($(BOARD), ok1028a-c)
toolchain ?= aarch64-none-elf-
user_ldflags = -N -Ttext 0
cflags = -Wall -g -std=c11 -mtune=cortex-a72 -nostdlib -nodefaultlibs -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
endif
cc = ${toolchain}gcc
ld = ${toolchain}g++
objdump = ${toolchain}objdump

View File

@ -79,15 +79,26 @@ struct IpcMsg* new_ipc_msg(struct Session* session, const int argc, const int* a
bool ipc_msg_set_nth_arg(struct IpcMsg* msg, const int arg_num, const void* const data, const int len)
{
if (arg_num >= msg->header.nr_args) {
printf("[%s] IPC: arg_num out of msg range, arg_num: %d, nr_args: %d\n", __func__, arg_num, msg->header.nr_args);
printf("[%s] IPC: arg_num out of msg range, arg_num: %d, nr_args: %u\n", __func__, arg_num, msg->header.nr_args);
return false;
}
struct IpcArgInfo* nth_arg_info = IPCMSG_ARG_INFO(msg, arg_num);
if (len > nth_arg_info->len) {
printf("[%s] IPC: size of arg out of buffer range, given len: %d, len %d\n", __func__, len, nth_arg_info->len);
if (len < 0 || (uint32_t)len > (uint32_t)nth_arg_info->len) {
printf("[%s] IPC: size of arg out of buffer range, given len: %d, len %u\n", __func__, len, nth_arg_info->len);
return false;
}
void* buf = ipc_msg_get_nth_arg_buf(msg, arg_num);
// handle attributes of different params
if (data == NULL) {
nth_arg_info->null_ptr = 1;
memset(buf, 0x0, len);
return true;
} else {
nth_arg_info->null_ptr = 0;
}
memmove(buf, data, len);
return true;
}
@ -109,6 +120,12 @@ bool ipc_msg_get_nth_arg(struct IpcMsg* msg, const int arg_num, void* data, cons
printf("[%s] IPC: size of arg out of buffer range", __func__);
return false;
}
// handle null ptr: do nothing
if (nth_arg_info->null_ptr == 1) {
return true;
}
void* buf = ipc_msg_get_nth_arg_buf(msg, arg_num);
memmove(data, buf, len);
return true;
@ -170,12 +187,6 @@ bool is_cur_handler_been_delayed()
return ipc_server_loop_cur_msg->header.delayed == 1;
}
bool server_set_cycle_handler(struct IpcNode* ipc_node, void (*handler)())
{
ipc_node->cycle_handler = handler;
return true;
}
void ipc_server_loop(struct IpcNode* ipc_node)
{
struct Session session_list[NR_MAX_SESSION];
@ -204,7 +215,6 @@ void ipc_server_loop(struct IpcNode* ipc_node)
interfaces[opcode] should explicitly call delay_session() and return to delay this session
*/
while (ipc_server_loop_cur_msg->header.magic == IPC_MSG_MAGIC && ipc_server_loop_cur_msg->header.valid == 1 && ipc_server_loop_cur_msg->header.done == 0) {
// printf("session %d [%d, %d]\n", session_list[i].id, session_list[i].head, session_list[i].tail);
if (session_used_size(&session_list[i]) == 0 && session_forward_tail(&session_list[i], ipc_server_loop_cur_msg->header.len) < 0) {
break;
}
@ -213,13 +223,13 @@ void ipc_server_loop(struct IpcNode* ipc_node)
if (ipc_node->interfaces[ipc_server_loop_cur_msg->header.opcode]) {
ipc_node->interfaces[ipc_server_loop_cur_msg->header.opcode](ipc_server_loop_cur_msg);
// check if this session is delayed by op handler, all messages after the delayed message in current session is blocked.
if (is_cur_session_delayed()) {
if (ipc_server_loop_cur_msg->header.done == 0) {
ipc_server_loop_cur_msg->header.delayed = 1;
has_delayed = true;
break;
}
} else {
printf("Unsupport opcode(%d) for server: %s\n", ipc_server_loop_cur_msg->header.opcode, ipc_node->name);
printf("Unsupport opcode(%u) for server: %s\n", ipc_server_loop_cur_msg->header.opcode, ipc_node->name);
}
// current msg is a message that needs to ignore
// finish this message in server's perspective
@ -233,8 +243,5 @@ void ipc_server_loop(struct IpcNode* ipc_node)
ipc_server_loop_cur_msg = NULL;
}
}
if (ipc_node->cycle_handler) {
ipc_node->cycle_handler();
}
}
}

View File

@ -60,6 +60,13 @@ typedef struct {
struct IpcArgInfo {
uint16_t offset;
uint16_t len;
union {
uint16_t attr;
struct {
uint16_t null_ptr : 1;
uint16_t reserved : 15;
};
};
} __attribute__((packed));
/* [header, ipc_arg_buffer_len[], ipc_arg_buffer[]] */
@ -76,7 +83,6 @@ typedef int (*IpcInterface)(struct IpcMsg* msg);
struct IpcNode {
char* name;
IpcInterface interfaces[UINT8_MAX];
void (*cycle_handler)();
} __attribute__((packed));
#define IPC_SERVER_LOOP(ipc_node_name) rpc_server_loop_##rpc_node_name
@ -105,6 +111,10 @@ struct IpcNode {
/// @return
__attribute__((__always_inline__)) static inline void* ipc_msg_get_nth_arg_buf(struct IpcMsg* msg, int arg_num)
{
if (IPCMSG_ARG_INFO(msg, arg_num)->null_ptr == 1) {
return NULL;
}
return (void*)((char*)msg + IPCMSG_ARG_INFO(msg, arg_num)->offset);
}
@ -243,6 +253,8 @@ bool is_cur_session_delayed(void);
}
int cur_session_id(void);
bool server_set_cycle_handler(struct IpcNode* ipc_node, void (*handler)());
/// @brief delay the session(message, or a inter-process-call)
/// the delayed call will be handled again later from begining, not from the position where delay_session() is called.
/// @param
void delay_session(void);
bool is_cur_handler_been_delayed();

View File

@ -46,10 +46,10 @@ int free_session(struct Session* session)
void* session_alloc_buf(struct Session* session, int len)
{
if (len > session_remain_capacity(session)) {
if (len < 0 || len > session_remain_capacity(session)) {
return NULL;
}
void* buf = session->buf + session->tail;
void* buf = (void*)((uintptr_t)session->buf + session->tail);
// we mapped double size of page, so it's ok to write buffer directly
memset(buf, 0, len);
session_forward_tail(session, len);
@ -58,7 +58,7 @@ void* session_alloc_buf(struct Session* session, int len)
bool session_free_buf(struct Session* session, int len)
{
if (len > session_used_size(session)) {
if (len < 0 || len > session_used_size(session)) {
return false;
}
assert(session_forward_head(session, len) != -1);

View File

@ -1,15 +1,23 @@
ifeq ($(BOARD), imx6q-sabrelite)
toolchain ?= arm-none-eabi-
cflags = -std=c11 -march=armv7-a -mtune=cortex-a9 -nostdlib -nodefaultlibs -mfloat-abi=soft -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
user_ldflags = -N -Ttext 0
endif
ifeq ($(BOARD), zynq7000-zc702)
toolchain ?= arm-xilinx-eabi-
cflags = -std=c11 -march=armv7-a -mtune=cortex-a9 -nostdlib -nodefaultlibs -mfloat-abi=soft -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
user_ldflags = -N -Ttext 0
endif
ifeq ($(BOARD), ok1028a-c)
toolchain ?= aarch64-none-elf-
user_ldflags = -N -Ttext 0
cflags = -Wall -g -std=c11 -mtune=cortex-a72 -nostdlib -nodefaultlibs -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
endif
cc = ${toolchain}gcc
ld = ${toolchain}g++
objdump = ${toolchain}objdump
user_ldflags = -N -Ttext 0
cflags = -std=c11 -march=armv7-a -mtune=cortex-a9 -nostdlib -nodefaultlibs -mfloat-abi=soft -fno-pic -static -fno-builtin -fno-strict-aliasing -Wall -ggdb -Wno-unused -Werror -fno-omit-frame-pointer -fno-stack-protector -fno-pie
c_useropts = -O2
INC_DIR = -I$(KERNEL_ROOT)/services/app \

View File

@ -41,7 +41,7 @@
#define PUT_NOTAG(p, val) (*(unsigned int*)(p) = (val))
// Store predecessor or successor pointer for free blocks
#define SET_PTR(p, ptr) (*(unsigned int*)(p) = (unsigned int)(ptr))
#define SET_PTR(p, ptr) (*(uintptr_t*)(p) = (uintptr_t)(ptr))
// Read the size and allocation bit from address p
#define GET_SIZE(p) (GET(p) & ~0x7)

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