Merge branch 'smp' into lwip

This commit is contained in:
lr 2024-05-15 18:02:27 +08:00
commit 40726602ec
133 changed files with 141214 additions and 1678 deletions

View File

@ -31,32 +31,14 @@ Modification:
context_switch: context_switch:
# store original context to stack # store original context to stack
str lr, [r13, #-4]! stmfd r13!, {r4-r12, lr}
str r12, [r13, #-4]!
str r11, [r13, #-4]!
str r10, [r13, #-4]!
str r9, [r13, #-4]!
str r8, [r13, #-4]!
str r7, [r13, #-4]!
str r6, [r13, #-4]!
str r5, [r13, #-4]!
str r4, [r13, #-4]!
# switch the stack # switch the stack
str r13, [r0] // save current sp to the old PCB (**old) str r13, [r0] // save current sp to the old PCB (**old)
mov r13, r1 // load the next stack mov r13, r1 // load the next stack
# restore context from stack # restore context from stack
ldr r4, [r13], #4 ldmfd r13!, {r4-r12, lr}
ldr r5, [r13], #4
ldr r6, [r13], #4
ldr r7, [r13], #4
ldr r8, [r13], #4
ldr r9, [r13], #4
ldr r10, [r13], #4
ldr r11, [r13], #4
ldr r12, [r13], #4
ldr lr, [r13], #4
# return to the caller # return to the caller
bx lr bx lr

View File

@ -76,7 +76,7 @@ Modification:
#define NR_CPU 4 #define NR_CPU 4
__attribute__((always_inline)) static inline uint32_t user_mode() __attribute__((always_inline, optimize("O0"))) static inline uint32_t user_mode()
{ {
uint32_t val; uint32_t val;
@ -92,6 +92,16 @@ __attribute__((always_inline)) static inline uint32_t user_mode()
return val; 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 { struct context {
uint32_t r4; uint32_t r4;
uint32_t r5; uint32_t r5;
@ -103,12 +113,12 @@ struct context {
uint32_t r11; uint32_t r11;
uint32_t r12; uint32_t r12;
uint32_t lr; uint32_t lr;
}; } __attribute__((packed));
/// @brief init task context, set return address to trap return /// @brief init task context, set return address to trap return
/// @param /// @param
extern void task_prepare_enter(); extern void task_prepare_enter();
__attribute__((__always_inline__)) static inline void arch_init_context(struct context* ctx) __attribute__((always_inline, optimize("O0"))) static inline void arch_init_context(struct context* ctx)
{ {
memset(ctx, 0, sizeof(*ctx)); memset(ctx, 0, sizeof(*ctx));
ctx->lr = (uint32_t)(task_prepare_enter + 4); ctx->lr = (uint32_t)(task_prepare_enter + 4);
@ -133,13 +143,13 @@ struct trapframe {
uint32_t r11; uint32_t r11;
uint32_t r12; uint32_t r12;
uint32_t pc; uint32_t pc;
}; } __attribute__((packed));
/// @brief init task trapframe (*especially the user mode cpsr) /// @brief init task trapframe (*especially the user mode cpsr)
/// @param tf /// @param tf
/// @param sp /// @param sp
/// @param pc /// @param pc
__attribute__((__always_inline__)) static inline void arch_init_trapframe(struct trapframe* tf, uintptr_t sp, uintptr_t pc) __attribute__((always_inline, optimize("O0"))) static inline void arch_init_trapframe(struct trapframe* tf, uintptr_t sp, uintptr_t pc)
{ {
memset(tf, 0, sizeof(*tf)); memset(tf, 0, sizeof(*tf));
tf->spsr = user_mode(); tf->spsr = user_mode();
@ -153,7 +163,7 @@ __attribute__((__always_inline__)) static inline void arch_init_trapframe(struct
/// @param tf /// @param tf
/// @param sp /// @param sp
/// @param pc /// @param pc
__attribute__((__always_inline__)) static inline void arch_trapframe_set_sp_pc(struct trapframe* tf, uintptr_t sp, uintptr_t pc) __attribute__((always_inline, optimize("O0"))) static inline void arch_trapframe_set_sp_pc(struct trapframe* tf, uintptr_t sp, uintptr_t pc)
{ {
tf->sp_usr = sp; tf->sp_usr = sp;
tf->pc = pc; tf->pc = pc;
@ -163,7 +173,7 @@ __attribute__((__always_inline__)) static inline void arch_trapframe_set_sp_pc(s
/// @param tf /// @param tf
/// @param argc /// @param argc
/// @param argv /// @param argv
__attribute__((__always_inline__)) static inline void arch_set_main_params(struct trapframe* tf, int argc, uintptr_t argv) __attribute__((always_inline, optimize("O0"))) static inline void arch_set_main_params(struct trapframe* tf, int argc, uintptr_t argv)
{ {
tf->r0 = (uint32_t)argc; tf->r0 = (uint32_t)argc;
tf->r1 = (uint32_t)argv; tf->r1 = (uint32_t)argv;
@ -178,7 +188,7 @@ __attribute__((__always_inline__)) static inline void arch_set_main_params(struc
/// @param param5 /// @param param5
/// @return /// @return
extern int syscall(int sys_num, uintptr_t param1, uintptr_t param2, uintptr_t param3, uintptr_t param4); 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) __attribute__((always_inline, optimize("O0"))) static inline int arch_syscall(struct trapframe* tf, int* syscall_num)
{ {
// call syscall // call syscall
*syscall_num = tf->r0; *syscall_num = tf->r0;
@ -188,7 +198,7 @@ __attribute__((__always_inline__)) static inline int arch_syscall(struct trapfra
/// @brief set return reg to trapframe /// @brief set return reg to trapframe
/// @param tf /// @param tf
/// @param ret /// @param ret
__attribute__((__always_inline__)) static inline void arch_set_return(struct trapframe* tf, int ret) __attribute__((always_inline, optimize("O0"))) static inline void arch_set_return(struct trapframe* tf, int ret)
{ {
tf->r0 = (uint32_t)ret; tf->r0 = (uint32_t)ret;
} }

View File

@ -1,6 +1,7 @@
export CROSS_COMPILE ?= arm-none-eabi- export CROSS_COMPILE ?= arm-none-eabi-
export DEVICE = -march=armv7-a -mtune=cortex-a9 -mfpu=vfpv3-d16 -ftree-vectorize -ffast-math -mfloat-abi=softfp export DEVICE = -march=armv7-a -mtune=cortex-a9 -mfpu=vfpv3-d16 -ftree-vectorize -ffast-math -mfloat-abi=softfp
export CFLAGS := $(DEVICE) -Wall -O0 -g -gdwarf-2 # export CFLAGS := $(DEVICE) -std=c11 -Wall -O2 -g -gdwarf-2 -Wnull-dereference -Waddress -Warray-bounds -Wchar-subscripts -Wimplicit-int -Wimplicit-function-declaration -Wcomment -Wformat -Wmissing-braces -Wnonnull -Wparentheses -Wpointer-sign -Wreturn-type -Wsequence-point -Wstrict-aliasing -Wstrict-overflow=1 -Wswitch -Wtrigraphs -Wuninitialized -Wunknown-pragmas -Wunused-function -Wunused-label -Wunused-value -Wunused-variable -Wunused-function
export CFLAGS := $(DEVICE) -std=c11 -Wall -O2 -g -gdwarf-2 -Waddress -Warray-bounds -Wchar-subscripts -Wimplicit-int -Wimplicit-function-declaration -Wcomment -Wformat -Wmissing-braces -Wnonnull -Wparentheses -Wpointer-sign -Wreturn-type -Wsequence-point -Wstrict-aliasing -Wstrict-overflow=1 -Wswitch -Wtrigraphs -Wuninitialized -Wunknown-pragmas -Wunused-function -Wunused-label -Wunused-value -Wunused-variable -Wunused-function
export AFLAGS := -c $(DEVICE) -x assembler-with-cpp -D__ASSEMBLY__ -gdwarf-2 export AFLAGS := -c $(DEVICE) -x assembler-with-cpp -D__ASSEMBLY__ -gdwarf-2
# export LFLAGS := $(DEVICE) -Wl,-Map=XiZi-imx6q-sabrelite.map,-cref,-u,_boot_start -T $(KERNEL_ROOT)/hardkernel/arch/arm/armv7-a/cortex-a9/preboot_for_imx6q-sabrelite/nxp_imx6q_sabrelite.lds # export LFLAGS := $(DEVICE) -Wl,-Map=XiZi-imx6q-sabrelite.map,-cref,-u,_boot_start -T $(KERNEL_ROOT)/hardkernel/arch/arm/armv7-a/cortex-a9/preboot_for_imx6q-sabrelite/nxp_imx6q_sabrelite.lds
export LFLAGS := $(DEVICE) --specs=nosys.specs -Wl,-Map=XiZi-imx6q-sabrelite.map,-cref,-u,_boot_start -T $(KERNEL_ROOT)/hardkernel/arch/arm/armv7-a/cortex-a9/preboot_for_imx6q-sabrelite/nxp_imx6q_sabrelite.lds export LFLAGS := $(DEVICE) --specs=nosys.specs -Wl,-Map=XiZi-imx6q-sabrelite.map,-cref,-u,_boot_start -T $(KERNEL_ROOT)/hardkernel/arch/arm/armv7-a/cortex-a9/preboot_for_imx6q-sabrelite/nxp_imx6q_sabrelite.lds

View File

@ -70,10 +70,10 @@ Modification:
#define ISB() __asm__ volatile("isb\n\t") #define ISB() __asm__ volatile("isb\n\t")
#define _ARM_MRC(coproc, opcode1, Rt, CRn, CRm, opcode2) \ #define _ARM_MRC(coproc, opcode1, Rt, CRn, CRm, opcode2) \
asm volatile("mrc p" #coproc ", " #opcode1 ", %[output], c" #CRn ", c" #CRm ", " #opcode2 "\n" : [output] "=r"(Rt)) __asm__ volatile("mrc p" #coproc ", " #opcode1 ", %[output], c" #CRn ", c" #CRm ", " #opcode2 "\n" : [output] "=r"(Rt))
#define _ARM_MCR(coproc, opcode1, Rt, CRn, CRm, opcode2) \ #define _ARM_MCR(coproc, opcode1, Rt, CRn, CRm, opcode2) \
asm volatile("mcr p" #coproc ", " #opcode1 ", %[input], c" #CRn ", c" #CRm ", " #opcode2 "\n" ::[input] "r"(Rt)) __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 WriteReg(value, address) (*(volatile unsigned int*)(address) = (value))
#define ReadReg(address) (*(volatile unsigned int*)(address)) #define ReadReg(address) (*(volatile unsigned int*)(address))

View File

@ -56,7 +56,7 @@ typedef unsigned int reg32_t;
#endif #endif
// //
// Typecast macro for C or asm. In C, the cast is applied, while in asm it is excluded. This is // Typecast macro for C or __asm__. In C, the cast is applied, while in __asm__ it is excluded. This is
// used to simplify macro definitions in the module register headers. // used to simplify macro definitions in the module register headers.
// //
#ifndef __REG_VALUE_TYPE #ifndef __REG_VALUE_TYPE

View File

@ -18,14 +18,14 @@
/** /**
* @file soc_memory_map.h * @file soc_memory_map.h
* @brief support imx6q soc memory map define, reference from u-boot-2009-08/include/asm-arm/arch-mx6/mx6.h * @brief support imx6q soc memory map define, reference from u-boot-2009-08/include/__asm__-arm/arch-mx6/mx6.h
* @version 3.0 * @version 3.0
* @author AIIT XUOS Lab * @author AIIT XUOS Lab
* @date 2023.09.08 * @date 2023.09.08
*/ */
/************************************************* /*************************************************
File name: soc_memory_map.h File name: soc_memory_map.h
Description: support imx6q soc memory map define, reference from u-boot-2009-08/include/asm-arm/arch-mx6/mx6.h Description: support imx6q soc memory map define, reference from u-boot-2009-08/include/__asm__-arm/arch-mx6/mx6.h
Others: Others:
History: History:
1. Date: 2023-08-28 1. Date: 2023-08-28

View File

@ -77,11 +77,15 @@ BOOT_STACK_SIZE = 0x4000;
RAM_VECTORS_SIZE = 72; RAM_VECTORS_SIZE = 72;
/* Specify the memory areas */ /* Specify the memory areas */
/*
ddr3: physical area: [0x10000000, 0x50000000);
virt_ddr3: virt area exclude boot(start_sec), that will be [0x90000000 + 0x11000, 0xD0000000)
*/
MEMORY MEMORY
{ {
ocram (rwx) : ORIGIN = 0x00900000, LENGTH = 256K ocram (rwx) : ORIGIN = 0x00900000, LENGTH = 256K
ddr3 (rwx) : ORIGIN = 0x10000000, LENGTH = 1024M ddr3 (rwx) : ORIGIN = 0x10000000, LENGTH = 1024M
virt_ddr3 (WRX) : ORIGIN = 0x90011000, LENGTH = 1024M virt_ddr3 (WRX) : ORIGIN = 0x90014000, LENGTH = 1024M
} }
SECTIONS SECTIONS
@ -154,8 +158,8 @@ SECTIONS
PROVIDE(boot_end_addr = .); PROVIDE(boot_end_addr = .);
} > ddr3 } > ddr3
/* Other Kernel code is placed over 0x80000000 + 128KB. */ /* Other Kernel code is placed over 0x10011000(phy) and 0x90011000(virt). */
.text : AT(0x10011000) { .text : AT(0x10014000) {
*(.vectors) *(.vectors)
. = ALIGN(0x1000); . = ALIGN(0x1000);
*(.text .text.* .gnu.linkonce.t.*) *(.text .text.* .gnu.linkonce.t.*)

View File

@ -85,12 +85,13 @@ void ccm_init(void)
#endif #endif
// Ungate clocks that are not enabled in a driver - need to be updated // Ungate clocks that are not enabled in a driver - need to be updated
HW_CCM_CCGR0_WR(0xffffffff); HW_CCM_CCGR0_WR(0xffffffff);
HW_CCM_CCGR1_WR(0xFFCF0FFF); // EPIT, ESAI, GPT enabled by driver HW_CCM_CCGR1_WR(0xFFCF0FFF); // EPIT, ESAI, GPT enabled by driver
HW_CCM_CCGR2_WR(0xFFFFF03F); // I2C enabled by driver HW_CCM_CCGR2_WR(0xFFFFF03F); // I2C enabled by driver
HW_CCM_CCGR3_WR(0xffffffff); HW_CCM_CCGR3_WR(0xffffffff);
HW_CCM_CCGR4_WR(0x00FFFF03); // GPMI, Perfmon enabled by driver HW_CCM_CCGR4_WR(0x00FFFF03); // GPMI, Perfmon enabled by driver
HW_CCM_CCGR5_WR(0xF0FFFFCF); // UART, SATA enabled by driver // HW_CCM_CCGR5_WR(0xF0FFFFCF); // UART, SATA enabled by driver
HW_CCM_CCGR6_WR(0xffffffff); HW_CCM_CCGR6_WR(0xffffffff);
/* /*

View File

@ -39,6 +39,8 @@ Modification:
static void _sys_clock_init() static void _sys_clock_init()
{ {
uint32_t freq = get_main_clock(IPG_CLK); uint32_t freq = get_main_clock(IPG_CLK);
ccm_init();
gpt_init(CLKSRC_IPG_CLK, freq / 1000000, RESTART_MODE, WAIT_MODE_EN | STOP_MODE_EN); gpt_init(CLKSRC_IPG_CLK, freq / 1000000, RESTART_MODE, WAIT_MODE_EN | STOP_MODE_EN);
gpt_set_compare_event(kGPTOutputCompare1, OUTPUT_CMP_DISABLE, 1000); gpt_set_compare_event(kGPTOutputCompare1, OUTPUT_CMP_DISABLE, 1000);
gpt_counter_enable(kGPTOutputCompare1); gpt_counter_enable(kGPTOutputCompare1);

View File

@ -37,6 +37,7 @@ Modification:
#include "assert.h" #include "assert.h"
#include "pagetable.h" #include "pagetable.h"
#include "spinlock.h"
#define KERN_BOOT_DRIVER(n, bi, f) \ #define KERN_BOOT_DRIVER(n, bi, f) \
{ \ { \

View File

@ -125,20 +125,22 @@ void iabort_reason(struct trapframe* r)
void handle_undefined_instruction(struct trapframe* tf) void handle_undefined_instruction(struct trapframe* tf)
{ {
// unimplemented trap handler // unimplemented trap handler
xizi_enter_kernel();
ERROR("undefined instruction at %x\n", tf->pc); ERROR("undefined instruction at %x\n", tf->pc);
xizi_enter_kernel();
panic(""); panic("");
} }
void handle_reserved(void) void handle_reserved(void)
{ {
// unimplemented trap handler // unimplemented trap handler
ERROR("Unimplemented Reserved\n");
xizi_enter_kernel(); xizi_enter_kernel();
panic("Unimplemented Reserved\n"); panic("");
} }
void handle_fiq(void) void handle_fiq(void)
{ {
ERROR("Unimplemented FIQ\n");
xizi_enter_kernel(); xizi_enter_kernel();
panic("Unimplemented FIQ\n"); panic("");
} }

View File

@ -45,6 +45,8 @@ Author: AIIT XUOS Lab
Modification: Modification:
1. take only gicd part of functions 1. take only gicd part of functions
*************************************************/ *************************************************/
#include "string.h"
#include "gicv2_common_opa.h" #include "gicv2_common_opa.h"
#include "gicv2_registers.h" #include "gicv2_registers.h"
@ -139,7 +141,7 @@ void gic_send_sgi(uint32_t irqID, uint32_t target_list, uint32_t filter_list)
void gic_init(void) void gic_init(void)
{ {
gicd_t* gicd = gic_get_gicd(); volatile gicd_t* gicd = gic_get_gicd();
// First disable the distributor. // First disable the distributor.
gic_enable(false); gic_enable(false);
@ -150,7 +152,9 @@ void gic_init(void)
for (uint32_t i = 0; i < 255; i++) { for (uint32_t i = 0; i < 255; i++) {
*(uint32_t*)(&gicd->IPRIORITYRn[i * sizeof(uint32_t)]) = (uint32_t)0x80808080; *(uint32_t*)(&gicd->IPRIORITYRn[i * sizeof(uint32_t)]) = (uint32_t)0x80808080;
// memset((void*)&gicd->IPRIORITYRn[i * sizeof(uint32_t)], 0x80, sizeof(uint32_t));
*(uint32_t*)(&gicd->ITARGETSRn[i * sizeof(uint32_t)]) = (uint32_t)0x01010101; *(uint32_t*)(&gicd->ITARGETSRn[i * sizeof(uint32_t)]) = (uint32_t)0x01010101;
// memset((void*)&gicd->IPRIORITYRn[i * sizeof(uint32_t)], 0x01, sizeof(uint32_t));
} }
// Init the GIC CPU interface. // Init the GIC CPU interface.

View File

@ -156,29 +156,11 @@ static uint32_t _hw_cur_int_num(uint32_t int_info)
return int_info & 0x1FF; return int_info & 0x1FF;
} }
static uint32_t _hw_cur_int_cpu(uint32_t int_info)
{
return (int_info >> 10) & 0x7;
}
static void _hw_after_irq(uint32_t int_info) static void _hw_after_irq(uint32_t int_info)
{ {
gic_write_end_of_irq(int_info); gic_write_end_of_irq(int_info);
} }
static int _is_interruptable(void)
{
uint32_t val;
__asm__ __volatile__(
"mrs %0, cpsr"
: "=r"(val)
:
:);
return !(val & DIS_INT);
}
int _cur_cpu_id() int _cur_cpu_id()
{ {
return cpu_get_current(); return cpu_get_current();
@ -196,10 +178,8 @@ static struct XiziTrapDriver xizi_trap_driver = {
.bind_irq_handler = _bind_irq_handler, .bind_irq_handler = _bind_irq_handler,
.is_interruptable = _is_interruptable,
.hw_before_irq = _hw_before_irq, .hw_before_irq = _hw_before_irq,
.hw_cur_int_num = _hw_cur_int_num, .hw_cur_int_num = _hw_cur_int_num,
.hw_cur_int_cpu = _hw_cur_int_cpu,
.hw_after_irq = _hw_after_irq, .hw_after_irq = _hw_after_irq,
}; };

View File

@ -163,29 +163,11 @@ static uint32_t _hw_cur_int_num(uint32_t int_info)
return int_info & XSCUGIC_ACK_INTID_MASK; return int_info & XSCUGIC_ACK_INTID_MASK;
} }
static uint32_t _hw_cur_int_cpu(uint32_t int_info)
{
return (int_info >> 5) & 0x3;
}
static void _hw_after_irq(uint32_t int_info) static void _hw_after_irq(uint32_t int_info)
{ {
XScuGic_CPUWriteReg(&IntcInstance, XSCUGIC_EOI_OFFSET, int_info); XScuGic_CPUWriteReg(&IntcInstance, XSCUGIC_EOI_OFFSET, int_info);
} }
static int _is_interruptable(void)
{
uint32_t val;
__asm__ __volatile__(
"mrs %0, cpsr"
: "=r"(val)
:
:);
return !(val & DIS_INT);
}
int _cur_cpu_id() int _cur_cpu_id()
{ {
return cpu_get_current(); return cpu_get_current();
@ -203,10 +185,8 @@ static struct XiziTrapDriver xizi_trap_driver = {
.bind_irq_handler = _bind_irq_handler, .bind_irq_handler = _bind_irq_handler,
.is_interruptable = _is_interruptable,
.hw_before_irq = _hw_before_irq, .hw_before_irq = _hw_before_irq,
.hw_cur_int_num = _hw_cur_int_num, .hw_cur_int_num = _hw_cur_int_num,
.hw_cur_int_cpu = _hw_cur_int_cpu,
.hw_after_irq = _hw_after_irq, .hw_after_irq = _hw_after_irq,
}; };

View File

@ -52,7 +52,7 @@ enum {
SPINLOCK_LOCK_WAITFOREVER = 0xFFFFFFFF, SPINLOCK_LOCK_WAITFOREVER = 0xFFFFFFFF,
}; };
void spinlock_init(struct spinlock* lock, char* name) __attribute__((optimize("O0"))) void spinlock_init(struct spinlock* lock, char* name)
{ {
lock->owner_cpu = SPINLOCK_STATE_UNLOCK; lock->owner_cpu = SPINLOCK_STATE_UNLOCK;
strncpy(lock->name, name, 24); strncpy(lock->name, name, 24);
@ -61,7 +61,7 @@ void spinlock_init(struct spinlock* lock, char* name)
extern int _spinlock_lock(struct spinlock* lock, uint32_t timeout); extern int _spinlock_lock(struct spinlock* lock, uint32_t timeout);
void _spinlock_unlock(struct spinlock* lock); void _spinlock_unlock(struct spinlock* lock);
void spinlock_lock(struct spinlock* lock) __attribute__((optimize("O0"))) void spinlock_lock(struct spinlock* lock)
{ {
int cur_cpu_id = cur_cpuid(); int cur_cpu_id = cur_cpuid();
if (lock->owner_cpu != SPINLOCK_STATE_UNLOCK && lock->owner_cpu == cur_cpu_id) { if (lock->owner_cpu != SPINLOCK_STATE_UNLOCK && lock->owner_cpu == cur_cpu_id) {
@ -80,7 +80,7 @@ void spinlock_lock(struct spinlock* lock)
_spinlock_lock(lock, SPINLOCK_LOCK_WAITFOREVER); _spinlock_lock(lock, SPINLOCK_LOCK_WAITFOREVER);
} }
void spinlock_unlock(struct spinlock* lock) __attribute__((optimize("O0"))) void spinlock_unlock(struct spinlock* lock)
{ {
struct double_list_node* p_lock_node = &core_lock_request[cur_cpuid()].node; struct double_list_node* p_lock_node = &core_lock_request[cur_cpuid()].node;
assert(lock_request_guard.next == p_lock_node); assert(lock_request_guard.next == p_lock_node);
@ -91,7 +91,7 @@ void spinlock_unlock(struct spinlock* lock)
_spinlock_unlock(lock); _spinlock_unlock(lock);
} }
bool spinlock_try_lock(struct spinlock* lock) __attribute__((optimize("O0"))) bool spinlock_try_lock(struct spinlock* lock)
{ {
int cur_cpu_id = cur_cpuid(); int cur_cpu_id = cur_cpuid();
if (lock->owner_cpu != SPINLOCK_STATE_UNLOCK && lock->owner_cpu == cur_cpu_id) { if (lock->owner_cpu != SPINLOCK_STATE_UNLOCK && lock->owner_cpu == cur_cpu_id) {
@ -115,5 +115,5 @@ bool spinlock_try_lock(struct spinlock* lock)
bool is_spinlock_hold_by_current_cpu(struct spinlock* lock) bool is_spinlock_hold_by_current_cpu(struct spinlock* lock)
{ {
return lock->owner_cpu; return lock->owner_cpu == cur_cpuid();
} }

View File

@ -56,8 +56,6 @@ struct irq_table_entry {
struct XiziTrapDriver { struct XiziTrapDriver {
/* irq number table*/ /* irq number table*/
struct irq_table_entry sw_irqtbl[NR_IRQS]; struct irq_table_entry sw_irqtbl[NR_IRQS];
/* current irq number happening in cpu*/
uint32_t curr_int[NR_CPU];
void (*sys_irq_init)(int); void (*sys_irq_init)(int);
int (*cur_cpu_id)(); int (*cur_cpu_id)();
@ -71,11 +69,9 @@ struct XiziTrapDriver {
void (*bind_irq_handler)(int, irq_handler_t); void (*bind_irq_handler)(int, irq_handler_t);
/* check if no if interruptable */ /* check if no if interruptable */
int (*is_interruptable)();
/* code runs before irq handling */ /* code runs before irq handling */
uint32_t (*hw_before_irq)(); uint32_t (*hw_before_irq)();
uint32_t (*hw_cur_int_num)(uint32_t int_info); uint32_t (*hw_cur_int_num)(uint32_t int_info);
uint32_t (*hw_cur_int_cpu)(uint32_t int_info);
/* code runs after irq handling */ /* code runs after irq handling */
void (*hw_after_irq)(uint32_t int_info); void (*hw_after_irq)(uint32_t int_info);
}; };

View File

@ -38,24 +38,6 @@ Modification:
// extern struct MmuCommonDone mmu_common_done; // extern struct MmuCommonDone mmu_common_done;
static struct MmuDriverRightGroup right_group; static struct MmuDriverRightGroup right_group;
void load_pgdir_critical(uintptr_t pgdir_paddr, struct TraceTag* intr_driver_tag)
{
/* 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);
/* get intr driver */
struct XiziTrapDriver* p_intr_driver = AchieveResource(intr_driver_tag);
p_intr_driver->cpu_irq_disable();
TTBR0_W((uint32_t)pgdir_paddr);
CLEARTLB(0);
p_icache_done->invalidateall();
p_dcache_done->flushall();
p_intr_driver->cpu_irq_enable();
}
void load_pgdir(uintptr_t pgdir_paddr) void load_pgdir(uintptr_t pgdir_paddr)
{ {
/* get cache driver */ /* get cache driver */
@ -94,7 +76,6 @@ static struct MmuCommonDone mmu_common_done = {
.MmuUsrDevPteAttr = GetUsrDevPteAttr, .MmuUsrDevPteAttr = GetUsrDevPteAttr,
.MmuKernPteAttr = GetKernPteAttr, .MmuKernPteAttr = GetKernPteAttr,
.LoadPgdirCrit = load_pgdir_critical,
.LoadPgdir = load_pgdir, .LoadPgdir = load_pgdir,
.TlbFlushAll = tlb_flush_all, .TlbFlushAll = tlb_flush_all,
.TlbFlush = tlb_flush_range, .TlbFlush = tlb_flush_range,

View File

@ -56,6 +56,9 @@ void GetUsrDevPteAttr(uintptr_t* attr)
usr_pte_attr.entry = 0; usr_pte_attr.entry = 0;
usr_pte_attr.desc_type = PAGE_4K; usr_pte_attr.desc_type = PAGE_4K;
usr_pte_attr.TEX = 2;
// usr_pte_attr.B = 1;
usr_pte_attr.S = 1;
usr_pte_attr.AP1_0 = AccessPermission_KernelUser; usr_pte_attr.AP1_0 = AccessPermission_KernelUser;
} }
*attr = usr_pte_attr.entry; *attr = usr_pte_attr.entry;
@ -87,6 +90,7 @@ void GetKernPteAttr(uintptr_t* attr)
kern_pte_attr.B = 1; kern_pte_attr.B = 1;
kern_pte_attr.C = 1; kern_pte_attr.C = 1;
kern_pte_attr.S = 1; kern_pte_attr.S = 1;
kern_pte_attr.TEX = 1;
kern_pte_attr.AP1_0 = AccessPermission_KernelOnly; kern_pte_attr.AP1_0 = AccessPermission_KernelOnly;
} }
*attr = kern_pte_attr.entry; *attr = kern_pte_attr.entry;
@ -94,5 +98,13 @@ void GetKernPteAttr(uintptr_t* attr)
void GetPdeAttr(uintptr_t* attr) void GetPdeAttr(uintptr_t* attr)
{ {
*attr = PAGE_DIR_COARSE; static char init = 0;
static PageDirEntry pde_attr;
if (init == 0) {
init = 1;
pde_attr.entry = 0;
pde_attr.desc_type = PAGE_DIR_COARSE;
}
*attr = pde_attr.entry;
} }

View File

@ -27,7 +27,6 @@ struct MmuCommonDone
void (*MmuUsrDevPteAttr)(uintptr_t* attr); void (*MmuUsrDevPteAttr)(uintptr_t* attr);
void (*MmuKernPteAttr)(uintptr_t* attr); void (*MmuKernPteAttr)(uintptr_t* attr);
void (*LoadPgdirCrit)(uintptr_t pgdir_paddr, struct TraceTag*);
void (*LoadPgdir)(uintptr_t pgdir_paddr); void (*LoadPgdir)(uintptr_t pgdir_paddr);
void (*TlbFlushAll)(); void (*TlbFlushAll)();
void (*TlbFlush)(uintptr_t vaddr, int len); void (*TlbFlush)(uintptr_t vaddr, int len);

View File

@ -21,14 +21,14 @@
/** /**
* @file iomux_v3.h * @file iomux_v3.h
* @brief support imx6q iomux function define, reference from u-boot-2009-08/include/asm-arm/arch-mx6/iomux_v3.h * @brief support imx6q iomux function define, reference from u-boot-2009-08/include/__asm__-arm/arch-mx6/iomux_v3.h
* @version 3.0 * @version 3.0
* @author AIIT XUOS Lab * @author AIIT XUOS Lab
* @date 2023.09.08 * @date 2023.09.08
*/ */
/************************************************* /*************************************************
File name: iomux_v3.h File name: iomux_v3.h
Description: support imx6q iomux function define, reference from u-boot-2009-08/include/asm-arm/arch-mx6/iomux_v3.h Description: support imx6q iomux function define, reference from u-boot-2009-08/include/__asm__-arm/arch-mx6/iomux_v3.h
Others: Others:
History: History:
1. Date: 2023-09-08 1. Date: 2023-09-08

View File

@ -21,14 +21,14 @@
/** /**
* @file regs_pins.h * @file regs_pins.h
* @brief support imx6q pin map define, reference from u-boot-2009-08/include/asm-arm/arch-mx6/mx6_pins.h * @brief support imx6q pin map define, reference from u-boot-2009-08/include/__asm__-arm/arch-mx6/mx6_pins.h
* @version 3.0 * @version 3.0
* @author AIIT XUOS Lab * @author AIIT XUOS Lab
* @date 2023.09.08 * @date 2023.09.08
*/ */
/************************************************* /*************************************************
File name: regs_pins.h File name: regs_pins.h
Description: support imx6q pin map define, reference from u-boot-2009-08/include/asm-arm/arch-mx6/mx6_pins.h Description: support imx6q pin map define, reference from u-boot-2009-08/include/__asm__-arm/arch-mx6/mx6_pins.h
Others: Others:
History: History:
1. Date: 2023-09-08 1. Date: 2023-09-08

View File

@ -0,0 +1,102 @@
///////////////////////////////////////////////////////////////////////////////
// \author (c) Marco Paland (info@paland.com)
// 2014-2019, PALANDesign Hannover, Germany
//
// \license The MIT License (MIT)
//
// 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.
//
// \brief Tiny printf, sprintf and snprintf implementation, optimized for speed on
// embedded systems with a very limited resources.
// Use this instead of bloated standard/newlib printf.
// These routines are thread safe and reentrant.
//
///////////////////////////////////////////////////////////////////////////////
#ifndef _PRINTF_H_
#define _PRINTF_H_
#include <stdarg.h>
#include <stddef.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* Tiny printf implementation
* You have to implement _putchar if you use printf()
* To avoid conflicts with the regular printf() API it is overridden by macro defines
* and internal underscore-appended functions like printf_() are used
* \param format A string that specifies the format of the output
* \return The number of characters that are written into the array, not counting the terminating null character
*/
#define KPrintf printf_
#define printf printf_
int printf_(const char* format, ...);
/**
* Tiny sprintf implementation
* Due to security reasons (buffer overflow) YOU SHOULD CONSIDER USING (V)SNPRINTF INSTEAD!
* \param buffer A pointer to the buffer where to store the formatted string. MUST be big enough to store the output!
* \param format A string that specifies the format of the output
* \return The number of characters that are WRITTEN into the buffer, not counting the terminating null character
*/
#define sprintf sprintf_
int sprintf_(char* buffer, const char* format, ...);
/**
* Tiny snprintf/vsnprintf implementation
* \param buffer A pointer to the buffer where to store the formatted string
* \param count The maximum number of characters to store in the buffer, including a terminating null character
* \param format A string that specifies the format of the output
* \param va A value identifying a variable arguments list
* \return The number of characters that COULD have been written into the buffer, not counting the terminating
* null character. A value equal or larger than count indicates truncation. Only when the returned value
* is non-negative and less than count, the string has been completely written.
*/
#define snprintf snprintf_
#define vsnprintf vsnprintf_
int snprintf_(char* buffer, size_t count, const char* format, ...);
int vsnprintf_(char* buffer, size_t count, const char* format, va_list va);
/**
* Tiny vprintf implementation
* \param format A string that specifies the format of the output
* \param va A value identifying a variable arguments list
* \return The number of characters that are WRITTEN into the buffer, not counting the terminating null character
*/
#define vprintf vprintf_
int vprintf_(const char* format, va_list va);
/**
* printf with output function
* You may use this as dynamic alternative to printf() with its fixed _putchar() output
* \param out An output function which takes one character and an argument pointer
* \param arg An argument pointer for user data passed to output function
* \param format A string that specifies the format of the output
* \return The number of characters that are sent to the output function, not counting the terminating null character
*/
int fctprintf(void (*out)(char character, void* arg), void* arg, const char* format, ...);
#ifdef __cplusplus
}
#endif
#endif // _PRINTF_H_

View File

@ -1,15 +1,34 @@
/* ///////////////////////////////////////////////////////////////////////////////
* Copyright (c) 2020 AIIT XUOS Lab // \author (c) Marco Paland (info@paland.com)
* XiUOS is licensed under Mulan PSL v2. // 2014-2019, PALANDesign Hannover, Germany
* 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: // \license The MIT License (MIT)
* http://license.coscl.org.cn/MulanPSL2 //
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND, // Permission is hereby granted, free of charge, to any person obtaining a copy
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT, // of this software and associated documentation files (the "Software"), to deal
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE. // in the Software without restriction, including without limitation the rights
* See the Mulan PSL v2 for more details. // 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.
//
// \brief Tiny printf, sprintf and (v)snprintf implementation, optimized for speed on
// embedded systems with a very limited resources. These routines are thread
// safe and reentrant!
// Use this instead of the bloated standard/newlib printf cause these use
// malloc for printf (and may not be thread safe).
//
///////////////////////////////////////////////////////////////////////////////
/** /**
* @file uart_common_ope.c * @file uart_common_ope.c
* @brief support uart common operation * @brief support uart common operation
@ -17,8 +36,10 @@
* @author AIIT XUOS Lab * @author AIIT XUOS Lab
* @date 2023.11.20 * @date 2023.11.20
*/ */
#include <stdbool.h>
#include <stdint.h>
#include "uart_common_ope.h" #include "uart_common_ope.h"
#include "assert.h"
struct PrintProxy { struct PrintProxy {
struct TraceTag uart_driver_tag; struct TraceTag uart_driver_tag;
@ -38,85 +59,840 @@ int serial_init(struct TraceTag* uart_driver_tag)
return 0; return 0;
} }
static void PrintInt(int xx, int base, int sign) // 'ntoa' conversion buffer size, this must be big enough to hold one converted
// numeric number including padded zeros (dynamically created on stack)
// default: 32 byte
#define PRINTF_NTOA_BUFFER_SIZE 32U
#define PRINTF_FTOA_BUFFER_SIZE 32U
// support for the floating point type (%f)
// default: activated
#define PRINTF_SUPPORT_FLOAT
// support for exponential floating point notation (%e/%g)
// default: activated
#define PRINTF_SUPPORT_EXPONENTIAL
// define the default floating point precision
// default: 6 digits
#define PRINTF_DEFAULT_FLOAT_PRECISION 6U
// define the largest float suitable to print with %f
// default: 1e9
#define PRINTF_MAX_FLOAT 1e9
// support for the long long types (%llu or %p)
// default: activated
#define PRINTF_SUPPORT_LONG_LONG
// support for the ptrdiff_t type (%t)
// ptrdiff_t is normally defined in <stddef.h> as long or long long type
// default: activated
#define PRINTF_SUPPORT_PTRDIFF_T
#define _putchar proxy()->serial->putc
///////////////////////////////////////////////////////////////////////////////
// internal flag definitions
#define FLAGS_ZEROPAD (1U << 0U)
#define FLAGS_LEFT (1U << 1U)
#define FLAGS_PLUS (1U << 2U)
#define FLAGS_SPACE (1U << 3U)
#define FLAGS_HASH (1U << 4U)
#define FLAGS_UPPERCASE (1U << 5U)
#define FLAGS_CHAR (1U << 6U)
#define FLAGS_SHORT (1U << 7U)
#define FLAGS_LONG (1U << 8U)
#define FLAGS_LONG_LONG (1U << 9U)
#define FLAGS_PRECISION (1U << 10U)
#define FLAGS_ADAPT_EXP (1U << 11U)
// import float.h for DBL_MAX
#if defined(PRINTF_SUPPORT_FLOAT)
#include <float.h>
#endif
// output function type
typedef void (*out_fct_type)(char character, void* buffer, size_t idx, size_t maxlen);
// wrapper (used as buffer) for output function type
typedef struct {
void (*fct)(char character, void* arg);
void* arg;
} out_fct_wrap_type;
// internal buffer output
static inline void _out_buffer(char character, void* buffer, size_t idx, size_t maxlen)
{ {
static char digits[] = "0123456789ABCDEF"; if (idx < maxlen) {
char buf[16]; ((char*)buffer)[idx] = character;
int i;
uint32_t x;
if (sign && (sign = xx < 0)) {
x = -xx;
} else {
x = xx;
} }
i = 0;
do {
buf[i++] = digits[x % base];
} while ((x /= base) != 0);
if (sign)
buf[i++] = '-';
while (--i >= 0)
proxy()->serial->putc(buf[i]);
} }
void KPrintf(char* fmt, ...) // internal null output
static inline void _out_null(char character, void* buffer, size_t idx, size_t maxlen)
{ {
int i, c; (void)character;
uint32_t* argp; (void)buffer;
char* s; (void)idx;
(void)maxlen;
}
if (fmt == 0) { // internal _putchar wrapper
KPrintf("null fmt"); static inline void _out_char(char character, void* buffer, size_t idx, size_t maxlen)
return; {
(void)buffer;
(void)idx;
(void)maxlen;
if (character) {
_putchar(character);
}
}
// internal output function wrapper
static inline void _out_fct(char character, void* buffer, size_t idx, size_t maxlen)
{
(void)idx;
(void)maxlen;
if (character) {
// buffer is the output fct pointer
((out_fct_wrap_type*)buffer)->fct(character, ((out_fct_wrap_type*)buffer)->arg);
}
}
// internal secure strlen
// \return The length of the string (excluding the terminating 0) limited by 'maxsize'
static inline unsigned int _strnlen_s(const char* str, size_t maxsize)
{
const char* s;
for (s = str; *s && maxsize--; ++s)
;
return (unsigned int)(s - str);
}
// internal test if char is a digit (0-9)
// \return true if char is a digit
static inline bool _is_digit(char ch)
{
return (ch >= '0') && (ch <= '9');
}
// internal ASCII string to unsigned int conversion
static unsigned int _atoi(const char** str)
{
unsigned int i = 0U;
while (_is_digit(**str)) {
i = i * 10U + (unsigned int)(*((*str)++) - '0');
}
return i;
}
// output the specified string in reverse, taking care of any zero-padding
static size_t _out_rev(out_fct_type out, char* buffer, size_t idx, size_t maxlen, const char* buf, size_t len, unsigned int width, unsigned int flags)
{
const size_t start_idx = idx;
// pad spaces up to given width
if (!(flags & FLAGS_LEFT) && !(flags & FLAGS_ZEROPAD)) {
for (size_t i = len; i < width; i++) {
out(' ', buffer, idx++, maxlen);
}
} }
argp = (uint32_t*)(void*)(&fmt + 1); // reverse string
while (len) {
out(buf[--len], buffer, idx++, maxlen);
}
for (i = 0; (c = fmt[i] & 0xff) != 0; i++) { // append pad spaces up to given width
if (c != '%') { if (flags & FLAGS_LEFT) {
proxy()->serial->putc(c); while (idx - start_idx < width) {
out(' ', buffer, idx++, maxlen);
}
}
return idx;
}
// internal itoa format
static size_t _ntoa_format(out_fct_type out, char* buffer, size_t idx, size_t maxlen, char* buf, size_t len, bool negative, unsigned int base, unsigned int prec, unsigned int width, unsigned int flags)
{
// pad leading zeros
if (!(flags & FLAGS_LEFT)) {
if (width && (flags & FLAGS_ZEROPAD) && (negative || (flags & (FLAGS_PLUS | FLAGS_SPACE)))) {
width--;
}
while ((len < prec) && (len < PRINTF_NTOA_BUFFER_SIZE)) {
buf[len++] = '0';
}
while ((flags & FLAGS_ZEROPAD) && (len < width) && (len < PRINTF_NTOA_BUFFER_SIZE)) {
buf[len++] = '0';
}
}
// handle hash
if (flags & FLAGS_HASH) {
if (!(flags & FLAGS_PRECISION) && len && ((len == prec) || (len == width))) {
len--;
if (len && (base == 16U)) {
len--;
}
}
if ((base == 16U) && !(flags & FLAGS_UPPERCASE) && (len < PRINTF_NTOA_BUFFER_SIZE)) {
buf[len++] = 'x';
} else if ((base == 16U) && (flags & FLAGS_UPPERCASE) && (len < PRINTF_NTOA_BUFFER_SIZE)) {
buf[len++] = 'X';
} else if ((base == 2U) && (len < PRINTF_NTOA_BUFFER_SIZE)) {
buf[len++] = 'b';
}
if (len < PRINTF_NTOA_BUFFER_SIZE) {
buf[len++] = '0';
}
}
if (len < PRINTF_NTOA_BUFFER_SIZE) {
if (negative) {
buf[len++] = '-';
} else if (flags & FLAGS_PLUS) {
buf[len++] = '+'; // ignore the space if the '+' exists
} else if (flags & FLAGS_SPACE) {
buf[len++] = ' ';
}
}
return _out_rev(out, buffer, idx, maxlen, buf, len, width, flags);
}
// internal itoa for 'long' type
static size_t _ntoa_long(out_fct_type out, char* buffer, size_t idx, size_t maxlen, unsigned long value, bool negative, unsigned long base, unsigned int prec, unsigned int width, unsigned int flags)
{
char buf[PRINTF_NTOA_BUFFER_SIZE];
size_t len = 0U;
// no hash for 0 values
if (!value) {
flags &= ~FLAGS_HASH;
}
// write if precision != 0 and value is != 0
if (!(flags & FLAGS_PRECISION) || value) {
do {
const char digit = (char)(value % base);
buf[len++] = digit < 10 ? '0' + digit : (flags & FLAGS_UPPERCASE ? 'A' : 'a') + digit - 10;
value /= base;
} while (value && (len < PRINTF_NTOA_BUFFER_SIZE));
}
return _ntoa_format(out, buffer, idx, maxlen, buf, len, negative, (unsigned int)base, prec, width, flags);
}
// internal itoa for 'long long' type
#if defined(PRINTF_SUPPORT_LONG_LONG)
static size_t _ntoa_long_long(out_fct_type out, char* buffer, size_t idx, size_t maxlen, unsigned long long value, bool negative, unsigned long long base, unsigned int prec, unsigned int width, unsigned int flags)
{
char buf[PRINTF_NTOA_BUFFER_SIZE];
size_t len = 0U;
// no hash for 0 values
if (!value) {
flags &= ~FLAGS_HASH;
}
// write if precision != 0 and value is != 0
if (!(flags & FLAGS_PRECISION) || value) {
do {
const char digit = (char)(value % base);
buf[len++] = digit < 10 ? '0' + digit : (flags & FLAGS_UPPERCASE ? 'A' : 'a') + digit - 10;
value /= base;
} while (value && (len < PRINTF_NTOA_BUFFER_SIZE));
}
return _ntoa_format(out, buffer, idx, maxlen, buf, len, negative, (unsigned int)base, prec, width, flags);
}
#endif // PRINTF_SUPPORT_LONG_LONG
#if defined(PRINTF_SUPPORT_FLOAT)
#if defined(PRINTF_SUPPORT_EXPONENTIAL)
// forward declaration so that _ftoa can switch to exp notation for values > PRINTF_MAX_FLOAT
static size_t _etoa(out_fct_type out, char* buffer, size_t idx, size_t maxlen, double value, unsigned int prec, unsigned int width, unsigned int flags);
#endif
// internal ftoa for fixed decimal floating point
static size_t _ftoa(out_fct_type out, char* buffer, size_t idx, size_t maxlen, double value, unsigned int prec, unsigned int width, unsigned int flags)
{
char buf[PRINTF_FTOA_BUFFER_SIZE];
size_t len = 0U;
double diff = 0.0;
// powers of 10
static const double pow10[] = { 1, 10, 100, 1000, 10000, 100000, 1000000, 10000000, 100000000, 1000000000 };
// test for special values
if (value != value)
return _out_rev(out, buffer, idx, maxlen, "nan", 3, width, flags);
if (value < -DBL_MAX)
return _out_rev(out, buffer, idx, maxlen, "fni-", 4, width, flags);
if (value > DBL_MAX)
return _out_rev(out, buffer, idx, maxlen, (flags & FLAGS_PLUS) ? "fni+" : "fni", (flags & FLAGS_PLUS) ? 4U : 3U, width, flags);
// test for very large values
// standard printf behavior is to print EVERY whole number digit -- which could be 100s of characters overflowing your buffers == bad
if ((value > PRINTF_MAX_FLOAT) || (value < -PRINTF_MAX_FLOAT)) {
#if defined(PRINTF_SUPPORT_EXPONENTIAL)
return _etoa(out, buffer, idx, maxlen, value, prec, width, flags);
#else
return 0U;
#endif
}
// test for negative
bool negative = false;
if (value < 0) {
negative = true;
value = 0 - value;
}
// set default precision, if not set explicitly
if (!(flags & FLAGS_PRECISION)) {
prec = PRINTF_DEFAULT_FLOAT_PRECISION;
}
// limit precision to 9, cause a prec >= 10 can lead to overflow errors
while ((len < PRINTF_FTOA_BUFFER_SIZE) && (prec > 9U)) {
buf[len++] = '0';
prec--;
}
int whole = (int)value;
double tmp = (value - whole) * pow10[prec];
unsigned long frac = (unsigned long)tmp;
diff = tmp - frac;
if (diff > 0.5) {
++frac;
// handle rollover, e.g. case 0.99 with prec 1 is 1.0
if (frac >= pow10[prec]) {
frac = 0;
++whole;
}
} else if (diff < 0.5) {
} else if ((frac == 0U) || (frac & 1U)) {
// if halfway, round up if odd OR if last digit is 0
++frac;
}
if (prec == 0U) {
diff = value - (double)whole;
if ((!(diff < 0.5) || (diff > 0.5)) && (whole & 1)) {
// exactly 0.5 and ODD, then round up
// 1.5 -> 2, but 2.5 -> 2
++whole;
}
} else {
unsigned int count = prec;
// now do fractional part, as an unsigned number
while (len < PRINTF_FTOA_BUFFER_SIZE) {
--count;
buf[len++] = (char)(48U + (frac % 10U));
if (!(frac /= 10U)) {
break;
}
}
// add extra 0s
while ((len < PRINTF_FTOA_BUFFER_SIZE) && (count-- > 0U)) {
buf[len++] = '0';
}
if (len < PRINTF_FTOA_BUFFER_SIZE) {
// add decimal
buf[len++] = '.';
}
}
// do whole part, number is reversed
while (len < PRINTF_FTOA_BUFFER_SIZE) {
buf[len++] = (char)(48 + (whole % 10));
if (!(whole /= 10)) {
break;
}
}
// pad leading zeros
if (!(flags & FLAGS_LEFT) && (flags & FLAGS_ZEROPAD)) {
if (width && (negative || (flags & (FLAGS_PLUS | FLAGS_SPACE)))) {
width--;
}
while ((len < width) && (len < PRINTF_FTOA_BUFFER_SIZE)) {
buf[len++] = '0';
}
}
if (len < PRINTF_FTOA_BUFFER_SIZE) {
if (negative) {
buf[len++] = '-';
} else if (flags & FLAGS_PLUS) {
buf[len++] = '+'; // ignore the space if the '+' exists
} else if (flags & FLAGS_SPACE) {
buf[len++] = ' ';
}
}
return _out_rev(out, buffer, idx, maxlen, buf, len, width, flags);
}
#if defined(PRINTF_SUPPORT_EXPONENTIAL)
// internal ftoa variant for exponential floating-point type, contributed by Martijn Jasperse <m.jasperse@gmail.com>
static size_t _etoa(out_fct_type out, char* buffer, size_t idx, size_t maxlen, double value, unsigned int prec, unsigned int width, unsigned int flags)
{
// check for NaN and special values
if ((value != value) || (value > DBL_MAX) || (value < -DBL_MAX)) {
return _ftoa(out, buffer, idx, maxlen, value, prec, width, flags);
}
// determine the sign
const bool negative = value < 0;
if (negative) {
value = -value;
}
// default precision
if (!(flags & FLAGS_PRECISION)) {
prec = PRINTF_DEFAULT_FLOAT_PRECISION;
}
// determine the decimal exponent
// based on the algorithm by David Gay (https://www.ampl.com/netlib/fp/dtoa.c)
union {
uint64_t U;
double F;
} conv;
conv.F = value;
int exp2 = (int)((conv.U >> 52U) & 0x07FFU) - 1023; // effectively log2
conv.U = (conv.U & ((1ULL << 52U) - 1U)) | (1023ULL << 52U); // drop the exponent so conv.F is now in [1,2)
// now approximate log10 from the log2 integer part and an expansion of ln around 1.5
int expval = (int)(0.1760912590558 + exp2 * 0.301029995663981 + (conv.F - 1.5) * 0.289529654602168);
// now we want to compute 10^expval but we want to be sure it won't overflow
exp2 = (int)(expval * 3.321928094887362 + 0.5);
const double z = expval * 2.302585092994046 - exp2 * 0.6931471805599453;
const double z2 = z * z;
conv.U = (uint64_t)(exp2 + 1023) << 52U;
// compute exp(z) using continued fractions, see https://en.wikipedia.org/wiki/Exponential_function#Continued_fractions_for_ex
conv.F *= 1 + 2 * z / (2 - z + (z2 / (6 + (z2 / (10 + z2 / 14)))));
// correct for rounding errors
if (value < conv.F) {
expval--;
conv.F /= 10;
}
// the exponent format is "%+03d" and largest value is "307", so set aside 4-5 characters
unsigned int minwidth = ((expval < 100) && (expval > -100)) ? 4U : 5U;
// in "%g" mode, "prec" is the number of *significant figures* not decimals
if (flags & FLAGS_ADAPT_EXP) {
// do we want to fall-back to "%f" mode?
if ((value >= 1e-4) && (value < 1e6)) {
if ((int)prec > expval) {
prec = (unsigned)((int)prec - expval - 1);
} else {
prec = 0;
}
flags |= FLAGS_PRECISION; // make sure _ftoa respects precision
// no characters in exponent
minwidth = 0U;
expval = 0;
} else {
// we use one sigfig for the whole part
if ((prec > 0) && (flags & FLAGS_PRECISION)) {
--prec;
}
}
}
// will everything fit?
unsigned int fwidth = width;
if (width > minwidth) {
// we didn't fall-back so subtract the characters required for the exponent
fwidth -= minwidth;
} else {
// not enough characters, so go back to default sizing
fwidth = 0U;
}
if ((flags & FLAGS_LEFT) && minwidth) {
// if we're padding on the right, DON'T pad the floating part
fwidth = 0U;
}
// rescale the float value
if (expval) {
value /= conv.F;
}
// output the floating part
const size_t start_idx = idx;
idx = _ftoa(out, buffer, idx, maxlen, negative ? -value : value, prec, fwidth, flags & ~FLAGS_ADAPT_EXP);
// output the exponent part
if (minwidth) {
// output the exponential symbol
out((flags & FLAGS_UPPERCASE) ? 'E' : 'e', buffer, idx++, maxlen);
// output the exponent value
idx = _ntoa_long(out, buffer, idx, maxlen, (expval < 0) ? -expval : expval, expval < 0, 10, 0, minwidth - 1, FLAGS_ZEROPAD | FLAGS_PLUS);
// might need to right-pad spaces
if (flags & FLAGS_LEFT) {
while (idx - start_idx < width)
out(' ', buffer, idx++, maxlen);
}
}
return idx;
}
#endif // PRINTF_SUPPORT_EXPONENTIAL
#endif // PRINTF_SUPPORT_FLOAT
// internal vsnprintf
static int _vsnprintf(out_fct_type out, char* buffer, const size_t maxlen, const char* format, va_list va)
{
unsigned int flags, width, precision, n;
size_t idx = 0U;
if (!buffer) {
// use null output function
out = _out_null;
}
while (*format) {
// format specifier? %[flags][width][.precision][length]
if (*format != '%') {
// no
out(*format, buffer, idx++, maxlen);
format++;
continue; continue;
} else {
// yes, evaluate it
format++;
} }
c = fmt[++i] & 0xff; // evaluate flags
flags = 0U;
do {
switch (*format) {
case '0':
flags |= FLAGS_ZEROPAD;
format++;
n = 1U;
break;
case '-':
flags |= FLAGS_LEFT;
format++;
n = 1U;
break;
case '+':
flags |= FLAGS_PLUS;
format++;
n = 1U;
break;
case ' ':
flags |= FLAGS_SPACE;
format++;
n = 1U;
break;
case '#':
flags |= FLAGS_HASH;
format++;
n = 1U;
break;
default:
n = 0U;
break;
}
} while (n);
if (!c) // evaluate width field
width = 0U;
if (_is_digit(*format)) {
width = _atoi(&format);
} else if (*format == '*') {
const int w = va_arg(va, int);
if (w < 0) {
flags |= FLAGS_LEFT; // reverse padding
width = (unsigned int)-w;
} else {
width = (unsigned int)w;
}
format++;
}
// evaluate precision field
precision = 0U;
if (*format == '.') {
flags |= FLAGS_PRECISION;
format++;
if (_is_digit(*format)) {
precision = _atoi(&format);
} else if (*format == '*') {
const int prec = (int)va_arg(va, int);
precision = prec > 0 ? (unsigned int)prec : 0U;
format++;
}
}
// evaluate length field
switch (*format) {
case 'l':
flags |= FLAGS_LONG;
format++;
if (*format == 'l') {
flags |= FLAGS_LONG_LONG;
format++;
}
break; break;
case 'h':
flags |= FLAGS_SHORT;
format++;
if (*format == 'h') {
flags |= FLAGS_CHAR;
format++;
}
break;
#if defined(PRINTF_SUPPORT_PTRDIFF_T)
case 't':
flags |= (sizeof(ptrdiff_t) == sizeof(long) ? FLAGS_LONG : FLAGS_LONG_LONG);
format++;
break;
#endif
case 'j':
flags |= (sizeof(intmax_t) == sizeof(long) ? FLAGS_LONG : FLAGS_LONG_LONG);
format++;
break;
case 'z':
flags |= (sizeof(size_t) == sizeof(long) ? FLAGS_LONG : FLAGS_LONG_LONG);
format++;
break;
default:
break;
}
switch (c) { // evaluate specifier
switch (*format) {
case 'd': case 'd':
PrintInt(*argp++, 10, 1); case 'i':
break; case 'u':
case 'x': case 'x':
case 'p': case 'X':
PrintInt(*argp++, 16, 0); case 'o':
break; case 'b': {
// set the base
case 's': unsigned int base;
if ((s = (char*)*argp++) == 0) { if (*format == 'x' || *format == 'X') {
s = "(null)"; base = 16U;
} else if (*format == 'o') {
base = 8U;
} else if (*format == 'b') {
base = 2U;
} else {
base = 10U;
flags &= ~FLAGS_HASH; // no hash for dec format
}
// uppercase
if (*format == 'X') {
flags |= FLAGS_UPPERCASE;
} }
for (; *s; s++) { // no plus or space flag for u, x, X, o, b
proxy()->serial->putc(*s); if ((*format != 'i') && (*format != 'd')) {
flags &= ~(FLAGS_PLUS | FLAGS_SPACE);
} }
// ignore '0' flag when precision is given
if (flags & FLAGS_PRECISION) {
flags &= ~FLAGS_ZEROPAD;
}
// convert the integer
if ((*format == 'i') || (*format == 'd')) {
// signed
if (flags & FLAGS_LONG_LONG) {
#if defined(PRINTF_SUPPORT_LONG_LONG)
const long long value = va_arg(va, long long);
idx = _ntoa_long_long(out, buffer, idx, maxlen, (unsigned long long)(value > 0 ? value : 0 - value), value < 0, base, precision, width, flags);
#endif
} else if (flags & FLAGS_LONG) {
const long value = va_arg(va, long);
idx = _ntoa_long(out, buffer, idx, maxlen, (unsigned long)(value > 0 ? value : 0 - value), value < 0, base, precision, width, flags);
} else {
const int value = (flags & FLAGS_CHAR) ? (char)va_arg(va, int) : (flags & FLAGS_SHORT) ? (short int)va_arg(va, int)
: va_arg(va, int);
idx = _ntoa_long(out, buffer, idx, maxlen, (unsigned int)(value > 0 ? value : 0 - value), value < 0, base, precision, width, flags);
}
} else {
// unsigned
if (flags & FLAGS_LONG_LONG) {
#if defined(PRINTF_SUPPORT_LONG_LONG)
idx = _ntoa_long_long(out, buffer, idx, maxlen, va_arg(va, unsigned long long), false, base, precision, width, flags);
#endif
} else if (flags & FLAGS_LONG) {
idx = _ntoa_long(out, buffer, idx, maxlen, va_arg(va, unsigned long), false, base, precision, width, flags);
} else {
const unsigned int value = (flags & FLAGS_CHAR) ? (unsigned char)va_arg(va, unsigned int) : (flags & FLAGS_SHORT) ? (unsigned short int)va_arg(va, unsigned int)
: va_arg(va, unsigned int);
idx = _ntoa_long(out, buffer, idx, maxlen, value, false, base, precision, width, flags);
}
}
format++;
break; break;
}
#if defined(PRINTF_SUPPORT_FLOAT)
case 'f':
case 'F':
if (*format == 'F')
flags |= FLAGS_UPPERCASE;
idx = _ftoa(out, buffer, idx, maxlen, va_arg(va, double), precision, width, flags);
format++;
break;
#if defined(PRINTF_SUPPORT_EXPONENTIAL)
case 'e':
case 'E':
case 'g':
case 'G':
if ((*format == 'g') || (*format == 'G'))
flags |= FLAGS_ADAPT_EXP;
if ((*format == 'E') || (*format == 'G'))
flags |= FLAGS_UPPERCASE;
idx = _etoa(out, buffer, idx, maxlen, va_arg(va, double), precision, width, flags);
format++;
break;
#endif // PRINTF_SUPPORT_EXPONENTIAL
#endif // PRINTF_SUPPORT_FLOAT
case 'c': {
unsigned int l = 1U;
// pre padding
if (!(flags & FLAGS_LEFT)) {
while (l++ < width) {
out(' ', buffer, idx++, maxlen);
}
}
// char output
out((char)va_arg(va, int), buffer, idx++, maxlen);
// post padding
if (flags & FLAGS_LEFT) {
while (l++ < width) {
out(' ', buffer, idx++, maxlen);
}
}
format++;
break;
}
case 's': {
const char* p = va_arg(va, char*);
unsigned int l = _strnlen_s(p, precision ? precision : (size_t)-1);
// pre padding
if (flags & FLAGS_PRECISION) {
l = (l < precision ? l : precision);
}
if (!(flags & FLAGS_LEFT)) {
while (l++ < width) {
out(' ', buffer, idx++, maxlen);
}
}
// string output
while ((*p != 0) && (!(flags & FLAGS_PRECISION) || precision--)) {
out(*(p++), buffer, idx++, maxlen);
}
// post padding
if (flags & FLAGS_LEFT) {
while (l++ < width) {
out(' ', buffer, idx++, maxlen);
}
}
format++;
break;
}
case 'p': {
width = sizeof(void*) * 2U;
flags |= FLAGS_ZEROPAD | FLAGS_UPPERCASE;
#if defined(PRINTF_SUPPORT_LONG_LONG)
const bool is_ll = sizeof(uintptr_t) == sizeof(long long);
if (is_ll) {
idx = _ntoa_long_long(out, buffer, idx, maxlen, (uintptr_t)va_arg(va, void*), false, 16U, precision, width, flags);
} else {
#endif
idx = _ntoa_long(out, buffer, idx, maxlen, (unsigned long)((uintptr_t)va_arg(va, void*)), false, 16U, precision, width, flags);
#if defined(PRINTF_SUPPORT_LONG_LONG)
}
#endif
format++;
break;
}
case '%': case '%':
proxy()->serial->putc('%'); out('%', buffer, idx++, maxlen);
format++;
break; break;
default: default:
// Print unknown % sequence to draw attention. out(*format, buffer, idx++, maxlen);
proxy()->serial->putc('%'); format++;
proxy()->serial->putc(c);
break; break;
} }
} }
// termination
out((char)0, buffer, idx < maxlen ? idx : maxlen - 1U, maxlen);
// return written chars without terminating \0
return (int)idx;
} }
///////////////////////////////////////////////////////////////////////////////
int printf_(const char* format, ...)
{
va_list va;
va_start(va, format);
char buffer[1];
const int ret = _vsnprintf(_out_char, buffer, (size_t)-1, format, va);
va_end(va);
return ret;
}
int sprintf_(char* buffer, const char* format, ...)
{
va_list va;
va_start(va, format);
const int ret = _vsnprintf(_out_buffer, buffer, (size_t)-1, format, va);
va_end(va);
return ret;
}
int snprintf_(char* buffer, size_t count, const char* format, ...)
{
va_list va;
va_start(va, format);
const int ret = _vsnprintf(_out_buffer, buffer, count, format, va);
va_end(va);
return ret;
}
int vprintf_(const char* format, va_list va)
{
char buffer[1];
return _vsnprintf(_out_char, buffer, (size_t)-1, format, va);
}
int vsnprintf_(char* buffer, size_t count, const char* format, va_list va)
{
return _vsnprintf(_out_buffer, buffer, count, format, va);
}
int fctprintf(void (*out)(char character, void* arg), void* arg, const char* format, ...)
{
va_list va;
va_start(va, format);
const out_fct_wrap_type out_fct_wrap = { out, arg };
const int ret = _vsnprintf(_out_fct, (char*)(uintptr_t)&out_fct_wrap, (size_t)-1, format, va);
va_end(va);
return ret;
}

View File

@ -24,6 +24,7 @@
#include <stdint.h> #include <stdint.h>
#include "actracer.h" #include "actracer.h"
#include "printf.h"
struct XiziSerialDriver { struct XiziSerialDriver {
void (*sys_serial_init)(); void (*sys_serial_init)();
@ -33,8 +34,6 @@ struct XiziSerialDriver {
void (*putc)(uint8_t); void (*putc)(uint8_t);
}; };
void KPrintf(char* fmt, ...);
struct XiziSerialDriver* hardkernel_uart_init(struct TraceTag* hardkernel_tag); struct XiziSerialDriver* hardkernel_uart_init(struct TraceTag* hardkernel_tag);
int serial_init(struct TraceTag* uart_driver_tag); int serial_init(struct TraceTag* uart_driver_tag);

View File

@ -1,4 +1,4 @@
SRC_DIR := SRC_DIR :=
SRC_FILES := actracer.c actracer_mem_chunk.c SRC_FILES := actracer.c
include $(KERNEL_ROOT)/compiler.mk include $(KERNEL_ROOT)/compiler.mk

View File

@ -29,267 +29,43 @@ Modification:
#include <stddef.h> #include <stddef.h>
#include <string.h> #include <string.h>
#include "trap_common.h"
#include "assert.h"
#include "multicores.h"
#include "spinlock.h"
#include "task.h"
#include "actracer.h" #include "actracer.h"
#include "assert.h"
#ifndef min static struct SysTracer sys_tracer;
#define min(a, b) ((a) < (b) ? (a) : (b)) static char root_name[TRACER_NODE_NAME_LEN] = "ROOT\0";
#endif
struct SysTracer sys_tracer; static void tracer_init_node(TracerNode* node, char* name, tracemeta_ac_type type, void* p_resource)
char* tracer_space[TRACER_MEM_CHUNK_SIZE * NR_TRACER_MEM_CHUNKS];
struct TraceTag* const RequireRootTag()
{ {
static struct TraceTag root_trace_tag = { NULL }; node->type = type;
return &root_trace_tag; node->parent = NULL;
} if (name != NULL) {
char* p_name = (char*)slab_alloc(&sys_tracer.node_name_allocator);
static inline int namecmp(const char* s, const char* t) strcpy(p_name, name);
{ p_name[TRACER_NODE_NAME_LEN - 1] = '\0';
return strncmp(s, t, RESOURCE_NAME_SIZE); node->name = p_name;
}
/// @brief alloc a trace meta to trace resource
static struct TraceMeta* alloc_trace_meta()
{
int index = -1;
for (uint32_t idx = 0; idx < BITS_TRACEMETA_BITMAP; idx++) {
if (sys_tracer.trace_meta_bit_map[idx] == 0xFFFFFFFF) {
continue;
}
uint32_t position = __builtin_ffs(~sys_tracer.trace_meta_bit_map[idx]) - 1;
if (position != 31) {
// found a free bit
sys_tracer.trace_meta_bit_map[idx] |= (1 << (position));
index = idx * 32 + position;
break;
}
} }
if (node->type == TRACER_OWNER) {
if (index == -1) { doubleListNodeInit(&node->children_guard);
panic("Tracer no enough TracerMeta.");
}
sys_tracer.trace_meta_poll[index].index = index;
return &sys_tracer.trace_meta_poll[index];
}
static bool dealloc_trace_meta(struct TraceMeta* meta)
{
int index = meta->index;
// clear bitmap
uint32_t outer_index = index / 32;
uint32_t inner_index = index % 32;
sys_tracer.trace_meta_bit_map[outer_index] &= (uint32_t)(~(1 << inner_index));
// clear meta
sys_tracer.trace_meta_poll[index].type = TRACER_INVALID;
if (index == -1) {
panic("Tracer no enough TracerMeta.");
}
sys_tracer.trace_meta_poll[index].index = index;
return &sys_tracer.trace_meta_poll[index];
}
static tracer_mem_chunk_idx_t trace_meta_map_mem_chunk(struct TraceMeta* const p_trace_meta, tracer_mem_chunk_idx_t mem_chunk_num)
{
tracer_mem_chunk_idx_t addr;
/* direct mapping */
if (mem_chunk_num < TRACEMETA_NR_DIRECT) {
if ((addr = p_trace_meta->addr[mem_chunk_num]) == 0) {
p_trace_meta->addr[mem_chunk_num] = addr = tracer_mem_chunk_alloc();
}
return addr;
}
/* indirect mapping */
mem_chunk_num -= TRACEMETA_NR_DIRECT;
int indirect_mem_chunk_id = mem_chunk_num / NR_ADDR_PER_MEM_CHUNK;
if (indirect_mem_chunk_id < TRACEMETA_NR_INDIRECT) {
if ((addr = p_trace_meta->addr[TRACEMETA_NR_DIRECT + indirect_mem_chunk_id]) == 0) {
p_trace_meta->addr[TRACEMETA_NR_DIRECT + indirect_mem_chunk_id] = addr = tracer_mem_chunk_alloc();
}
mem_chunk_num -= indirect_mem_chunk_id * NR_ADDR_PER_MEM_CHUNK;
} else { } else {
panic("tracer inode, bmap out of range"); node->p_resource = p_resource;
// no return
} }
doubleListNodeInit(&node->list_node);
// index mem_chunk
struct tracer_mem_chunk* tracer_mem_chunk = tracer_mem_chunk_read(addr);
tracer_mem_chunk_idx_t* indirect_list = (tracer_mem_chunk_idx_t*)tracer_mem_chunk->data;
if ((addr = indirect_list[mem_chunk_num]) == 0) {
indirect_list[mem_chunk_num] = addr = tracer_mem_chunk_alloc();
tracer_mem_chunk_write(tracer_mem_chunk);
}
tracer_mem_chunk_release(tracer_mem_chunk);
return addr;
} }
/// @brief write trace info by trace meta void sys_tracer_init()
static int trace_write_info(struct TraceMeta* const p_trace_meta, char* src, uint32_t off, uint32_t n)
{ {
if (p_trace_meta->type == TRACER_INVALID) { // set sys_tracer resource identity
return -1; tracer_init_node(&sys_tracer.root_node, NULL, TRACER_OWNER, NULL);
} sys_tracer.root_node.name = root_name;
sys_tracer.sys_tracer_tag.meta = &sys_tracer.root_node;
// fast path // init memory allocator
if (off == 0 && n <= sizeof(uintptr_t)) { slab_init(&sys_tracer.node_allocator, sizeof(TracerNode));
p_trace_meta->reserved = *(uintptr_t*)src; slab_init(&sys_tracer.node_name_allocator, sizeof(char[TRACER_NODE_NAME_LEN]));
return n;
}
if (UNLIKELY(off > p_trace_meta->size || off + n > VFS_FILE_MAXSIZE * TRACER_MEM_CHUNK_SIZE || off + n < off)) {
return -1;
}
struct tracer_mem_chunk* tracer_mem_chunk;
uint32_t m;
for (uint32_t tot = 0; tot < n; tot += m, off += m, src += m) {
tracer_mem_chunk = tracer_mem_chunk_read(trace_meta_map_mem_chunk(p_trace_meta, off / TRACER_MEM_CHUNK_SIZE));
m = min(n - tot, TRACER_MEM_CHUNK_SIZE - off % TRACER_MEM_CHUNK_SIZE);
memmove(tracer_mem_chunk->data + off % TRACER_MEM_CHUNK_SIZE, src, m);
tracer_mem_chunk_write(tracer_mem_chunk);
tracer_mem_chunk_release(tracer_mem_chunk);
}
if (n > 0 && off > p_trace_meta->size) {
p_trace_meta->size = off;
}
return n;
} }
/// @brief read trace info by trace meta static char* parse_path(char* path, char* const name)
static int trace_read_info(struct TraceMeta* const p_trace_meta, char* dst, uint32_t off, uint32_t n)
{
if (p_trace_meta->type == TRACER_INVALID) {
return -1;
}
if (off == 0 && n <= sizeof(uintptr_t)) {
*(uintptr_t*)dst = p_trace_meta->reserved;
return n;
}
if (UNLIKELY(off > p_trace_meta->size || off + n < off)) {
return -1;
}
if (UNLIKELY(off + n > p_trace_meta->size)) {
n = p_trace_meta->size - off;
}
static struct tracer_mem_chunk* tracer_mem_chunk;
uint32_t m;
for (uint32_t tot = 0; tot < n; tot += m, off += m, dst += m) {
tracer_mem_chunk = tracer_mem_chunk_read(trace_meta_map_mem_chunk(p_trace_meta, off / TRACER_MEM_CHUNK_SIZE));
m = min(n - tot, TRACER_MEM_CHUNK_SIZE - off % TRACER_MEM_CHUNK_SIZE);
memmove(dst, tracer_mem_chunk->data + off % TRACER_MEM_CHUNK_SIZE, m);
tracer_mem_chunk_release(tracer_mem_chunk);
}
return n;
}
static struct TraceMeta* tracer_find_meta_onestep(struct TraceMeta* const p_owner, char* name, uint32_t* poff)
{
struct TraceResourceEntry resource_entry;
if (p_owner->type != TRACER_OWNER) {
ERROR("tracer_find_meta_onestep, not a dir, index: %d\n", p_owner->index);
return NULL;
}
for (uint32_t off = 0; off < p_owner->size; off += sizeof(resource_entry)) {
if (trace_read_info(p_owner, (char*)&resource_entry, off, sizeof(resource_entry)) != sizeof(resource_entry)) {
panic("tracer_find_meta_onestep: read trace owner's resources failed\n");
}
if (resource_entry.index == 0) {
continue;
}
if (namecmp(name, resource_entry.name) == 0) {
if (poff) {
*poff = off;
}
uint32_t vindex = resource_entry.index;
assert(vindex >= 0 && vindex < NR_MAX_TRACEMETA);
return &sys_tracer.trace_meta_poll[vindex];
}
}
return NULL;
}
// Write a new vdirectory entry (name, index) into the vdirectory dp.
static int tracer_append_meta(struct TraceMeta* p_owner, char* name, uint32_t index)
{
struct TraceResourceEntry resource_entry;
int offset = 0;
for (offset = 0; offset < p_owner->size; offset += sizeof(resource_entry)) {
if (trace_read_info(p_owner, (char*)&resource_entry, offset, sizeof(resource_entry)) != sizeof(resource_entry)) {
ERROR("tracer_append_meta failed, read owner's resources failed.\n");
return -1;
}
if (resource_entry.index == 0) {
break;
}
}
strncpy(resource_entry.name, name, RESOURCE_NAME_SIZE);
resource_entry.index = index;
if (trace_write_info(p_owner, (char*)&resource_entry, offset, sizeof(resource_entry)) != sizeof(resource_entry)) {
ERROR("tracer_append_meta failed, append resource to owner failed.\n");
return -1;
}
return 0;
}
static struct TraceMeta* tracer_new_meta(struct TraceMeta* p_owner, char* name, short type)
{
struct TraceMeta* p_trace_meta;
// check if owner entry exists
uint32_t offset;
if ((p_trace_meta = tracer_find_meta_onestep(p_owner, name, &offset)) != 0) {
LOG("create resource(trace meta) failed, %s is existed\n", name);
return NULL;
}
if ((p_trace_meta = alloc_trace_meta()) == 0) {
ERROR("create resource(trace meta) failed, cache is no free\n");
return NULL;
}
p_trace_meta->type = type;
p_trace_meta->size = 0;
// update parent directory
tracer_append_meta(p_owner, name, p_trace_meta->index);
// update "." and ".." for vfs inode
if (p_trace_meta->type == TRACER_OWNER) {
tracer_append_meta(p_trace_meta, ".", p_trace_meta->index);
tracer_append_meta(p_trace_meta, "..", p_owner->index);
}
return p_trace_meta;
}
static char* parse_path(char* path, char* name)
{ {
// skip extra '/' // skip extra '/'
while (*path == '/') { while (*path == '/') {
@ -307,8 +83,9 @@ static char* parse_path(char* path, char* name)
// handle current name // handle current name
int len = path - cur_start; int len = path - cur_start;
if (len >= RESOURCE_NAME_SIZE) { if (len >= TRACER_NODE_NAME_LEN) {
strncpy(name, cur_start, RESOURCE_NAME_SIZE); strncpy(name, cur_start, TRACER_NODE_NAME_LEN);
name[TRACER_NODE_NAME_LEN - 1] = '\0';
} else { } else {
strncpy(name, cur_start, len); strncpy(name, cur_start, len);
name[len] = '\0'; name[len] = '\0';
@ -317,215 +94,101 @@ static char* parse_path(char* path, char* name)
return path; return path;
} }
static struct TraceMeta* tracer_find_meta(struct TraceMeta* const p_owner, char* path, int nameiparent, char* name) static TracerNode* tracer_find_node_onestep(TracerNode* const owner, const char* const name)
{ {
struct TraceMeta* p_owner_inside = p_owner; TracerNode* iter = NULL;
struct TraceMeta* vnp; assert(owner->type == TRACER_OWNER);
DOUBLE_LIST_FOR_EACH_ENTRY(iter, &owner->children_guard, list_node)
/* traverse TRACER_OWNER */ {
while ((path = parse_path(path, name)) != 0) { if (iter->name == NULL) {
if (p_owner_inside->type != TRACER_OWNER) {
return NULL;
}
if (nameiparent && *path == '\0') {
return p_owner_inside;
}
if ((vnp = tracer_find_meta_onestep(p_owner_inside, name, NULL)) == 0) {
DEBUG("Not such object: %s\n", path);
return NULL;
}
p_owner_inside = vnp;
}
if (nameiparent) {
return NULL;
}
return p_owner_inside;
}
int tracer_write_trace(struct TraceTag* const p_trace_tag, char* src, uint32_t off, uint32_t n)
{
if (src == NULL || p_trace_tag == NULL || p_trace_tag->meta == NULL) {
return -1;
}
return trace_write_info(p_trace_tag->meta, src, off, n);
}
int tracer_read_trace(struct TraceTag* const p_trace_tag, char* dst, uint32_t off, uint32_t n)
{
if (dst == NULL || p_trace_tag == NULL || p_trace_tag->meta == NULL) {
return -1;
}
return trace_read_info(p_trace_tag->meta, dst, off, n);
}
/// @brief
static void trace_locate_inner(struct TraceTag* target, struct TraceTag* const p_trace_tag, char* path, bool parent)
{
char name[RESOURCE_NAME_SIZE];
struct TraceMeta* p_trace_meta = tracer_find_meta(p_trace_tag->meta, path, parent, name);
// p_trace_meta: TRACER_OWNER, VT_FS or other.
// TRACER_OWNER: path: "", name: "dir name"
// other: path: "", name: "file name"
if (!p_trace_meta) {
DEBUG("trace_locate, not found\n");
}
target->type = p_trace_meta->type;
target->meta = p_trace_meta;
}
static inline void trace_locate(struct TraceTag* target, struct TraceTag* const p_trace_tag, char* path)
{
trace_locate_inner(target, p_trace_tag, path, 0);
}
static inline void trace_locate_parent(struct TraceTag* target, struct TraceTag* const p_trace_tag, char* path)
{
trace_locate_inner(target, p_trace_tag, path, 1);
}
bool tracer_create_trace(struct TraceTag* target, struct TraceTag* p_trace_tag, char* path, short type)
{
struct TraceMeta *p_trace_meta, *p_owner;
// find parent vfs inode
if ((p_owner = p_trace_tag->meta) == 0) {
LOG("create tracemeta failed, parent is null\n");
target->meta = NULL;
return false;
}
p_trace_meta = tracer_new_meta(p_owner, path, type);
target->meta = p_trace_meta;
return true;
}
bool tracer_delete_trace(struct TraceTag* target, struct TraceTag* owner)
{
if (target->meta == NULL || owner->type != TRACER_OWNER) {
return false;
}
struct TraceMeta* p_trace_meta = target->meta;
struct TraceMeta* p_owner_meta = owner->meta;
assert(p_trace_meta->type != TRACER_INVALID);
if (p_trace_meta->type == TRACER_OWNER) {
/// @todo support recursive delete
}
struct TraceResourceEntry resource_entry;
bool is_owned = false;
for (uint32_t off = 0; off < p_owner_meta->size; off += sizeof(resource_entry)) {
if (trace_read_info(p_owner_meta, (char*)&resource_entry, off, sizeof(resource_entry)) != sizeof(resource_entry)) {
panic("tracer_find_meta_onestep: read trace owner's resources failed\n");
}
if (resource_entry.index == 0) {
continue; continue;
} }
if (resource_entry.index == p_trace_meta->index) { if (strcmp(name, iter->name) == 0) {
resource_entry.index = 0; return iter;
trace_write_info(owner->meta, (char*)&resource_entry, off, sizeof(resource_entry));
is_owned = true;
break;
} }
} }
if (!is_owned) { return NULL;
ERROR("delete trace(%d) not owned by given owner(%d).\n", target->meta->index, owner->meta->index); }
return false;
}
dealloc_trace_meta(p_trace_meta);
TraceTag* const RequireRootTag()
{
return &sys_tracer.sys_tracer_tag;
}
bool AchieveResourceTag(TraceTag* target, TraceTag* owner, char* name)
{
static char name_buffer[TRACER_NODE_NAME_LEN];
TracerNode* inner_node = owner->meta;
assert(inner_node != NULL && inner_node->type == TRACER_OWNER);
while ((name = parse_path(name, name_buffer)) != NULL) {
if ((inner_node = tracer_find_node_onestep(inner_node, name_buffer)) == NULL) {
DEBUG("Tracer: No such object, owner: %s, child: %s\n", //
owner->meta->name == NULL ? "NULL" : owner->meta->name, name == NULL ? "NULL" : name_buffer);
return false;
}
}
target->meta = inner_node;
return true; return true;
} }
void tracer_init(void) void* AchieveResource(TraceTag* tag)
{ {
/* init sys_tracer, the manager */ assert(tag != NULL);
spinlock_init(&sys_tracer.mem_chunk_bitmap_lock, "tracer_mem_chunk_bitmap"); if (tag->meta == NULL || tag->meta->type == TRACER_OWNER) {
spinlock_init(&sys_tracer.trace_meta_bitmap_lock, "tracer_meta_bitmap");
memset(sys_tracer.mem_chunks_bit_map, 0, sizeof(sys_tracer.mem_chunk_bitmap_lock));
memset(sys_tracer.trace_meta_bit_map, 0, sizeof(sys_tracer.trace_meta_bit_map));
assert((TRACER_MEM_CHUNK_SIZE % sizeof(struct TraceMeta)) == 0);
assert((TRACER_MEM_CHUNK_SIZE % sizeof(struct TraceResourceEntry)) == 0);
// mem_chunk space, fit with mem_chunk_bit_map
mem_chunk_synchronizer_init((uintptr_t)tracer_space, TRACER_MEM_CHUNK_SIZE, NR_TRACER_MEM_CHUNKS);
/* build root inode */
alloc_trace_meta(); // inode as guard.
/* build root trace_meta */
struct TraceMeta* root_tracemeta = alloc_trace_meta();
assert(root_tracemeta->index == 1);
root_tracemeta->type = TRACER_OWNER;
root_tracemeta->size = 0;
tracer_append_meta(root_tracemeta, ".", root_tracemeta->index);
tracer_append_meta(root_tracemeta, "..", root_tracemeta->index);
RequireRootTag()->meta = root_tracemeta;
}
/// @brief find resource tag
void tracer_find_tag(struct TraceTag* target, struct TraceTag* const source, char* path)
{
target->meta = NULL;
struct TraceTag* p_trace_tag;
if (*path == '/' || source == NULL) {
p_trace_tag = RequireRootTag();
} else {
p_trace_tag = source;
}
if (p_trace_tag == NULL || p_trace_tag->meta == NULL) {
return;
}
trace_locate(target, p_trace_tag, path);
}
bool AchieveResourceTag(struct TraceTag* target, struct TraceTag* owner, char* name)
{
tracer_find_tag(target, owner, name);
if (target->meta == NULL) {
return false;
}
return true;
}
void* AchieveResource(struct TraceTag* target)
{
if (target->type == TRACER_OWNER) {
return NULL; return NULL;
} }
void* p_resource = NULL;
tracer_read_trace(target, (char*)&p_resource, 0, sizeof(void*)); return tag->meta->p_resource;
assert(p_resource != NULL);
return p_resource;
} }
bool CreateResourceTag(struct TraceTag* new_tag, struct TraceTag* owner, char* name, tracemeta_ac_type type, void* p_resource) bool CreateResourceTag(TraceTag* new_tag, TraceTag* owner, char* name, tracemeta_ac_type type, void* p_resource)
{ {
new_tag->type = type; assert(new_tag != NULL && owner != NULL);
if (type == TRACER_OWNER) { if (owner->meta == NULL) {
return tracer_create_trace(new_tag, owner, name, type); ERROR("Tracer: Empty owner\n");
return false;
} }
assert(owner->meta->type == TRACER_OWNER);
TracerNode* new_node = (TracerNode*)slab_alloc(&sys_tracer.node_allocator);
if (new_node == NULL) {
ERROR("Tracer: No memory for new node\n");
return false;
}
tracer_init_node(new_node, name, type, p_resource);
// handle ac resource types // new node add to owner's children list
if (p_resource == NULL) { doubleListAddOnHead(&new_node->list_node, &owner->meta->children_guard);
new_node->parent = owner->meta;
new_tag->meta = new_node;
return true;
}
bool DeleteResource(TraceTag* target, TraceTag* owner)
{
assert(target != NULL && owner != NULL);
assert(owner->meta != NULL && owner->meta->type == TRACER_OWNER);
if (target->meta == NULL) {
ERROR("Tracer: Delete a empty resource\n");
return false; return false;
} }
if (!tracer_create_trace(new_tag, owner, name, type)) { assert(target->meta->parent == owner->meta);
return false; doubleListDel(&target->meta->list_node);
// delete name
if (target->meta->name != NULL) {
slab_free(&sys_tracer.node_name_allocator, target->meta->name);
} }
bool ret = tracer_write_trace(new_tag, (char*)&p_resource, 0, sizeof(void*)) == sizeof(void*); // delete all children
return ret; /// @attention currently donot allow multilevel resource deletion
} if (target->meta->type == TRACER_OWNER) {
assert(IS_DOUBLE_LIST_EMPTY(&target->meta->children_guard));
bool DeleteResource(struct TraceTag* target, struct TraceTag* owner) }
{ slab_free(&sys_tracer.node_allocator, target->meta);
return tracer_delete_trace(target, owner); target->meta = NULL;
return true;
} }

View File

@ -30,8 +30,10 @@ Modification:
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include "actracer_mem_chunk.h" #include "list.h"
#include "spinlock.h" #include "object_allocator.h"
#define TRACER_NODE_NAME_LEN 32
typedef enum { typedef enum {
TRACER_INVALID = 0, TRACER_INVALID = 0,
@ -42,52 +44,32 @@ typedef enum {
TRACER_MEM_FROM_BUDDY_AC_RESOURCE, TRACER_MEM_FROM_BUDDY_AC_RESOURCE,
} tracemeta_ac_type; } tracemeta_ac_type;
typedef uint16_t tracer_mem_chunk_idx_t; typedef struct TracerNode {
#define TRACEMETA_NR_DIRECT 5 tracemeta_ac_type type;
#define TRACEMETA_NR_INDIRECT 4 char* name;
#define NR_ADDR_PER_MEM_CHUNK TRACER_MEM_CHUNK_SIZE / sizeof(tracer_mem_chunk_idx_t) union {
#define VFS_FILE_MAXSIZE (TRACEMETA_NR_DIRECT + (TRACEMETA_NR_INDIRECT * NR_ADDR_PER_MEM_CHUNK)) struct double_list_node children_guard;
struct TraceMeta { void* p_resource;
uint32_t size; };
tracemeta_ac_type type; // TRACER_OWNER, etc. struct TracerNode* parent;
uintptr_t reserved; // fast path to store pointer if content is a pointer struct double_list_node list_node;
uint16_t index; } TracerNode;
tracer_mem_chunk_idx_t addr[TRACEMETA_NR_DIRECT + TRACEMETA_NR_INDIRECT]; // 指向data mem_chunks, TRACER_OWNER 用于存放 dir entries, VT_FS用于存放bind
} __attribute__((aligned(32)));
/// @brief tag for other module to reference trace meta /// @brief tag for other module to reference trace meta
struct TraceTag { typedef struct TraceTag {
struct TraceMeta* meta; TracerNode* meta;
short type; // TRACER_OWNER, etc. } TraceTag;
};
#define RESOURCE_NAME_SIZE 14
struct TraceResourceEntry {
uint16_t index;
char name[RESOURCE_NAME_SIZE];
};
struct SysTracer { struct SysTracer {
#define NR_TRACER_MEM_CHUNKS 256 TracerNode root_node;
#define TRACER_MEM_CHUNK_SIZE sizeof(struct TraceMeta) TraceTag sys_tracer_tag;
#define BITS_MEM_CHUNK_BITMAP (NR_TRACER_MEM_CHUNKS / 32) struct slab_allocator node_allocator;
uint32_t mem_chunks_bit_map[BITS_MEM_CHUNK_BITMAP]; struct slab_allocator node_name_allocator;
struct spinlock mem_chunk_bitmap_lock;
#define NR_MAX_TRACEMETA 128
#define BITS_TRACEMETA_BITMAP (NR_MAX_TRACEMETA / 32)
uint32_t trace_meta_bit_map[BITS_TRACEMETA_BITMAP];
struct spinlock trace_meta_bitmap_lock;
struct TraceMeta trace_meta_poll[NR_MAX_TRACEMETA];
}; };
void tracer_init(void); void sys_tracer_init();
TraceTag* const RequireRootTag();
extern struct SysTracer sys_tracer;
extern struct TraceTag root_tracetag;
struct TraceTag* const RequireRootTag();
bool AchieveResourceTag(struct TraceTag* target, struct TraceTag* owner, char* name); bool AchieveResourceTag(struct TraceTag* target, struct TraceTag* owner, char* name);
void* AchieveResource(struct TraceTag* target); void* AchieveResource(struct TraceTag* target);
bool CreateResourceTag(struct TraceTag* new_tag, struct TraceTag* owner, char* name, tracemeta_ac_type type, void* p_resource); 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); bool DeleteResource(struct TraceTag* target, struct TraceTag* owner);

View File

@ -1,178 +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.
*/
/**
* @file actracer_mem_chunk.c
* @brief tracer mem chunk implememntation
* @version 3.0
* @author AIIT XUOS Lab
* @date 2023.08.25
*/
/*************************************************
File name: actracer_mem_chunk.c
Description: tracer mem chunk implementation
Others:
History:
1. Date: 2023-08-28
Author: AIIT XUOS Lab
Modification:
1. first version
*************************************************/
#include <string.h>
#include "assert.h"
#include "spinlock.h"
#include "actracer.h"
#include "actracer_mem_chunk.h"
/// @brief to assert that a mem_chunk of memory will only write by one object
struct mem_chunk_synchronizer {
uintptr_t mem_chunk_base;
uint32_t mem_chunk_size;
uint32_t nr_mem_chunks;
struct spinlock lock;
struct tracer_mem_chunk mem_chunk_access_list[NR_MEM_CHUNK_CACHE];
struct double_list_node head;
};
static struct mem_chunk_synchronizer tracer_mem_chunk_syner;
static void tracer_mem_chunk_sync(struct tracer_mem_chunk* b)
{
if (!(b->flag & TRACER_MEM_CHUNK_BUSY)) {
panic("mem_chunk_sync: buf not busy");
}
if (b->chunk_id >= tracer_mem_chunk_syner.nr_mem_chunks) {
panic("mem_chunk_sync: sector out of range");
}
b->data = (uint8_t*)(tracer_mem_chunk_syner.mem_chunk_base + b->chunk_id * tracer_mem_chunk_syner.mem_chunk_size);
b->flag |= TRACER_MEM_CHUNK_VALID;
}
void mem_chunk_synchronizer_init(uintptr_t mem_chunk_base, uint32_t mem_chunk_size, uint32_t nr_mem_chunks)
{
tracer_mem_chunk_syner.mem_chunk_base = mem_chunk_base;
tracer_mem_chunk_syner.mem_chunk_size = mem_chunk_size;
tracer_mem_chunk_syner.nr_mem_chunks = nr_mem_chunks;
// Create linked list of buffers
doubleListNodeInit(&tracer_mem_chunk_syner.head);
for (struct tracer_mem_chunk* b = tracer_mem_chunk_syner.mem_chunk_access_list; b < tracer_mem_chunk_syner.mem_chunk_access_list + NR_MEM_CHUNK_CACHE; b++) {
doubleListNodeInit(&b->list_node);
doubleListAddOnHead(&b->list_node, &tracer_mem_chunk_syner.head);
}
}
static struct tracer_mem_chunk* tracer_get_mem_chunk_cache(uint32_t chunk_id)
{
// cached mem_chunk cache
struct tracer_mem_chunk* b;
DOUBLE_LIST_FOR_EACH_ENTRY(b, &tracer_mem_chunk_syner.head, list_node)
{
if (b->chunk_id == chunk_id) {
if (!(b->flag & TRACER_MEM_CHUNK_BUSY)) {
b->flag |= TRACER_MEM_CHUNK_BUSY;
return b;
}
}
}
// Non-cached mem_chunk cache
DOUBLE_LIST_FOR_EACH_ENTRY_REVERSE(b, &tracer_mem_chunk_syner.head, list_node)
{
if ((b->flag & TRACER_MEM_CHUNK_BUSY) == 0) {
b->chunk_id = chunk_id;
b->flag = TRACER_MEM_CHUNK_BUSY;
return b;
}
}
panic("tracer_get_mem_chunk_cache: no cache");
return NULL;
}
// Return a TRACER_MEM_CHUNK_BUSY buf with the contents of the indicated disk sector.
struct tracer_mem_chunk* tracer_mem_chunk_read(uint32_t chunk_id)
{
struct tracer_mem_chunk* b = tracer_get_mem_chunk_cache(chunk_id);
if (!(b->flag & TRACER_MEM_CHUNK_VALID)) {
tracer_mem_chunk_sync(b);
b->flag |= TRACER_MEM_CHUNK_VALID;
}
return b;
}
void tracer_mem_chunk_write(struct tracer_mem_chunk* b)
{
if ((b->flag & TRACER_MEM_CHUNK_BUSY) == 0) {
panic("tracer mem_chunk write a no busy mem_chunk");
}
tracer_mem_chunk_sync(b);
}
void tracer_mem_chunk_release(struct tracer_mem_chunk* b)
{
if ((b->flag & TRACER_MEM_CHUNK_BUSY) == 0) {
panic("tracer mem_chunk release but it's not busy occupied");
}
// move mem_chunk that just used to the head of cache list
doubleListDel(&b->list_node);
doubleListAddOnHead(&b->list_node, &tracer_mem_chunk_syner.head);
b->flag &= ~TRACER_MEM_CHUNK_BUSY;
}
static void tracer_mem_chunk_zero(uint32_t chunk_id)
{
assert(chunk_id >= 0 && chunk_id < tracer_mem_chunk_syner.nr_mem_chunks);
struct tracer_mem_chunk* tracer_mem_chunk = NULL;
tracer_mem_chunk = tracer_mem_chunk_read(chunk_id);
memset(tracer_mem_chunk->data, 0, tracer_mem_chunk_syner.mem_chunk_size);
tracer_mem_chunk_write(tracer_mem_chunk);
tracer_mem_chunk_release(tracer_mem_chunk);
}
/// @return mem_chunk_idx in bit_map
static uint32_t find_first_free_mem_chunk()
{
/// @todo another mem_chunk
for (uint32_t idx = 0; idx < BITS_MEM_CHUNK_BITMAP; idx++) {
if (sys_tracer.mem_chunks_bit_map[idx] == 0xFFFFFFFF) {
continue;
}
uint32_t position = __builtin_ffs(~sys_tracer.mem_chunks_bit_map[idx]);
if (position != 32) {
sys_tracer.mem_chunks_bit_map[idx] |= (1 << (position - 1));
return idx * 32 + position;
}
}
panic("Tracer no enough space.");
return 0;
}
uint32_t tracer_mem_chunk_alloc()
{
tracer_mem_chunk_idx_t idx = find_first_free_mem_chunk();
tracer_mem_chunk_zero(idx);
return idx;
}
void tracer_mem_chunk_free(uint32_t chunk_id)
{
assert(chunk_id >= 0 && chunk_id < NR_TRACER_MEM_CHUNKS);
uint32_t idx = chunk_id % 32;
uint32_t inner_mem_chunk_bit = chunk_id / 32;
// assert mem_chunk is allocated
assert((sys_tracer.mem_chunks_bit_map[idx] & (1 << inner_mem_chunk_bit)) != 0);
sys_tracer.mem_chunks_bit_map[idx] &= (uint32_t)(~(1 << inner_mem_chunk_bit));
}

View File

@ -1,54 +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.
*/
/**
* @file actracer_mem_chunk.h
* @brief tracer mem chunk header
* @version 3.0
* @author AIIT XUOS Lab
* @date 2023.08.25
*/
/*************************************************
File name: actracer_mem_chunk.h
Description: tracer mem chunk header
Others:
History:
1. Date: 2023-08-28
Author: AIIT XUOS Lab
Modification:
1. first version
*************************************************/
#pragma once
#include <stdint.h>
#include "list.h"
#define NR_MEM_CHUNK_CACHE 128
typedef enum {
TRACER_MEM_CHUNK_BUSY = 0x1,
TRACER_MEM_CHUNK_VALID = 0x2,
} tracer_mem_chunk_flag;
struct tracer_mem_chunk {
tracer_mem_chunk_flag flag;
uint32_t chunk_id;
struct double_list_node list_node;
uint8_t* data;
};
void mem_chunk_synchronizer_init(uintptr_t mem_chunk_base, uint32_t mem_chunk_size, uint32_t nr_mem_chunks);
struct tracer_mem_chunk* tracer_mem_chunk_read(uint32_t chunk_id);
void tracer_mem_chunk_write(struct tracer_mem_chunk* b);
void tracer_mem_chunk_release(struct tracer_mem_chunk* b);
uint32_t tracer_mem_chunk_alloc();
void tracer_mem_chunk_free(uint32_t chunk_id);

View File

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

View File

@ -1,12 +1,12 @@
ifeq ($(BOARD), imx6q-sabrelite) ifeq ($(BOARD), imx6q-sabrelite)
toolchain ?= arm-none-eabi- toolchain ?= arm-none-eabi-
user_ldflags = --specs=nosys.specs -Wl,-Map=user.map,-cref -N user_ldflags = --specs=nosys.specs -Wl,-Map=user.map,-cref -N
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 -no-pie cflags = -std=c11 -O2 -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
endif endif
ifeq ($(BOARD), zynq7000-zc702) ifeq ($(BOARD), zynq7000-zc702)
toolchain ?= arm-xilinx-eabi- toolchain ?= arm-xilinx-eabi-
user_ldflags = -Wl,--start-group,-lgcc,-lc,--end-group -N user_ldflags = -Wl,--start-group,-lgcc,-lc,--end-group -N
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 = -std=c11 -O2 -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
board_specs = stub.o board_specs = stub.o
#cflags = -Wall -g -std=c11 #cflags = -Wall -g -std=c11
endif endif
@ -14,19 +14,21 @@ endif
cc = ${toolchain}gcc cc = ${toolchain}gcc
ld = ${toolchain}g++ ld = ${toolchain}g++
objdump = ${toolchain}objdump objdump = ${toolchain}objdump
c_useropts = -O0 c_useropts = -O2
INC_DIR = -I$(KERNEL_ROOT)/services/shell/letter-shell \ INC_DIR = -I$(KERNEL_ROOT)/services/shell/letter-shell \
-I$(KERNEL_ROOT)/services/lib/ipc \ -I$(KERNEL_ROOT)/services/lib/ipc \
-I$(KERNEL_ROOT)/services/lib/memory \ -I$(KERNEL_ROOT)/services/lib/memory \
-I$(KERNEL_ROOT)/services/lib/serial \
-I$(KERNEL_ROOT)/services/lib/usyscall \
-I$(KERNEL_ROOT)/services/fs/libfs \ -I$(KERNEL_ROOT)/services/fs/libfs \
-I$(KERNEL_ROOT)/services/boards/$(BOARD) \ -I$(KERNEL_ROOT)/services/boards/$(BOARD) \
-I$(KERNEL_ROOT)/services/app -I$(KERNEL_ROOT)/services/app
ifeq ($(BOARD), imx6q-sabrelite) ifeq ($(BOARD), imx6q-sabrelite)
all: init test_fs simple_client simple_server shell fs_server test_priority test_irq_hdlr test_irq_send readme.txt | bin all: init test_fs simple_client simple_server shell fs_server test_irq_hdlr test_irq_block test_irq_send eth_driver timer_server readme.txt | bin
else else
all: init test_fs simple_client simple_server shell fs_server test_priority test_irq_hdlr readme.txt | bin all: init test_fs simple_client simple_server shell fs_server test_irq_hdlr readme.txt | bin
endif endif
../tools/mkfs/mkfs ./fs.img $^ ../tools/mkfs/mkfs ./fs.img $^
@mv $(filter-out readme.txt, $^) bin @mv $(filter-out readme.txt, $^) bin
@ -37,40 +39,52 @@ bin:
@mkdir -p bin @mkdir -p bin
ifeq ($(BOARD), imx6q-sabrelite) ifeq ($(BOARD), imx6q-sabrelite)
test_irq_send: test_irq_sender.o usyscall.o libserial.o test_irq_send: test_irq_sender.o usyscall.o arch_usyscall.o libserial.o printf.o
@${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs}
@${objdump} -S $@ > $@.asm
eth_driver: enet_drv.o enet_test.o board_network.o enet_iomux_config.o imx6dq_gpio_map.o gpio.o ccm_pll.o libserial.o printf.o libmem.o usyscall.o arch_usyscall.o session.o libipc.o sabrelite_libtimer.o
@${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs}
@${objdump} -S $@ > $@.asm
timer_server: timer.o epit.o ccm_pll.o usyscall.o arch_usyscall.o libserial.o printf.o libipc.o session.o
@${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs} @${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs}
@${objdump} -S $@ > $@.asm @${objdump} -S $@ > $@.asm
endif endif
test_irq_hdlr: test_irq_handler.o libserial.o libipc.o session.o usyscall.o libmem.o test_irq_block: test_irq_block.o libserial.o printf.o libipc.o session.o usyscall.o arch_usyscall.o libmem.o
@${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs} @${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs}
@${objdump} -S $@ > $@.asm @${objdump} -S $@ > $@.asm
shell: shell_port.o libserial.o shell_cmd_list.o shell.o shell_ext.o libfs_to_client.o libipc.o session.o usyscall.o libmem.o test_irq_hdlr: test_irq_handler.o libserial.o printf.o libipc.o session.o usyscall.o arch_usyscall.o libmem.o
@${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs}
@${objdump} -S $@ > $@.asm
shell: shell_port.o libserial.o printf.o shell_cmd_list.o shell.o shell_ext.o libfs_to_client.o libipc.o session.o usyscall.o arch_usyscall.o libmem.o
@${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs} @${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs}
@${objdump} -S $@ > $@.asm @${objdump} -S $@ > $@.asm
init: init.o libfs_to_client.o libipc.o session.o libserial.o usyscall.o libmem.o init: init.o libfs_to_client.o libipc.o session.o libserial.o printf.o usyscall.o arch_usyscall.o libmem.o
@${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs} @${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs}
@${objdump} -S $@ > $@.asm @${objdump} -S $@ > $@.asm
test_fs: test_fs.o libfs_to_client.o libipc.o session.o libserial.o usyscall.o libmem.o test_fs: test_fs.o libfs_to_client.o libipc.o session.o libserial.o printf.o usyscall.o arch_usyscall.o libmem.o
@${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs} @${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs}
@${objdump} -S $@ > $@.asm @${objdump} -S $@ > $@.asm
simple_client: simple_client.o libserial.o libipc.o session.o simple_service.o libfs_to_client.o usyscall.o libmem.o simple_client: simple_client.o libserial.o printf.o libipc.o session.o simple_service.o libfs_to_client.o usyscall.o arch_usyscall.o libmem.o
@${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs} @${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs}
@${objdump} -S $@ > $@.asm @${objdump} -S $@ > $@.asm
simple_server: simple_server.o libserial.o libipc.o session.o simple_service.o usyscall.o libmem.o simple_server: simple_server.o libserial.o printf.o libipc.o session.o simple_service.o usyscall.o arch_usyscall.o libmem.o
@${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs} @${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs}
@${objdump} -S $@ > $@.asm @${objdump} -S $@ > $@.asm
fs_server: fs_server.o libfs_to_client.o fs.o libserial.o libipc.o session.o block_io.o usyscall.o libmem.o fs_server: fs_server.o libfs_to_client.o fs.o libserial.o printf.o libipc.o session.o block_io.o usyscall.o arch_usyscall.o libmem.o
@${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs} @${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs}
@${objdump} -S $@ > $@.asm @${objdump} -S $@ > $@.asm
test_priority: test_priority.o libserial.o usyscall.o libmem.o test_priority: test_priority.o libserial.o printf.o usyscall.o arch_usyscall.o libmem.o
@${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs} @${ld} ${user_ldflags} -e main -o $@ $^ ${board_specs}
@${objdump} -S $@ > $@.asm @${objdump} -S $@ > $@.asm

View File

@ -84,7 +84,7 @@ int main(int argc, char** argv)
if (argc >= 2) { if (argc >= 2) {
id = string_to_integer(argv[1]); id = string_to_integer(argv[1]);
} }
printf("This is Simple Client %d, size is 0x%x\n", id, task_heap_base()); // printf("This is Simple Client %d, size is 0x%x\n", id, task_heap_base());
struct Session session_wait; struct Session session_wait;
struct Session session_nowait; struct Session session_nowait;

View File

@ -9,10 +9,12 @@
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE. * MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details. * See the Mulan PSL v2 for more details.
*/ */
#include "libipc.h"
#include "libserial.h"
#include "usyscall.h"
/// this file is only used for debug IPC_SERVICES(IpcSwIntrHandler, Ipc_intr_3, Ipc_wait_intr_3);
#pragma once
void printf(char* fmt, ...); enum {
SW_INTERRUPT_3 = 3,
char getc(); };

View File

@ -0,0 +1,35 @@
/*
* 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 "test_irq.h"
IPC_INTERFACE(Ipc_wait_intr_3, 1, ignore, 0);
int wait_intr(struct Session* session)
{
return IPC_CALL(Ipc_wait_intr_3)(session, NULL);
}
static char prog_name[] = "TEST_IRQ_BLOCK";
int main(int argc, char* argv[])
{
struct Session session;
if (connect_session(&session, "TestIRQ", 4096) < 0) {
printf("connect session failed\n");
exit();
}
printf("%s start waiting for IRQ.\n", prog_name);
wait_intr(&session);
printf("%s return from waiting for IRQ.\n", prog_name);
exit();
}

View File

@ -10,35 +10,45 @@
* See the Mulan PSL v2 for more details. * See the Mulan PSL v2 for more details.
*/ */
#include "libipc.h" #include "test_irq.h"
#include "libserial.h"
#include "usyscall.h"
IPC_SERVICES(IpcSwIntrHandler, Ipc_intr_3); static bool has_one_interrupt = false;
int IPC_DO_SERVE_FUNC(Ipc_intr_3)(void* ignore)
enum {
SW_INTERRUPT_3 = 3,
};
void sgi_test_handler(void)
{ {
printf("TEST_SW_HDLR: In %s()\n", __func__); printf("TEST_SW_HDLR: In %s()\n", __func__);
has_one_interrupt = true;
return 0;
} }
int IPC_DO_SERVE_FUNC(Ipc_intr_3)(void* useless) int IPC_DO_SERVE_FUNC(Ipc_wait_intr_3)(void* ignore)
{ {
sgi_test_handler(); // delay the this handle
if (!has_one_interrupt) {
delay_session();
return -1;
}
// serve can be done by now
has_one_interrupt = false;
return 0; return 0;
} }
IPC_SERVER_INTERFACE(Ipc_intr_3, 1); IPC_SERVER_INTERFACE(Ipc_intr_3, 1);
IPC_SERVER_REGISTER_INTERFACES(IpcSwIntrHandler, 1, Ipc_intr_3); IPC_SERVER_INTERFACE(Ipc_wait_intr_3, 1);
IPC_SERVER_REGISTER_INTERFACES(IpcSwIntrHandler, 2, Ipc_intr_3, Ipc_wait_intr_3);
int main() int main()
{ {
if (register_irq(SW_INTERRUPT_3, Ipc_intr_3) == -1) { if (register_irq(SW_INTERRUPT_3, Ipc_intr_3) < 0) {
printf("TEST_SW_HDLR: bind failed"); printf("TEST_SW_HDLR: bind failed");
exit(); exit();
} }
static char prog_name[] = "TestIRQ";
if (register_server("TestIRQ") < 0) {
printf("register server name: %s failed.\n", prog_name);
exit();
}
ipc_server_loop(&IpcSwIntrHandler); ipc_server_loop(&IpcSwIntrHandler);
exit(); exit();

View File

@ -9,17 +9,19 @@ ld = ${toolchain}g++
objdump = ${toolchain}objdump objdump = ${toolchain}objdump
user_ldflags = -N -Ttext 0 user_ldflags = -N -Ttext 0
cflags = -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 -no-pie 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 = -O0 c_useropts = -O2
INC_DIR = -I$(KERNEL_ROOT)/services/fs/libfs \ INC_DIR = -I$(KERNEL_ROOT)/services/fs/libfs \
-I$(KERNEL_ROOT)/services/lib/ipc \ -I$(KERNEL_ROOT)/services/lib/ipc \
-I$(KERNEL_ROOT)/services/lib/memory \ -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/boards/$(BOARD) \
-I$(KERNEL_ROOT)/services/app -I$(KERNEL_ROOT)/services/app
board: libserial.o usyscall.o test_irq_sender.o board: libserial.o arch_usyscall.o test_irq_sender.o
@mv $^ ../../app @mv $^ $(KERNEL_ROOT)/services/app
%.o: %.c %.o: %.c
@echo "cc $^" @echo "cc $^"

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 r0, %1;\
mov r1, %2;\
mov r2, %3;\
mov r3, %4;\
mov r4, %5;\
swi 0;\
dsb;\
isb;\
mov %0, r0"
: "=r"(ret)
: "r"(sys_num), "r"(a1), "r"(a2), "r"(a3), "r"(a4)
: "memory", "r0", "r1", "r2", "r3", "r4");
return ret;
}

View File

@ -82,7 +82,7 @@ typedef union _hw_uart_utxd {
#define USER_UART_BASE 0x6FFFF000 #define USER_UART_BASE 0x6FFFF000
// #define USER_UART_BASE 0x621e8000 // #define USER_UART_BASE 0x621e8000
static bool init_uart_mmio() bool init_uart_mmio()
{ {
static int mapped = 0; static int mapped = 0;
if (mapped == 0) { if (mapped == 0) {
@ -94,7 +94,7 @@ static bool init_uart_mmio()
return true; return true;
} }
static void putc(char c) void putc(char c)
{ {
while ((*(volatile hw_uart_uts_t*)(USER_UART_BASE + 0xb4)).B.TXFULL) while ((*(volatile hw_uart_uts_t*)(USER_UART_BASE + 0xb4)).B.TXFULL)
; ;
@ -127,80 +127,3 @@ char getc(void)
return (char)read_data; return (char)read_data;
} }
static void printint(int xx, int base, int sgn)
{
static char digits[] = "0123456789ABCDEF";
char buf[16];
int i, neg;
uint32_t x;
neg = 0;
if (sgn && xx < 0) {
neg = 1;
x = -xx;
} else {
x = xx;
}
i = 0;
do {
buf[i++] = digits[x % base];
} while ((x /= base) != 0);
if (neg)
buf[i++] = '-';
while (--i >= 0)
putc(buf[i]);
}
// Print to usart. Only understands %d, %x, %p, %s.
void printf(char* fmt, ...)
{
if (!init_uart_mmio()) {
return;
}
char* s;
int c, i, state;
uint32_t* ap;
state = 0;
ap = (uint32_t*)(void*)&fmt + 1;
for (i = 0; fmt[i]; i++) {
c = fmt[i] & 0xff;
if (state == 0) {
if (c == '%') {
state = '%';
} else {
putc(c);
}
} else if (state == '%') {
if (c == 'd') {
printint(*ap, 10, 1);
ap++;
} else if (c == 'x' || c == 'p') {
printint(*ap, 16, 0);
ap++;
} else if (c == 's') {
s = (char*)*ap;
ap++;
if (s == 0)
s = "(null)";
while (*s != 0) {
putc(*s);
s++;
}
} else if (c == 'c') {
putc(*ap);
ap++;
} else if (c == '%') {
putc(c);
} else {
// Unknown % sequence. Print it to draw attention.
putc('%');
putc(c);
}
state = 0;
}
}
}

View File

@ -88,7 +88,8 @@ int main()
printf("%s: Mapping GIC\n", prog_name); printf("%s: Mapping GIC\n", prog_name);
mmap(ARM_PERIPHERAL_VIRT_BASE, ARM_PERIPHERAL_BASE, 0x2000, true); mmap(ARM_PERIPHERAL_VIRT_BASE, ARM_PERIPHERAL_BASE, 0x2000, true);
int send_time = 1000; // int send_time = 1000;
int send_time = 1;
printf("%s: Sending soft interrupt for %d times\n", prog_name, send_time); printf("%s: Sending soft interrupt for %d times\n", prog_name, send_time);
for (int i = 0; i < send_time; i++) { for (int i = 0; i < send_time; i++) {
gic_send_sgi(SW_INTERRUPT_3, 0xF, kGicSgiFilter_UseTargetList); gic_send_sgi(SW_INTERRUPT_3, 0xF, kGicSgiFilter_UseTargetList);

View File

@ -1,124 +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.
*/
#include "usyscall.h"
#include "libmem.h"
static int
syscall(int sys_num, intptr_t a1, intptr_t a2, intptr_t a3, intptr_t a4)
{
int ret = -1;
__asm__ volatile(
"mov r0, %1;\
mov r1, %2;\
mov r2, %3;\
mov r3, %4;\
mov r4, %5;\
swi 0;\
dsb;\
isb;\
mov %0, r0"
: "=r"(ret)
: "r"(sys_num), "r"(a1), "r"(a2), "r"(a3), "r"(a4)
: "memory", "r0", "r1", "r2", "r3", "r4");
return ret;
}
int spawn(struct Session* session, int fd, ipc_read_fn ipc_read, ipc_fsize_fn ipc_fsize, char* name, char** argv)
{
int file_size = ipc_fsize(session, fd);
void* img = malloc(file_size);
int read_len = 0, cur_read_len = 0;
while (read_len < file_size) {
cur_read_len = file_size - read_len < 4096 ? file_size - read_len : 4096;
read_len += ipc_read(session, fd, img + read_len, read_len, cur_read_len);
}
int ret = syscall(SYSCALL_SPAWN, (intptr_t)img, (intptr_t)name, (intptr_t)argv, 0);
free(img);
return ret;
}
int exit()
{
return syscall(SYSCALL_EXIT, 0, 0, 0, 0);
}
int yield(task_yield_reason reason)
{
return syscall(SYSCALL_YIELD, (uintptr_t)reason, 0, 0, 0);
}
int kill(int pid)
{
return syscall(SYSCALL_KILL, (intptr_t)pid, 0, 0, 0);
}
int register_server(char* name)
{
return syscall(SYSCALL_SERVER, (intptr_t)name, 0, 0, 0);
}
int session(char* path, int capacity, struct Session* user_session)
{
return syscall(SYSCALL_SESSION, (intptr_t)path, (intptr_t)capacity, (intptr_t)user_session, 0);
}
int poll_session(struct Session* userland_session_arr, int arr_capacity)
{
return syscall(SYSCALL_POLL_SESSION, (intptr_t)userland_session_arr, (intptr_t)arr_capacity, 0, 0);
}
int close_session(struct Session* session)
{
return syscall(SYSCALL_CLOSE_SESSION, (intptr_t)session, 0, 0, 0);
}
int get_memblock_info(sys_state_info* info)
{
return syscall(SYSCALL_SYS_STATE, SYS_STATE_MEMBLOCK_INFO, (intptr_t)info, 0, 0);
}
int set_priority(sys_state_info* info)
{
return syscall(SYSCALL_SYS_STATE, SYS_STATE_SET_TASK_PRIORITY, (intptr_t)info, 0, 0);
}
int task_heap_base()
{
return syscall(SYSCALL_SYS_STATE, SYS_STATE_GET_HEAP_BASE, 0, 0, 0);
}
int show_task()
{
return syscall(SYSCALL_SYS_STATE, SYS_STATE_SHOW_TASKS, 0, 0, 0);
}
int show_mem()
{
return syscall(SYSCALL_SYS_STATE, SYS_STATE_SHOW_MEM_INFO, 0, 0, 0);
}
int show_cpu()
{
return syscall(SYSCALL_SYS_STATE, SYS_STATE_SHOW_CPU_INFO, 0, 0, 0);
}
int mmap(uintptr_t vaddr, uintptr_t paddr, int len, bool is_dev)
{
return syscall(SYSCALL_MMAP, vaddr, paddr, (intptr_t)len, (intptr_t)is_dev);
}
int register_irq(int irq, int opcode)
{
return syscall(SYSCALL_REGISTER_IRQ, (intptr_t)irq, (intptr_t)opcode, 0, 0);
}

View File

@ -1,80 +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.
*/
#pragma once
#include <stdint.h>
#include "libserial.h"
#include "session.h"
// clang-format off
#define SYSCALL_TEST 0
#define SYSCALL_SPAWN 1 // generate a brand new task to run elf
#define SYSCALL_EXIT 2 // exit task, delete the task cb
#define SYSCALL_YIELD 3 // yield task, go to scheduler
#define SYSCALL_MMAP 4 // map a virt page to phy page
#define SYSCALL_SERVER 5 // register current task as a server
#define SYSCALL_SESSION 6 // create a session to a server
#define SYSCALL_POLL_SESSION 7 // server poll for it's server sessions
#define SYSCALL_CLOSE_SESSION 8 // client close it's client sessions
#define SYSCALL_EXEC 9 // run elf using current task
#define SYSCALL_SYS_STATE 10 // run system state
#define SYSCALL_REGISTER_IRQ 11 //
#define SYSCALL_KILL 12 // kill the task by id
// clang-format on
typedef enum {
SYS_STATE_TEST = 0,
SYS_STATE_SET_TASK_PRIORITY,
SYS_STATE_GET_HEAP_BASE,
SYS_STATE_MEMBLOCK_INFO,
SYS_STATE_SHOW_TASKS,
SYS_STATE_SHOW_MEM_INFO,
SYS_STATE_SHOW_CPU_INFO,
} sys_state_option;
typedef enum {
SYS_TASK_YIELD_NO_REASON = 0x0,
SYS_TASK_YIELD_FOREVER = 0x1,
SYS_TASK_YIELD_BLOCK_IPC = 0x2,
} task_yield_reason;
typedef union {
struct {
uintptr_t memblock_start;
uintptr_t memblock_end;
} memblock_info;
int priority;
} sys_state_info;
typedef int (*ipc_read_fn)(struct Session* session, int fd, char* dst, int offset, int len);
typedef int (*ipc_fsize_fn)(struct Session* session, int fd);
typedef int (*ipc_write_fn)(struct Session* session, int fd, char* src, int offset, int len);
int spawn(struct Session* session, int fd, ipc_read_fn ipc_read, ipc_fsize_fn ipc_fsize, char* name, char** argv);
int exit();
int yield(task_yield_reason reason);
int kill(int pid);
int register_server(char* name);
int session(char* path, int capacity, struct Session* user_session);
int poll_session(struct Session* userland_session_arr, int arr_capacity);
int close_session(struct Session* session);
int task_heap_base();
int get_memblock_info(sys_state_info* info);
int set_priority(sys_state_info* info);
int show_task();
int show_mem();
int show_cpu();
int mmap(uintptr_t vaddr, uintptr_t paddr, int len, bool is_dev);
int register_irq(int irq, int opcode);

View File

@ -19,10 +19,12 @@ INC_DIR = -I$(KERNEL_ROOT)/services/fs/libfs \
-I$(KERNEL_ROOT)/services/fs/fs_server/include \ -I$(KERNEL_ROOT)/services/fs/fs_server/include \
-I$(KERNEL_ROOT)/services/lib/ipc \ -I$(KERNEL_ROOT)/services/lib/ipc \
-I$(KERNEL_ROOT)/services/lib/memory \ -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/boards/$(BOARD) \
-I$(KERNEL_ROOT)/services/app -I$(KERNEL_ROOT)/services/app
board: libserial.o stub.o usyscall.o board: libserial.o stub.o arch_usyscall.o
@mv $^ ../../app @mv $^ ../../app
%.o: %.c %.o: %.c

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 r0, %1;\
mov r1, %2;\
mov r2, %3;\
mov r3, %4;\
mov r4, %5;\
swi 0;\
dsb;\
isb;\
mov %0, r0"
: "=r"(ret)
: "r"(sys_num), "r"(a1), "r"(a2), "r"(a3), "r"(a4)
: "memory", "r0", "r1", "r2", "r3", "r4");
return ret;
}

View File

@ -23,6 +23,7 @@ void Xil_Out32(intptr_t Addr, uint32_t Value)
uint32_t* LocalAddr = (uint32_t*)Addr; uint32_t* LocalAddr = (uint32_t*)Addr;
*LocalAddr = Value; *LocalAddr = Value;
} }
#define XUartPs_IsTransmitFull(BaseAddress) \ #define XUartPs_IsTransmitFull(BaseAddress) \
((*(volatile uint32_t*)((BaseAddress) + 0x002CU) & (uint32_t)0x00000010U) == (uint32_t)0x00000010U) ((*(volatile uint32_t*)((BaseAddress) + 0x002CU) & (uint32_t)0x00000010U) == (uint32_t)0x00000010U)
#define XUartPs_WriteReg(BaseAddress, RegOffset, RegisterValue) \ #define XUartPs_WriteReg(BaseAddress, RegOffset, RegisterValue) \
@ -47,7 +48,7 @@ uint8_t XUartPs_RecvByte(uint32_t BaseAddress)
#define USER_UART_BASE 0x6FFFF000 #define USER_UART_BASE 0x6FFFF000
static bool init_uart_mmio() bool init_uart_mmio()
{ {
static int mapped = 0; static int mapped = 0;
if (mapped == 0) { if (mapped == 0) {
@ -59,7 +60,7 @@ static bool init_uart_mmio()
return true; return true;
} }
static void putc(char c) void putc(char c)
{ {
if (c == '\n') { if (c == '\n') {
while (XUartPs_IsTransmitFull(USER_UART_BASE)) { while (XUartPs_IsTransmitFull(USER_UART_BASE)) {
@ -83,80 +84,3 @@ char getc(void)
} }
return XUartPs_RecvByte(USER_UART_BASE); return XUartPs_RecvByte(USER_UART_BASE);
} }
static void printint(int xx, int base, int sgn)
{
static char digits[] = "0123456789ABCDEF";
char buf[16];
int i, neg;
uint32_t x;
neg = 0;
if (sgn && xx < 0) {
neg = 1;
x = -xx;
} else {
x = xx;
}
i = 0;
do {
buf[i++] = digits[x % base];
} while ((x /= base) != 0);
if (neg)
buf[i++] = '-';
while (--i >= 0)
putc(buf[i]);
}
// Print to usart. Only understands %d, %x, %p, %s.
void printf(char* fmt, ...)
{
if (!init_uart_mmio()) {
return;
}
char* s;
int c, i, state;
uint32_t* ap;
state = 0;
ap = (uint32_t*)(void*)&fmt + 1;
for (i = 0; fmt[i]; i++) {
c = fmt[i] & 0xff;
if (state == 0) {
if (c == '%') {
state = '%';
} else {
putc(c);
}
} else if (state == '%') {
if (c == 'd') {
printint(*ap, 10, 1);
ap++;
} else if (c == 'x' || c == 'p') {
printint(*ap, 16, 0);
ap++;
} else if (c == 's') {
s = (char*)*ap;
ap++;
if (s == 0)
s = "(null)";
while (*s != 0) {
putc(*s);
s++;
}
} else if (c == 'c') {
putc(*ap);
ap++;
} else if (c == '%') {
putc(c);
} else {
// Unknown % sequence. Print it to draw attention.
putc('%');
putc(c);
}
state = 0;
}
}
}

View File

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

View File

@ -0,0 +1,4 @@
SRC_DIR := clock enet gpio lib
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,30 @@
ifeq ($(BOARD), imx6q-sabrelite)
toolchain ?= arm-none-eabi-
endif
ifeq ($(BOARD), zynq7000-zc702)
toolchain ?= arm-xilinx-eabi-
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 \
-I$(KERNEL_ROOT)/services/boards/$(BOARD) \
-I$(KERNEL_ROOT)/services/lib/serial \
-I$(KERNEL_ROOT)/services/drivers/$(BOARD)/include \
-I$(KERNEL_ROOT)/services/drivers/$(BOARD)/enet \
-I$(KERNEL_ROOT)/services/drivers/$(BOARD)/clock \
-I$(KERNEL_ROOT)/services/drivers/$(BOARD)/lib \
-I$(KERNEL_ROOT)/services/lib/usyscall \
-I$(KERNEL_ROOT)/services/lib/ipc
all: ccm_pll.o epit.o timer.o
@mv $^ $(KERNEL_ROOT)/services/app
%.o: %.c
@echo "cc $^"
@${cc} ${cflags} ${c_useropts} ${INC_DIR} -o $@ -c $^

View File

@ -0,0 +1,221 @@
/*
* Copyright (c) 2011-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 ccm_pll.c
* @brief support imx6q soc ccm pll functions
* @version 3.0
* @author AIIT XUOS Lab
* @date 2023.09.08
*/
/*************************************************
File name: ccm_pll.c
Description: support imx6q soc ccm pll functions
Others:
History:
1. Date: 2023-08-28
Author: AIIT XUOS Lab
Modification:
1. Delete unnecessary functions;
2. Slim clock_gating_config to fit only uart and gpt(clock)
*************************************************/
#include "soc_memory_map.h"
#include <stdbool.h>
#include <stdint.h>
#include "regsccm.h"
#include "regsccmanalog.h"
#include "regsgpc.h"
#include "regsepit.h"
#include "regsgpt.h"
#include "ccm_pll.h"
////////////////////////////////////////////////////////////////////////////////
// Variables
////////////////////////////////////////////////////////////////////////////////
const uint32_t PLL1_OUTPUT = 792000000;
const uint32_t PLL2_OUTPUT[] = { 528000000, 396000000, 352000000, 198000000, 594000000 };
const uint32_t PLL3_OUTPUT[] = { 480000000, 720000000, 540000000, 508235294, 454736842 };
const uint32_t PLL4_OUTPUT = 650000000;
const uint32_t PLL5_OUTPUT = 650000000;
////////////////////////////////////////////////////////////////////////////////
// Code
////////////////////////////////////////////////////////////////////////////////
uint32_t get_main_clock(main_clocks_t clock)
{
uint32_t ret_val = 0;
uint32_t pre_periph_clk_sel = HW_CCM_CBCMR.B.PRE_PERIPH_CLK_SEL;
switch (clock) {
case CPU_CLK:
ret_val = PLL1_OUTPUT;
break;
#if !defined(CHIP_MX6SL)
case AXI_CLK:
ret_val = PLL2_OUTPUT[pre_periph_clk_sel] / (HW_CCM_CBCDR.B.AXI_PODF + 1);
break;
case MMDC_CH0_AXI_CLK:
ret_val = PLL2_OUTPUT[pre_periph_clk_sel] / (HW_CCM_CBCDR.B.MMDC_CH0_AXI_PODF + 1);
break;
#endif
case AHB_CLK:
ret_val = PLL2_OUTPUT[pre_periph_clk_sel] / (HW_CCM_CBCDR.B.AHB_PODF + 1);
break;
case IPG_CLK:
ret_val = PLL2_OUTPUT[pre_periph_clk_sel] / (HW_CCM_CBCDR.B.AHB_PODF + 1) / (HW_CCM_CBCDR.B.IPG_PODF + 1);
break;
case IPG_PER_CLK:
ret_val = PLL2_OUTPUT[pre_periph_clk_sel] / (HW_CCM_CBCDR.B.AHB_PODF + 1) / (HW_CCM_CBCDR.B.IPG_PODF + 1) / (HW_CCM_CSCMR1.B.PERCLK_PODF + 1);
break;
#if !defined(CHIP_MX6SL)
case MMDC_CH1_AXI_CLK:
ret_val = PLL2_OUTPUT[pre_periph_clk_sel] / (HW_CCM_CBCDR.B.MMDC_CH1_AXI_PODF + 1);
break;
#endif
default:
break;
}
return ret_val;
}
uint32_t get_peri_clock(peri_clocks_t clock)
{
uint32_t ret_val = 0;
switch (clock) {
case UART1_MODULE_CLK:
case UART2_MODULE_CLK:
case UART3_MODULE_CLK:
case UART4_MODULE_CLK:
// UART source clock is a fixed PLL3 / 6
ret_val = PLL3_OUTPUT[0] / 6 / (HW_CCM_CSCDR1.B.UART_CLK_PODF + 1);
break;
// eCSPI clock:
// PLL3(480) -> /8 -> CSCDR2[ECSPI_CLK_PODF]
case SPI_CLK:
ret_val = PLL3_OUTPUT[0] / 8 / (HW_CCM_CSCDR2.B.ECSPI_CLK_PODF + 1);
break;
#if !defined(CHIP_MX6SL)
case RAWNAND_CLK:
ret_val = PLL3_OUTPUT[0] / (HW_CCM_CS2CDR.B.ENFC_CLK_PRED + 1) / (HW_CCM_CS2CDR.B.ENFC_CLK_PODF + 1);
break;
case CAN_CLK:
// For i.mx6dq/sdl CAN source clock is a fixed PLL3 / 8
ret_val = PLL3_OUTPUT[0] / 8 / (HW_CCM_CSCMR2.B.CAN_CLK_PODF + 1);
break;
#endif
default:
break;
}
return ret_val;
}
void ccm_set_lpm_wakeup_source(uint32_t irq_id, bool doEnable)
{
uint32_t reg_offset = 0;
uint32_t bit_offset = 0;
uint32_t gpc_imr = 0;
// calculate the offset of the register handling that interrupt ID
// ID starts at 32, so for instance ID=89 is handled by IMR2 because
// the integer part of the division is reg_offset = 2
reg_offset = (irq_id / 32);
// and the rest of the previous division is used to calculate the bit
// offset in the register, so for ID=89 this is bit_offset = 25
bit_offset = irq_id - 32 * reg_offset;
// get the current value of the corresponding GPC_IMRx register
gpc_imr = *((volatile uint32_t*)(HW_GPC_IMR1_ADDR + (reg_offset - 1) * 4));
if (doEnable) {
// clear the corresponding bit to unmask the interrupt source
gpc_imr &= ~(1 << bit_offset);
// write the new mask
*((volatile uint32_t*)(HW_GPC_IMR1_ADDR + (reg_offset - 1) * 4)) = (gpc_imr);
} else {
// set the corresponding bit to mask the interrupt source
gpc_imr |= (1 << bit_offset);
// write the new mask
*((volatile uint32_t*)(HW_GPC_IMR1_ADDR + (reg_offset - 1) * 4)) = (gpc_imr);
}
}
/*!
* Set/unset clock gating for a peripheral.
* @param ccm_ccgrx Address of the clock gating register: CCM_CCGR1,...
* @param cgx_offset Offset of the clock gating field: CG(x).
* @param gating_mode Clock gating mode: CLOCK_ON or CLOCK_OFF.
*/
void ccm_ccgr_config(uint32_t ccm_ccgrx, uint32_t cgx_offset, uint32_t gating_mode)
{
if (gating_mode == CLOCK_ON) {
*(volatile uint32_t*)(ccm_ccgrx) |= cgx_offset;
} else {
*(volatile uint32_t*)(ccm_ccgrx) &= ~cgx_offset;
}
}
void clock_gating_config(uint32_t base_address, uint32_t gating_mode)
{
uint32_t ccm_ccgrx = 0;
uint32_t cgx_offset = 0;
switch (base_address) {
case REGS_EPIT1_BASE:
ccm_ccgrx = HW_CCM_CCGR1_ADDR;
cgx_offset = CG(6);
break;
case REGS_EPIT2_BASE:
ccm_ccgrx = HW_CCM_CCGR1_ADDR;
cgx_offset = CG(7);
break;
default:
break;
}
// apply changes only if a valid address was found
if (ccm_ccgrx != 0) {
ccm_ccgr_config(ccm_ccgrx, cgx_offset, gating_mode);
}
}
////////////////////////////////////////////////////////////////////////////////
// End of file
////////////////////////////////////////////////////////////////////////////////

View File

@ -0,0 +1,194 @@
/*
* Copyright (c) 2011-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 epit.c
* @brief EPIT driver source file.
*
* @ingroup diag_timer
*/
#include "epit.h"
#include "ccm_pll.h"
#include "regsepit.h"
#include "timer.h"
#include "usyscall.h"
////////////////////////////////////////////////////////////////////////////////
// Code
////////////////////////////////////////////////////////////////////////////////
uint32_t g_system_timer_port = HW_EPIT1;
void epit_reload_counter(uint32_t instance, uint32_t load_val)
{
// set the load register especially if RLD=reload_mode=SET_AND_FORGET=1
HW_EPIT_LR_WR(instance, load_val);
}
uint32_t epit_get_counter_value(uint32_t instance)
{
return HW_EPIT_CNR_RD(instance);
}
void epit_set_compare_event(uint32_t instance, uint32_t compare_val)
{
HW_EPIT_CMPR_WR(instance, compare_val);
}
uint32_t epit_get_compare_event(uint32_t instance)
{
uint32_t status_register;
// get the status
status_register = HW_EPIT_SR_RD(instance);
// clear it if found set
if (status_register & BM_EPIT_SR_OCIF) {
HW_EPIT_SR_SET(instance, BM_EPIT_SR_OCIF);
}
// return the read value before the bit was cleared
return status_register & BM_EPIT_SR_OCIF;
}
void epit_counter_disable(uint32_t instance)
{
/* temporary workaround for the discovered issue when disabling the
* counter during end of count/reload/set compare flag ??.
* Set to the max value so that it ensures that the counter couldn't
* reach 0 when it is disabled.
*/
HW_EPIT_LR_WR(instance, 0xFFFFFFFF);
// disable the counter
HW_EPIT_CR_CLR(instance, BM_EPIT_CR_EN);
// ensure to leave the counter in a proper state
// by disabling the output compare interrupt
HW_EPIT_CR_CLR(instance, BM_EPIT_CR_OCIEN);
// and clearing possible remaining compare event
HW_EPIT_SR_SET(instance, BM_EPIT_SR_OCIF);
}
void epit_counter_enable(uint32_t instance, uint32_t load_val, uint32_t irq_mode)
{
// set the load register especially if RLD=reload_mode=SET_AND_FORGET=1
// and if the value is different from 0 which is the lowest counter value
if (load_val != 0) {
HW_EPIT_LR_WR(instance, load_val);
}
// ensure to start the counter in a proper state
// by clearing possible remaining compare event
HW_EPIT_SR_SET(instance, BM_EPIT_SR_OCIF);
// set the mode when the output compare event occur: IRQ or polling
if (irq_mode == IRQ_MODE) {
HW_EPIT_CR_SET(instance, BM_EPIT_CR_OCIEN);
} else {
// polling
HW_EPIT_CR_CLR(instance, BM_EPIT_CR_OCIEN);
}
// finally, enable the counter
HW_EPIT_CR_SET(instance, BM_EPIT_CR_EN);
}
void epit_setup_interrupt(uint32_t instance, void (*irq_subroutine)(void), bool enableIt)
{
// uint32_t irq_id = EPIT_IRQS(instance);
// if (enableIt) {
// // register the IRQ sub-routine
// register_interrupt_routine(irq_id, irq_subroutine);
// // enable the IRQ
// enable_interrupt(irq_id, 0, 0);
// } else {
// // disable the IRQ
// disable_interrupt(irq_id, 0);
// }
}
void epit_init(uint32_t instance, uint32_t clock_src, uint32_t prescaler,
uint32_t reload_mode, uint32_t load_val, uint32_t low_power_mode)
{
uint32_t control_reg_tmp = 0;
uint32_t base = REGS_EPIT_BASE(instance);
// enable the source clocks to the EPIT port
clock_gating_config(base, CLOCK_ON);
// start with a known state by disabling and reseting the module
HW_EPIT_CR_WR(instance, BM_EPIT_CR_SWR);
// wait for the reset to complete
while ((HW_EPIT_CR(instance).B.SWR) != 0)
;
// set the reference source clock for the counter
control_reg_tmp |= BF_EPIT_CR_CLKSRC(clock_src);
// set the counter clock prescaler value - 0 to 4095
control_reg_tmp |= BF_EPIT_CR_PRESCALAR(prescaler - 1);
// set the reload mode
if (reload_mode == SET_AND_FORGET) {
control_reg_tmp |= BM_EPIT_CR_RLD;
}
// set behavior for low power mode
if (low_power_mode & WAIT_MODE_EN) {
control_reg_tmp |= BM_EPIT_CR_WAITEN;
}
if (low_power_mode & STOP_MODE_EN) {
control_reg_tmp |= BM_EPIT_CR_STOPEN;
}
// make the counter start from a known value when enabled, this is loaded from
// EPITLR register if RLD=reload_mode=1 or 0xFFFFFFFF if RLD=reload_mode=0
control_reg_tmp |= BM_EPIT_CR_IOVW | BM_EPIT_CR_ENMOD;
// finally write the control register
HW_EPIT_CR_WR(instance, control_reg_tmp);
// initialize the load register especially if RLD=reload_mode=SET_AND_FORGET=1
// and if the value is different from 0 which is the lowest counter value
if (load_val != 0) {
HW_EPIT_LR_WR(instance, load_val);
}
}
////////////////////////////////////////////////////////////////////////////////
// EOF
////////////////////////////////////////////////////////////////////////////////

View File

@ -0,0 +1,172 @@
/*
* Copyright (c) 2011-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.
*/
//! @addtogroup diag_epit
//! @{
/*!
* @file epit.h
* @brief EPIT driver public interface.
*/
#ifndef __EPIT_H__
#define __EPIT_H__
#include <stdbool.h>
#include "timer.h"
////////////////////////////////////////////////////////////////////////////////
// Definitions
////////////////////////////////////////////////////////////////////////////////
//! @brief Free running reload mode.
//!
//! When the counter reaches zero it rolls over to 0xFFFF_FFFF.
#define FREE_RUNNING 0
//! @brief Set and forget reload mode.
//!
//! When the counter reaches zero it reloads from the modulus register.
#define SET_AND_FORGET 1
//! @brief Pass to epit_counter_enable() to enable interrupts.
#define IRQ_MODE 1
//! @brief Get the irq id of RPIT by instance number.
//! @param x I2C instance number, from 1 through 2.
#define EPIT_IRQS(x) ((x) == HW_EPIT1 ? 88 : (x) == HW_EPIT2 ? 89 \
: 0xFFFFFFFF)
////////////////////////////////////////////////////////////////////////////////
// API
////////////////////////////////////////////////////////////////////////////////
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @brief Initialize the EPIT timer.
*
* @param instance the EPIT instance number.
* @param clock_src Source clock of the counter: CLKSRC_OFF, CLKSRC_IPG_CLK,
* CLKSRC_PER_CLK, CLKSRC_CKIL.
* @param prescaler Prescaler of source clock from 1 to 4096.
* @param reload_mode Counter reload mode: FREE_RUNNING or SET_AND_FORGET.
* @param load_val Load value from where the counter start.
* @param low_power_mode Low power during which the timer is enabled:
* WAIT_MODE_EN and/or STOP_MODE_EN.
*/
void epit_init(uint32_t instance, uint32_t clock_src, uint32_t prescaler,
uint32_t reload_mode, uint32_t load_val, uint32_t low_power_mode);
/*!
* @brief Setup EPIT interrupt.
*
* It enables or disables the related HW module interrupt, and attached the related sub-routine
* into the vector table.
*
* @param instance the EPIT instance number.
* @param irq_subroutine the EPIT interrupt interrupt routine.
* @param enableIt True to enable the interrupt, false to disable.
*/
void epit_setup_interrupt(uint32_t instance, void (*irq_subroutine)(void), bool enableIt);
/*!
* @brief Enable the EPIT module.
*
* Used typically when the epit_init is done, and other interrupt related settings are ready.
*
* In interrupt mode, when the interrupt fires you should call epit_get_compare_event() to
* clear the compare flag.
*
* @param instance the EPIT instance number.
* @param load_val Load value from where the counter starts.
* @param irq_mode Interrupt mode: IRQ_MODE or POLLING_MODE.
*/
void epit_counter_enable(uint32_t instance, uint32_t load_val, uint32_t irq_mode);
/*!
* @brief Disable the counter.
*
* It saves energy when not used.
*
* @param instance the EPIT instance number.
*/
void epit_counter_disable(uint32_t instance);
/*!
* @brief Get the output compare status flag and clear it if set.
*
* This function can typically be used for polling method, but
* is also used to clear the status compare flag in IRQ mode.
*
* @param instance the EPIT instance number.
* @return Value of the compare event flag.
*/
uint32_t epit_get_compare_event(uint32_t instance);
/*!
* @brief Set the output compare register.
*
*
* @param instance the EPIT instance number.
* @param Value of the compare register.
*/
void epit_set_compare_event(uint32_t instance, uint32_t compare_val);
/*!
* @brief Get the counter value.
*
*
* @param instance the EPIT instance number.
* @return Value of the counter register.
*/
uint32_t epit_get_counter_value(uint32_t instance);
/*!
* @brief Reload the counter with a known value.
*
* @param instance the EPIT instance number.
* @param load_val Value loaded into the timer counter.
*/
void epit_reload_counter(uint32_t instance, uint32_t load_val);
#if defined(__cplusplus)
}
#endif
//! @}
#endif //__EPIT_H__
////////////////////////////////////////////////////////////////////////////////
// EOF
////////////////////////////////////////////////////////////////////////////////

View File

@ -0,0 +1,525 @@
/*
* Copyright (c) 2012, Freescale Semiconductor, Inc.
* All rights reserved.
*
* THIS SOFTWARE IS PROVIDED BY FREESCALE "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 FREESCALE 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.
*/
/*
* WARNING! DO NOT EDIT THIS FILE DIRECTLY!
*
* This file was generated automatically and any changes may be lost.
*/
#ifndef __HW_ARMGLOBALTIMER_REGISTERS_H__
#define __HW_ARMGLOBALTIMER_REGISTERS_H__
#include "regs.h"
#include "soc_memory_map.h"
/*
* i.MX6SL ARMGLOBALTIMER
*
* ARM Cortex-A9 Global Timer
*
* Registers defined in this header file:
* - HW_ARMGLOBALTIMER_COUNTERn - Global Timer Counter Registers
* - HW_ARMGLOBALTIMER_CONTROL - Global Timer Control Register
* - HW_ARMGLOBALTIMER_IRQSTATUS - Global Timer Interrupt Status Register
* - HW_ARMGLOBALTIMER_COMPARATORn - Global Timer Comparator Value Registers
* - HW_ARMGLOBALTIMER_AUTOINCREMENT - Global Timer Auto-increment Register
*
* - hw_armglobaltimer_t - Struct containing all module registers.
*/
//! @name Module base addresses
//@{
#ifndef REGS_ARMGLOBALTIMER_BASE
#define HW_ARMGLOBALTIMER_INSTANCE_COUNT (1) //!< Number of instances of the ARMGLOBALTIMER module.
#define REGS_ARMGLOBALTIMER_BASE USERLAND_MMIO_P2V(0x00a00000) //!< Base address for ARMGLOBALTIMER.
#endif
//@}
//-------------------------------------------------------------------------------------------
// HW_ARMGLOBALTIMER_COUNTERn - Global Timer Counter Registers
//-------------------------------------------------------------------------------------------
#ifndef __LANGUAGE_ASM__
/*!
* @brief HW_ARMGLOBALTIMER_COUNTERn - Global Timer Counter Registers (RW)
*
* Reset value: 0x00000000
*
* There are two timer counter registers. They are the lower 32-bit timer counter at offset 0x00 and
* the upper 32-bit timer counter at offset 0x04.
*/
typedef union _hw_armglobaltimer_countern {
reg32_t U;
struct _hw_armglobaltimer_countern_bitfields {
unsigned VALUE : 32; //!< [31:0] 32-bits of the counter value.
} B;
} hw_armglobaltimer_countern_t;
#endif
/*!
* @name Constants and macros for entire ARMGLOBALTIMER_COUNTERn register
*/
//@{
//! @brief Number of instances of the ARMGLOBALTIMER_COUNTERn register.
#define HW_ARMGLOBALTIMER_COUNTERn_COUNT (2)
#define HW_ARMGLOBALTIMER_COUNTERn_ADDR(n) (REGS_ARMGLOBALTIMER_BASE + 0x200 + (0x4 * (n)))
#ifndef __LANGUAGE_ASM__
#define HW_ARMGLOBALTIMER_COUNTERn(n) (*(volatile hw_armglobaltimer_countern_t*)HW_ARMGLOBALTIMER_COUNTERn_ADDR(n))
#define HW_ARMGLOBALTIMER_COUNTERn_RD(n) (HW_ARMGLOBALTIMER_COUNTERn(n).U)
#define HW_ARMGLOBALTIMER_COUNTERn_WR(n, v) (HW_ARMGLOBALTIMER_COUNTERn(n).U = (v))
#define HW_ARMGLOBALTIMER_COUNTERn_SET(n, v) (HW_ARMGLOBALTIMER_COUNTERn_WR(n, HW_ARMGLOBALTIMER_COUNTERn_RD(n) | (v)))
#define HW_ARMGLOBALTIMER_COUNTERn_CLR(n, v) (HW_ARMGLOBALTIMER_COUNTERn_WR(n, HW_ARMGLOBALTIMER_COUNTERn_RD(n) & ~(v)))
#define HW_ARMGLOBALTIMER_COUNTERn_TOG(n, v) (HW_ARMGLOBALTIMER_COUNTERn_WR(n, HW_ARMGLOBALTIMER_COUNTERn_RD(n) ^ (v)))
#endif
//@}
/*
* constants & macros for individual ARMGLOBALTIMER_COUNTERn bitfields
*/
/*! @name Register ARMGLOBALTIMER_COUNTERn, field VALUE[31:0] (RW)
*
* 32-bits of the counter value.
*/
//@{
#define BP_ARMGLOBALTIMER_COUNTERn_VALUE (0) //!< Bit position for ARMGLOBALTIMER_COUNTERn_VALUE.
#define BM_ARMGLOBALTIMER_COUNTERn_VALUE (0xffffffff) //!< Bit mask for ARMGLOBALTIMER_COUNTERn_VALUE.
//! @brief Get value of ARMGLOBALTIMER_COUNTERn_VALUE from a register value.
#define BG_ARMGLOBALTIMER_COUNTERn_VALUE(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_ARMGLOBALTIMER_COUNTERn_VALUE) >> BP_ARMGLOBALTIMER_COUNTERn_VALUE)
//! @brief Format value for bitfield ARMGLOBALTIMER_COUNTERn_VALUE.
#define BF_ARMGLOBALTIMER_COUNTERn_VALUE(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_ARMGLOBALTIMER_COUNTERn_VALUE) & BM_ARMGLOBALTIMER_COUNTERn_VALUE)
#ifndef __LANGUAGE_ASM__
//! @brief Set the VALUE field to a new value.
#define BW_ARMGLOBALTIMER_COUNTERn_VALUE(n, v) (HW_ARMGLOBALTIMER_COUNTERn_WR(n, (HW_ARMGLOBALTIMER_COUNTERn_RD(n) & ~BM_ARMGLOBALTIMER_COUNTERn_VALUE) | BF_ARMGLOBALTIMER_COUNTERn_VALUE(v)))
#endif
//@}
//-------------------------------------------------------------------------------------------
// HW_ARMGLOBALTIMER_CONTROL - Global Timer Control Register
//-------------------------------------------------------------------------------------------
#ifndef __LANGUAGE_ASM__
/*!
* @brief HW_ARMGLOBALTIMER_CONTROL - Global Timer Control Register (RW)
*
* Reset value: 0x00000000
*
* Configuration and control of the Global Timer.
*/
typedef union _hw_armglobaltimer_control {
reg32_t U;
struct _hw_armglobaltimer_control_bitfields {
unsigned TIMER_ENABLE : 1; //!< [0] Timer enable.
unsigned COMP_ENABLE : 1; //!< [1] This bit is banked per Cortex-A9 processor.
unsigned IRQ_ENABLE : 1; //!< [2] This bit is banked per Cortex-A9 processor.
unsigned AUTO_INCREMENT : 1; //!< [3] This bit is banked per Cortex-A9 processor.
unsigned RESERVED0 : 4; //!< [7:4] Reserved
unsigned PRESCALER : 8; //!< [15:8] The prescaler modifies the clock period for the decrementing event for the Counter Register.
unsigned RESERVED1 : 16; //!< [31:16] Reserved.
} B;
} hw_armglobaltimer_control_t;
#endif
/*!
* @name Constants and macros for entire ARMGLOBALTIMER_CONTROL register
*/
//@{
#define HW_ARMGLOBALTIMER_CONTROL_ADDR (REGS_ARMGLOBALTIMER_BASE + 0x208)
#ifndef __LANGUAGE_ASM__
#define HW_ARMGLOBALTIMER_CONTROL (*(volatile hw_armglobaltimer_control_t*)HW_ARMGLOBALTIMER_CONTROL_ADDR)
#define HW_ARMGLOBALTIMER_CONTROL_RD() (HW_ARMGLOBALTIMER_CONTROL.U)
#define HW_ARMGLOBALTIMER_CONTROL_WR(v) (HW_ARMGLOBALTIMER_CONTROL.U = (v))
#define HW_ARMGLOBALTIMER_CONTROL_SET(v) (HW_ARMGLOBALTIMER_CONTROL_WR(HW_ARMGLOBALTIMER_CONTROL_RD() | (v)))
#define HW_ARMGLOBALTIMER_CONTROL_CLR(v) (HW_ARMGLOBALTIMER_CONTROL_WR(HW_ARMGLOBALTIMER_CONTROL_RD() & ~(v)))
#define HW_ARMGLOBALTIMER_CONTROL_TOG(v) (HW_ARMGLOBALTIMER_CONTROL_WR(HW_ARMGLOBALTIMER_CONTROL_RD() ^ (v)))
#endif
//@}
/*
* constants & macros for individual ARMGLOBALTIMER_CONTROL bitfields
*/
/*! @name Register ARMGLOBALTIMER_CONTROL, field TIMER_ENABLE[0] (RW)
*
* Timer enable.
*
* Values:
* - DISABLED = 0 - Timer is disabled and the counter does not increment. All registers can still be read and written.
* - ENABLED = 1 - Timer is enabled and the counter increments normally.
*/
//@{
#define BP_ARMGLOBALTIMER_CONTROL_TIMER_ENABLE (0) //!< Bit position for ARMGLOBALTIMER_CONTROL_TIMER_ENABLE.
#define BM_ARMGLOBALTIMER_CONTROL_TIMER_ENABLE (0x00000001) //!< Bit mask for ARMGLOBALTIMER_CONTROL_TIMER_ENABLE.
//! @brief Get value of ARMGLOBALTIMER_CONTROL_TIMER_ENABLE from a register value.
#define BG_ARMGLOBALTIMER_CONTROL_TIMER_ENABLE(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_ARMGLOBALTIMER_CONTROL_TIMER_ENABLE) >> BP_ARMGLOBALTIMER_CONTROL_TIMER_ENABLE)
//! @brief Format value for bitfield ARMGLOBALTIMER_CONTROL_TIMER_ENABLE.
#define BF_ARMGLOBALTIMER_CONTROL_TIMER_ENABLE(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_ARMGLOBALTIMER_CONTROL_TIMER_ENABLE) & BM_ARMGLOBALTIMER_CONTROL_TIMER_ENABLE)
#ifndef __LANGUAGE_ASM__
//! @brief Set the TIMER_ENABLE field to a new value.
#define BW_ARMGLOBALTIMER_CONTROL_TIMER_ENABLE(v) (HW_ARMGLOBALTIMER_CONTROL_WR((HW_ARMGLOBALTIMER_CONTROL_RD() & ~BM_ARMGLOBALTIMER_CONTROL_TIMER_ENABLE) | BF_ARMGLOBALTIMER_CONTROL_TIMER_ENABLE(v)))
#endif
//! @brief Macro to simplify usage of value macros.
#define BF_ARMGLOBALTIMER_CONTROL_TIMER_ENABLE_V(v) BF_ARMGLOBALTIMER_CONTROL_TIMER_ENABLE(BV_ARMGLOBALTIMER_CONTROL_TIMER_ENABLE__##v)
#define BV_ARMGLOBALTIMER_CONTROL_TIMER_ENABLE__DISABLED (0x0) //!< Timer is disabled and the counter does not increment. All registers can still be read and written.
#define BV_ARMGLOBALTIMER_CONTROL_TIMER_ENABLE__ENABLED (0x1) //!< Timer is enabled and the counter increments normally.
//@}
/*! @name Register ARMGLOBALTIMER_CONTROL, field COMP_ENABLE[1] (RW)
*
* This bit is banked per Cortex-A9 processor. If set, it enables the comparison between the 64-bit
* Timer Counter and the related 64-bit Comparator Register. When the Auto-increment and Comp enable
* bits are set, an IRQ is generated every auto-increment register value.
*
* Values:
* - DISABLED = 0 - Comparison is disabled.
* - ENABLED = 1 - Comparison is enabled.
*/
//@{
#define BP_ARMGLOBALTIMER_CONTROL_COMP_ENABLE (1) //!< Bit position for ARMGLOBALTIMER_CONTROL_COMP_ENABLE.
#define BM_ARMGLOBALTIMER_CONTROL_COMP_ENABLE (0x00000002) //!< Bit mask for ARMGLOBALTIMER_CONTROL_COMP_ENABLE.
//! @brief Get value of ARMGLOBALTIMER_CONTROL_COMP_ENABLE from a register value.
#define BG_ARMGLOBALTIMER_CONTROL_COMP_ENABLE(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_ARMGLOBALTIMER_CONTROL_COMP_ENABLE) >> BP_ARMGLOBALTIMER_CONTROL_COMP_ENABLE)
//! @brief Format value for bitfield ARMGLOBALTIMER_CONTROL_COMP_ENABLE.
#define BF_ARMGLOBALTIMER_CONTROL_COMP_ENABLE(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_ARMGLOBALTIMER_CONTROL_COMP_ENABLE) & BM_ARMGLOBALTIMER_CONTROL_COMP_ENABLE)
#ifndef __LANGUAGE_ASM__
//! @brief Set the COMP_ENABLE field to a new value.
#define BW_ARMGLOBALTIMER_CONTROL_COMP_ENABLE(v) (HW_ARMGLOBALTIMER_CONTROL_WR((HW_ARMGLOBALTIMER_CONTROL_RD() & ~BM_ARMGLOBALTIMER_CONTROL_COMP_ENABLE) | BF_ARMGLOBALTIMER_CONTROL_COMP_ENABLE(v)))
#endif
//! @brief Macro to simplify usage of value macros.
#define BF_ARMGLOBALTIMER_CONTROL_COMP_ENABLE_V(v) BF_ARMGLOBALTIMER_CONTROL_COMP_ENABLE(BV_ARMGLOBALTIMER_CONTROL_COMP_ENABLE__##v)
#define BV_ARMGLOBALTIMER_CONTROL_COMP_ENABLE__DISABLED (0x0) //!< Comparison is disabled.
#define BV_ARMGLOBALTIMER_CONTROL_COMP_ENABLE__ENABLED (0x1) //!< Comparison is enabled.
//@}
/*! @name Register ARMGLOBALTIMER_CONTROL, field IRQ_ENABLE[2] (RW)
*
* This bit is banked per Cortex-A9 processor. If set, the interrupt ID 27 is set as pending in the
* Interrupt Distributor when the event flag is set in the Timer Status Register.
*
* Values:
* - DISABLED = 0 - Interrupts are disabled.
* - ENABLED = 1 - Interrupts are enabled.
*/
//@{
#define BP_ARMGLOBALTIMER_CONTROL_IRQ_ENABLE (2) //!< Bit position for ARMGLOBALTIMER_CONTROL_IRQ_ENABLE.
#define BM_ARMGLOBALTIMER_CONTROL_IRQ_ENABLE (0x00000004) //!< Bit mask for ARMGLOBALTIMER_CONTROL_IRQ_ENABLE.
//! @brief Get value of ARMGLOBALTIMER_CONTROL_IRQ_ENABLE from a register value.
#define BG_ARMGLOBALTIMER_CONTROL_IRQ_ENABLE(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_ARMGLOBALTIMER_CONTROL_IRQ_ENABLE) >> BP_ARMGLOBALTIMER_CONTROL_IRQ_ENABLE)
//! @brief Format value for bitfield ARMGLOBALTIMER_CONTROL_IRQ_ENABLE.
#define BF_ARMGLOBALTIMER_CONTROL_IRQ_ENABLE(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_ARMGLOBALTIMER_CONTROL_IRQ_ENABLE) & BM_ARMGLOBALTIMER_CONTROL_IRQ_ENABLE)
#ifndef __LANGUAGE_ASM__
//! @brief Set the IRQ_ENABLE field to a new value.
#define BW_ARMGLOBALTIMER_CONTROL_IRQ_ENABLE(v) (HW_ARMGLOBALTIMER_CONTROL_WR((HW_ARMGLOBALTIMER_CONTROL_RD() & ~BM_ARMGLOBALTIMER_CONTROL_IRQ_ENABLE) | BF_ARMGLOBALTIMER_CONTROL_IRQ_ENABLE(v)))
#endif
//! @brief Macro to simplify usage of value macros.
#define BF_ARMGLOBALTIMER_CONTROL_IRQ_ENABLE_V(v) BF_ARMGLOBALTIMER_CONTROL_IRQ_ENABLE(BV_ARMGLOBALTIMER_CONTROL_IRQ_ENABLE__##v)
#define BV_ARMGLOBALTIMER_CONTROL_IRQ_ENABLE__DISABLED (0x0) //!< Interrupts are disabled.
#define BV_ARMGLOBALTIMER_CONTROL_IRQ_ENABLE__ENABLED (0x1) //!< Interrupts are enabled.
//@}
/*! @name Register ARMGLOBALTIMER_CONTROL, field AUTO_INCREMENT[3] (RW)
*
* This bit is banked per Cortex-A9 processor.
*
* Values:
* - SINGLE_SHOT_MODE = 0 - When the counter reaches the comparator value, sets the event flag. It is the responsibility of
* software to update the comparator value to get more events.
* - AUTO_INCREMENT_MODE = 1 - Each time the counter reaches the comparator value, the comparator register is incremented with the
* auto-increment register, so that more events can be set periodically without any software
* updates.
*/
//@{
#define BP_ARMGLOBALTIMER_CONTROL_AUTO_INCREMENT (3) //!< Bit position for ARMGLOBALTIMER_CONTROL_AUTO_INCREMENT.
#define BM_ARMGLOBALTIMER_CONTROL_AUTO_INCREMENT (0x00000008) //!< Bit mask for ARMGLOBALTIMER_CONTROL_AUTO_INCREMENT.
//! @brief Get value of ARMGLOBALTIMER_CONTROL_AUTO_INCREMENT from a register value.
#define BG_ARMGLOBALTIMER_CONTROL_AUTO_INCREMENT(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_ARMGLOBALTIMER_CONTROL_AUTO_INCREMENT) >> BP_ARMGLOBALTIMER_CONTROL_AUTO_INCREMENT)
//! @brief Format value for bitfield ARMGLOBALTIMER_CONTROL_AUTO_INCREMENT.
#define BF_ARMGLOBALTIMER_CONTROL_AUTO_INCREMENT(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_ARMGLOBALTIMER_CONTROL_AUTO_INCREMENT) & BM_ARMGLOBALTIMER_CONTROL_AUTO_INCREMENT)
#ifndef __LANGUAGE_ASM__
//! @brief Set the AUTO_INCREMENT field to a new value.
#define BW_ARMGLOBALTIMER_CONTROL_AUTO_INCREMENT(v) (HW_ARMGLOBALTIMER_CONTROL_WR((HW_ARMGLOBALTIMER_CONTROL_RD() & ~BM_ARMGLOBALTIMER_CONTROL_AUTO_INCREMENT) | BF_ARMGLOBALTIMER_CONTROL_AUTO_INCREMENT(v)))
#endif
//! @brief Macro to simplify usage of value macros.
#define BF_ARMGLOBALTIMER_CONTROL_AUTO_INCREMENT_V(v) BF_ARMGLOBALTIMER_CONTROL_AUTO_INCREMENT(BV_ARMGLOBALTIMER_CONTROL_AUTO_INCREMENT__##v)
#define BV_ARMGLOBALTIMER_CONTROL_AUTO_INCREMENT__SINGLE_SHOT_MODE (0x0) //!< When the counter reaches the comparator value, sets the event flag. It is the responsibility of software to update the comparator value to get more events.
#define BV_ARMGLOBALTIMER_CONTROL_AUTO_INCREMENT__AUTO_INCREMENT_MODE (0x1) //!< Each time the counter reaches the comparator value, the comparator register is incremented with the auto-increment register, so that more events can be set periodically without any software updates.
//@}
/*! @name Register ARMGLOBALTIMER_CONTROL, field PRESCALER[15:8] (RW)
*
* The prescaler modifies the clock period for the decrementing event for the Counter Register.
*/
//@{
#define BP_ARMGLOBALTIMER_CONTROL_PRESCALER (8) //!< Bit position for ARMGLOBALTIMER_CONTROL_PRESCALER.
#define BM_ARMGLOBALTIMER_CONTROL_PRESCALER (0x0000ff00) //!< Bit mask for ARMGLOBALTIMER_CONTROL_PRESCALER.
//! @brief Get value of ARMGLOBALTIMER_CONTROL_PRESCALER from a register value.
#define BG_ARMGLOBALTIMER_CONTROL_PRESCALER(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_ARMGLOBALTIMER_CONTROL_PRESCALER) >> BP_ARMGLOBALTIMER_CONTROL_PRESCALER)
//! @brief Format value for bitfield ARMGLOBALTIMER_CONTROL_PRESCALER.
#define BF_ARMGLOBALTIMER_CONTROL_PRESCALER(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_ARMGLOBALTIMER_CONTROL_PRESCALER) & BM_ARMGLOBALTIMER_CONTROL_PRESCALER)
#ifndef __LANGUAGE_ASM__
//! @brief Set the PRESCALER field to a new value.
#define BW_ARMGLOBALTIMER_CONTROL_PRESCALER(v) (HW_ARMGLOBALTIMER_CONTROL_WR((HW_ARMGLOBALTIMER_CONTROL_RD() & ~BM_ARMGLOBALTIMER_CONTROL_PRESCALER) | BF_ARMGLOBALTIMER_CONTROL_PRESCALER(v)))
#endif
//@}
//-------------------------------------------------------------------------------------------
// HW_ARMGLOBALTIMER_IRQSTATUS - Global Timer Interrupt Status Register
//-------------------------------------------------------------------------------------------
#ifndef __LANGUAGE_ASM__
/*!
* @brief HW_ARMGLOBALTIMER_IRQSTATUS - Global Timer Interrupt Status Register (RW)
*
* Reset value: 0x00000000
*
* This is a banked register for all Cortex-A9 processors present.
*/
typedef union _hw_armglobaltimer_irqstatus {
reg32_t U;
struct _hw_armglobaltimer_irqstatus_bitfields {
unsigned EVENT_FLAG : 1; //!< [0] The event flag is a sticky bit that is automatically set when the Counter Register reaches the Comparator Register value.
unsigned RESERVED0 : 31; //!< [31:1] Reserved.
} B;
} hw_armglobaltimer_irqstatus_t;
#endif
/*!
* @name Constants and macros for entire ARMGLOBALTIMER_IRQSTATUS register
*/
//@{
#define HW_ARMGLOBALTIMER_IRQSTATUS_ADDR (REGS_ARMGLOBALTIMER_BASE + 0x20c)
#ifndef __LANGUAGE_ASM__
#define HW_ARMGLOBALTIMER_IRQSTATUS (*(volatile hw_armglobaltimer_irqstatus_t*)HW_ARMGLOBALTIMER_IRQSTATUS_ADDR)
#define HW_ARMGLOBALTIMER_IRQSTATUS_RD() (HW_ARMGLOBALTIMER_IRQSTATUS.U)
#define HW_ARMGLOBALTIMER_IRQSTATUS_WR(v) (HW_ARMGLOBALTIMER_IRQSTATUS.U = (v))
#define HW_ARMGLOBALTIMER_IRQSTATUS_SET(v) (HW_ARMGLOBALTIMER_IRQSTATUS_WR(HW_ARMGLOBALTIMER_IRQSTATUS_RD() | (v)))
#define HW_ARMGLOBALTIMER_IRQSTATUS_CLR(v) (HW_ARMGLOBALTIMER_IRQSTATUS_WR(HW_ARMGLOBALTIMER_IRQSTATUS_RD() & ~(v)))
#define HW_ARMGLOBALTIMER_IRQSTATUS_TOG(v) (HW_ARMGLOBALTIMER_IRQSTATUS_WR(HW_ARMGLOBALTIMER_IRQSTATUS_RD() ^ (v)))
#endif
//@}
/*
* constants & macros for individual ARMGLOBALTIMER_IRQSTATUS bitfields
*/
/*! @name Register ARMGLOBALTIMER_IRQSTATUS, field EVENT_FLAG[0] (W1C)
*
* The event flag is a sticky bit that is automatically set when the Counter Register reaches the
* Comparator Register value. If the timer interrupt is enabled, Interrupt ID 27 is set as pending
* in the Interrupt Distributor after the event flag is set. The event flag is cleared when written
* to 1.
*/
//@{
#define BP_ARMGLOBALTIMER_IRQSTATUS_EVENT_FLAG (0) //!< Bit position for ARMGLOBALTIMER_IRQSTATUS_EVENT_FLAG.
#define BM_ARMGLOBALTIMER_IRQSTATUS_EVENT_FLAG (0x00000001) //!< Bit mask for ARMGLOBALTIMER_IRQSTATUS_EVENT_FLAG.
//! @brief Get value of ARMGLOBALTIMER_IRQSTATUS_EVENT_FLAG from a register value.
#define BG_ARMGLOBALTIMER_IRQSTATUS_EVENT_FLAG(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_ARMGLOBALTIMER_IRQSTATUS_EVENT_FLAG) >> BP_ARMGLOBALTIMER_IRQSTATUS_EVENT_FLAG)
//! @brief Format value for bitfield ARMGLOBALTIMER_IRQSTATUS_EVENT_FLAG.
#define BF_ARMGLOBALTIMER_IRQSTATUS_EVENT_FLAG(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_ARMGLOBALTIMER_IRQSTATUS_EVENT_FLAG) & BM_ARMGLOBALTIMER_IRQSTATUS_EVENT_FLAG)
#ifndef __LANGUAGE_ASM__
//! @brief Set the EVENT_FLAG field to a new value.
#define BW_ARMGLOBALTIMER_IRQSTATUS_EVENT_FLAG(v) (HW_ARMGLOBALTIMER_IRQSTATUS_WR((HW_ARMGLOBALTIMER_IRQSTATUS_RD() & ~BM_ARMGLOBALTIMER_IRQSTATUS_EVENT_FLAG) | BF_ARMGLOBALTIMER_IRQSTATUS_EVENT_FLAG(v)))
#endif
//@}
//-------------------------------------------------------------------------------------------
// HW_ARMGLOBALTIMER_COMPARATORn - Global Timer Comparator Value Registers
//-------------------------------------------------------------------------------------------
#ifndef __LANGUAGE_ASM__
/*!
* @brief HW_ARMGLOBALTIMER_COMPARATORn - Global Timer Comparator Value Registers (RW)
*
* Reset value: 0x00000000
*
* There are two timer counter registers. They are the lower 32-bit timer counter at offset 0x00 and
* the upper 32-bit timer counter at offset 0x04.
*/
typedef union _hw_armglobaltimer_comparatorn {
reg32_t U;
struct _hw_armglobaltimer_comparatorn_bitfields {
unsigned VALUE : 32; //!< [31:0] 32-bits of the comparator value.
} B;
} hw_armglobaltimer_comparatorn_t;
#endif
/*!
* @name Constants and macros for entire ARMGLOBALTIMER_COMPARATORn register
*/
//@{
//! @brief Number of instances of the ARMGLOBALTIMER_COMPARATORn register.
#define HW_ARMGLOBALTIMER_COMPARATORn_COUNT (2)
#define HW_ARMGLOBALTIMER_COMPARATORn_ADDR(n) (REGS_ARMGLOBALTIMER_BASE + 0x210 + (0x4 * (n)))
#ifndef __LANGUAGE_ASM__
#define HW_ARMGLOBALTIMER_COMPARATORn(n) (*(volatile hw_armglobaltimer_comparatorn_t*)HW_ARMGLOBALTIMER_COMPARATORn_ADDR(n))
#define HW_ARMGLOBALTIMER_COMPARATORn_RD(n) (HW_ARMGLOBALTIMER_COMPARATORn(n).U)
#define HW_ARMGLOBALTIMER_COMPARATORn_WR(n, v) (HW_ARMGLOBALTIMER_COMPARATORn(n).U = (v))
#define HW_ARMGLOBALTIMER_COMPARATORn_SET(n, v) (HW_ARMGLOBALTIMER_COMPARATORn_WR(n, HW_ARMGLOBALTIMER_COMPARATORn_RD(n) | (v)))
#define HW_ARMGLOBALTIMER_COMPARATORn_CLR(n, v) (HW_ARMGLOBALTIMER_COMPARATORn_WR(n, HW_ARMGLOBALTIMER_COMPARATORn_RD(n) & ~(v)))
#define HW_ARMGLOBALTIMER_COMPARATORn_TOG(n, v) (HW_ARMGLOBALTIMER_COMPARATORn_WR(n, HW_ARMGLOBALTIMER_COMPARATORn_RD(n) ^ (v)))
#endif
//@}
/*
* constants & macros for individual ARMGLOBALTIMER_COMPARATORn bitfields
*/
/*! @name Register ARMGLOBALTIMER_COMPARATORn, field VALUE[31:0] (RW)
*
* 32-bits of the comparator value.
*/
//@{
#define BP_ARMGLOBALTIMER_COMPARATORn_VALUE (0) //!< Bit position for ARMGLOBALTIMER_COMPARATORn_VALUE.
#define BM_ARMGLOBALTIMER_COMPARATORn_VALUE (0xffffffff) //!< Bit mask for ARMGLOBALTIMER_COMPARATORn_VALUE.
//! @brief Get value of ARMGLOBALTIMER_COMPARATORn_VALUE from a register value.
#define BG_ARMGLOBALTIMER_COMPARATORn_VALUE(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_ARMGLOBALTIMER_COMPARATORn_VALUE) >> BP_ARMGLOBALTIMER_COMPARATORn_VALUE)
//! @brief Format value for bitfield ARMGLOBALTIMER_COMPARATORn_VALUE.
#define BF_ARMGLOBALTIMER_COMPARATORn_VALUE(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_ARMGLOBALTIMER_COMPARATORn_VALUE) & BM_ARMGLOBALTIMER_COMPARATORn_VALUE)
#ifndef __LANGUAGE_ASM__
//! @brief Set the VALUE field to a new value.
#define BW_ARMGLOBALTIMER_COMPARATORn_VALUE(n, v) (HW_ARMGLOBALTIMER_COMPARATORn_WR(n, (HW_ARMGLOBALTIMER_COMPARATORn_RD(n) & ~BM_ARMGLOBALTIMER_COMPARATORn_VALUE) | BF_ARMGLOBALTIMER_COMPARATORn_VALUE(v)))
#endif
//@}
//-------------------------------------------------------------------------------------------
// HW_ARMGLOBALTIMER_AUTOINCREMENT - Global Timer Auto-increment Register
//-------------------------------------------------------------------------------------------
#ifndef __LANGUAGE_ASM__
/*!
* @brief HW_ARMGLOBALTIMER_AUTOINCREMENT - Global Timer Auto-increment Register (RW)
*
* Reset value: 0x00000000
*
* This 32-bit register gives the increment value of the Comparator Register when the Auto-increment
* bit is set in the Timer Control Register. Each Cortex-A9 processor present has its own Auto-
* increment Register. If the comp enable and auto-increment bits are set when the global counter
* reaches the Comparator Register value, the comparator is incremented by the auto-increment value,
* so that a new event can be set periodically. The global timer is not affected and goes on
* incrementing.
*/
typedef union _hw_armglobaltimer_autoincrement {
reg32_t U;
struct _hw_armglobaltimer_autoincrement_bitfields {
unsigned VALUE : 32; //!< [31:0] 32-bit auto-increment value.
} B;
} hw_armglobaltimer_autoincrement_t;
#endif
/*!
* @name Constants and macros for entire ARMGLOBALTIMER_AUTOINCREMENT register
*/
//@{
#define HW_ARMGLOBALTIMER_AUTOINCREMENT_ADDR (REGS_ARMGLOBALTIMER_BASE + 0x218)
#ifndef __LANGUAGE_ASM__
#define HW_ARMGLOBALTIMER_AUTOINCREMENT (*(volatile hw_armglobaltimer_autoincrement_t*)HW_ARMGLOBALTIMER_AUTOINCREMENT_ADDR)
#define HW_ARMGLOBALTIMER_AUTOINCREMENT_RD() (HW_ARMGLOBALTIMER_AUTOINCREMENT.U)
#define HW_ARMGLOBALTIMER_AUTOINCREMENT_WR(v) (HW_ARMGLOBALTIMER_AUTOINCREMENT.U = (v))
#define HW_ARMGLOBALTIMER_AUTOINCREMENT_SET(v) (HW_ARMGLOBALTIMER_AUTOINCREMENT_WR(HW_ARMGLOBALTIMER_AUTOINCREMENT_RD() | (v)))
#define HW_ARMGLOBALTIMER_AUTOINCREMENT_CLR(v) (HW_ARMGLOBALTIMER_AUTOINCREMENT_WR(HW_ARMGLOBALTIMER_AUTOINCREMENT_RD() & ~(v)))
#define HW_ARMGLOBALTIMER_AUTOINCREMENT_TOG(v) (HW_ARMGLOBALTIMER_AUTOINCREMENT_WR(HW_ARMGLOBALTIMER_AUTOINCREMENT_RD() ^ (v)))
#endif
//@}
/*
* constants & macros for individual ARMGLOBALTIMER_AUTOINCREMENT bitfields
*/
/*! @name Register ARMGLOBALTIMER_AUTOINCREMENT, field VALUE[31:0] (RW)
*
* 32-bit auto-increment value.
*/
//@{
#define BP_ARMGLOBALTIMER_AUTOINCREMENT_VALUE (0) //!< Bit position for ARMGLOBALTIMER_AUTOINCREMENT_VALUE.
#define BM_ARMGLOBALTIMER_AUTOINCREMENT_VALUE (0xffffffff) //!< Bit mask for ARMGLOBALTIMER_AUTOINCREMENT_VALUE.
//! @brief Get value of ARMGLOBALTIMER_AUTOINCREMENT_VALUE from a register value.
#define BG_ARMGLOBALTIMER_AUTOINCREMENT_VALUE(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_ARMGLOBALTIMER_AUTOINCREMENT_VALUE) >> BP_ARMGLOBALTIMER_AUTOINCREMENT_VALUE)
//! @brief Format value for bitfield ARMGLOBALTIMER_AUTOINCREMENT_VALUE.
#define BF_ARMGLOBALTIMER_AUTOINCREMENT_VALUE(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_ARMGLOBALTIMER_AUTOINCREMENT_VALUE) & BM_ARMGLOBALTIMER_AUTOINCREMENT_VALUE)
#ifndef __LANGUAGE_ASM__
//! @brief Set the VALUE field to a new value.
#define BW_ARMGLOBALTIMER_AUTOINCREMENT_VALUE(v) (HW_ARMGLOBALTIMER_AUTOINCREMENT_WR((HW_ARMGLOBALTIMER_AUTOINCREMENT_RD() & ~BM_ARMGLOBALTIMER_AUTOINCREMENT_VALUE) | BF_ARMGLOBALTIMER_AUTOINCREMENT_VALUE(v)))
#endif
//@}
//-------------------------------------------------------------------------------------------
// hw_armglobaltimer_t - module struct
//-------------------------------------------------------------------------------------------
/*!
* @brief All ARMGLOBALTIMER module registers.
*/
#ifndef __LANGUAGE_ASM__
#pragma pack(1)
typedef struct _hw_armglobaltimer {
reg32_t _reserved0[128];
volatile hw_armglobaltimer_countern_t COUNTERn[2]; //!< Global Timer Counter Registers
volatile hw_armglobaltimer_control_t CONTROL; //!< Global Timer Control Register
volatile hw_armglobaltimer_irqstatus_t IRQSTATUS; //!< Global Timer Interrupt Status Register
volatile hw_armglobaltimer_comparatorn_t COMPARATORn[2]; //!< Global Timer Comparator Value Registers
volatile hw_armglobaltimer_autoincrement_t AUTOINCREMENT; //!< Global Timer Auto-increment Register
} hw_armglobaltimer_t;
#pragma pack()
//! @brief Macro to access all ARMGLOBALTIMER registers.
//! @return Reference (not a pointer) to the registers struct. To get a pointer to the struct,
//! use the '&' operator, like <code>&HW_ARMGLOBALTIMER</code>.
#define HW_ARMGLOBALTIMER (*(hw_armglobaltimer_t*)REGS_ARMGLOBALTIMER_BASE)
#endif
#endif // __HW_ARMGLOBALTIMER_REGISTERS_H__
// v18/121106/1.2.2
// EOF

View File

@ -0,0 +1,710 @@
/*
* Copyright (c) 2012, Freescale Semiconductor, Inc.
* All rights reserved.
*
* THIS SOFTWARE IS PROVIDED BY FREESCALE "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 FREESCALE 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.
*/
/*
* WARNING! DO NOT EDIT THIS FILE DIRECTLY!
*
* This file was generated automatically and any changes may be lost.
*/
#ifndef __HW_EPIT_REGISTERS_H__
#define __HW_EPIT_REGISTERS_H__
#include "regs.h"
#include "soc_memory_map.h"
/*
* i.MX6SL EPIT
*
* EPIT
*
* Registers defined in this header file:
* - HW_EPIT_CR - Control register
* - HW_EPIT_SR - Status register
* - HW_EPIT_LR - Load register
* - HW_EPIT_CMPR - Compare register
* - HW_EPIT_CNR - Counter register
*
* - hw_epit_t - Struct containing all module registers.
*/
//! @name Module base addresses
//@{
#ifndef REGS_EPIT_BASE
#define HW_EPIT_INSTANCE_COUNT (2) //!< Number of instances of the EPIT module.
#define HW_EPIT1 (1) //!< Instance number for EPIT1.
#define HW_EPIT2 (2) //!< Instance number for EPIT2.
#define REGS_EPIT1_BASE USERLAND_MMIO_P2V(0x020d0000) //!< Base address for EPIT instance number 1.
#define REGS_EPIT2_BASE USERLAND_MMIO_P2V(0x020d4000) //!< Base address for EPIT instance number 2.
//! @brief Get the base address of EPIT by instance number.
//! @param x EPIT instance number, from 1 through 2.
#define REGS_EPIT_BASE(x) ((x) == HW_EPIT1 ? REGS_EPIT1_BASE : (x) == HW_EPIT2 ? REGS_EPIT2_BASE \
: 0x00d00000)
//! @brief Get the instance number given a base address.
//! @param b Base address for an instance of EPIT.
#define REGS_EPIT_INSTANCE(b) ((b) == REGS_EPIT1_BASE ? HW_EPIT1 : (b) == REGS_EPIT2_BASE ? HW_EPIT2 \
: 0)
#endif
//@}
//-------------------------------------------------------------------------------------------
// HW_EPIT_CR - Control register
//-------------------------------------------------------------------------------------------
#ifndef __LANGUAGE_ASM__
/*!
* @brief HW_EPIT_CR - Control register (RW)
*
* Reset value: 0x00000000
*
* The EPIT control register (EPIT_CR) is used to configure the operating settings of the EPIT. It
* contains the clock division prescaler value and also the interrupt enable bit. Additionally, it
* contains other control bits which are described below. Peripheral Bus Write access to EPIT
* Control Register (EPIT_CR) results in one cycle of the wait state, while other valid peripheral
* bus accesses are with 0 wait state.
*/
typedef union _hw_epit_cr {
reg32_t U;
struct _hw_epit_cr_bitfields {
unsigned EN : 1; //!< [0] This bit enables the EPIT.
unsigned ENMOD : 1; //!< [1] EPIT enable mode.
unsigned OCIEN : 1; //!< [2] Output compare interrupt enable.
unsigned RLD : 1; //!< [3] Counter reload control.
unsigned PRESCALAR : 12; //!< [15:4] Counter clock prescaler value.
unsigned SWR : 1; //!< [16] Software reset.
unsigned IOVW : 1; //!< [17] EPIT counter overwrite enable.
unsigned DBGEN : 1; //!< [18] This bit is used to keep the EPIT functional in debug mode.
unsigned WAITEN : 1; //!< [19] This read/write control bit enables the operation of the EPIT during wait mode.
unsigned RESERVED0 : 1; //!< [20] Reserved.
unsigned STOPEN : 1; //!< [21] EPIT stop mode enable.
unsigned OM : 2; //!< [23:22] EPIT output mode.This bit field determines the mode of EPIT output on the output pin.
unsigned CLKSRC : 2; //!< [25:24] Select clock source
unsigned RESERVED1 : 6; //!< [31:26] Reserved.
} B;
} hw_epit_cr_t;
#endif
/*!
* @name Constants and macros for entire EPIT_CR register
*/
//@{
#define HW_EPIT_CR_ADDR(x) (REGS_EPIT_BASE(x) + 0x0)
#ifndef __LANGUAGE_ASM__
#define HW_EPIT_CR(x) (*(volatile hw_epit_cr_t*)HW_EPIT_CR_ADDR(x))
#define HW_EPIT_CR_RD(x) (HW_EPIT_CR(x).U)
#define HW_EPIT_CR_WR(x, v) (HW_EPIT_CR(x).U = (v))
#define HW_EPIT_CR_SET(x, v) (HW_EPIT_CR_WR(x, HW_EPIT_CR_RD(x) | (v)))
#define HW_EPIT_CR_CLR(x, v) (HW_EPIT_CR_WR(x, HW_EPIT_CR_RD(x) & ~(v)))
#define HW_EPIT_CR_TOG(x, v) (HW_EPIT_CR_WR(x, HW_EPIT_CR_RD(x) ^ (v)))
#endif
//@}
/*
* constants & macros for individual EPIT_CR bitfields
*/
/*! @name Register EPIT_CR, field EN[0] (RW)
*
* This bit enables the EPIT. EPIT counter and prescaler value when EPIT is enabled (EN = 1), is
* dependent upon ENMOD and RLD bit as described for ENMOD bit. It is recommended that all registers
* be properly programmed before setting this bit. This bit is reset by a hardware reset. A software
* reset does not affect this bit.
*
* Values:
* - 0 - EPIT is disabled
* - 1 - EPIT is enabled
*/
//@{
#define BP_EPIT_CR_EN (0) //!< Bit position for EPIT_CR_EN.
#define BM_EPIT_CR_EN (0x00000001) //!< Bit mask for EPIT_CR_EN.
//! @brief Get value of EPIT_CR_EN from a register value.
#define BG_EPIT_CR_EN(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CR_EN) >> BP_EPIT_CR_EN)
//! @brief Format value for bitfield EPIT_CR_EN.
#define BF_EPIT_CR_EN(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CR_EN) & BM_EPIT_CR_EN)
#ifndef __LANGUAGE_ASM__
//! @brief Set the EN field to a new value.
#define BW_EPIT_CR_EN(x, v) (HW_EPIT_CR_WR(x, (HW_EPIT_CR_RD(x) & ~BM_EPIT_CR_EN) | BF_EPIT_CR_EN(v)))
#endif
//@}
/*! @name Register EPIT_CR, field ENMOD[1] (RW)
*
* EPIT enable mode. When EPIT is disabled (EN=0), both main counter and prescaler counter freeze
* their count at current count values. ENMOD bit is a r/w bit that determines the counter value
* when the EPIT is enabled again by setting EN bit. If ENMOD bit is set, then main counter is
* loaded with the load value (If RLD=1)/ 0xFFFF_FFFF (If RLD=0) and prescaler counter is reset,
* when EPIT is enabled (EN=1). If ENMOD is programmed to 0 then both main counter and prescaler
* counter restart counting from their frozen values when EPIT is enabled (EN=1). If EPIT is
* programmed to be disabled in a low-power mode (STOP/WAIT/DEBUG), then both the main counter and
* the prescaler counter freeze at their current count values when EPIT enters low-power mode. When
* EPIT exits the low-power mode, both main counter and prescaler counter start counting from their
* frozen values irrespective of the ENMOD bit. This bit is reset by a hardware reset. A software
* reset does not affect this bit.
*
* Values:
* - 0 - Counter starts counting from the value it had when it was disabled.
* - 1 - Counter starts count from load value (RLD=1) or 0xFFFF_FFFF (If RLD=0)
*/
//@{
#define BP_EPIT_CR_ENMOD (1) //!< Bit position for EPIT_CR_ENMOD.
#define BM_EPIT_CR_ENMOD (0x00000002) //!< Bit mask for EPIT_CR_ENMOD.
//! @brief Get value of EPIT_CR_ENMOD from a register value.
#define BG_EPIT_CR_ENMOD(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CR_ENMOD) >> BP_EPIT_CR_ENMOD)
//! @brief Format value for bitfield EPIT_CR_ENMOD.
#define BF_EPIT_CR_ENMOD(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CR_ENMOD) & BM_EPIT_CR_ENMOD)
#ifndef __LANGUAGE_ASM__
//! @brief Set the ENMOD field to a new value.
#define BW_EPIT_CR_ENMOD(x, v) (HW_EPIT_CR_WR(x, (HW_EPIT_CR_RD(x) & ~BM_EPIT_CR_ENMOD) | BF_EPIT_CR_ENMOD(v)))
#endif
//@}
/*! @name Register EPIT_CR, field OCIEN[2] (RW)
*
* Output compare interrupt enable. This bit enables the generation of interrupt on occurrence of
* compare event.
*
* Values:
* - 0 - Compare interrupt disabled
* - 1 - Compare interrupt enabled
*/
//@{
#define BP_EPIT_CR_OCIEN (2) //!< Bit position for EPIT_CR_OCIEN.
#define BM_EPIT_CR_OCIEN (0x00000004) //!< Bit mask for EPIT_CR_OCIEN.
//! @brief Get value of EPIT_CR_OCIEN from a register value.
#define BG_EPIT_CR_OCIEN(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CR_OCIEN) >> BP_EPIT_CR_OCIEN)
//! @brief Format value for bitfield EPIT_CR_OCIEN.
#define BF_EPIT_CR_OCIEN(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CR_OCIEN) & BM_EPIT_CR_OCIEN)
#ifndef __LANGUAGE_ASM__
//! @brief Set the OCIEN field to a new value.
#define BW_EPIT_CR_OCIEN(x, v) (HW_EPIT_CR_WR(x, (HW_EPIT_CR_RD(x) & ~BM_EPIT_CR_OCIEN) | BF_EPIT_CR_OCIEN(v)))
#endif
//@}
/*! @name Register EPIT_CR, field RLD[3] (RW)
*
* Counter reload control. This bit is cleared by hardware reset. It decides the counter
* functionality, whether to run in free-running mode or set-and-forget mode.
*
* Values:
* - 0 - When the counter reaches zero it rolls over to 0xFFFF_FFFF (free-running mode)
* - 1 - When the counter reaches zero it reloads from the modulus register (set-and-forget mode)
*/
//@{
#define BP_EPIT_CR_RLD (3) //!< Bit position for EPIT_CR_RLD.
#define BM_EPIT_CR_RLD (0x00000008) //!< Bit mask for EPIT_CR_RLD.
//! @brief Get value of EPIT_CR_RLD from a register value.
#define BG_EPIT_CR_RLD(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CR_RLD) >> BP_EPIT_CR_RLD)
//! @brief Format value for bitfield EPIT_CR_RLD.
#define BF_EPIT_CR_RLD(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CR_RLD) & BM_EPIT_CR_RLD)
#ifndef __LANGUAGE_ASM__
//! @brief Set the RLD field to a new value.
#define BW_EPIT_CR_RLD(x, v) (HW_EPIT_CR_WR(x, (HW_EPIT_CR_RD(x) & ~BM_EPIT_CR_RLD) | BF_EPIT_CR_RLD(v)))
#endif
//@}
/*! @name Register EPIT_CR, field PRESCALAR[15:4] (RW)
*
* Counter clock prescaler value. This bit field determines the prescaler value by which the clock
* is divided before it goes to the counter
*
* Values:
* - 0x000 - Divide by 1
* - 0x001 - Divide by 2...
* - 0xFFF - Divide by 4096
*/
//@{
#define BP_EPIT_CR_PRESCALAR (4) //!< Bit position for EPIT_CR_PRESCALAR.
#define BM_EPIT_CR_PRESCALAR (0x0000fff0) //!< Bit mask for EPIT_CR_PRESCALAR.
//! @brief Get value of EPIT_CR_PRESCALAR from a register value.
#define BG_EPIT_CR_PRESCALAR(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CR_PRESCALAR) >> BP_EPIT_CR_PRESCALAR)
//! @brief Format value for bitfield EPIT_CR_PRESCALAR.
#define BF_EPIT_CR_PRESCALAR(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CR_PRESCALAR) & BM_EPIT_CR_PRESCALAR)
#ifndef __LANGUAGE_ASM__
//! @brief Set the PRESCALAR field to a new value.
#define BW_EPIT_CR_PRESCALAR(x, v) (HW_EPIT_CR_WR(x, (HW_EPIT_CR_RD(x) & ~BM_EPIT_CR_PRESCALAR) | BF_EPIT_CR_PRESCALAR(v)))
#endif
//@}
/*! @name Register EPIT_CR, field SWR[16] (RW)
*
* Software reset. The EPIT is reset when this bit is set to 1. It is a self clearing bit. This bit
* is set when the block is in reset state and is cleared when the reset procedure is over. Setting
* this bit resets all the registers to their reset values, except for the EN, ENMOD, STOPEN, WAITEN
* and DBGEN bits in this control register
*
* Values:
* - 0 - EPIT is out of reset
* - 1 - EPIT is undergoing reset
*/
//@{
#define BP_EPIT_CR_SWR (16) //!< Bit position for EPIT_CR_SWR.
#define BM_EPIT_CR_SWR (0x00010000) //!< Bit mask for EPIT_CR_SWR.
//! @brief Get value of EPIT_CR_SWR from a register value.
#define BG_EPIT_CR_SWR(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CR_SWR) >> BP_EPIT_CR_SWR)
//! @brief Format value for bitfield EPIT_CR_SWR.
#define BF_EPIT_CR_SWR(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CR_SWR) & BM_EPIT_CR_SWR)
#ifndef __LANGUAGE_ASM__
//! @brief Set the SWR field to a new value.
#define BW_EPIT_CR_SWR(x, v) (HW_EPIT_CR_WR(x, (HW_EPIT_CR_RD(x) & ~BM_EPIT_CR_SWR) | BF_EPIT_CR_SWR(v)))
#endif
//@}
/*! @name Register EPIT_CR, field IOVW[17] (RW)
*
* EPIT counter overwrite enable. This bit controls the counter data when the modulus register is
* written. When this bit is set, all writes to the load register overwrites the counter contents
* and the counter starts subsequently counting down from the programmed value.
*
* Values:
* - 0 - Write to load register does not result in counter value being overwritten.
* - 1 - Write to load register results in immediate overwriting of counter value.
*/
//@{
#define BP_EPIT_CR_IOVW (17) //!< Bit position for EPIT_CR_IOVW.
#define BM_EPIT_CR_IOVW (0x00020000) //!< Bit mask for EPIT_CR_IOVW.
//! @brief Get value of EPIT_CR_IOVW from a register value.
#define BG_EPIT_CR_IOVW(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CR_IOVW) >> BP_EPIT_CR_IOVW)
//! @brief Format value for bitfield EPIT_CR_IOVW.
#define BF_EPIT_CR_IOVW(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CR_IOVW) & BM_EPIT_CR_IOVW)
#ifndef __LANGUAGE_ASM__
//! @brief Set the IOVW field to a new value.
#define BW_EPIT_CR_IOVW(x, v) (HW_EPIT_CR_WR(x, (HW_EPIT_CR_RD(x) & ~BM_EPIT_CR_IOVW) | BF_EPIT_CR_IOVW(v)))
#endif
//@}
/*! @name Register EPIT_CR, field DBGEN[18] (RW)
*
* This bit is used to keep the EPIT functional in debug mode. When this bit is cleared, the input
* clock is gated off in debug mode.This bit is reset by hardware reset. A software reset does not
* affect this bit.
*
* Values:
* - 0 - Inactive in debug mode
* - 1 - Active in debug mode
*/
//@{
#define BP_EPIT_CR_DBGEN (18) //!< Bit position for EPIT_CR_DBGEN.
#define BM_EPIT_CR_DBGEN (0x00040000) //!< Bit mask for EPIT_CR_DBGEN.
//! @brief Get value of EPIT_CR_DBGEN from a register value.
#define BG_EPIT_CR_DBGEN(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CR_DBGEN) >> BP_EPIT_CR_DBGEN)
//! @brief Format value for bitfield EPIT_CR_DBGEN.
#define BF_EPIT_CR_DBGEN(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CR_DBGEN) & BM_EPIT_CR_DBGEN)
#ifndef __LANGUAGE_ASM__
//! @brief Set the DBGEN field to a new value.
#define BW_EPIT_CR_DBGEN(x, v) (HW_EPIT_CR_WR(x, (HW_EPIT_CR_RD(x) & ~BM_EPIT_CR_DBGEN) | BF_EPIT_CR_DBGEN(v)))
#endif
//@}
/*! @name Register EPIT_CR, field WAITEN[19] (RW)
*
* This read/write control bit enables the operation of the EPIT during wait mode. This bit is reset
* by a hardware reset. A software reset does not affect this bit.
*
* Values:
* - 0 - EPIT is disabled in wait mode
* - 1 - EPIT is enabled in wait mode
*/
//@{
#define BP_EPIT_CR_WAITEN (19) //!< Bit position for EPIT_CR_WAITEN.
#define BM_EPIT_CR_WAITEN (0x00080000) //!< Bit mask for EPIT_CR_WAITEN.
//! @brief Get value of EPIT_CR_WAITEN from a register value.
#define BG_EPIT_CR_WAITEN(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CR_WAITEN) >> BP_EPIT_CR_WAITEN)
//! @brief Format value for bitfield EPIT_CR_WAITEN.
#define BF_EPIT_CR_WAITEN(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CR_WAITEN) & BM_EPIT_CR_WAITEN)
#ifndef __LANGUAGE_ASM__
//! @brief Set the WAITEN field to a new value.
#define BW_EPIT_CR_WAITEN(x, v) (HW_EPIT_CR_WR(x, (HW_EPIT_CR_RD(x) & ~BM_EPIT_CR_WAITEN) | BF_EPIT_CR_WAITEN(v)))
#endif
//@}
/*! @name Register EPIT_CR, field STOPEN[21] (RW)
*
* EPIT stop mode enable. This read/write control bit enables the operation of the EPIT during stop
* mode. This bit is reset by a hardware reset and unaffected by software reset.
*
* Values:
* - 0 - EPIT is disabled in stop mode
* - 1 - EPIT is enabled in stop mode
*/
//@{
#define BP_EPIT_CR_STOPEN (21) //!< Bit position for EPIT_CR_STOPEN.
#define BM_EPIT_CR_STOPEN (0x00200000) //!< Bit mask for EPIT_CR_STOPEN.
//! @brief Get value of EPIT_CR_STOPEN from a register value.
#define BG_EPIT_CR_STOPEN(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CR_STOPEN) >> BP_EPIT_CR_STOPEN)
//! @brief Format value for bitfield EPIT_CR_STOPEN.
#define BF_EPIT_CR_STOPEN(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CR_STOPEN) & BM_EPIT_CR_STOPEN)
#ifndef __LANGUAGE_ASM__
//! @brief Set the STOPEN field to a new value.
#define BW_EPIT_CR_STOPEN(x, v) (HW_EPIT_CR_WR(x, (HW_EPIT_CR_RD(x) & ~BM_EPIT_CR_STOPEN) | BF_EPIT_CR_STOPEN(v)))
#endif
//@}
/*! @name Register EPIT_CR, field OM[23:22] (RW)
*
* EPIT output mode.This bit field determines the mode of EPIT output on the output pin.
*
* Values:
* - 00 - EPIT output is disconnected from pad
* - 01 - Toggle output pin
* - 10 - Clear output pin
* - 11 - Set output pin
*/
//@{
#define BP_EPIT_CR_OM (22) //!< Bit position for EPIT_CR_OM.
#define BM_EPIT_CR_OM (0x00c00000) //!< Bit mask for EPIT_CR_OM.
//! @brief Get value of EPIT_CR_OM from a register value.
#define BG_EPIT_CR_OM(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CR_OM) >> BP_EPIT_CR_OM)
//! @brief Format value for bitfield EPIT_CR_OM.
#define BF_EPIT_CR_OM(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CR_OM) & BM_EPIT_CR_OM)
#ifndef __LANGUAGE_ASM__
//! @brief Set the OM field to a new value.
#define BW_EPIT_CR_OM(x, v) (HW_EPIT_CR_WR(x, (HW_EPIT_CR_RD(x) & ~BM_EPIT_CR_OM) | BF_EPIT_CR_OM(v)))
#endif
//@}
/*! @name Register EPIT_CR, field CLKSRC[25:24] (RW)
*
* Select clock source These bits determine which clock input is to be selected for running the
* counter. This field value should only be changed when the EPIT is disabled by clearing the EN bit
* in this register. For other programming requirements while changing clock source, refer to .
*
* Values:
* - 00 - Clock is off
* - 01 - Peripheral clock
* - 10 - High-frequency reference clock
* - 11 - Low-frequency reference clock
*/
//@{
#define BP_EPIT_CR_CLKSRC (24) //!< Bit position for EPIT_CR_CLKSRC.
#define BM_EPIT_CR_CLKSRC (0x03000000) //!< Bit mask for EPIT_CR_CLKSRC.
//! @brief Get value of EPIT_CR_CLKSRC from a register value.
#define BG_EPIT_CR_CLKSRC(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CR_CLKSRC) >> BP_EPIT_CR_CLKSRC)
//! @brief Format value for bitfield EPIT_CR_CLKSRC.
#define BF_EPIT_CR_CLKSRC(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CR_CLKSRC) & BM_EPIT_CR_CLKSRC)
#ifndef __LANGUAGE_ASM__
//! @brief Set the CLKSRC field to a new value.
#define BW_EPIT_CR_CLKSRC(x, v) (HW_EPIT_CR_WR(x, (HW_EPIT_CR_RD(x) & ~BM_EPIT_CR_CLKSRC) | BF_EPIT_CR_CLKSRC(v)))
#endif
//@}
//-------------------------------------------------------------------------------------------
// HW_EPIT_SR - Status register
//-------------------------------------------------------------------------------------------
#ifndef __LANGUAGE_ASM__
/*!
* @brief HW_EPIT_SR - Status register (RW)
*
* Reset value: 0x00000000
*
* The EPIT status register (EPIT_SR) has a single status bit for the output compare event. The bit
* is a write 1 to clear bit.
*/
typedef union _hw_epit_sr {
reg32_t U;
struct _hw_epit_sr_bitfields {
unsigned OCIF : 1; //!< [0] Output compare interrupt flag.
unsigned RESERVED0 : 31; //!< [31:1] Reserved.
} B;
} hw_epit_sr_t;
#endif
/*!
* @name Constants and macros for entire EPIT_SR register
*/
//@{
#define HW_EPIT_SR_ADDR(x) (REGS_EPIT_BASE(x) + 0x4)
#ifndef __LANGUAGE_ASM__
#define HW_EPIT_SR(x) (*(volatile hw_epit_sr_t*)HW_EPIT_SR_ADDR(x))
#define HW_EPIT_SR_RD(x) (HW_EPIT_SR(x).U)
#define HW_EPIT_SR_WR(x, v) (HW_EPIT_SR(x).U = (v))
#define HW_EPIT_SR_SET(x, v) (HW_EPIT_SR_WR(x, HW_EPIT_SR_RD(x) | (v)))
#define HW_EPIT_SR_CLR(x, v) (HW_EPIT_SR_WR(x, HW_EPIT_SR_RD(x) & ~(v)))
#define HW_EPIT_SR_TOG(x, v) (HW_EPIT_SR_WR(x, HW_EPIT_SR_RD(x) ^ (v)))
#endif
//@}
/*
* constants & macros for individual EPIT_SR bitfields
*/
/*! @name Register EPIT_SR, field OCIF[0] (W1C)
*
* Output compare interrupt flag. This bit is the interrupt flag that is set when the content of
* counter equals the content of the compare register (EPIT_CMPR). The bit is a write 1 to clear
* bit.
*
* Values:
* - 0 - Compare event has not occurred
* - 1 - Compare event occurred
*/
//@{
#define BP_EPIT_SR_OCIF (0) //!< Bit position for EPIT_SR_OCIF.
#define BM_EPIT_SR_OCIF (0x00000001) //!< Bit mask for EPIT_SR_OCIF.
//! @brief Get value of EPIT_SR_OCIF from a register value.
#define BG_EPIT_SR_OCIF(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_SR_OCIF) >> BP_EPIT_SR_OCIF)
//! @brief Format value for bitfield EPIT_SR_OCIF.
#define BF_EPIT_SR_OCIF(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_SR_OCIF) & BM_EPIT_SR_OCIF)
#ifndef __LANGUAGE_ASM__
//! @brief Set the OCIF field to a new value.
#define BW_EPIT_SR_OCIF(x, v) (HW_EPIT_SR_WR(x, (HW_EPIT_SR_RD(x) & ~BM_EPIT_SR_OCIF) | BF_EPIT_SR_OCIF(v)))
#endif
//@}
//-------------------------------------------------------------------------------------------
// HW_EPIT_LR - Load register
//-------------------------------------------------------------------------------------------
#ifndef __LANGUAGE_ASM__
/*!
* @brief HW_EPIT_LR - Load register (RW)
*
* Reset value: 0xffffffff
*
* The EPIT load register (EPIT_LR) contains the value that is to be loaded into the counter when
* EPIT counter reaches zero if the RLD bit in EPIT_CR is set. If the IOVW bit in the EPIT_CR is set
* then a write to this register overwrites the value of the EPIT counter register in addition to
* updating this registers value. This overwrite feature is active even if the RLD bit is not set.
*/
typedef union _hw_epit_lr {
reg32_t U;
struct _hw_epit_lr_bitfields {
unsigned LOAD : 32; //!< [31:0] Load value.
} B;
} hw_epit_lr_t;
#endif
/*!
* @name Constants and macros for entire EPIT_LR register
*/
//@{
#define HW_EPIT_LR_ADDR(x) (REGS_EPIT_BASE(x) + 0x8)
#ifndef __LANGUAGE_ASM__
#define HW_EPIT_LR(x) (*(volatile hw_epit_lr_t*)HW_EPIT_LR_ADDR(x))
#define HW_EPIT_LR_RD(x) (HW_EPIT_LR(x).U)
#define HW_EPIT_LR_WR(x, v) (HW_EPIT_LR(x).U = (v))
#define HW_EPIT_LR_SET(x, v) (HW_EPIT_LR_WR(x, HW_EPIT_LR_RD(x) | (v)))
#define HW_EPIT_LR_CLR(x, v) (HW_EPIT_LR_WR(x, HW_EPIT_LR_RD(x) & ~(v)))
#define HW_EPIT_LR_TOG(x, v) (HW_EPIT_LR_WR(x, HW_EPIT_LR_RD(x) ^ (v)))
#endif
//@}
/*
* constants & macros for individual EPIT_LR bitfields
*/
/*! @name Register EPIT_LR, field LOAD[31:0] (RW)
*
* Load value. Value that is loaded into the counter at the start of each count cycle.
*/
//@{
#define BP_EPIT_LR_LOAD (0) //!< Bit position for EPIT_LR_LOAD.
#define BM_EPIT_LR_LOAD (0xffffffff) //!< Bit mask for EPIT_LR_LOAD.
//! @brief Get value of EPIT_LR_LOAD from a register value.
#define BG_EPIT_LR_LOAD(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_LR_LOAD) >> BP_EPIT_LR_LOAD)
//! @brief Format value for bitfield EPIT_LR_LOAD.
#define BF_EPIT_LR_LOAD(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_LR_LOAD) & BM_EPIT_LR_LOAD)
#ifndef __LANGUAGE_ASM__
//! @brief Set the LOAD field to a new value.
#define BW_EPIT_LR_LOAD(x, v) (HW_EPIT_LR_WR(x, (HW_EPIT_LR_RD(x) & ~BM_EPIT_LR_LOAD) | BF_EPIT_LR_LOAD(v)))
#endif
//@}
//-------------------------------------------------------------------------------------------
// HW_EPIT_CMPR - Compare register
//-------------------------------------------------------------------------------------------
#ifndef __LANGUAGE_ASM__
/*!
* @brief HW_EPIT_CMPR - Compare register (RW)
*
* Reset value: 0x00000000
*
* The EPIT compare register (EPIT_CMPR) holds the value that determines when a compare event is
* generated.
*/
typedef union _hw_epit_cmpr {
reg32_t U;
struct _hw_epit_cmpr_bitfields {
unsigned COMPARE : 32; //!< [31:0] Compare Value.
} B;
} hw_epit_cmpr_t;
#endif
/*!
* @name Constants and macros for entire EPIT_CMPR register
*/
//@{
#define HW_EPIT_CMPR_ADDR(x) (REGS_EPIT_BASE(x) + 0xc)
#ifndef __LANGUAGE_ASM__
#define HW_EPIT_CMPR(x) (*(volatile hw_epit_cmpr_t*)HW_EPIT_CMPR_ADDR(x))
#define HW_EPIT_CMPR_RD(x) (HW_EPIT_CMPR(x).U)
#define HW_EPIT_CMPR_WR(x, v) (HW_EPIT_CMPR(x).U = (v))
#define HW_EPIT_CMPR_SET(x, v) (HW_EPIT_CMPR_WR(x, HW_EPIT_CMPR_RD(x) | (v)))
#define HW_EPIT_CMPR_CLR(x, v) (HW_EPIT_CMPR_WR(x, HW_EPIT_CMPR_RD(x) & ~(v)))
#define HW_EPIT_CMPR_TOG(x, v) (HW_EPIT_CMPR_WR(x, HW_EPIT_CMPR_RD(x) ^ (v)))
#endif
//@}
/*
* constants & macros for individual EPIT_CMPR bitfields
*/
/*! @name Register EPIT_CMPR, field COMPARE[31:0] (RW)
*
* Compare Value. When the counter value equals this bit field value a compare event is generated.
*/
//@{
#define BP_EPIT_CMPR_COMPARE (0) //!< Bit position for EPIT_CMPR_COMPARE.
#define BM_EPIT_CMPR_COMPARE (0xffffffff) //!< Bit mask for EPIT_CMPR_COMPARE.
//! @brief Get value of EPIT_CMPR_COMPARE from a register value.
#define BG_EPIT_CMPR_COMPARE(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CMPR_COMPARE) >> BP_EPIT_CMPR_COMPARE)
//! @brief Format value for bitfield EPIT_CMPR_COMPARE.
#define BF_EPIT_CMPR_COMPARE(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_EPIT_CMPR_COMPARE) & BM_EPIT_CMPR_COMPARE)
#ifndef __LANGUAGE_ASM__
//! @brief Set the COMPARE field to a new value.
#define BW_EPIT_CMPR_COMPARE(x, v) (HW_EPIT_CMPR_WR(x, (HW_EPIT_CMPR_RD(x) & ~BM_EPIT_CMPR_COMPARE) | BF_EPIT_CMPR_COMPARE(v)))
#endif
//@}
//-------------------------------------------------------------------------------------------
// HW_EPIT_CNR - Counter register
//-------------------------------------------------------------------------------------------
#ifndef __LANGUAGE_ASM__
/*!
* @brief HW_EPIT_CNR - Counter register (RO)
*
* Reset value: 0xffffffff
*
* The EPIT counter register (EPIT_CNR) contains the current count value and can be read at any time
* without disturbing the counter. This is a read-only register and any attempt to write into it
* generates a transfer error. But if the IOVW bit in EPIT_CR is set, the value of this register can
* be overwritten with a write to EPIT_LR. This change is reflected when this register is
* subsequently read.
*/
typedef union _hw_epit_cnr {
reg32_t U;
struct _hw_epit_cnr_bitfields {
unsigned COUNT : 32; //!< [31:0] Counter value.
} B;
} hw_epit_cnr_t;
#endif
/*!
* @name Constants and macros for entire EPIT_CNR register
*/
//@{
#define HW_EPIT_CNR_ADDR(x) (REGS_EPIT_BASE(x) + 0x10)
#ifndef __LANGUAGE_ASM__
#define HW_EPIT_CNR(x) (*(volatile hw_epit_cnr_t*)HW_EPIT_CNR_ADDR(x))
#define HW_EPIT_CNR_RD(x) (HW_EPIT_CNR(x).U)
#endif
//@}
/*
* constants & macros for individual EPIT_CNR bitfields
*/
/*! @name Register EPIT_CNR, field COUNT[31:0] (RO)
*
* Counter value. This contains the current value of the counter.
*/
//@{
#define BP_EPIT_CNR_COUNT (0) //!< Bit position for EPIT_CNR_COUNT.
#define BM_EPIT_CNR_COUNT (0xffffffff) //!< Bit mask for EPIT_CNR_COUNT.
//! @brief Get value of EPIT_CNR_COUNT from a register value.
#define BG_EPIT_CNR_COUNT(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_EPIT_CNR_COUNT) >> BP_EPIT_CNR_COUNT)
//@}
//-------------------------------------------------------------------------------------------
// hw_epit_t - module struct
//-------------------------------------------------------------------------------------------
/*!
* @brief All EPIT module registers.
*/
#ifndef __LANGUAGE_ASM__
#pragma pack(1)
typedef struct _hw_epit {
volatile hw_epit_cr_t CR; //!< Control register
volatile hw_epit_sr_t SR; //!< Status register
volatile hw_epit_lr_t LR; //!< Load register
volatile hw_epit_cmpr_t CMPR; //!< Compare register
volatile hw_epit_cnr_t CNR; //!< Counter register
} hw_epit_t;
#pragma pack()
//! @brief Macro to access all EPIT registers.
//! @param x EPIT instance number.
//! @return Reference (not a pointer) to the registers struct. To get a pointer to the struct,
//! use the '&' operator, like <code>&HW_EPIT(0)</code>.
#define HW_EPIT(x) (*(hw_epit_t*)REGS_EPIT_BASE(x))
#endif
#endif // __HW_EPIT_REGISTERS_H__
// v18/121106/1.2.2
// EOF

View File

@ -0,0 +1,195 @@
/*
* Copyright (c) 2011-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, WHTIMER ER 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 timer.c
* @brief Basic timer functions
*
* @ingroup diag_timer
*/
#include "timer.h"
#include "ccm_pll.h"
#include "epit.h"
#include "regsarmglobaltimer.h"
#include "regsepit.h"
#include "soc_memory_map.h"
#include "libserial.h"
#include "usyscall.h"
#include "sabrelite_timer.h"
////////////////////////////////////////////////////////////////////////////////
// Prototypes
////////////////////////////////////////////////////////////////////////////////
static void time_init_global_timer();
////////////////////////////////////////////////////////////////////////////////
// Variables
////////////////////////////////////////////////////////////////////////////////
uint32_t g_microsecondTimerMultiple;
////////////////////////////////////////////////////////////////////////////////
// Code
////////////////////////////////////////////////////////////////////////////////
//! Init the ARM global timer to a microsecond-frequency clock.
void time_init_global_timer()
{
// The ARM private peripheral clock is half the CPU clock.
uint32_t periphClock = get_main_clock(CPU_CLK) / 2;
uint32_t prescaler = (periphClock / 1000000) - 1;
// Divide down the prescaler until it fits into 8 bits. We add up the number of ticks
// it takes to equal a microsecond interval.
g_microsecondTimerMultiple = 1;
while (prescaler > 0xff) {
prescaler /= 2;
++g_microsecondTimerMultiple;
}
// Make sure the timer is off.
HW_ARMGLOBALTIMER_CONTROL.B.TIMER_ENABLE = 0;
// Clear counter.
HW_ARMGLOBALTIMER_COUNTERn_WR(0, 0);
HW_ARMGLOBALTIMER_COUNTERn_WR(1, 0);
// Set prescaler and clear other flags.
HW_ARMGLOBALTIMER_CONTROL_WR(BF_ARMGLOBALTIMER_CONTROL_PRESCALER(prescaler));
// Now turn on the timer.
HW_ARMGLOBALTIMER_CONTROL.B.TIMER_ENABLE = 1;
}
void system_time_init(void)
{
uint32_t freq;
// Init microsecond tick counter.
time_init_global_timer();
/* EPIT1 is used for the delay function */
/* Initialize the EPIT timer used for system time functions */
/* typical IPG_CLK is in MHz, so divide it to get a reference
clock of 1MHz => 1us per count */
freq = get_main_clock(IPG_CLK);
epit_init(g_system_timer_port, CLKSRC_IPG_CLK, freq / 1000000,
SET_AND_FORGET, 1000, WAIT_MODE_EN | STOP_MODE_EN);
}
int IPC_DO_SERVE_FUNC(Ipc_delay_us)(uint32_t* usecs)
{
// uint32_t instance = g_system_timer_port;
// if (*usecs == 0) {
// return 0;
// }
// /* enable the counter first */
// epit_counter_enable(instance, *usecs, POLLING_MODE);
// /* wait for the compare event */
// while (!epit_get_compare_event(instance))
// ;
// /* disable the counter to save power */
// epit_counter_disable(instance);
return 0;
}
int IPC_DO_SERVE_FUNC(Ipc_get_microseconds)(uint64_t* microseconds)
{
// First read upper.
uint32_t upper = HW_ARMGLOBALTIMER_COUNTERn_RD(1);
uint32_t lower;
*microseconds = 0;
while (true) {
// Read lower.
lower = HW_ARMGLOBALTIMER_COUNTERn_RD(0);
// Read upper again.
uint32_t newUpper = HW_ARMGLOBALTIMER_COUNTERn_RD(1);
// If the first and second read of the upper bits are the same, then return.
if (newUpper == upper) {
*microseconds = (((uint64_t)upper << 32) | (uint64_t)lower) / g_microsecondTimerMultiple;
break;
}
// Otherwise, start over again.
upper = newUpper;
}
return 0;
}
IPC_SERVER_INTERFACE(Ipc_delay_us, 1);
IPC_SERVER_INTERFACE(Ipc_get_microseconds, 1);
IPC_SERVER_REGISTER_INTERFACES(IpcSabreliteTimer, 2, Ipc_delay_us, Ipc_get_microseconds);
int main(int argc, char** argv)
{
printf("TIMER: Mapping %08x(size: %x) to %08x\n", AIPS1_ARB_PHY_BASE_ADDR, AIPS1_ARB_END_ADDR - AIPS1_ARB_BASE_ADDR, AIPS1_ARB_BASE_ADDR);
if (!mmap(AIPS1_ARB_BASE_ADDR, AIPS1_ARB_PHY_BASE_ADDR, AIPS1_ARB_END_ADDR - AIPS1_ARB_BASE_ADDR, true)) {
printf("TIMER : mmap AIPS1 ARB(%-08x) failed\n", AIPS1_ARB_PHY_BASE_ADDR);
}
printf("TIMER: Mapping %08x(size: %x) to %08x\n", AIPS2_ARB_PHY_BASE_ADDR, AIPS2_ARB_END_ADDR - AIPS2_ARB_BASE_ADDR, AIPS2_ARB_BASE_ADDR);
if (!mmap(AIPS2_ARB_BASE_ADDR, AIPS2_ARB_PHY_BASE_ADDR, AIPS2_ARB_END_ADDR - AIPS2_ARB_BASE_ADDR, true)) {
printf("TIMER : mmap AIPS1 ARB(%-08x) failed\n", AIPS2_ARB_PHY_BASE_ADDR);
}
printf("TIMER: Mapping %08x(size: %x) to %08x\n", REGS_ARMGLOBALTIMER_BASE, 0x1000, 0x00a00000);
if (!mmap(REGS_ARMGLOBALTIMER_BASE, 0x00a00000, 0x1000, true)) {
printf("TIMER : mmap GLOBAL TIMER(%-08x) failed\n", 0x00a00000);
}
static char server_name[] = "TimerServer";
if (register_server(server_name) < 0) {
printf("register server name %s failed\n", server_name);
exit();
}
static uint32_t epit_instance = HW_EPIT2;
epit_counter_disable(epit_instance);
system_time_init();
ipc_server_loop(&IpcSabreliteTimer);
exit();
}
////////////////////////////////////////////////////////////////////////////////
// EOF
////////////////////////////////////////////////////////////////////////////////

View File

@ -0,0 +1,78 @@
/*
* Copyright (c) 2011-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.
*/
//! @addtogroup diag_timer
//! @{
/*!
* @file timer.h
* @brief various defines used by the timer driver.
*/
#ifndef __TIMER_H__
#define __TIMER_H__
#include <stddef.h>
#include <stdint.h>
////////////////////////////////////////////////////////////////////////////////
// Constants
////////////////////////////////////////////////////////////////////////////////
//! @brief Options for low power mode support for the timers.
//!
//! These constants are bit masks that are or'd together to select in which low
//! power modes the timer will continue counting.
enum _timer_low_power_modes {
WAIT_MODE_EN = 1, //!< Timer is enabled in wait mode.
STOP_MODE_EN = 2 //!< Timer is enabled in stop mode.
};
//! @brief Available clock sources for the timers.
enum _timer_clock_sources {
CLKSRC_OFF = 0, //!< clock source is OFF
CLKSRC_IPG_CLK = 1, //!< clock source is peripheral clock
CLKSRC_PER_CLK = 2, //!< clock source is high-freq reference clock
CLKSRC_CLKIN = 3, //!< clock source is external from a CLKIN input
CLKSRC_CKIL = 3 //!< clock source is low-freq reference clock
};
//! @brief Do not enable interrupts.
#define POLLING_MODE 0
////////////////////////////////////////////////////////////////////////////////
// Externs
////////////////////////////////////////////////////////////////////////////////
extern uint32_t g_system_timer_port;
#endif // __TIMER_H__
////////////////////////////////////////////////////////////////////////////////
// EOF
////////////////////////////////////////////////////////////////////////////////

View File

@ -0,0 +1,38 @@
ifeq ($(BOARD), imx6q-sabrelite)
toolchain ?= arm-none-eabi-
endif
ifeq ($(BOARD), zynq7000-zc702)
toolchain ?= arm-xilinx-eabi-
endif
cc = ${toolchain}gcc
ld = ${toolchain}g++
objdump = ${toolchain}objdump
user_ldflags = -N -Ttext 0
cflags = -std=c11 -march=armv7-a -mcpu=cortex-a9 -mtune=cortex-a9 -g \
-Wno-unused -Wno-format -fno-common -ffreestanding -fno-builtin -static \
-Wno-unaligned-access -fdce -Wall -Werror -Wno-uninitialized -Wno-strict-aliasing -fdiagnostics-show-option \
-mapcs -marm -mfpu=neon -ftree-vectorize -fno-math-errno -funsafe-math-optimizations -fno-signed-zeros -mfloat-abi=softfp \
-fno-omit-frame-pointer -fno-stack-protector -fno-pie
# 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 \
-I$(KERNEL_ROOT)/services/boards/$(BOARD) \
-I$(KERNEL_ROOT)/services/lib/serial \
-I$(KERNEL_ROOT)/services/drivers/$(BOARD)/include \
-I$(KERNEL_ROOT)/services/drivers/$(BOARD)/enet \
-I$(KERNEL_ROOT)/services/drivers/$(BOARD)/lib \
-I$(KERNEL_ROOT)/services/lib/usyscall \
-I$(KERNEL_ROOT)/services/lib/ipc \
-I$(KERNEL_ROOT)/services/lib/memory
all: enet_drv.o enet_test.o board_network.o enet_iomux_config.o
@mv $^ $(KERNEL_ROOT)/services/app
%.o: %.c
@echo "cc $^"
@${cc} ${cflags} ${c_useropts} ${INC_DIR} -o $@ -c $^

View File

@ -0,0 +1,133 @@
/*
* 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.
*/
#include "enet.h"
#include "gpio.h"
#include "iomux_config.h"
#include "regsiomuxc.h"
#include "soc_memory_map.h"
////////////////////////////////////////////////////////////////////////////////
// Code
////////////////////////////////////////////////////////////////////////////////
/* ENET iomux config */
void imx_ar8031_iomux()
{
enet_iomux_config(); // iomux tool output
}
/*CPU_PER_RST_B low to high*/
void imx_KSZ9021RN_reset(void)
{
// max7310_set_gpio_output(0, 2, GPIO_LOW_LEVEL);
// hal_delay_us(1000000);
// max7310_set_gpio_output(0, 2, GPIO_HIGH_LEVEL);
#ifdef BOARD_SABRE_LITE
gpio_set_level(GPIO_PORT3, 23, GPIO_LOW_LEVEL);
hal_delay_us(100000); // hold in reset for a delay
gpio_set_level(GPIO_PORT3, 23, GPIO_HIGH_LEVEL);
hal_delay_us(10000);
#endif
}
/*CPU_PER_RST_B low to high*/
void imx_ar8031_reset(void)
{
#if defined(BOARD_SMART_DEVICE)
/* Select ALT5 mode of ENET_CRS-DV for GPIO1_25 - PGMII_NRST */
/* active low output */
gpio_set_direction(GPIO_PORT1, 25, GPIO_GDIR_OUTPUT);
gpio_set_level(GPIO_PORT1, 25, GPIO_LOW_LEVEL);
hal_delay_us(500);
gpio_set_level(GPIO_PORT1, 25, GPIO_HIGH_LEVEL);
#elif defined(BOARD_SABRE_AI) && !defined(BOARD_REV_A)
/* CPU_PER_RST_B low to high */
// max7310_set_gpio_output(0, 2, GPIO_LOW_LEVEL);
// hal_delay_us(1000);
// max7310_set_gpio_output(0, 2, GPIO_HIGH_LEVEL);
#endif
}
/*! From obds
* ENET iomux config
*/
void imx_enet_iomux(void)
{
enet_iomux_config(); // iomux tool output
#ifdef BOARD_SABRE_LITE
gpio_set_gpio(GPIO_PORT6, 30);
gpio_set_gpio(GPIO_PORT6, 25);
gpio_set_gpio(GPIO_PORT6, 27);
gpio_set_gpio(GPIO_PORT6, 28);
gpio_set_gpio(GPIO_PORT6, 29);
gpio_set_gpio(GPIO_PORT6, 24);
gpio_set_gpio(GPIO_PORT3, 23);
gpio_set_direction(GPIO_PORT3, 23, GPIO_GDIR_OUTPUT);
gpio_set_direction(GPIO_PORT6, 30, GPIO_GDIR_OUTPUT);
gpio_set_direction(GPIO_PORT6, 25, GPIO_GDIR_OUTPUT);
gpio_set_direction(GPIO_PORT6, 27, GPIO_GDIR_OUTPUT);
gpio_set_direction(GPIO_PORT6, 28, GPIO_GDIR_OUTPUT);
gpio_set_direction(GPIO_PORT6, 29, GPIO_GDIR_OUTPUT);
// set correct phy address and operation mode in KSZ9021RN
gpio_set_level(GPIO_PORT3, 23, GPIO_LOW_LEVEL);
gpio_set_level(GPIO_PORT6, 30, GPIO_HIGH_LEVEL);
gpio_set_level(GPIO_PORT6, 25, GPIO_HIGH_LEVEL);
gpio_set_level(GPIO_PORT6, 27, GPIO_HIGH_LEVEL);
gpio_set_level(GPIO_PORT6, 28, GPIO_HIGH_LEVEL);
gpio_set_level(GPIO_PORT6, 29, GPIO_HIGH_LEVEL);
gpio_set_direction(GPIO_PORT6, 24, GPIO_GDIR_OUTPUT);
gpio_set_level(GPIO_PORT6, 24, GPIO_HIGH_LEVEL);
#endif
}
#ifdef BOARD_SABRE_LITE
void imx_enet_iomux_reconfig(void)
{
// reconfigure RGMII_RD0-3, RGMII_RXC and RGMII_RX_CTL pads initially configured as GPIOs
enet_iomux_reconfig();
}
#endif
void imx_enet_phy_reset(void)
{
#ifdef BOARD_SABRE_LITE
imx_KSZ9021RN_reset();
#else
imx_ar8031_reset();
#endif
}
////////////////////////////////////////////////////////////////////////////////
// EOF
////////////////////////////////////////////////////////////////////////////////

View File

@ -0,0 +1,206 @@
/*
* Copyright (c) 2011-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.
*/
#ifndef __ENET_H__
#define __ENET_H__
#include <stddef.h>
#include <stdint.h>
#include "regsenet.h"
#include "sabrelite_timer.h"
////////////////////////////////////////////////////////////////////////////////
// Definitions
////////////////////////////////////////////////////////////////////////////////
//! @brief Definitions of the event bits.
enum {
ENET_EVENT_HBERR = 0x80000000,
ENET_EVENT_BABR = BM_ENET_EIR_BABR,
ENET_EVENT_BABT = BM_ENET_EIR_BABT,
ENET_EVENT_GRA = BM_ENET_EIR_GRA,
ENET_EVENT_TXF = BM_ENET_EIR_TXF,
ENET_EVENT_TXB = BM_ENET_EIR_TXB,
ENET_EVENT_RXF = BM_ENET_EIR_RXF,
ENET_EVENT_RXB = BM_ENET_EIR_RXB,
ENET_EVENT_MII = BM_ENET_EIR_MII,
ENET_EVENT_EBERR = BM_ENET_EIR_EBERR,
ENET_EVENT_LC = BM_ENET_EIR_LC,
ENET_EVENT_RL = BM_ENET_EIR_RL,
ENET_EVENT_UN = BM_ENET_EIR_UN,
ENET_EVENT_TX = ENET_EVENT_TXF,
ENET_EVENT_TX_ERR = (ENET_EVENT_BABT | ENET_EVENT_LC | ENET_EVENT_RL | ENET_EVENT_UN),
ENET_EVENT_RX = ENET_EVENT_RXF,
ENET_EVENT_ERR = (ENET_EVENT_HBERR | ENET_EVENT_EBERR)
};
//! @brief MII type
enum imx_mii_type {
MII,
RMII,
RGMII,
};
// Forward declaration.
typedef struct imx_enet_bd imx_enet_bd_t;
//! @brief Data structure for ENET device
typedef struct imx_enet_priv_s {
hw_enet_t* enet_reg; //!< the reister base address of ENET
uint8_t phy_addr; //!< the address of PHY which associated with ENET controller
uint32_t phy_id; //!< ID of the PHY
uint8_t tx_busy; //!< 0:free, 1:transmitting frame
uint8_t res[2];
uint32_t status; //!< the status of ENET device:link-status etc.
uint32_t tx_key; //!< save the key delivered from send function
imx_enet_bd_t* rx_bd; //!< the receive buffer description ring
imx_enet_bd_t* rx_cur; //!< the next recveive buffer description
imx_enet_bd_t* tx_bd; //!< the transmit buffer description rign
imx_enet_bd_t* tx_cur; //!< the next transmit buffer description
// TODO: Add interrupt about fields
// TODO: Add timer about fields
} imx_enet_priv_t;
//! @brief Definitions of the status field of imx_enet_priv_t.
enum {
ENET_STATUS_LINK_ON = 0x80000000,
ENET_STATUS_FULL_DPLX = 0x40000000,
ENET_STATUS_AUTO_NEG = 0x20000000,
ENET_STATUS_10M = 0x8000000,
ENET_STATUS_100M = 0x10000000,
ENET_STATUS_1000M = 0x20000000
};
////////////////////////////////////////////////////////////////////////////////
// API
////////////////////////////////////////////////////////////////////////////////
#if defined(__cplusplus)
extern "C" {
#endif
#include "usyscall.h"
extern char enet_server_name[];
extern char timer_server_name[];
extern struct Session timer_session;
static inline void hal_delay_us(int tick)
{
delay_us(&timer_session, tick);
}
/*!
* @brief Enable ENET and start transfer.
* @param dev a pointer of ENET interface(imx_enet_priv_t)
* @param enaddr a pointer of MAC address
*
* @return none
*/
void imx_enet_start(imx_enet_priv_t* dev, unsigned char* enaddr);
/*!
* @brief Disable ENET
* @param dev a pointer of ENET interface(imx_enet_priv_t)
*
* @return none
*/
void imx_enet_stop(imx_enet_priv_t* dev);
/*!
* @brief Initialize ENET PHY, like LAN8700, 8720, AR8031, etc
* @param dev a pointer of ENET interface(imx_enet_priv_t)
*
* @return none
*/
void imx_enet_phy_init(imx_enet_priv_t* dev);
/*!
* @brief Reads the current status from the PHY.
* @param dev Pointer to the enet interface struct.
* @return Current status of the PHY. This is a bitmask composed of the ENET_STATUS_x enums,
* such as #ENET_STATUS_LINK_ON and #ENET_STATUS_100M.
*/
uint32_t imx_enet_get_phy_status(imx_enet_priv_t* dev);
/*!
* @brief Initialize ENET interface, including buffer descriptor and MAC
* @param dev a pointer of ENET interface(imx_enet_priv_t)
* @param reg_base base address of ethernet registers
* @param phy_addr phy address, 0 or 1
*
* @return zero
*/
int imx_enet_init(imx_enet_priv_t* dev, unsigned long reg_base, int phy_addr);
/*!
* @brief Poll ENET events
* @param dev a pointer of ENET interface(imx_enet_priv_t)
*
* @return event value
*/
unsigned long imx_enet_poll(imx_enet_priv_t* dev);
/*!
* @brief Recieve ENET packet
* @param dev a pointer of ENET interface(imx_enet_priv_t)
* @param buf a pointer of buffer for received packet
* @param length the length of received packet
*
* @return 0 if succeeded,
* -1 if failed
*
*/
int imx_enet_recv(imx_enet_priv_t* dev, unsigned char* buf, int* length);
/*!
* @brief Transmit ENET packet
* @param dev a pointer of ENET interface(imx_enet_priv_t)
* @param buf a pointer of buffer for packet to be sent
* @param length the length of packet to be sent
* @param key key
*
* @return zero
*/
int imx_enet_send(imx_enet_priv_t* dev, unsigned char* buf, int length, unsigned long key);
/*!
* @brief Switch the PHY to external loopback mode for testing.
*/
void imx_enet_phy_enable_external_loopback(imx_enet_priv_t* dev);
#if defined(__cplusplus)
}
#endif
#endif //__ENET_H__
////////////////////////////////////////////////////////////////////////////////
// EOF
////////////////////////////////////////////////////////////////////////////////

View File

@ -0,0 +1,620 @@
/*
* Copyright (c) 2011-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 enet_drv.c
* @brief Driver of the i.MX ENET controller.
*
* @ingroup diag_enet
*/
#include <string.h>
#include "ccm_pll.h"
#include "enet.h"
#include "enet_private.h"
#include "libmem.h"
#include "libserial.h"
#include "usyscall.h"
extern uint32_t get_main_clock(main_clocks_t clock);
/*!
* This function gets the value of the PHY registers through the MII interface.
*/
int imx_enet_mii_read(volatile hw_enet_t* enet_reg, unsigned char phy_addr,
unsigned char reg_addr, unsigned short int* value)
{
unsigned long waiting = ENET_MII_TIMEOUT;
if (enet_reg->EIR.U & ENET_EVENT_MII) {
enet_reg->EIR.U = ENET_EVENT_MII;
}
enet_reg->MMFR.U = ENET_MII_READ(phy_addr, reg_addr); /*Write CMD */
while (1) {
if (enet_reg->EIR.U & ENET_EVENT_MII) {
printf("[%s %d], EIR: %08x\n", __func__, __LINE__, enet_reg->EIR.U);
enet_reg->EIR.U = ENET_EVENT_MII;
break;
}
if ((--waiting) == 0)
return -1;
hal_delay_us(0);
}
printf("[%s %d], EIR: %08x\n", __func__, __LINE__, enet_reg->EIR.U);
*value = ENET_MII_GET_DATA(enet_reg->MMFR.U);
return 0;
}
/*!
* This function sets the value of the PHY registers through the MII interface.
*/
int imx_enet_mii_write(volatile hw_enet_t* enet_reg, unsigned char phy_addr,
unsigned char reg_addr, unsigned short int value)
{
unsigned long waiting = ENET_MII_TIMEOUT;
if (enet_reg->EIR.U & ENET_EVENT_MII) {
enet_reg->EIR.U = ENET_EVENT_MII;
}
enet_reg->MMFR.U = ENET_MII_WRITE(phy_addr, reg_addr, value); /* Write CMD */
printf("MMFR.U: %08x value: %08x\n", enet_reg->MMFR.U, value);
while (1) {
if (enet_reg->EIR.U & ENET_EVENT_MII) {
enet_reg->EIR.U = ENET_EVENT_MII;
break;
}
if ((--waiting) == 0)
return -1;
hal_delay_us(ENET_MII_TICK);
}
return 0;
}
/*!
* The function initializes the description buffer for receiving or transmitting.
*/
static void imx_enet_bd_init(imx_enet_priv_t* dev, int dev_idx)
{
int i;
imx_enet_bd_t* p;
imx_enet_bd_t *rx_bd_base = (imx_enet_bd_t*)malloc(sizeof(imx_enet_bd_t) * (ENET_BD_RX_NUM * NUM_OF_ETH_DEVS)), //
*tx_bd_base = (imx_enet_bd_t*)malloc(sizeof(imx_enet_bd_t) * (ENET_BD_TX_NUM * NUM_OF_ETH_DEVS));
#define _SABRELITE_ENET_BUFFER_SIZE 2048
p = dev->rx_bd = (imx_enet_bd_t*)rx_bd_base;
for (i = 0; i < ENET_BD_RX_NUM; i++, p++) {
p->status = BD_RX_ST_EMPTY;
p->length = 0;
p->data = (unsigned char*)malloc(_SABRELITE_ENET_BUFFER_SIZE);
// printf("rx bd %x, buffer is %x\n", (unsigned int)p, (unsigned int)p->data);
}
dev->rx_bd[i - 1].status |= BD_RX_ST_WRAP;
dev->rx_cur = dev->rx_bd;
p = dev->tx_bd = (imx_enet_bd_t*)tx_bd_base;
for (i = 0; i < ENET_BD_TX_NUM; i++, p++) {
p->status = 0;
p->length = 0;
p->data = (unsigned char*)malloc(_SABRELITE_ENET_BUFFER_SIZE);
// printf("tx bd %x, buffer is %x\n", (unsigned int)p, (unsigned int)p->data);
}
dev->tx_bd[i - 1].status |= BD_TX_ST_WRAP;
dev->tx_cur = dev->tx_bd;
/*TODO:: add the sync function for items */
}
/*!
* This function initializes the ENET controller.
*/
static void imx_enet_chip_init(imx_enet_priv_t* dev)
{
volatile hw_enet_t* enet_reg = (hw_enet_t*)dev->enet_reg;
unsigned int ipg_clk;
enet_reg->ECR.U = ENET_RESET;
while (enet_reg->ECR.U & ENET_RESET) {
hal_delay_us(ENET_COMMON_TICK);
}
enet_reg->EIMR.U = 0x00000000;
enet_reg->EIR.U = 0xFFFFFFFF;
/*
* setup the MII gasket for RMII mode
*/
enet_reg->RCR.U = (enet_reg->RCR.U & ~(0x0000003F)) | ENET_RCR_RGMII_EN | ENET_RCR_FCE | ENET_RCR_PROM;
enet_reg->TCR.U |= ENET_TCR_FDEN;
enet_reg->MIBC.U |= ENET_MIB_DISABLE;
enet_reg->IAUR.U = 0;
enet_reg->IALR.U = 0;
enet_reg->GAUR.U = 0;
enet_reg->GALR.U = 0;
/*TODO:: Use MII_SPEED(IPG_CLK) to get the value */
ipg_clk = get_main_clock(IPG_CLK);
enet_reg->MSCR.U = (enet_reg->MSCR.U & (~0x7e)) | (((ipg_clk + 499999) / 5000000) << 1);
/*Enable ETHER_EN */
enet_reg->MRBR.U = 2048 - 16;
enet_reg->RDSR.U = (unsigned long)dev->rx_bd;
enet_reg->TDSR.U = (unsigned long)dev->tx_bd;
}
void enet_phy_rework_ar8031(imx_enet_priv_t* dev)
{
unsigned short val = 0;
#if 0
int i;
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0x1d, 0x1F); // ?? unknown debug reg
imx_enet_mii_read(dev->enet_reg, dev->phy_addr, 0x1e, &val);
//printf("debug before 0x1F val = 0x%x\n", val);
val |= 0x4;
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0x1e, val);
imx_enet_mii_read(dev->enet_reg, dev->phy_addr, 0x1e, &val);
//printf("debug after 0x1F val = 0x%x\n", val);
// Set CLK_25M Clock Select MDIO register
// select_clk25m = 3'b110 = 125 MHz from local PLL source
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0xd, 0x7); // MMD Access Control; device addr=7
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0xe, 0x8016); // MMD Access Address Data; reg=0x8016 (CLK_25M Clock Select)
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0xd, 0x4007); // MMD Access Control; func=data, device addr=7
imx_enet_mii_read(dev->enet_reg, dev->phy_addr, 0xe, &val);
//printf("debug read from 0x8016 val = 0x%x\n", val);
val &= 0xffe3;
val |= 0x18;
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0xe, val);
imx_enet_mii_read(dev->enet_reg, dev->phy_addr, 0xe, &val);
//printf("debug after read from 0x8016 val = 0x%x\n", val);
for (i = 0; i < 100000; i++) ;
//debug register 0x5[8]=1'b1 - suggest add 2ns GTX_CLK delay
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0x1d, 0x5); // debug reg 0x05 = SerDes Test and System Mode Control
imx_enet_mii_read(dev->enet_reg, dev->phy_addr, 0x1e, &val);
val |= 0x0100; // bit 8 = RGMII_tx_clk_dly
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0x1e, val);
// Disable hibernate
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0x1d, 0xb); // Hib Control and Auto-negotiation Test
imx_enet_mii_read(dev->enet_reg, dev->phy_addr, 0x1e, &val);
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0x1e, 0x3c40); // disable hibernate
// Config to external loopback
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0x1d, 0x11); // External Loopback selection
imx_enet_mii_read(dev->enet_reg, dev->phy_addr, 0x1e, &val);
val |= 0x0001; // enable ext loopback
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0x1e, val);
// PHY AR8031 Integrated 10/100/1000 Gigabit
// Reset & full duplex
// Use default speed - after Pwer on reset - 1000Mbs
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0, 0x8140);
imx_enet_mii_read(dev->enet_reg, dev->phy_addr, 0, &val);
while (val == 0x8140)
imx_enet_mii_read(dev->enet_reg, dev->phy_addr, 0, &val);
#else
/* To enable AR8031 ouput a 125MHz clk from CLK_25M */
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0xd, 0x7);
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0xe, 0x8016);
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0xd, 0x4007);
imx_enet_mii_read(dev->enet_reg, dev->phy_addr, 0xe, &val);
val &= 0xffe3;
val |= 0x18;
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0xe, val);
/* introduce tx clock delay */
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0x1d, 0x5);
imx_enet_mii_read(dev->enet_reg, dev->phy_addr, 0x1e, &val);
val |= 0x0100;
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0x1e, val);
#endif
}
void enet_phy_rework_ksz9021(imx_enet_priv_t* dev)
{
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0x9, 0x1c00);
/* min rx data delay */
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0x0b, 0x8105);
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0x0c, 0x0000);
/* max rx/tx clock delay, min rx/tx control delay */
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0x0b, 0x8104);
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0x0c, 0xf0f0);
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0x0b, 0x104);
}
/*!
* This function initializes the PHY connected to the ENET controller.
*/
void imx_enet_phy_init(imx_enet_priv_t* dev)
{
unsigned short value = 0;
unsigned long id = 0;
// Read PHY ID registers.
imx_enet_mii_read(dev->enet_reg, dev->phy_addr, PHY_IDENTIFY_1, &value);
id = (value & PHY_ID1_MASK) << PHY_ID1_SHIFT;
imx_enet_mii_read(dev->enet_reg, dev->phy_addr, PHY_IDENTIFY_2, &value);
id |= (value & PHY_ID2_MASK) << PHY_ID2_SHIFT;
id &= 0xfffffff0; // mask off lower 4 bits
switch (id) {
case 0x00540088: // ?? PHY
break;
case PHY_LAN8700_ID:
printf("ENET LAN8700 PHY: ID=%lx\n", id);
break;
case PHY_LAN8720_ID:
printf("ENET LAN8720 PHY: ID=%lx\n", id);
break;
case PHY_AR8031_ID:
printf("ENET AR8031 PHY: ID=%lx\n", id);
enet_phy_rework_ar8031(dev);
break;
case PHY_KSZ9021RN_ID:
printf("ENET KSZ9021RN PHY: ID=%lx\n", id);
enet_phy_rework_ksz9021(dev);
break;
default:
printf("[Warning] ENET not connect right PHY: ID=%lx\n", id);
}
dev->phy_id = id;
// Reset PHY
imx_enet_mii_read(dev->enet_reg, dev->phy_addr, PHY_CTRL_REG, &value);
value |= PHY_CTRL_RESET;
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, PHY_CTRL_REG, value);
// Wait for reset to complete.
do {
imx_enet_mii_read(dev->enet_reg, dev->phy_addr, PHY_CTRL_REG, &value);
} while (value & PHY_CTRL_RESET);
/* restart auto-negotiation */
#if 1
#if 1
imx_enet_mii_read(dev->enet_reg, dev->phy_addr, PHY_CTRL_REG, &value);
value |= 0x1200;
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, PHY_CTRL_REG, value);
#else
value = 0x8100;
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0x1f, value);
#endif
#endif
// Read current PHY status.
imx_enet_get_phy_status(dev);
}
uint32_t imx_enet_get_phy_status(imx_enet_priv_t* dev)
{
uint16_t value;
// Reset saved status.
dev->status = 0;
imx_enet_mii_read(dev->enet_reg, dev->phy_addr, PHY_STATUS_REG, &value);
printf("enet phy status %0d: %04x\n", dev->phy_addr, value); // 0x7809 or 0x782d
if (value & PHY_STATUS_LINK_ST) {
dev->status |= ENET_STATUS_LINK_ON;
} else {
dev->status &= ~ENET_STATUS_LINK_ON;
}
if (dev->phy_id == PHY_AR8031_ID) {
#if 0
imx_enet_mii_read(dev->enet_reg, dev->phy_addr, 0x1b, &value); // Cable Diagnostic Tester (CDT)
if (value & (1 << 2))
dev->status |= ENET_STATUS_FULL_DPLX;
else
dev->status &= ~ENET_STATUS_FULL_DPLX;
if (value & 0x2)
dev->status |= ENET_STATUS_1000M;
else if (value & 0x1)
dev->status |= ENET_STATUS_100M;
else
dev->status |= ENET_STATUS_10M;
#else
imx_enet_mii_read(dev->enet_reg, dev->phy_addr, 0x11, &value); // PHY-Specific status reg
printf("AR8031 reg 0x11 = %04x\n", value);
if (value & (1 << 13))
dev->status |= ENET_STATUS_FULL_DPLX;
else
dev->status &= ~ENET_STATUS_FULL_DPLX;
if (((value >> 14) & 0x3) == 0x2)
dev->status |= ENET_STATUS_1000M;
else if (((value >> 14) & 0x3) == 0x2)
dev->status |= ENET_STATUS_100M;
else
dev->status |= ENET_STATUS_10M;
#endif
} else if (dev->phy_id == PHY_KSZ9021RN_ID) {
imx_enet_mii_read(dev->enet_reg, dev->phy_addr, 0x1f, &value);
printf("KSZ9021 reg 0x1f = %04x\n", value);
if (value & (1 << 3))
dev->status |= ENET_STATUS_FULL_DPLX;
else
dev->status &= ~ENET_STATUS_FULL_DPLX;
if (value & (1 << 6))
dev->status |= ENET_STATUS_1000M;
else if (value & (1 << 5))
dev->status |= ENET_STATUS_100M;
else
dev->status |= ENET_STATUS_10M;
} else {
if (value & 0xe000)
dev->status |= ENET_STATUS_100M;
else
dev->status |= ENET_STATUS_10M;
if (value & 0x5000)
dev->status |= ENET_STATUS_FULL_DPLX;
else
dev->status &= ~ENET_STATUS_FULL_DPLX;
}
// printf("ENET %0d: [ %s ] [ %s ] [ %s ]:\n", dev->phy_addr,
// (dev->status & ENET_STATUS_FULL_DPLX) ? "FULL_DUPLEX" : "HALF_DUPLEX",
// (dev->status & ENET_STATUS_LINK_ON) ? "connected" : "disconnected",
// (dev->status & ENET_STATUS_1000M) ? "1000M bps" : (dev->status & ENET_STATUS_100M) ?
// "100M bps" : "10M bps");
return dev->status;
}
void imx_enet_phy_enable_external_loopback(imx_enet_priv_t* dev)
{
uint16_t val;
if (dev->phy_id == PHY_AR8031_ID) {
// Disable hibernate
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0x1d, 0xb); // Hib Control and Auto-negotiation Test
imx_enet_mii_read(dev->enet_reg, dev->phy_addr, 0x1e, &val);
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0x1e, 0x3c40); // disable hibernate
// Config to external loopback
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0x1d, 0x11); // External Loopback selection
imx_enet_mii_read(dev->enet_reg, dev->phy_addr, 0x1e, &val);
val |= 0x0001; // enable ext loopback
imx_enet_mii_write(dev->enet_reg, dev->phy_addr, 0x1e, val);
}
}
unsigned long imx_enet_poll(imx_enet_priv_t* dev)
{
volatile hw_enet_t* enet_reg = dev->enet_reg;
unsigned int value = 0;
value = enet_reg->EIR.U;
enet_reg->EIR.U = value & (~ENET_EVENT_MII);
if (value & ENET_EVENT_TX_ERR) {
printf("WARNING[POLL]: There are error(%x) for transmit\n", value & ENET_EVENT_TX_ERR);
dev->tx_busy = 0;
} else {
if (value & ENET_EVENT_TX) {
dev->tx_busy = 0;
}
}
if (value & ENET_EVENT_RX) {
// imx_enet_check_rx_bd(sc);
}
if (value & ENET_EVENT_HBERR) {
printf("WARNGING[POLL]: Hearbeat error!\n");
}
if (value & ENET_EVENT_EBERR) {
printf("WARNING[POLL]: Ethernet Bus Error!\n");
}
return value;
}
int imx_enet_send(imx_enet_priv_t* dev, unsigned char* buf, int length, unsigned long key)
{
volatile hw_enet_t* enet_reg = dev->enet_reg;
imx_enet_bd_t* p = dev->tx_cur;
memcpy(p->data, buf, length);
p->length = length;
p->status &= ~(BD_TX_ST_LAST | BD_TX_ST_RDY | BD_TX_ST_TC | BD_TX_ST_ABC);
p->status |= BD_TX_ST_LAST | BD_TX_ST_RDY | BD_TX_ST_TC;
if (p->status & BD_TX_ST_WRAP) {
p = dev->tx_bd;
} else {
p++;
}
dev->tx_cur = p;
dev->tx_busy = 1;
dev->tx_key = key;
enet_reg->TDAR.U = ENET_RX_TX_ACTIVE;
printf("EIR: %08x, ECR: %08x, TDAR.U: %08x, RDAR.U: %08x (%08x)\n", dev->enet_reg->EIR.U, dev->enet_reg->ECR.U, dev->enet_reg->TDAR.U, dev->enet_reg->RDAR.U, ENET_RX_TX_ACTIVE);
return 0;
}
int imx_enet_recv(imx_enet_priv_t* dev, unsigned char* buf, int* length)
{
imx_enet_bd_t* p = dev->rx_cur;
volatile hw_enet_t* enet_reg = dev->enet_reg;
if (p->status & BD_RX_ST_EMPTY) {
return -1;
}
if (!(p->status & BD_RX_ST_LAST)) {
printf("BUG[RX]: status=%x, length=%x\n", p->status, p->length);
return -1;
}
if ((p->status & BD_RX_ST_ERRS) || (p->length > ENET_FRAME_LEN)) {
printf("BUG1[RX]: status=%x, length=%x\n", p->status, p->length);
} else {
memcpy(buf, p->data, p->length - 4);
*length = p->length - 4;
}
p->status = (p->status & BD_RX_ST_WRAP) | BD_RX_ST_EMPTY;
if (p->status & BD_RX_ST_WRAP) {
p = dev->rx_bd;
} else {
p++;
}
dev->rx_cur = p;
enet_reg->ECR.U |= ENET_ETHER_EN;
enet_reg->RDAR.U |= ENET_RX_TX_ACTIVE;
return 0;
}
int imx_enet_init(imx_enet_priv_t* dev, unsigned long reg_base, int phy_addr)
{
dev->enet_reg = (hw_enet_t*)reg_base;
dev->tx_busy = 0;
dev->status = 0;
dev->phy_addr = phy_addr; /* 0 or 1 */
imx_enet_bd_init(dev, phy_addr);
imx_enet_chip_init(dev);
return 0;
}
static void imx_enet_set_mac_address(volatile hw_enet_t* enet_reg, unsigned char* enaddr)
{
unsigned long value;
value = enaddr[0];
value = (value << 8) + enaddr[1];
value = (value << 8) + enaddr[2];
value = (value << 8) + enaddr[3];
enet_reg->PALR.U = value;
value = enaddr[4];
value = (value << 8) + enaddr[5];
enet_reg->PAUR.U = (value << 16);
}
void imx_enet_start(imx_enet_priv_t* dev, unsigned char* enaddr)
{
imx_enet_set_mac_address(dev->enet_reg, enaddr);
dev->tx_busy = 0;
dev->enet_reg->ECR.U |= ENET_ETHER_EN | ENET_ETHER_SPEED_1000M | ENET_ETHER_LITTLE_ENDIAN;
dev->enet_reg->RDAR.U |= ENET_RX_TX_ACTIVE;
HW_ENET_RDAR_WR(ENET_RX_TX_ACTIVE);
printf("addr1: %x, addr2: %x\n", &dev->enet_reg->RDAR.U, HW_ENET_RDAR_ADDR);
printf("EIR: %08x, ECR: %08x, TDAR.U: %08x, RDAR.U: %08x (%08x)\n", dev->enet_reg->EIR.U, dev->enet_reg->ECR.U, dev->enet_reg->TDAR.U, dev->enet_reg->RDAR.U, ENET_RX_TX_ACTIVE);
}
void imx_enet_stop(imx_enet_priv_t* dev)
{
dev->enet_reg->ECR.U &= ~ENET_ETHER_EN;
}
int imx_enet_isolate_phy(imx_enet_priv_t* dev)
{
unsigned short value = 0;
if (!imx_enet_mii_read(dev->enet_reg, dev->phy_addr, PHY_CTRL_REG, &value)) {
value |= (0x01 << 10);
if (!imx_enet_mii_write(dev->enet_reg, dev->phy_addr, PHY_CTRL_REG, value)) {
return 0;
}
}
return -1;
}
int imx_enet_unisolate_phy(imx_enet_priv_t* dev)
{
unsigned short value = 0;
if (!imx_enet_mii_read(dev->enet_reg, dev->phy_addr, PHY_CTRL_REG, &value)) {
value &= ~(0x01 << 10);
if (!imx_enet_mii_write(dev->enet_reg, dev->phy_addr, PHY_CTRL_REG, value)) {
imx_enet_mii_read(dev->enet_reg, dev->phy_addr, PHY_CTRL_REG, &value);
return 0;
}
}
return -1;
}
int imx_enet_mii_type(imx_enet_priv_t* dev, enum imx_mii_type mii_type)
{
volatile hw_enet_t* enet_reg = dev->enet_reg;
switch (mii_type) {
case MII:
/*clear RMII and RGMII */
enet_reg->RCR.U &= ~(ENET_RCR_RMII_MODE | ENET_RCR_RGMII_EN);
enet_reg->RCR.U |= ENET_RCR_MII_MODE;
break;
case RMII:
enet_reg->RCR.U &= ~(ENET_RCR_RGMII_EN);
enet_reg->RCR.U |= (ENET_RCR_MII_MODE | ENET_RCR_RMII_MODE);
break;
case RGMII:
enet_reg->RCR.U &= ~(ENET_RCR_RMII_MODE | ENET_RCR_MII_MODE);
enet_reg->RCR.U |= ENET_RCR_RGMII_EN;
enet_reg->TFWR.U = 0x3f; // for mx6dq
break;
default:
printf("BUG:unknow MII type=%x\n", mii_type);
break;
}
printf("RCR: %08x, TFWR: %08x\n", enet_reg->RCR.U, enet_reg->TFWR.U);
return 0;
}

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,245 @@
/*
* Copyright (c) 2011-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.
*/
#ifndef __ENET_PRIVATE_H__
#define __ENET_PRIVATE_H__
#include "enet.h"
////////////////////////////////////////////////////////////////////////////////
// Definitions
////////////////////////////////////////////////////////////////////////////////
// clang-format off
#define NUM_OF_ETH_DEVS 1
#define ENET_RX_FRAMES 8
#define ENET_FRAME_LEN (1540+4)
/* the defines to active transmit or receive frame */
#define ENET_RX_TX_ACTIVE BM_ENET_TDAR_TDAR //BM_ENET_RDAR_RDAR
/* the defines of Ethernet Control register */
#define ENET_RESET BM_ENET_ECR_RESET
#define ENET_ETHER_EN BM_ENET_ECR_ETHEREN
#define ENET_ETHER_SPEED_1000M (1<<5)
#define ENET_ETHER_LITTLE_ENDIAN (1<<8)
/* the defins of MII operation */
#define ENET_MII_ST 0x40000000
#define ENET_MII_OP_OFF BP_ENET_MMFR_OP
#define ENET_MII_OP_MASK 0x03
#define ENET_MII_OP_RD 0x02
#define ENET_MII_OP_WR 0x01
#define ENET_MII_PA_OFF BP_ENET_MMFR_PA
#define ENET_MII_PA_MASK 0xFF
#define ENET_MII_RA_OFF 18
#define ENET_MII_RA_MASK 0xFF
#define ENET_MII_TA 0x00020000
#define ENET_MII_DATA_OFF BP_ENET_MMFR_DATA
#define ENET_MII_DATA_MASK 0x0000FFFF
#define ENET_MII_FRAME ( ENET_MII_ST | ENET_MII_TA )
#define ENET_MII_OP(x) ( ((x) & ENET_MII_OP_MASK) << ENET_MII_OP_OFF )
#define ENET_MII_PA(pa) (((pa)& ENET_MII_PA_MASK) << ENET_MII_PA_OFF)
#define ENET_MII_RA(ra) (((ra)& ENET_MII_RA_MASK) << ENET_MII_RA_OFF)
#define ENET_MII_SET_DATA(v) (((v) & ENET_MII_DATA_MASK) << ENET_MII_DATA_OFF)
#define ENET_MII_GET_DATA(v) (((v) >> ENET_MII_DATA_OFF) & ENET_MII_DATA_MASK )
#define ENET_MII_READ(pa, ra) ( ( ENET_MII_FRAME | ENET_MII_OP(ENET_MII_OP_RD) )|\
ENET_MII_PA(pa) | ENET_MII_RA(ra) )
#define ENET_MII_WRITE(pa, ra, v) ( ENET_MII_FRAME | ENET_MII_OP(ENET_MII_OP_WR)|\
ENET_MII_PA(pa) | ENET_MII_RA(ra) |ENET_MII_SET_DATA(v) )
#define MII_SPEED_SHIFT 1
#define MII_SPEED_MASK 0x0000003F
#define MII_SPEED(x) ( (((((x)+499999)/2500000)&(MII_SPEED_MASK))>>1)<<(MII_SPEED_SHIFT) )
/*the defines of MIB control */
#define ENET_MIB_DISABLE BM_ENET_MIBC_MIB_DIS
/*the defines of Receive Control*/
#define ENET_RCR_FCE BM_ENET_RCR_FCE
#define ENET_RCR_BC_REJ BM_ENET_RCR_BC_REJ
#define ENET_RCR_PROM BM_ENET_RCR_PROM
#define ENET_RCR_MII_MODE (BM_ENET_RCR_MII_MODE)
#define ENET_RCR_RGMII_EN (1<<6) /*RGMII enable/disable */
#define ENET_RCR_RMII_MODE (BM_ENET_RCR_RMII_MODE) /*RMII mode:1->10M, 0->100M */
/*the defines of Transmit Control*/
#define ENET_TCR_RFC_PAUSE BM_ENET_TCR_RFC_PAUSE
#define ENET_TCR_FDEN BM_ENET_TCR_FDEN
/*the defines of buffer description*/
#define ENET_BD_RX_NUM 8
#define ENET_BD_TX_NUM 2
#define BD_RX_ST_EMPTY 0x8000
#define BD_RX_ST_WRAP 0x2000
#define BD_RX_ST_LAST 0x0800
#define BD_RX_ST_ERRS 0x0037
#define BD_TX_ST_RDY 0x8000
#define BD_TX_ST_WRAP 0x2000
#define BD_TX_ST_LAST 0x0800
#define BD_TX_ST_TC 0x0400
#define BD_TX_ST_ABC 0x0200
//! @brief Data structure for Tx/Rx buffer descriptor
typedef struct imx_enet_bd {
unsigned short int length; /*packet size */
unsigned short int status; /*control & statue of this buffer description */
unsigned char *data; /*frame buffer address */
} imx_enet_bd_t;
#define MXC_ENET_PRIVATE(x) ((imx_enet_priv_t *)(x)->driver_private)
/*The defines of the status field of imx_enet_priv_t */
#define ENET_STATUS_LINK_ON 0x80000000
#define ENET_STATUS_FULL_DPLX 0x40000000
#define ENET_STATUS_AUTO_NEG 0x20000000
#define ENET_STATUS_10M 0x8000000
#define ENET_STATUS_100M 0x10000000
#define ENET_STATUS_1000M 0x20000000
enum
{
PHY_LAN8700_ID = 0x0007c0c0,
PHY_LAN8720_ID = 0x0007c0f0,
PHY_AR8031_ID = 0x004dd070,
PHY_KSZ9021RN_ID = 0x00221610
};
#define PHY_CTRL_REG 0x00
#define PHY_CTRL_RESET 0x8000
#define PHY_CTRL_AUTO_NEG 0x1000
#define PHY_CTRL_FULL_DPLX 0x0100
#define PHY_STATUS_REG 0x01
#define PHY_STATUS_LINK_ST 0x0004
#define PHY_IDENTIFY_1 0x02
#define PHY_IDENTIFY_2 0x03
#define PHY_ID1_SHIFT 16
#define PHY_ID1_MASK 0xFFFF
#define PHY_ID2_SHIFT 0
#define PHY_ID2_MASK 0xFFFF
#define PHY_MODE_NUM 0x03F0
#define PHY_REV_NUM 0x000F
#define PHY_DIAG_REG 0x12
#define PHY_DIAG_DPLX 0x0800
#define PHY_DIAG_RATE 0x0400
#define PHY_MODE_REG 0x15
#define PHY_LED_SEL 0x200
#define PHY_AUTO_NEG_REG 0x5
#define PHY_AUTO_10BASET 0x20
#define PHY_AUTO_10BASET_DPLX 0x40
#define PHY_AUTO_100BASET 0x80
#define PHY_AUTO_100BASET_DPLX 0x100
#define PHY_AUTO_NEG_EXP_REG 0x6
#define PHY_AUTO_NEG_NEW_PAGE 0x2
#define PHY_AUTO_NEG_CAP 0x1
#define PHY_INT_SRC_REG 29
#define PHY_INT_AUTO_NEG 0x40
#define ENET_COMMON_TICK 2
#define ENET_COMMON_TIMEOUT (1000*1000)
#define ENET_MII_TICK 2
#define ENET_MII_TIMEOUT (1000*1000)
// clang-format on
#endif //__ENET_PRIVATE_H__
////////////////////////////////////////////////////////////////////////////////
// EOF
////////////////////////////////////////////////////////////////////////////////

View File

@ -0,0 +1,273 @@
/*
* Copyright (c) 2011-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 enet_test.c
* @brief Test for the ethernet interface through the ENET + PHY.
*
* @ingroup diag_enet
*/
#include <stddef.h>
#include <string.h>
#include "enet.h"
#include "sdk_types.h"
#include "soc_memory_map.h"
#include "libserial.h"
#include "usyscall.h"
#define ENET_PHY_ADDR 6
static imx_enet_priv_t enet0;
static unsigned char pkt_send[2048], pkt_recv[2048];
static unsigned char mac_addr0[6] = { 0x00, 0x04, 0x9f, 0x00, 0x00, 0x01 };
extern int imx_enet_mii_type(imx_enet_priv_t* dev, enum imx_mii_type mii_type);
extern void imx_enet_iomux(void);
#ifdef BOARD_SABRE_LITE
extern void imx_enet_iomux_reconfig(void);
#endif
extern void imx_enet_phy_reset(void);
static void pkt_fill(unsigned char* packet, unsigned char* eth_addr, unsigned char seed, int length)
{
unsigned char* pkt = packet;
unsigned char eth_type[2] = { 0x08, 0x00 };
int i;
memset(pkt, 0xff, 6);
pkt += 6;
memcpy(pkt, eth_addr, 6);
pkt += 6;
memcpy(pkt, eth_type, 2);
pkt += 2;
for (i = 0; i < (length - 14); i++)
*pkt++ = (seed + i) & 0xff;
return;
}
static int pkt_compare(unsigned char* packet1, unsigned char* packet2, int length)
{
int i = 0;
unsigned char *pkt1 = packet1, *pkt2 = packet2;
for (i = 0; i < length; i++) {
if (*(pkt1 + i) != *(pkt2 + i))
break;
}
if (i < length)
return TEST_FAILED;
else
return 0;
}
//////////////////////////////////////////
void print_hw_enet(const hw_enet_t* enet)
{
printf("********************************\n");
printf("EIR: %08x\n", enet->EIR.U);
printf("EIMR: %08x\n", enet->EIMR.U);
printf("RDAR: %08x\n", enet->RDAR.U);
printf("TDAR: %08x\n", enet->TDAR.U);
printf("ECR: %08x\n", enet->ECR.U);
printf("MMFR: %08x\n", enet->MMFR.U);
printf("MSCR: %08x\n", enet->MSCR.U);
printf("MIBC: %08x\n", enet->MIBC.U);
printf("RCR: %08x\n", enet->RCR.U);
printf("TCR: %08x\n", enet->TCR.U);
printf("PALR: %08x\n", enet->PALR.U);
printf("PAUR: %08x\n", enet->PAUR.U);
printf("OPD: %08x\n", enet->OPD.U);
printf("IAUR: %08x\n", enet->IAUR.U);
printf("IALR: %08x\n", enet->IALR.U);
printf("GAUR: %08x\n", enet->GAUR.U);
printf("GALR: %08x\n", enet->GALR.U);
printf("TFWR: %08x\n", enet->TFWR.U);
printf("RDSR: %08x\n", enet->RDSR.U);
printf("TDSR: %08x\n", enet->TDSR.U);
printf("MRBR: %08x\n", enet->MRBR.U);
printf("RSFL: %08x\n", enet->RSFL.U);
printf("RSEM: %08x\n", enet->RSEM.U);
printf("RAEM: %08x\n", enet->RAEM.U);
printf("RAFL: %08x\n", enet->RAFL.U);
printf("TSEM: %08x\n", enet->TSEM.U);
printf("TAEM: %08x\n", enet->TAEM.U);
printf("TAFL: %08x\n", enet->TAFL.U);
printf("TIPG: %08x\n", enet->TIPG.U);
printf("FTRL: %08x\n", enet->FTRL.U);
printf("TACC: %08x\n", enet->TACC.U);
printf("RACC: %08x\n", enet->RACC.U);
printf("ATCR: %08x\n", enet->ATCR.U);
printf("ATVR: %08x\n", enet->ATVR.U);
printf("ATOFF: %08x\n", enet->ATOFF.U);
printf("ATPER: %08x\n", enet->ATPER.U);
printf("ATCOR: %08x\n", enet->ATCOR.U);
printf("ATINC: %08x\n", enet->ATINC.U);
printf("ATSTMP: %08x\n", enet->ATSTMP.U);
printf("********************************\n");
}
//////////////////////////////////////////
/*!
* This test performs a loopback transfer on the RGMII interface through
* an external AR8031 giga ethernet PHY.
*
* @return TEST_PASSED or TEST_FAILED
*/
int enet_test()
{
imx_enet_priv_t* dev0 = &enet0;
int pkt_len_send = 0, pkt_len_recv = 0, ret = 0, i;
unsigned int enet_events = 0;
unsigned char try = 100;
// Enet loopback test
printf("\nWould you like to run the Ethernet loopback test?\n \
(Please note that in order to run the test, you need to\n \
first plug in a loopback cable to the Ethernet port) \n");
// setup iomux for ENET
imx_enet_iomux();
imx_enet_phy_reset();
#ifdef BOARD_SABRE_LITE
imx_enet_iomux_reconfig();
#endif
// init enet0
imx_enet_init(dev0, ENET_BASE_ADDR, ENET_PHY_ADDR);
imx_enet_mii_type(dev0, RGMII);
// init phy0.
imx_enet_phy_init(dev0);
while (try--) {
uint32_t status = imx_enet_get_phy_status(dev0);
if (status & ENET_STATUS_LINK_ON) {
printf("Ethernet link is up!\n");
break;
}
hal_delay_us(100000); // 100 ms
}
// imx_enet_phy_enable_external_loopback(dev0);
printf("ENET %0d: [ %s ] [ %s ] [ %s ]:\n", dev0->phy_addr,
(dev0->status & ENET_STATUS_FULL_DPLX) ? "FULL_DUPLEX" : "HALF_DUPLEX",
(dev0->status & ENET_STATUS_LINK_ON) ? "connected" : "disconnected",
(dev0->status & ENET_STATUS_1000M) ? "1000M bps" : (dev0->status & ENET_STATUS_100M) ? "100M bps"
: "10M bps");
// check phy status
if (!(dev0->status & ENET_STATUS_LINK_ON)) {
printf("ENET link status check fail\n");
return TEST_FAILED;
}
imx_enet_start(dev0, mac_addr0);
// send packet
printf("send packet\n");
pkt_len_send = 1500;
pkt_fill(pkt_send, mac_addr0, 0x23, pkt_len_send);
imx_enet_send(dev0, pkt_send, pkt_len_send, 1);
enet_events = 0;
for (i = 0; i < 100; i++) {
enet_events = imx_enet_poll(dev0);
if (ENET_EVENT_TX & enet_events) {
printf("enet_events = %08x\n", enet_events);
break;
}
hal_delay_us(100);
}
if (!(ENET_EVENT_TX & enet_events)) {
printf("ENET tx fail event: %08x\n", enet_events);
return TEST_FAILED;
}
if (!(ENET_EVENT_RX & enet_events)) {
printf("ENET rx fail\n");
return TEST_FAILED;
}
pkt_len_recv = 0;
imx_enet_recv(dev0, pkt_recv, &pkt_len_recv);
if (pkt_len_recv != pkt_len_send) {
printf("ENET rx length check fail \n");
return TEST_FAILED;
}
ret = pkt_compare(pkt_send, pkt_recv, pkt_len_send);
if (ret != 0) {
printf("ENET rx packet check fail \n");
return TEST_FAILED;
}
#ifdef DEBUG_PRINT
printf("ENET rx ok\n");
#endif
printf(" ENET loopback test pass\n");
imx_enet_stop(dev0);
return TEST_PASSED;
}
char enet_server_name[] = "EnetServer";
char timer_server_name[] = "TimerServer";
struct Session timer_session;
int main(int argc, char** argv)
{
if (connect_session(&timer_session, timer_server_name, 4096) < 0) {
printf("%s connect server: %s failed\n", enet_server_name, timer_server_name);
exit();
}
printf("%s: Mapping %08x(size: %x) to %08x\n", enet_server_name, AIPS1_ARB_PHY_BASE_ADDR, AIPS1_ARB_END_ADDR - AIPS1_ARB_BASE_ADDR, AIPS1_ARB_BASE_ADDR);
if (!mmap(AIPS1_ARB_BASE_ADDR, AIPS1_ARB_PHY_BASE_ADDR, AIPS1_ARB_END_ADDR - AIPS1_ARB_BASE_ADDR, true)) {
printf("%s: mmap AIPS1 ARB(%8x) failed\n", enet_server_name, AIPS1_ARB_PHY_BASE_ADDR);
exit();
}
printf("%s: Mapping %08x(size: %x) to %8x\n", enet_server_name, AIPS2_ARB_PHY_BASE_ADDR, AIPS2_ARB_END_ADDR - AIPS2_ARB_BASE_ADDR, AIPS2_ARB_BASE_ADDR);
if (!mmap(AIPS2_ARB_BASE_ADDR, AIPS2_ARB_PHY_BASE_ADDR, AIPS2_ARB_END_ADDR - AIPS2_ARB_BASE_ADDR, true)) {
printf("%s: mmap AIPS1 ARB(%08x) failed\n", enet_server_name, AIPS2_ARB_PHY_BASE_ADDR);
exit();
}
enet_test();
exit();
return 0;
}

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,28 @@
ifeq ($(BOARD), imx6q-sabrelite)
toolchain ?= arm-none-eabi-
endif
ifeq ($(BOARD), zynq7000-zc702)
toolchain ?= arm-xilinx-eabi-
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 \
-I$(KERNEL_ROOT)/services/boards/$(BOARD) \
-I$(KERNEL_ROOT)/services/lib/serial \
-I$(KERNEL_ROOT)/services/drivers/$(BOARD)/include \
-I$(KERNEL_ROOT)/services/drivers/$(BOARD)/enet \
-I$(KERNEL_ROOT)/services/lib/usyscall \
-I$(KERNEL_ROOT)/services/lib/ipc
all: gpio.o imx6dq_gpio_map.o
@mv $^ $(KERNEL_ROOT)/services/app
%.o: %.c
@echo "cc $^"
@${cc} ${cflags} ${c_useropts} ${INC_DIR} -o $@ -c $^

View File

@ -0,0 +1,260 @@
/*
* Copyright (c) 2011-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 gpio.c
* @brief Driver to control the GPIO module.
* @ingroup diag_gpio
*/
#include "gpio.h"
#include "gpio_map.h"
#include "regsgpio.h"
#include "regsiomuxc.h"
#include "sdk_types.h"
#include "libserial.h"
int32_t gpio_get_port_count(void)
{
return HW_GPIO_INSTANCE_COUNT;
}
int gpio_set_gpio(int32_t port, int32_t pin)
{
// Validate port and pin before indexing into the map arrays.
if (port < 1 || port > HW_GPIO_INSTANCE_COUNT || pin < 0 || pin > 31) {
debug_printf("Invalid GPIO port or pin number.\n");
return INVALID_PARAMETER;
}
// Look up mux register address.
uint32_t addr = k_gpio_mux_registers[port - 1][pin];
if (!addr) {
return INVALID_PARAMETER;
}
volatile uint32_t* reg = (volatile uint32_t*)addr;
// Switch mux to ALT5, which is always GPIO mode. We're just using this register's
// BM_ and BF_ macros because they are convenient, and is present on all three mx6.
*reg = (*reg & ~BM_IOMUXC_SW_MUX_CTL_PAD_KEY_COL0_MUX_MODE)
| BF_IOMUXC_SW_MUX_CTL_PAD_KEY_COL0_MUX_MODE_V(ALT5);
return SUCCESS;
}
int32_t gpio_set_direction(int32_t port, int32_t pin, int32_t dir)
{
uint32_t oldVal = 0, newVal = 0;
if ((port > HW_GPIO_INSTANCE_COUNT) || (port < 1)) {
debug_printf("Invalid GPIO Instance GPIO_PORT%d parameter. GPIO_PORT1~GPIO_PORT%d is allowed.\n",
port, HW_GPIO_INSTANCE_COUNT);
return INVALID_PARAMETER;
}
if ((pin > 31) || (pin < 0)) {
debug_printf("Invalid GPIO Pin %d parameter. Pin 0~31 is allowed.\n", pin);
return INVALID_PARAMETER;
}
oldVal = HW_GPIO_GDIR_RD(port);
if (dir == GPIO_GDIR_INPUT)
newVal = oldVal & (~(1 << pin));
else
newVal = oldVal | (1 << pin);
HW_GPIO_GDIR_WR(port, newVal);
return 0; // SUCCESS;
}
int32_t gpio_get_direction(int32_t port, int32_t pin)
{
if ((port > HW_GPIO_INSTANCE_COUNT) || (port < 1)) {
debug_printf("Invalid GPIO Instance GPIO_PORT%d parameter. GPIO_PORT1~GPIO_PORT%d is allowed.\n",
port, HW_GPIO_INSTANCE_COUNT);
return INVALID_PARAMETER;
}
if ((pin > 31) || (pin < 0)) {
debug_printf("Invalid GPIO Pin %d parameter. Pin 0~31 is allowed.\n", pin);
return INVALID_PARAMETER;
}
return (HW_GPIO_GDIR_RD(port) >> pin) & 1;
}
int32_t gpio_set_level(int32_t port, int32_t pin, uint32_t level)
{
if ((port > HW_GPIO_INSTANCE_COUNT) || (port < 1)) {
debug_printf("Invalid GPIO Instance GPIO_PORT%d parameter. GPIO_PORT1~GPIO_PORT%d is allowed.\n",
port, HW_GPIO_INSTANCE_COUNT);
return INVALID_PARAMETER;
}
if ((pin > 31) || (pin < 0)) {
debug_printf("Invalid GPIO Pin %d parameter. Pin 0~31 is allowed.\n", pin);
return INVALID_PARAMETER;
}
uint32_t mask = 1 << pin;
int32_t dir = HW_GPIO_GDIR_RD(port) & mask ? GPIO_GDIR_OUTPUT : GPIO_GDIR_INPUT;
if (dir != GPIO_GDIR_OUTPUT) {
printf("GPIO_PORT%d_%d is not configured to be output!\n", port, pin);
return -1;
}
uint32_t value = HW_GPIO_DR_RD(port); // read current value
if (level == GPIO_LOW_LEVEL) // fix it up
value &= ~mask;
else if (level == GPIO_HIGH_LEVEL)
value |= mask;
HW_GPIO_DR_WR(port, value); // write new value
return 0; // SUCCESS;
}
int32_t gpio_get_level(int32_t port, int32_t pin)
{
if ((port > HW_GPIO_INSTANCE_COUNT) || (port < 1)) {
debug_printf("Invalid GPIO Instance GPIO_PORT%d parameter. GPIO_PORT1~GPIO_PORT%d is allowed.\n",
port, HW_GPIO_INSTANCE_COUNT);
return INVALID_PARAMETER;
}
if ((pin > 31) || (pin < 0)) {
debug_printf("Invalid GPIO Pin %d parameter. Pin 0~31 is allowed.\n", pin);
return INVALID_PARAMETER;
}
uint32_t mask = 1 << pin;
return HW_GPIO_DR_RD(port) & mask ? GPIO_HIGH_LEVEL : GPIO_LOW_LEVEL;
}
int32_t gpio_set_interrupt_config(int32_t port, int32_t pin, int32_t config)
{
if ((port > HW_GPIO_INSTANCE_COUNT) || (port < 1)) {
debug_printf("Invalid GPIO Instance GPIO_PORT%d parameter. GPIO_PORT1~GPIO_PORT%d is allowed.\n",
port, HW_GPIO_INSTANCE_COUNT);
return INVALID_PARAMETER;
}
if ((pin > 31) || (pin < 0)) {
debug_printf("Invalid GPIO Pin %d parameter. Pin 0~31 is allowed.\n", pin);
return INVALID_PARAMETER;
}
if (pin < 16) {
// GPIOs 0-15 use ICR1 register
uint32_t value = HW_GPIO_ICR1_RD(port); // read current value
uint32_t field_offset = pin * 2; // fields are 2 bits wide
value &= ~(BM_GPIO_ICR1_ICR0 << field_offset); // clear specified field
value |= config << field_offset; // set specified field
HW_GPIO_ICR1_WR(port, value); // write new value
} else {
// GPIOs 16-31 use ICR2 register
uint32_t value = HW_GPIO_ICR2_RD(port); // read current value
uint32_t field_offset = (pin - 16) * 2; // fields are 2 bits wide
value &= ~(BM_GPIO_ICR2_ICR16 << field_offset); // clear specified field
value |= config << field_offset; // set specified field
HW_GPIO_ICR1_WR(port, value); // write new value
}
return 0; // SUCCESS;
}
int32_t gpio_set_interrupt_mask(int32_t port, int32_t pin, int32_t mask)
{
if ((port > HW_GPIO_INSTANCE_COUNT) || (port < 1)) {
debug_printf("Invalid GPIO Instance GPIO_PORT%d parameter. GPIO_PORT1~GPIO_PORT%d is allowed.\n",
port, HW_GPIO_INSTANCE_COUNT);
return INVALID_PARAMETER;
}
if ((pin > 31) || (pin < 0)) {
debug_printf("Invalid GPIO Pin %d parameter. Pin 0~31 is allowed.\n", pin);
return INVALID_PARAMETER;
}
uint32_t value = HW_GPIO_IMR_RD(port);
if (mask == GPIO_IMR_MASKED)
value &= ~(1 << pin);
else
value |= 1 << pin;
HW_GPIO_GDIR_WR(port, value);
return 0; // SUCCESS;
}
int32_t gpio_get_interrupt_status(int32_t port, int32_t pin)
{
if ((port > HW_GPIO_INSTANCE_COUNT) || (port < 1)) {
debug_printf("Invalid GPIO Instance GPIO_PORT%d parameter. GPIO_PORT1~GPIO_PORT%d is allowed.\n",
port, HW_GPIO_INSTANCE_COUNT);
return INVALID_PARAMETER;
}
if ((pin > 31) || (pin < 0)) {
debug_printf("Invalid GPIO Pin %d parameter. Pin 0~31 is allowed.\n", pin);
return INVALID_PARAMETER;
}
return HW_GPIO_ISR_RD(port) & (1 << pin) ? GPIO_ISR_ASSERTED : GPIO_ISR_NOT_ASSERTED;
}
int32_t gpio_clear_interrupt(int32_t port, int32_t pin)
{
if ((port > HW_GPIO_INSTANCE_COUNT) || (port < 1)) {
debug_printf("Invalid GPIO Instance GPIO_PORT%d parameter. GPIO_PORT1~GPIO_PORT%d is allowed.\n",
port, HW_GPIO_INSTANCE_COUNT);
return INVALID_PARAMETER;
}
if ((pin > 31) || (pin < 0)) {
debug_printf("Invalid GPIO Pin %d parameter. Pin 0~31 is allowed.\n", pin);
return INVALID_PARAMETER;
}
uint32_t value = HW_GPIO_ISR_RD(port);
value |= 1 << pin;
HW_GPIO_ISR_WR(port, value);
return 0; // SUCCESS;
}

View File

@ -0,0 +1,271 @@
/*
* Copyright (c) 2013, Freescale Semiconductor, Inc.
* All rights reserved.
*
* THIS SOFTWARE IS PROVIDED BY FREESCALE "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 FREESCALE 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.
*/
/*
* WARNING! DO NOT EDIT THIS FILE DIRECTLY!
*
* This file was generated automatically and any changes may be lost.
*/
#include "gpio_map.h"
#include "regsiomuxc.h"
// First subscript is bank, second is pin within the bank. There are always 32 pin
// entries per bank. If a pin does not have an assigned GPIO, its address is 0.
const uint32_t k_gpio_mux_registers[HW_GPIO_INSTANCE_COUNT][GPIO_PIN_COUNT] = {
// Bank 1
{
HW_IOMUXC_SW_MUX_CTL_PAD_GPIO00_ADDR, // Pin 0
HW_IOMUXC_SW_MUX_CTL_PAD_GPIO01_ADDR, // Pin 1
HW_IOMUXC_SW_MUX_CTL_PAD_GPIO02_ADDR, // Pin 2
HW_IOMUXC_SW_MUX_CTL_PAD_GPIO03_ADDR, // Pin 3
HW_IOMUXC_SW_MUX_CTL_PAD_GPIO04_ADDR, // Pin 4
HW_IOMUXC_SW_MUX_CTL_PAD_GPIO05_ADDR, // Pin 5
HW_IOMUXC_SW_MUX_CTL_PAD_GPIO06_ADDR, // Pin 6
HW_IOMUXC_SW_MUX_CTL_PAD_GPIO07_ADDR, // Pin 7
HW_IOMUXC_SW_MUX_CTL_PAD_GPIO08_ADDR, // Pin 8
HW_IOMUXC_SW_MUX_CTL_PAD_GPIO09_ADDR, // Pin 9
HW_IOMUXC_SW_MUX_CTL_PAD_SD2_CLK_ADDR, // Pin 10
HW_IOMUXC_SW_MUX_CTL_PAD_SD2_CMD_ADDR, // Pin 11
HW_IOMUXC_SW_MUX_CTL_PAD_SD2_DATA3_ADDR, // Pin 12
HW_IOMUXC_SW_MUX_CTL_PAD_SD2_DATA2_ADDR, // Pin 13
HW_IOMUXC_SW_MUX_CTL_PAD_SD2_DATA1_ADDR, // Pin 14
HW_IOMUXC_SW_MUX_CTL_PAD_SD2_DATA0_ADDR, // Pin 15
HW_IOMUXC_SW_MUX_CTL_PAD_SD1_DATA0_ADDR, // Pin 16
HW_IOMUXC_SW_MUX_CTL_PAD_SD1_DATA1_ADDR, // Pin 17
HW_IOMUXC_SW_MUX_CTL_PAD_SD1_CMD_ADDR, // Pin 18
HW_IOMUXC_SW_MUX_CTL_PAD_SD1_DATA2_ADDR, // Pin 19
HW_IOMUXC_SW_MUX_CTL_PAD_SD1_CLK_ADDR, // Pin 20
HW_IOMUXC_SW_MUX_CTL_PAD_SD1_DATA3_ADDR, // Pin 21
HW_IOMUXC_SW_MUX_CTL_PAD_ENET_MDIO_ADDR, // Pin 22
HW_IOMUXC_SW_MUX_CTL_PAD_ENET_REF_CLK_ADDR, // Pin 23
HW_IOMUXC_SW_MUX_CTL_PAD_ENET_RX_ER_ADDR, // Pin 24
HW_IOMUXC_SW_MUX_CTL_PAD_ENET_CRS_DV_ADDR, // Pin 25
HW_IOMUXC_SW_MUX_CTL_PAD_ENET_RX_DATA1_ADDR, // Pin 26
HW_IOMUXC_SW_MUX_CTL_PAD_ENET_RX_DATA0_ADDR, // Pin 27
HW_IOMUXC_SW_MUX_CTL_PAD_ENET_TX_EN_ADDR, // Pin 28
HW_IOMUXC_SW_MUX_CTL_PAD_ENET_TX_DATA1_ADDR, // Pin 29
HW_IOMUXC_SW_MUX_CTL_PAD_ENET_TX_DATA0_ADDR, // Pin 30
HW_IOMUXC_SW_MUX_CTL_PAD_ENET_MDC_ADDR, // Pin 31
},
// Bank 2
{
HW_IOMUXC_SW_MUX_CTL_PAD_NAND_DATA00_ADDR, // Pin 0
HW_IOMUXC_SW_MUX_CTL_PAD_NAND_DATA01_ADDR, // Pin 1
HW_IOMUXC_SW_MUX_CTL_PAD_NAND_DATA02_ADDR, // Pin 2
HW_IOMUXC_SW_MUX_CTL_PAD_NAND_DATA03_ADDR, // Pin 3
HW_IOMUXC_SW_MUX_CTL_PAD_NAND_DATA04_ADDR, // Pin 4
HW_IOMUXC_SW_MUX_CTL_PAD_NAND_DATA05_ADDR, // Pin 5
HW_IOMUXC_SW_MUX_CTL_PAD_NAND_DATA06_ADDR, // Pin 6
HW_IOMUXC_SW_MUX_CTL_PAD_NAND_DATA07_ADDR, // Pin 7
HW_IOMUXC_SW_MUX_CTL_PAD_SD4_DATA0_ADDR, // Pin 8
HW_IOMUXC_SW_MUX_CTL_PAD_SD4_DATA1_ADDR, // Pin 9
HW_IOMUXC_SW_MUX_CTL_PAD_SD4_DATA2_ADDR, // Pin 10
HW_IOMUXC_SW_MUX_CTL_PAD_SD4_DATA3_ADDR, // Pin 11
HW_IOMUXC_SW_MUX_CTL_PAD_SD4_DATA4_ADDR, // Pin 12
HW_IOMUXC_SW_MUX_CTL_PAD_SD4_DATA5_ADDR, // Pin 13
HW_IOMUXC_SW_MUX_CTL_PAD_SD4_DATA6_ADDR, // Pin 14
HW_IOMUXC_SW_MUX_CTL_PAD_SD4_DATA7_ADDR, // Pin 15
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_ADDR22_ADDR, // Pin 16
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_ADDR21_ADDR, // Pin 17
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_ADDR20_ADDR, // Pin 18
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_ADDR19_ADDR, // Pin 19
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_ADDR18_ADDR, // Pin 20
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_ADDR17_ADDR, // Pin 21
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_ADDR16_ADDR, // Pin 22
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_CS0_ADDR, // Pin 23
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_CS1_ADDR, // Pin 24
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_OE_ADDR, // Pin 25
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_RW_ADDR, // Pin 26
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_LBA_ADDR, // Pin 27
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_EB0_ADDR, // Pin 28
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_EB1_ADDR, // Pin 29
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_EB2_ADDR, // Pin 30
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_EB3_ADDR, // Pin 31
},
// Bank 3
{
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_AD00_ADDR, // Pin 0
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_AD01_ADDR, // Pin 1
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_AD02_ADDR, // Pin 2
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_AD03_ADDR, // Pin 3
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_AD04_ADDR, // Pin 4
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_AD05_ADDR, // Pin 5
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_AD06_ADDR, // Pin 6
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_AD07_ADDR, // Pin 7
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_AD08_ADDR, // Pin 8
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_AD09_ADDR, // Pin 9
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_AD10_ADDR, // Pin 10
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_AD11_ADDR, // Pin 11
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_AD12_ADDR, // Pin 12
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_AD13_ADDR, // Pin 13
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_AD14_ADDR, // Pin 14
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_AD15_ADDR, // Pin 15
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_DATA16_ADDR, // Pin 16
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_DATA17_ADDR, // Pin 17
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_DATA18_ADDR, // Pin 18
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_DATA19_ADDR, // Pin 19
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_DATA20_ADDR, // Pin 20
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_DATA21_ADDR, // Pin 21
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_DATA22_ADDR, // Pin 22
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_DATA23_ADDR, // Pin 23
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_DATA24_ADDR, // Pin 24
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_DATA25_ADDR, // Pin 25
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_DATA26_ADDR, // Pin 26
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_DATA27_ADDR, // Pin 27
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_DATA28_ADDR, // Pin 28
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_DATA29_ADDR, // Pin 29
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_DATA30_ADDR, // Pin 30
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_DATA31_ADDR, // Pin 31
},
// Bank 4
{
HW_IOMUXC_SW_MUX_CTL_PAD_GPIO19_ADDR, // Pin 5
HW_IOMUXC_SW_MUX_CTL_PAD_KEY_COL0_ADDR, // Pin 6
HW_IOMUXC_SW_MUX_CTL_PAD_KEY_ROW0_ADDR, // Pin 7
HW_IOMUXC_SW_MUX_CTL_PAD_KEY_COL1_ADDR, // Pin 8
HW_IOMUXC_SW_MUX_CTL_PAD_KEY_ROW1_ADDR, // Pin 9
HW_IOMUXC_SW_MUX_CTL_PAD_KEY_COL2_ADDR, // Pin 10
HW_IOMUXC_SW_MUX_CTL_PAD_KEY_ROW2_ADDR, // Pin 11
HW_IOMUXC_SW_MUX_CTL_PAD_KEY_COL3_ADDR, // Pin 12
HW_IOMUXC_SW_MUX_CTL_PAD_KEY_ROW3_ADDR, // Pin 13
HW_IOMUXC_SW_MUX_CTL_PAD_KEY_COL4_ADDR, // Pin 14
HW_IOMUXC_SW_MUX_CTL_PAD_KEY_ROW4_ADDR, // Pin 15
HW_IOMUXC_SW_MUX_CTL_PAD_DI0_DISP_CLK_ADDR, // Pin 16
HW_IOMUXC_SW_MUX_CTL_PAD_DI0_PIN15_ADDR, // Pin 17
HW_IOMUXC_SW_MUX_CTL_PAD_DI0_PIN02_ADDR, // Pin 18
HW_IOMUXC_SW_MUX_CTL_PAD_DI0_PIN03_ADDR, // Pin 19
HW_IOMUXC_SW_MUX_CTL_PAD_DI0_PIN04_ADDR, // Pin 20
HW_IOMUXC_SW_MUX_CTL_PAD_DISP0_DATA00_ADDR, // Pin 21
HW_IOMUXC_SW_MUX_CTL_PAD_DISP0_DATA01_ADDR, // Pin 22
HW_IOMUXC_SW_MUX_CTL_PAD_DISP0_DATA02_ADDR, // Pin 23
HW_IOMUXC_SW_MUX_CTL_PAD_DISP0_DATA03_ADDR, // Pin 24
HW_IOMUXC_SW_MUX_CTL_PAD_DISP0_DATA04_ADDR, // Pin 25
HW_IOMUXC_SW_MUX_CTL_PAD_DISP0_DATA05_ADDR, // Pin 26
HW_IOMUXC_SW_MUX_CTL_PAD_DISP0_DATA06_ADDR, // Pin 27
HW_IOMUXC_SW_MUX_CTL_PAD_DISP0_DATA07_ADDR, // Pin 28
HW_IOMUXC_SW_MUX_CTL_PAD_DISP0_DATA08_ADDR, // Pin 29
HW_IOMUXC_SW_MUX_CTL_PAD_DISP0_DATA09_ADDR, // Pin 30
HW_IOMUXC_SW_MUX_CTL_PAD_DISP0_DATA10_ADDR, // Pin 31
},
// Bank 5
{
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_WAIT_ADDR, // Pin 0
0, // Unassigned GPIO pin 1
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_ADDR25_ADDR, // Pin 2
0, // Unassigned GPIO pin 3
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_ADDR24_ADDR, // Pin 4
HW_IOMUXC_SW_MUX_CTL_PAD_DISP0_DATA11_ADDR, // Pin 5
HW_IOMUXC_SW_MUX_CTL_PAD_DISP0_DATA12_ADDR, // Pin 6
HW_IOMUXC_SW_MUX_CTL_PAD_DISP0_DATA13_ADDR, // Pin 7
HW_IOMUXC_SW_MUX_CTL_PAD_DISP0_DATA14_ADDR, // Pin 8
HW_IOMUXC_SW_MUX_CTL_PAD_DISP0_DATA15_ADDR, // Pin 9
HW_IOMUXC_SW_MUX_CTL_PAD_DISP0_DATA16_ADDR, // Pin 10
HW_IOMUXC_SW_MUX_CTL_PAD_DISP0_DATA17_ADDR, // Pin 11
HW_IOMUXC_SW_MUX_CTL_PAD_DISP0_DATA18_ADDR, // Pin 12
HW_IOMUXC_SW_MUX_CTL_PAD_DISP0_DATA19_ADDR, // Pin 13
HW_IOMUXC_SW_MUX_CTL_PAD_DISP0_DATA20_ADDR, // Pin 14
HW_IOMUXC_SW_MUX_CTL_PAD_DISP0_DATA21_ADDR, // Pin 15
HW_IOMUXC_SW_MUX_CTL_PAD_DISP0_DATA22_ADDR, // Pin 16
HW_IOMUXC_SW_MUX_CTL_PAD_DISP0_DATA23_ADDR, // Pin 17
HW_IOMUXC_SW_MUX_CTL_PAD_CSI0_PIXCLK_ADDR, // Pin 18
HW_IOMUXC_SW_MUX_CTL_PAD_CSI0_HSYNC_ADDR, // Pin 19
HW_IOMUXC_SW_MUX_CTL_PAD_CSI0_DATA_EN_ADDR, // Pin 20
HW_IOMUXC_SW_MUX_CTL_PAD_CSI0_VSYNC_ADDR, // Pin 21
HW_IOMUXC_SW_MUX_CTL_PAD_CSI0_DATA04_ADDR, // Pin 22
HW_IOMUXC_SW_MUX_CTL_PAD_CSI0_DATA05_ADDR, // Pin 23
HW_IOMUXC_SW_MUX_CTL_PAD_CSI0_DATA06_ADDR, // Pin 24
HW_IOMUXC_SW_MUX_CTL_PAD_CSI0_DATA07_ADDR, // Pin 25
HW_IOMUXC_SW_MUX_CTL_PAD_CSI0_DATA08_ADDR, // Pin 26
HW_IOMUXC_SW_MUX_CTL_PAD_CSI0_DATA09_ADDR, // Pin 27
HW_IOMUXC_SW_MUX_CTL_PAD_CSI0_DATA10_ADDR, // Pin 28
HW_IOMUXC_SW_MUX_CTL_PAD_CSI0_DATA11_ADDR, // Pin 29
HW_IOMUXC_SW_MUX_CTL_PAD_CSI0_DATA12_ADDR, // Pin 30
HW_IOMUXC_SW_MUX_CTL_PAD_CSI0_DATA13_ADDR, // Pin 31
},
// Bank 6
{
HW_IOMUXC_SW_MUX_CTL_PAD_CSI0_DATA14_ADDR, // Pin 0
HW_IOMUXC_SW_MUX_CTL_PAD_CSI0_DATA15_ADDR, // Pin 1
HW_IOMUXC_SW_MUX_CTL_PAD_CSI0_DATA16_ADDR, // Pin 2
HW_IOMUXC_SW_MUX_CTL_PAD_CSI0_DATA17_ADDR, // Pin 3
HW_IOMUXC_SW_MUX_CTL_PAD_CSI0_DATA18_ADDR, // Pin 4
HW_IOMUXC_SW_MUX_CTL_PAD_CSI0_DATA19_ADDR, // Pin 5
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_ADDR23_ADDR, // Pin 6
HW_IOMUXC_SW_MUX_CTL_PAD_NAND_CLE_ADDR, // Pin 7
HW_IOMUXC_SW_MUX_CTL_PAD_NAND_ALE_ADDR, // Pin 8
HW_IOMUXC_SW_MUX_CTL_PAD_NAND_WP_B_ADDR, // Pin 9
HW_IOMUXC_SW_MUX_CTL_PAD_NAND_READY_ADDR, // Pin 10
HW_IOMUXC_SW_MUX_CTL_PAD_NAND_CS0_B_ADDR, // Pin 11
0, // Unassigned GPIO pin 12
0, // Unassigned GPIO pin 13
HW_IOMUXC_SW_MUX_CTL_PAD_NAND_CS1_B_ADDR, // Pin 14
HW_IOMUXC_SW_MUX_CTL_PAD_NAND_CS2_B_ADDR, // Pin 15
HW_IOMUXC_SW_MUX_CTL_PAD_NAND_CS3_B_ADDR, // Pin 16
HW_IOMUXC_SW_MUX_CTL_PAD_SD3_DATA7_ADDR, // Pin 17
HW_IOMUXC_SW_MUX_CTL_PAD_SD3_DATA6_ADDR, // Pin 18
HW_IOMUXC_SW_MUX_CTL_PAD_RGMII_TXC_ADDR, // Pin 19
HW_IOMUXC_SW_MUX_CTL_PAD_RGMII_TD0_ADDR, // Pin 20
HW_IOMUXC_SW_MUX_CTL_PAD_RGMII_TD1_ADDR, // Pin 21
HW_IOMUXC_SW_MUX_CTL_PAD_RGMII_TD2_ADDR, // Pin 22
HW_IOMUXC_SW_MUX_CTL_PAD_RGMII_TD3_ADDR, // Pin 23
HW_IOMUXC_SW_MUX_CTL_PAD_RGMII_RX_CTL_ADDR, // Pin 24
HW_IOMUXC_SW_MUX_CTL_PAD_RGMII_RD0_ADDR, // Pin 25
HW_IOMUXC_SW_MUX_CTL_PAD_RGMII_TX_CTL_ADDR, // Pin 26
HW_IOMUXC_SW_MUX_CTL_PAD_RGMII_RD1_ADDR, // Pin 27
HW_IOMUXC_SW_MUX_CTL_PAD_RGMII_RD2_ADDR, // Pin 28
HW_IOMUXC_SW_MUX_CTL_PAD_RGMII_RD3_ADDR, // Pin 29
HW_IOMUXC_SW_MUX_CTL_PAD_RGMII_RXC_ADDR, // Pin 30
HW_IOMUXC_SW_MUX_CTL_PAD_EIM_BCLK_ADDR, // Pin 31
},
// Bank 7
{
HW_IOMUXC_SW_MUX_CTL_PAD_SD3_DATA5_ADDR, // Pin 0
HW_IOMUXC_SW_MUX_CTL_PAD_SD3_DATA4_ADDR, // Pin 1
HW_IOMUXC_SW_MUX_CTL_PAD_SD3_CMD_ADDR, // Pin 2
HW_IOMUXC_SW_MUX_CTL_PAD_SD3_CLK_ADDR, // Pin 3
HW_IOMUXC_SW_MUX_CTL_PAD_SD3_DATA0_ADDR, // Pin 4
HW_IOMUXC_SW_MUX_CTL_PAD_SD3_DATA1_ADDR, // Pin 5
HW_IOMUXC_SW_MUX_CTL_PAD_SD3_DATA2_ADDR, // Pin 6
HW_IOMUXC_SW_MUX_CTL_PAD_SD3_DATA3_ADDR, // Pin 7
HW_IOMUXC_SW_MUX_CTL_PAD_SD3_RESET_ADDR, // Pin 8
HW_IOMUXC_SW_MUX_CTL_PAD_SD4_CMD_ADDR, // Pin 9
HW_IOMUXC_SW_MUX_CTL_PAD_SD4_CLK_ADDR, // Pin 10
HW_IOMUXC_SW_MUX_CTL_PAD_GPIO16_ADDR, // Pin 11
HW_IOMUXC_SW_MUX_CTL_PAD_GPIO17_ADDR, // Pin 12
HW_IOMUXC_SW_MUX_CTL_PAD_GPIO18_ADDR, // Pin 13
0, // Unassigned GPIO pin 14
0, // Unassigned GPIO pin 15
0, // Unassigned GPIO pin 16
0, // Unassigned GPIO pin 17
0, // Unassigned GPIO pin 18
0, // Unassigned GPIO pin 19
0, // Unassigned GPIO pin 20
0, // Unassigned GPIO pin 21
0, // Unassigned GPIO pin 22
0, // Unassigned GPIO pin 23
0, // Unassigned GPIO pin 24
0, // Unassigned GPIO pin 25
0, // Unassigned GPIO pin 26
0, // Unassigned GPIO pin 27
0, // Unassigned GPIO pin 28
0, // Unassigned GPIO pin 29
0, // Unassigned GPIO pin 30
0, // Unassigned GPIO pin 31
},
};
// v1/121109/1.2.3
// EOF

View File

@ -0,0 +1,150 @@
/*
* 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.
*/
#ifndef _CCM_PLL_H_
#define _CCM_PLL_H_
#include "sdk_types.h"
//! @addtogroup diag_clocks
//! @{
////////////////////////////////////////////////////////////////////////////////
// Definitions
////////////////////////////////////////////////////////////////////////////////
#define CLK_SRC_32K 32768
//! @brief Create a clock gate bit mask value.
//! @param x 0..15, for CG0 to CG15
#define CG(x) (3 << (x*2))
//! @brief Constants for CCM CCGR register fields.
enum _clock_gate_constants
{
CLOCK_ON = 0x3, //!< Clock always on in both run and stop modes.
CLOCK_ON_RUN = 0x1, //!< Clock on only in run mode.
CLOCK_OFF = 0x0 //!< Clocked gated off.
};
//! @brief Low power mdoes.
typedef enum _lp_modes {
RUN_MODE,
WAIT_MODE,
STOP_MODE,
} lp_modes_t;
//! @brief Main clock sources.
typedef enum _main_clocks {
CPU_CLK,
AXI_CLK,
MMDC_CH0_AXI_CLK,
AHB_CLK,
IPG_CLK,
IPG_PER_CLK,
MMDC_CH1_AXI_CLK,
} main_clocks_t;
//! @brief Peripheral clocks.
typedef enum _peri_clocks {
UART1_MODULE_CLK,
UART2_MODULE_CLK,
UART3_MODULE_CLK,
UART4_MODULE_CLK,
SSI1_BAUD,
SSI2_BAUD,
CSI_BAUD,
MSTICK1_CLK,
MSTICK2_CLK,
RAWNAND_CLK,
USB_CLK,
VPU_CLK,
SPI_CLK,
CAN_CLK
} peri_clocks_t;
//! @brief Available PLLs.
typedef enum plls {
PLL1,
PLL2,
PLL3,
PLL4,
PLL5,
} plls_t;
extern const uint32_t PLL1_OUTPUT;
extern const uint32_t PLL2_OUTPUT[];
extern const uint32_t PLL3_OUTPUT[];
extern const uint32_t PLL4_OUTPUT;
extern const uint32_t PLL5_OUTPUT;
////////////////////////////////////////////////////////////////////////////////
// API
////////////////////////////////////////////////////////////////////////////////
#if defined(__cplusplus)
extern "C" {
#endif
//! @brief Set/unset clock gating for a peripheral.
//! @param base_address configure clock gating for that module from the base address.
//! @param gating_mode clock gating mode: CLOCK_ON or CLOCK_OFF.
void clock_gating_config(uint32_t base_address, uint32_t gating_mode);
//! @brief Returns the frequency of a clock in megahertz.
uint32_t get_main_clock(main_clocks_t clk);
//! @brief Returns the frequency of a clock in megahertz.
uint32_t get_peri_clock(peri_clocks_t clk);
//! @brief Inits clock sources.
void ccm_init(void);
//! @brief Prepare and enter in a low power mode.
//! @param lp_mode low power mode : WAIT_MODE or STOP_MODE.
void ccm_enter_low_power(lp_modes_t lp_mode);
//! @brief Mask/unmask an interrupt source that can wake up the processor when in a
//! low power mode.
//!
//! @param irq_id ID of the interrupt to mask/unmask.
//! @param doEnable Pass true to unmask the source ID.
void ccm_set_lpm_wakeup_source(uint32_t irq_id, bool doEnable);
#if defined(__cplusplus)
}
#endif
//! @}
#endif
////////////////////////////////////////////////////////////////////////////////
// EOF
////////////////////////////////////////////////////////////////////////////////

View File

@ -0,0 +1,200 @@
/*
* Copyright (c) 2011-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 gpio.h
* @brief Defines related to the GPIO controller and used by gpio.c
* @ingroup diag_gpio
*/
#ifndef __GPIO_H__
#define __GPIO_H__
#include <stddef.h>
#include <stdint.h>
//! @addtogroup diag_gpio
//! @{
////////////////////////////////////////////////////////////////////////////////
// Definitions
////////////////////////////////////////////////////////////////////////////////
//! @brief Available GPIO ports.
typedef enum {
GPIO_NONE = 0,
GPIO_PORT1 = 1,
GPIO_PORT2 = 2,
GPIO_PORT3 = 3,
GPIO_PORT4 = 4,
GPIO_PORT5 = 5,
GPIO_PORT6 = 6,
GPIO_PORT7 = 7,
} GPIO_PORT;
//! @name GPIO bitfield values
//@{
#define GPIO_GDIR_INPUT 0 //!< GPIO pin is input
#define GPIO_GDIR_OUTPUT 1 //!< GPIO pin is output
#define GPIO_LOW_LEVEL 0 //!< GPIO pin is low
#define GPIO_HIGH_LEVEL 1 //!< GPIO pin is high
#define GPIO_ICR_LOW_LEVEL 0 //!< Interrupt is low-level
#define GPIO_ICR_HIGH_LEVEL 1 //!< Interrupt is high-level
#define GPIO_ICR_RISE_EDGE 2 //!< Interrupt is rising edge
#define GPIO_ICR_FALL_EDGE 3 //!< Interrupt is falling edge
#define GPIO_IMR_MASKED 0 //!< Interrupt is masked
#define GPIO_IMR_UNMASKED 1 //!< Interrupt is unmasked
#define GPIO_ISR_NOT_ASSERTED 0 //!< Interrupt is not asserted
#define GPIO_ISR_ASSERTED 1 //!< Interrupt is asserted
#define GPIO_EDGE_SEL_DISABLE 0 //!< Edge select is disabled
#define GPIO_EDGE_SEL_ENABLE 1 //!< Edge select is enabled
//@}
////////////////////////////////////////////////////////////////////////////////
// API
////////////////////////////////////////////////////////////////////////////////
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @brief Returns the number of available GPIO instances.
* @return An integer number of GPIO instances on this hardware.
*/
int32_t gpio_get_port_count(void);
/*!
* @brief Sets a GPIO pin to GPIO mode in the IOMUX controller.
*
* @retval SUCCESS
* @retval INVALID_PARAMETER
*/
int gpio_set_gpio(int32_t port, int32_t pin);
/*!
* @brief Sets the GPIO direction for the specified pin.
*
* @param port GPIO module instance, GPIO_PORT1, GPIO_PORT2, ... gpio_get_port_count().
* @param pin GPIO pin 0 to 31.
* @param dir Direction for the pin. GPIO_GDIR_INPUT(0) or GPIO_GDIR_OUTPUT(1).
* @return INVALID_PARAMETER(-1)
*/
int32_t gpio_set_direction(int32_t port, int32_t pin, int32_t dir);
/*!
* @brief Returns the current direction for the specified pin.
*
* @param port GPIO module instance, GPIO_PORT1, GPIO_PORT2, ... gpio_get_port_count().
* @param pin GPIO pin 0 to 31.
* @retval GPIO_GDIR_INPUT The pin is currently set as an input.
* @retval GPIO_GDIR_OUTPUT The pin is currently set as an output.
*/
int32_t gpio_get_direction(int32_t port, int32_t pin);
/*!
* @brief Sets the GPIO level(high or low) for the specified pin.
*
* @warning Fails if pin is not configured as an output.
*
* @param port GPIO module instance, GPIO_PORT1, GPIO_PORT2, ... gpio_get_port_count().
* @param pin GPIO pin 0 to 31.
* @param level GPIO_LOW_LEVEL(0), GPIO_HIGH_LEVEL(1)
* @return INVALID_PARAMETER(-1)
*/
int32_t gpio_set_level(int32_t port, int32_t pin, uint32_t level);
/*!
* Gets the GPIO level(high or low) for the specified pin.
*
* @note Returns level for both input and output configured pins.
*
* @param port GPIO module instance, GPIO_PORT1, GPIO_PORT2, ... gpio_get_port_count().
* @param pin GPIO pin 0 to 31.
* @retval INVALID_PARAMETER(-1),
* @retval GPIO_LOW_LEVEL(0),
* @retval GPIO_HIGH_LEVEL(1)
*/
int32_t gpio_get_level(int32_t port, int32_t pin);
/*!
* @brief Configures the interrupt condition for the specified GPIO input pin.
*
* @param port GPIO module instance, GPIO_PORT1, GPIO_PORT2, ... gpio_get_port_count().
* @param pin GPIO pin 0 to 31.
* @param config Interrupt condition for the pin. GPIO_ICR_LOW_LEVEL(0), GPIO_ICR_HIGH_LEVEL(1),
* GPIO_ICR_RISE_EDGE(2), GPIO_ICR_FALL_EDGE(3)
* @return INVALID_PARAMETER(-1)
*/
int32_t gpio_set_interrupt_config(int32_t port, int32_t pin, int32_t config);
/*!
* @brief Enables/Disables the interrupt for the specified GPIO input pin.
*
* @param port GPIO module instance, GPIO_PORT1, GPIO_PORT2, ... gpio_get_port_count().
* @param pin GPIO pin 0 to 31.
* @param mask interrupt mask for the pin. GPIO_IMR_MASKED(0), GPIO_IMR_UNMASKED(1)
* @return INVALID_PARAMETER(-1)
*/
int32_t gpio_set_interrupt_mask(int32_t port, int32_t pin, int32_t mask);
/*!
* @brief Gets the GPIO interrupt status for the specified pin.
*
* @param port GPIO module instance, GPIO_PORT1, GPIO_PORT2, ... gpio_get_port_count().
* @param pin GPIO pin 0 to 31.
* @return INVALID_PARAMETER(-1), GPIO_ISR_NOT_ASSERTED(0), GPIO_ISR_ASSERTED(1)
*/
int32_t gpio_get_interrupt_status(int32_t port, int32_t pin);
/*!
* @brief Clears the GPIO interrupt for the specified pin.
*
* @param port GPIO module instance, GPIO_PORT1, GPIO_PORT2, ... gpio_get_port_count().
* @param pin GPIO pin 0 to 31.
* @return INVALID_PARAMETER(-1)
*/
int32_t gpio_clear_interrupt(int32_t port, int32_t pin);
#if defined(__cplusplus)
}
#endif
//! @}
#endif //__GPIO_H__
////////////////////////////////////////////////////////////////////////////////
// EOF
////////////////////////////////////////////////////////////////////////////////

View File

@ -0,0 +1,74 @@
/*
* Copyright (c) 2011-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 gpio_map.h
* @brief
* @ingroup diag_gpio
*/
#ifndef __GPIO_MAP_H__
#define __GPIO_MAP_H__
#include "regsgpio.h"
#include <stdint.h>
//! @addtogroup diag_gpio
//! @{
////////////////////////////////////////////////////////////////////////////////
// Definitions
////////////////////////////////////////////////////////////////////////////////
//! @brief Number of pins per GPIO bank.
#define GPIO_PIN_COUNT (32)
//! @brief Table to map GPIO pins to their mux control register addresses.
//!
//! First subscript is bank, second is pin within the bank. There are always 32 pin
//! entries per bank. If a pin does not have an assigned GPIO, its address is 0.
//!
//! Example code to set GPIO 3,12 to GPIO mode:
//! @code
//! uint32_t addr = k_gpio_mux_registers[3][12];
//! volatile uint32_t * reg = (volatile uint32_t *)addr;
//! *reg = (*reg & ~BM_IOMUXC_SW_MUX_CTL_PAD_GPIO00_MUX_MODE)
//! | BF_IOMUXC_SW_MUX_CTL_PAD_GPIO00_MUX_MODE_V(ALT5);
//! @endcode
//!
//! The code above uses the bit field macros from an arbitrary mux register definition.
extern const uint32_t k_gpio_mux_registers[HW_GPIO_INSTANCE_COUNT][GPIO_PIN_COUNT];
//! @}
#endif //__GPIO_MAP_H__
////////////////////////////////////////////////////////////////////////////////
// EOF
////////////////////////////////////////////////////////////////////////////////

View File

@ -0,0 +1,125 @@
/*
* Copyright (c) 2012, Freescale Semiconductor, Inc.
* All rights reserved.
*
* 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: iomux_config.h
/* ------------------------------------------------------------------------------
* <auto-generated>
* This code was generated by a tool.
* Runtime Version:3.4.0.3
*
* Changes to this file may cause incorrect behavior and will be lost if
* the code is regenerated.
* </auto-generated>
* ------------------------------------------------------------------------------
*/
#ifndef _IOMUX_CONFIG_H_
#define _IOMUX_CONFIG_H_
// Board and Module IOMUXC configuration function prototypes.
#if defined(__cplusplus)
extern "C" {
#endif
// Board IOMUXC configuration function.
void iomux_config(void);
// Module IOMUXC configuration functions.
void arm_iomux_config(void);
void asrc_iomux_config(void);
void audmux_iomux_config(void);
void ccm_iomux_config(void);
void dcic_iomux_config(int instance);
void dcic1_iomux_config(void);
void dcic2_iomux_config(void);
void ecspi_iomux_config(int instance);
void ecspi1_iomux_config(void);
void ecspi2_iomux_config(void);
void ecspi3_iomux_config(void);
void ecspi4_iomux_config(void);
void ecspi5_iomux_config(void);
void eim_iomux_config(void);
void enet_iomux_config(void);
void enet_iomux_reconfig(void);
void epit_iomux_config(int instance);
void epit1_iomux_config(void);
void epit2_iomux_config(void);
void esai_iomux_config(void);
void flexcan_iomux_config(int instance);
void flexcan1_iomux_config(void);
void flexcan2_iomux_config(void);
void gpio_iomux_config(int instance);
void gpio1_iomux_config(void);
void gpio2_iomux_config(void);
void gpio3_iomux_config(void);
void gpio4_iomux_config(void);
void gpio5_iomux_config(void);
void gpio6_iomux_config(void);
void gpio7_iomux_config(void);
void gpmi_iomux_config(void);
void gpt_iomux_config(void);
void hdmi_iomux_config(void);
void i2c_iomux_config(int instance);
void i2c1_iomux_config(void);
void i2c2_iomux_config(void);
void i2c3_iomux_config(void);
void ipu_iomux_config(int instance);
void ipu1_iomux_config(void);
void ipu2_iomux_config(void);
void kpp_iomux_config(void);
void ldb_iomux_config(void);
void mipi_csi_iomux_config(void);
void mipi_dsi_iomux_config(void);
void mipi_hsi_iomux_config(void);
void mlb_iomux_config(void);
void mmdc_iomux_config(void);
void pcie_iomux_config(void);
void pmu_iomux_config(void);
void pwm_iomux_config(int instance);
void pwm1_iomux_config(void);
void pwm2_iomux_config(void);
void pwm3_iomux_config(void);
void pwm4_iomux_config(void);
void sata_phy_iomux_config(void);
void sdma_iomux_config(void);
void sjc_iomux_config(void);
void snvs_iomux_config(void);
void spdif_iomux_config(void);
void src_iomux_config(void);
void uart_iomux_config(int instance);
void uart1_iomux_config(void);
void uart2_iomux_config(void);
void uart3_iomux_config(void);
void uart4_iomux_config(void);
void uart5_iomux_config(void);
void usb_iomux_config(void);
void usdhc_iomux_config(int instance);
void usdhc1_iomux_config(void);
void usdhc2_iomux_config(void);
void usdhc3_iomux_config(void);
void usdhc4_iomux_config(void);
void wdog_iomux_config(int instance);
void wdog1_iomux_config(void);
void wdog2_iomux_config(void);
void xtalosc_iomux_config(void);
#if defined(__cplusplus)
}
#endif
#endif // _IOMUX_CONFIG_H_

View File

@ -0,0 +1,482 @@
/*
* Copyright (c) 2012, Freescale Semiconductor, Inc.
* All rights reserved.
*
* THIS SOFTWARE IS PROVIDED BY FREESCALE "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 FREESCALE 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.
*/
#ifndef _REGS_H
#define _REGS_H 1
//
// define base address of the register block only if it is not already
// defined, which allows the compiler to override at build time for
// users who've mapped their registers to locations other than the
// physical location
//
#ifndef REGS_BASE
#define REGS_BASE 0x00000000
#endif
//
// common register types
//
#ifndef __LANGUAGE_ASM__
#include <stddef.h>
#include <stdint.h>
typedef uint8_t reg8_t;
typedef uint16_t reg16_t;
typedef uint32_t reg32_t;
#endif
//
// Typecast macro for C or asm. In C, the cast is applied, while in asm it is excluded. This is
// used to simplify macro definitions in the module register headers.
//
#ifndef __REG_VALUE_TYPE
#ifndef __LANGUAGE_ASM__
#define __REG_VALUE_TYPE(v, t) ((t)(v))
#else
#define __REG_VALUE_TYPE(v, t) (v)
#endif
#endif
//
// macros for single instance registers
//
#define BF_SET(reg, field) HW_##reg##_SET(BM_##reg##_##field)
#define BF_CLR(reg, field) HW_##reg##_CLR(BM_##reg##_##field)
#define BF_TOG(reg, field) HW_##reg##_TOG(BM_##reg##_##field)
#define BF_SETV(reg, field, v) HW_##reg##_SET(BF_##reg##_##field(v))
#define BF_CLRV(reg, field, v) HW_##reg##_CLR(BF_##reg##_##field(v))
#define BF_TOGV(reg, field, v) HW_##reg##_TOG(BF_##reg##_##field(v))
#define BV_FLD(reg, field, sym) BF_##reg##_##field(BV_##reg##_##field##__##sym)
#define BV_VAL(reg, field, sym) BV_##reg##_##field##__##sym
#define BF_RD(reg, field) HW_##reg.B.field
#define BF_WR(reg, field, v) BW_##reg##_##field(v)
#define BF_CS1(reg, f1, v1) \
(HW_##reg##_CLR(BM_##reg##_##f1), \
HW_##reg##_SET(BF_##reg##_##f1(v1)))
#define BF_CS2(reg, f1, v1, f2, v2) \
(HW_##reg##_CLR(BM_##reg##_##f1 | \
BM_##reg##_##f2), \
HW_##reg##_SET(BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2)))
#define BF_CS3(reg, f1, v1, f2, v2, f3, v3) \
(HW_##reg##_CLR(BM_##reg##_##f1 | \
BM_##reg##_##f2 | \
BM_##reg##_##f3), \
HW_##reg##_SET(BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2) | \
BF_##reg##_##f3(v3)))
#define BF_CS4(reg, f1, v1, f2, v2, f3, v3, f4, v4) \
(HW_##reg##_CLR(BM_##reg##_##f1 | \
BM_##reg##_##f2 | \
BM_##reg##_##f3 | \
BM_##reg##_##f4), \
HW_##reg##_SET(BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2) | \
BF_##reg##_##f3(v3) | \
BF_##reg##_##f4(v4)))
#define BF_CS5(reg, f1, v1, f2, v2, f3, v3, f4, v4, f5, v5) \
(HW_##reg##_CLR(BM_##reg##_##f1 | \
BM_##reg##_##f2 | \
BM_##reg##_##f3 | \
BM_##reg##_##f4 | \
BM_##reg##_##f5), \
HW_##reg##_SET(BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2) | \
BF_##reg##_##f3(v3) | \
BF_##reg##_##f4(v4) | \
BF_##reg##_##f5(v5)))
#define BF_CS6(reg, f1, v1, f2, v2, f3, v3, f4, v4, f5, v5, f6, v6) \
(HW_##reg##_CLR(BM_##reg##_##f1 | \
BM_##reg##_##f2 | \
BM_##reg##_##f3 | \
BM_##reg##_##f4 | \
BM_##reg##_##f5 | \
BM_##reg##_##f6), \
HW_##reg##_SET(BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2) | \
BF_##reg##_##f3(v3) | \
BF_##reg##_##f4(v4) | \
BF_##reg##_##f5(v5) | \
BF_##reg##_##f6(v6)))
#define BF_CS7(reg, f1, v1, f2, v2, f3, v3, f4, v4, f5, v5, f6, v6, f7, v7) \
(HW_##reg##_CLR(BM_##reg##_##f1 | \
BM_##reg##_##f2 | \
BM_##reg##_##f3 | \
BM_##reg##_##f4 | \
BM_##reg##_##f5 | \
BM_##reg##_##f6 | \
BM_##reg##_##f7), \
HW_##reg##_SET(BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2) | \
BF_##reg##_##f3(v3) | \
BF_##reg##_##f4(v4) | \
BF_##reg##_##f5(v5) | \
BF_##reg##_##f6(v6) | \
BF_##reg##_##f7(v7)))
#define BF_CS8(reg, f1, v1, f2, v2, f3, v3, f4, v4, f5, v5, f6, v6, f7, v7, f8, v8) \
(HW_##reg##_CLR(BM_##reg##_##f1 | \
BM_##reg##_##f2 | \
BM_##reg##_##f3 | \
BM_##reg##_##f4 | \
BM_##reg##_##f5 | \
BM_##reg##_##f6 | \
BM_##reg##_##f7 | \
BM_##reg##_##f8), \
HW_##reg##_SET(BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2) | \
BF_##reg##_##f3(v3) | \
BF_##reg##_##f4(v4) | \
BF_##reg##_##f5(v5) | \
BF_##reg##_##f6(v6) | \
BF_##reg##_##f7(v7) | \
BF_##reg##_##f8(v8)))
//
// macros for multiple instance registers
//
#define BF_SETn(reg, n, field) HW_##reg##_SET(n, BM_##reg##_##field)
#define BF_CLRn(reg, n, field) HW_##reg##_CLR(n, BM_##reg##_##field)
#define BF_TOGn(reg, n, field) HW_##reg##_TOG(n, BM_##reg##_##field)
#define BF_SETVn(reg, n, field, v) HW_##reg##_SET(n, BF_##reg##_##field(v))
#define BF_CLRVn(reg, n, field, v) HW_##reg##_CLR(n, BF_##reg##_##field(v))
#define BF_TOGVn(reg, n, field, v) HW_##reg##_TOG(n, BF_##reg##_##field(v))
#define BV_FLDn(reg, n, field, sym) BF_##reg##_##field(BV_##reg##_##field##__##sym)
#define BV_VALn(reg, n, field, sym) BV_##reg##_##field##__##sym
#define BF_RDn(reg, n, field) HW_##reg(n).B.field
#define BF_WRn(reg, n, field, v) BW_##reg##_##field(n, v)
#define BF_CS1n(reg, n, f1, v1) \
(HW_##reg##_CLR(n, (BM_##reg##_##f1)), \
HW_##reg##_SET(n, (BF_##reg##_##f1(v1))))
#define BF_CS2n(reg, n, f1, v1, f2, v2) \
(HW_##reg##_CLR(n, (BM_##reg##_##f1 | \
BM_##reg##_##f2)), \
HW_##reg##_SET(n, (BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2))))
#define BF_CS3n(reg, n, f1, v1, f2, v2, f3, v3) \
(HW_##reg##_CLR(n, (BM_##reg##_##f1 | \
BM_##reg##_##f2 | \
BM_##reg##_##f3)), \
HW_##reg##_SET(n, (BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2) | \
BF_##reg##_##f3(v3))))
#define BF_CS4n(reg, n, f1, v1, f2, v2, f3, v3, f4, v4) \
(HW_##reg##_CLR(n, (BM_##reg##_##f1 | \
BM_##reg##_##f2 | \
BM_##reg##_##f3 | \
BM_##reg##_##f4)), \
HW_##reg##_SET(n, (BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2) | \
BF_##reg##_##f3(v3) | \
BF_##reg##_##f4(v4))))
#define BF_CS5n(reg, n, f1, v1, f2, v2, f3, v3, f4, v4, f5, v5) \
(HW_##reg##_CLR(n, (BM_##reg##_##f1 | \
BM_##reg##_##f2 | \
BM_##reg##_##f3 | \
BM_##reg##_##f4 | \
BM_##reg##_##f5)), \
HW_##reg##_SET(n, (BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2) | \
BF_##reg##_##f3(v3) | \
BF_##reg##_##f4(v4) | \
BF_##reg##_##f5(v5))))
#define BF_CS6n(reg, n, f1, v1, f2, v2, f3, v3, f4, v4, f5, v5, f6, v6) \
(HW_##reg##_CLR(n, (BM_##reg##_##f1 | \
BM_##reg##_##f2 | \
BM_##reg##_##f3 | \
BM_##reg##_##f4 | \
BM_##reg##_##f5 | \
BM_##reg##_##f6)), \
HW_##reg##_SET(n, (BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2) | \
BF_##reg##_##f3(v3) | \
BF_##reg##_##f4(v4) | \
BF_##reg##_##f5(v5) | \
BF_##reg##_##f6(v6))))
#define BF_CS7n(reg, n, f1, v1, f2, v2, f3, v3, f4, v4, f5, v5, f6, v6, f7, v7) \
(HW_##reg##_CLR(n, (BM_##reg##_##f1 | \
BM_##reg##_##f2 | \
BM_##reg##_##f3 | \
BM_##reg##_##f4 | \
BM_##reg##_##f5 | \
BM_##reg##_##f6 | \
BM_##reg##_##f7)), \
HW_##reg##_SET(n, (BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2) | \
BF_##reg##_##f3(v3) | \
BF_##reg##_##f4(v4) | \
BF_##reg##_##f5(v5) | \
BF_##reg##_##f6(v6) | \
BF_##reg##_##f7(v7))))
#define BF_CS8n(reg, n, f1, v1, f2, v2, f3, v3, f4, v4, f5, v5, f6, v6, f7, v7, f8, v8) \
(HW_##reg##_CLR(n, (BM_##reg##_##f1 | \
BM_##reg##_##f2 | \
BM_##reg##_##f3 | \
BM_##reg##_##f4 | \
BM_##reg##_##f5 | \
BM_##reg##_##f6 | \
BM_##reg##_##f7 | \
BM_##reg##_##f8)), \
HW_##reg##_SET(n, (BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2) | \
BF_##reg##_##f3(v3) | \
BF_##reg##_##f4(v4) | \
BF_##reg##_##f5(v5) | \
BF_##reg##_##f6(v6) | \
BF_##reg##_##f7(v7) | \
BF_##reg##_##f8(v8))))
//
// macros for single instance MULTI-BLOCK registers
//
#define BFn_SET(reg, blk, field) HW_##reg##_SET(blk, BM_##reg##_##field)
#define BFn_CLR(reg, blk, field) HW_##reg##_CLR(blk, BM_##reg##_##field)
#define BFn_TOG(reg, blk, field) HW_##reg##_TOG(blk, BM_##reg##_##field)
#define BFn_SETV(reg, blk, field, v) HW_##reg##_SET(blk, BF_##reg##_##field(v))
#define BFn_CLRV(reg, blk, field, v) HW_##reg##_CLR(blk, BF_##reg##_##field(v))
#define BFn_TOGV(reg, blk, field, v) HW_##reg##_TOG(blk, BF_##reg##_##field(v))
#define BVn_FLD(reg, field, sym) BF_##reg##_##field(BV_##reg##_##field##__##sym)
#define BVn_VAL(reg, field, sym) BV_##reg##_##field##__##sym
#define BFn_RD(reg, blk, field) HW_##reg(blk).B.field
#define BFn_WR(reg, blk, field, v) BW_##reg##_##field(blk, v)
#define BFn_CS1(reg, blk, f1, v1) \
(HW_##reg##_CLR(blk, BM_##reg##_##f1), \
HW_##reg##_SET(blk, BF_##reg##_##f1(v1)))
#define BFn_CS2(reg, blk, f1, v1, f2, v2) \
(HW_##reg##_CLR(blk, BM_##reg##_##f1 | \
BM_##reg##_##f2), \
HW_##reg##_SET(blk, BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2)))
#define BFn_CS3(reg, blk, f1, v1, f2, v2, f3, v3) \
(HW_##reg##_CLR(blk, BM_##reg##_##f1 | \
BM_##reg##_##f2 | \
BM_##reg##_##f3), \
HW_##reg##_SET(blk, BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2) | \
BF_##reg##_##f3(v3)))
#define BFn_CS4(reg, blk, f1, v1, f2, v2, f3, v3, f4, v4) \
(HW_##reg##_CLR(blk, BM_##reg##_##f1 | \
BM_##reg##_##f2 | \
BM_##reg##_##f3 | \
BM_##reg##_##f4), \
HW_##reg##_SET(blk, BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2) | \
BF_##reg##_##f3(v3) | \
BF_##reg##_##f4(v4)))
#define BFn_CS5(reg, blk, f1, v1, f2, v2, f3, v3, f4, v4, f5, v5) \
(HW_##reg##_CLR(blk, BM_##reg##_##f1 | \
BM_##reg##_##f2 | \
BM_##reg##_##f3 | \
BM_##reg##_##f4 | \
BM_##reg##_##f5), \
HW_##reg##_SET(blk, BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2) | \
BF_##reg##_##f3(v3) | \
BF_##reg##_##f4(v4) | \
BF_##reg##_##f5(v5)))
#define BFn_CS6(reg, blk, f1, v1, f2, v2, f3, v3, f4, v4, f5, v5, f6, v6) \
(HW_##reg##_CLR(blk, BM_##reg##_##f1 | \
BM_##reg##_##f2 | \
BM_##reg##_##f3 | \
BM_##reg##_##f4 | \
BM_##reg##_##f5 | \
BM_##reg##_##f6), \
HW_##reg##_SET(blk, BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2) | \
BF_##reg##_##f3(v3) | \
BF_##reg##_##f4(v4) | \
BF_##reg##_##f5(v5) | \
BF_##reg##_##f6(v6)))
#define BFn_CS7(reg, blk, f1, v1, f2, v2, f3, v3, f4, v4, f5, v5, f6, v6, f7, v7) \
(HW_##reg##_CLR(blk, BM_##reg##_##f1 | \
BM_##reg##_##f2 | \
BM_##reg##_##f3 | \
BM_##reg##_##f4 | \
BM_##reg##_##f5 | \
BM_##reg##_##f6 | \
BM_##reg##_##f7), \
HW_##reg##_SET(blk, BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2) | \
BF_##reg##_##f3(v3) | \
BF_##reg##_##f4(v4) | \
BF_##reg##_##f5(v5) | \
BF_##reg##_##f6(v6) | \
BF_##reg##_##f7(v7)))
#define BFn_CS8(reg, blk, f1, v1, f2, v2, f3, v3, f4, v4, f5, v5, f6, v6, f7, v7, f8, v8) \
(HW_##reg##_CLR(blk, BM_##reg##_##f1 | \
BM_##reg##_##f2 | \
BM_##reg##_##f3 | \
BM_##reg##_##f4 | \
BM_##reg##_##f5 | \
BM_##reg##_##f6 | \
BM_##reg##_##f7 | \
BM_##reg##_##f8), \
HW_##reg##_SET(blk, BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2) | \
BF_##reg##_##f3(v3) | \
BF_##reg##_##f4(v4) | \
BF_##reg##_##f5(v5) | \
BF_##reg##_##f6(v6) | \
BF_##reg##_##f7(v7) | \
BF_##reg##_##f8(v8)))
//
// macros for MULTI-BLOCK multiple instance registers
//
#define BFn_SETn(reg, blk, n, field) HW_##reg##_SET(blk, n, BM_##reg##_##field)
#define BFn_CLRn(reg, blk, n, field) HW_##reg##_CLR(blk, n, BM_##reg##_##field)
#define BFn_TOGn(reg, blk, n, field) HW_##reg##_TOG(blk, n, BM_##reg##_##field)
#define BFn_SETVn(reg, blk, n, field, v) HW_##reg##_SET(blk, n, BF_##reg##_##field(v))
#define BFn_CLRVn(reg, blk, n, field, v) HW_##reg##_CLR(blk, n, BF_##reg##_##field(v))
#define BFn_TOGVn(reg, blk, n, field, v) HW_##reg##_TOG(blk, n, BF_##reg##_##field(v))
#define BVn_FLDn(reg, blk, n, field, sym) BF_##reg##_##field(BV_##reg##_##field##__##sym)
#define BVn_VALn(reg, blk, n, field, sym) BV_##reg##_##field##__##sym
#define BFn_RDn(reg, blk, n, field) HW_##reg(n).B.field
#define BFn_WRn(reg, blk, n, field, v) BW_##reg##_##field(n, v)
#define BFn_CS1n(reg, blk, n, f1, v1) \
(HW_##reg##_CLR(blk, n, (BM_##reg##_##f1)), \
HW_##reg##_SET(blk, n, (BF_##reg##_##f1(v1))))
#define BFn_CS2n(reg, blk, n, f1, v1, f2, v2) \
(HW_##reg##_CLR(blk, n, (BM_##reg##_##f1 | \
BM_##reg##_##f2)), \
HW_##reg##_SET(blk, n, (BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2))))
#define BFn_CS3n(reg, blk, n, f1, v1, f2, v2, f3, v3) \
(HW_##reg##_CLR(blk, n, (BM_##reg##_##f1 | \
BM_##reg##_##f2 | \
BM_##reg##_##f3)), \
HW_##reg##_SET(blk, n, (BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2) | \
BF_##reg##_##f3(v3))))
#define BFn_CS4n(reg, blk, n, f1, v1, f2, v2, f3, v3, f4, v4) \
(HW_##reg##_CLR(blk, n, (BM_##reg##_##f1 | \
BM_##reg##_##f2 | \
BM_##reg##_##f3 | \
BM_##reg##_##f4)), \
HW_##reg##_SET(blk, n, (BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2) | \
BF_##reg##_##f3(v3) | \
BF_##reg##_##f4(v4))))
#define BFn_CS5n(reg, blk, n, f1, v1, f2, v2, f3, v3, f4, v4, f5, v5) \
(HW_##reg##_CLR(blk, n, (BM_##reg##_##f1 | \
BM_##reg##_##f2 | \
BM_##reg##_##f3 | \
BM_##reg##_##f4 | \
BM_##reg##_##f5)), \
HW_##reg##_SET(blk, n, (BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2) | \
BF_##reg##_##f3(v3) | \
BF_##reg##_##f4(v4) | \
BF_##reg##_##f5(v5))))
#define BFn_CS6n(reg, blk, n, f1, v1, f2, v2, f3, v3, f4, v4, f5, v5, f6, v6) \
(HW_##reg##_CLR(blk, n, (BM_##reg##_##f1 | \
BM_##reg##_##f2 | \
BM_##reg##_##f3 | \
BM_##reg##_##f4 | \
BM_##reg##_##f5 | \
BM_##reg##_##f6)), \
HW_##reg##_SET(blk, n, (BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2) | \
BF_##reg##_##f3(v3) | \
BF_##reg##_##f4(v4) | \
BF_##reg##_##f5(v5) | \
BF_##reg##_##f6(v6))))
#define BFn_CS7n(reg, blk, n, f1, v1, f2, v2, f3, v3, f4, v4, f5, v5, f6, v6, f7, v7) \
(HW_##reg##_CLR(blk, n, (BM_##reg##_##f1 | \
BM_##reg##_##f2 | \
BM_##reg##_##f3 | \
BM_##reg##_##f4 | \
BM_##reg##_##f5 | \
BM_##reg##_##f6 | \
BM_##reg##_##f7)), \
HW_##reg##_SET(blk, n, (BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2) | \
BF_##reg##_##f3(v3) | \
BF_##reg##_##f4(v4) | \
BF_##reg##_##f5(v5) | \
BF_##reg##_##f6(v6) | \
BF_##reg##_##f7(v7))))
#define BFn_CS8n(reg, blk, n, f1, v1, f2, v2, f3, v3, f4, v4, f5, v5, f6, v6, f7, v7, f8, v8) \
(HW_##reg##_CLR(blk, n, (BM_##reg##_##f1 | \
BM_##reg##_##f2 | \
BM_##reg##_##f3 | \
BM_##reg##_##f4 | \
BM_##reg##_##f5 | \
BM_##reg##_##f6 | \
BM_##reg##_##f7 | \
BM_##reg##_##f8)), \
HW_##reg##_SET(blk, n, (BF_##reg##_##f1(v1) | \
BF_##reg##_##f2(v2) | \
BF_##reg##_##f3(v3) | \
BF_##reg##_##f4(v4) | \
BF_##reg##_##f5(v5) | \
BF_##reg##_##f6(v6) | \
BF_##reg##_##f7(v7) | \
BF_##reg##_##f8(v8))))
#endif // _REGS_H
////////////////////////////////////////////////////////////////////////////////

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,741 @@
/*
* Copyright (c) 2012, Freescale Semiconductor, Inc.
* All rights reserved.
*
* THIS SOFTWARE IS PROVIDED BY FREESCALE "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 FREESCALE 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.
*/
/*
* WARNING! DO NOT EDIT THIS FILE DIRECTLY!
*
* This file was generated automatically and any changes may be lost.
*/
/*************************************************
File name: regsgpc.h
Description:
Others:
History:
1. Date: 2023-11-23
Author: AIIT XUOS Lab
Modification:
1. Comment unnecessary macros
*************************************************/
#ifndef __HW_GPC_REGISTERS_H__
#define __HW_GPC_REGISTERS_H__
#include "regs.h"
#include "soc_memory_map.h"
/*
* i.MX6DQ GPC
*
* GPC
*
* Registers defined in this header file:
* - HW_GPC_CNTR - GPC Interface control register
* - HW_GPC_PGR - GPC Power Gating Register
* - HW_GPC_IMR1 - IRQ masking register 1
* - HW_GPC_IMR2 - IRQ masking register 2
* - HW_GPC_IMR3 - IRQ masking register 3
* - HW_GPC_IMR4 - IRQ masking register 4
* - HW_GPC_ISR1 - IRQ status resister 1
* - HW_GPC_ISR2 - IRQ status resister 2
* - HW_GPC_ISR3 - IRQ status resister 3
* - HW_GPC_ISR4 - IRQ status resister 4
*
* - hw_gpc_t - Struct containing all module registers.
*/
//! @name Module base addresses
//@{
#ifndef REGS_GPC_BASE
#define HW_GPC_INSTANCE_COUNT (1) //!< Number of instances of the GPC module.
#define REGS_GPC_BASE USERLAND_MMIO_P2V(0x020dc000) //!< Base address for GPC.
#endif
//@}
//-------------------------------------------------------------------------------------------
// HW_GPC_CNTR - GPC Interface control register
//-------------------------------------------------------------------------------------------
// #ifndef __LANGUAGE_ASM__
// /*!
// * @brief HW_GPC_CNTR - GPC Interface control register (RW)
// *
// * Reset value: 0x00100000
// */
// typedef union _hw_gpc_cntr
// {
// reg32_t U;
// struct _hw_gpc_cntr_bitfields
// {
// unsigned GPU_VPU_PDN_REQ : 1; //!< [0] GPU /VPU Power Down request.
// unsigned GPU_VPU_PUP_REQ : 1; //!< [1] GPU /VPU Power Up request.
// unsigned RESERVED2 : 14; //!< [15:2] Reserved.
// unsigned DVFS0CR : 1; //!< [16] DVFS0 (ARM) Change request (bit is read-only)
// unsigned RESERVED3 : 4; //!< [20:17] Reserved.
// unsigned GPCIRQM : 1; //!< [21] GPC interrupt/event masking
// unsigned RESERVED4 : 10; //!< [31:22] Reserved.
// } B;
// } hw_gpc_cntr_t;
// #endif
// /*!
// * @name Constants and macros for entire GPC_CNTR register
// */
// //@{
// #define HW_GPC_CNTR_ADDR (REGS_GPC_BASE + 0x0)
// #ifndef __LANGUAGE_ASM__
// #define HW_GPC_CNTR (*(volatile hw_gpc_cntr_t *) HW_GPC_CNTR_ADDR)
// #define HW_GPC_CNTR_RD() (HW_GPC_CNTR.U)
// #define HW_GPC_CNTR_WR(v) (HW_GPC_CNTR.U = (v))
// #define HW_GPC_CNTR_SET(v) (HW_GPC_CNTR_WR(HW_GPC_CNTR_RD() | (v)))
// #define HW_GPC_CNTR_CLR(v) (HW_GPC_CNTR_WR(HW_GPC_CNTR_RD() & ~(v)))
// #define HW_GPC_CNTR_TOG(v) (HW_GPC_CNTR_WR(HW_GPC_CNTR_RD() ^ (v)))
// #endif
// //@}
// /*
// * constants & macros for individual GPC_CNTR bitfields
// */
// /*! @name Register GPC_CNTR, field GPU_VPU_PDN_REQ[0] (RW)
// *
// * GPU /VPU Power Down request. Self-cleared bit. * Note: Power switch for GPU /VPU power domain is
// * controlled by ANALOG configuration, not GPU /VPU PGC signals
// *
// * Values:
// * - 0 - no request
// * - 1 - Request Power Down sequence to start for GPU /VPU
// */
// //@{
// #define BP_GPC_CNTR_GPU_VPU_PDN_REQ (0) //!< Bit position for GPC_CNTR_GPU_VPU_PDN_REQ.
// #define BM_GPC_CNTR_GPU_VPU_PDN_REQ (0x00000001) //!< Bit mask for GPC_CNTR_GPU_VPU_PDN_REQ.
// //! @brief Get value of GPC_CNTR_GPU_VPU_PDN_REQ from a register value.
// #define BG_GPC_CNTR_GPU_VPU_PDN_REQ(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_GPC_CNTR_GPU_VPU_PDN_REQ) >> BP_GPC_CNTR_GPU_VPU_PDN_REQ)
// //! @brief Format value for bitfield GPC_CNTR_GPU_VPU_PDN_REQ.
// #define BF_GPC_CNTR_GPU_VPU_PDN_REQ(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_GPC_CNTR_GPU_VPU_PDN_REQ) & BM_GPC_CNTR_GPU_VPU_PDN_REQ)
// #ifndef __LANGUAGE_ASM__
// //! @brief Set the GPU_VPU_PDN_REQ field to a new value.
// #define BW_GPC_CNTR_GPU_VPU_PDN_REQ(v) (HW_GPC_CNTR_WR((HW_GPC_CNTR_RD() & ~BM_GPC_CNTR_GPU_VPU_PDN_REQ) | BF_GPC_CNTR_GPU_VPU_PDN_REQ(v)))
// #endif
// //@}
// /*! @name Register GPC_CNTR, field GPU_VPU_PUP_REQ[1] (RW)
// *
// * GPU /VPU Power Up request. Self-cleared bit. * Note: Power switch for GPU /VPU power domain is
// * controlled by ANALOG configuration, not GPU /VPU PGC signals
// *
// * Values:
// * - 0 - no request
// * - 1 - Request Power Up sequence to start for GPU /VPU
// */
// //@{
// #define BP_GPC_CNTR_GPU_VPU_PUP_REQ (1) //!< Bit position for GPC_CNTR_GPU_VPU_PUP_REQ.
// #define BM_GPC_CNTR_GPU_VPU_PUP_REQ (0x00000002) //!< Bit mask for GPC_CNTR_GPU_VPU_PUP_REQ.
// //! @brief Get value of GPC_CNTR_GPU_VPU_PUP_REQ from a register value.
// #define BG_GPC_CNTR_GPU_VPU_PUP_REQ(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_GPC_CNTR_GPU_VPU_PUP_REQ) >> BP_GPC_CNTR_GPU_VPU_PUP_REQ)
// //! @brief Format value for bitfield GPC_CNTR_GPU_VPU_PUP_REQ.
// #define BF_GPC_CNTR_GPU_VPU_PUP_REQ(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_GPC_CNTR_GPU_VPU_PUP_REQ) & BM_GPC_CNTR_GPU_VPU_PUP_REQ)
// #ifndef __LANGUAGE_ASM__
// //! @brief Set the GPU_VPU_PUP_REQ field to a new value.
// #define BW_GPC_CNTR_GPU_VPU_PUP_REQ(v) (HW_GPC_CNTR_WR((HW_GPC_CNTR_RD() & ~BM_GPC_CNTR_GPU_VPU_PUP_REQ) | BF_GPC_CNTR_GPU_VPU_PUP_REQ(v)))
// #endif
// //@}
// /*! @name Register GPC_CNTR, field DVFS0CR[16] (RO)
// *
// * DVFS0 (ARM) Change request (bit is read-only)
// *
// * Values:
// * - 0 - DVFS0 has no request
// * - 1 - DVFS0 is requesting for frequency/voltage update
// */
// //@{
// #define BP_GPC_CNTR_DVFS0CR (16) //!< Bit position for GPC_CNTR_DVFS0CR.
// #define BM_GPC_CNTR_DVFS0CR (0x00010000) //!< Bit mask for GPC_CNTR_DVFS0CR.
// //! @brief Get value of GPC_CNTR_DVFS0CR from a register value.
// #define BG_GPC_CNTR_DVFS0CR(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_GPC_CNTR_DVFS0CR) >> BP_GPC_CNTR_DVFS0CR)
// //@}
// /*! @name Register GPC_CNTR, field GPCIRQM[21] (RW)
// *
// * GPC interrupt/event masking
// *
// * Values:
// * - 0 - not masked
// * - 1 - interrupt/event is masked
// */
// //@{
// #define BP_GPC_CNTR_GPCIRQM (21) //!< Bit position for GPC_CNTR_GPCIRQM.
// #define BM_GPC_CNTR_GPCIRQM (0x00200000) //!< Bit mask for GPC_CNTR_GPCIRQM.
// //! @brief Get value of GPC_CNTR_GPCIRQM from a register value.
// #define BG_GPC_CNTR_GPCIRQM(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_GPC_CNTR_GPCIRQM) >> BP_GPC_CNTR_GPCIRQM)
// //! @brief Format value for bitfield GPC_CNTR_GPCIRQM.
// #define BF_GPC_CNTR_GPCIRQM(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_GPC_CNTR_GPCIRQM) & BM_GPC_CNTR_GPCIRQM)
// #ifndef __LANGUAGE_ASM__
// //! @brief Set the GPCIRQM field to a new value.
// #define BW_GPC_CNTR_GPCIRQM(v) (HW_GPC_CNTR_WR((HW_GPC_CNTR_RD() & ~BM_GPC_CNTR_GPCIRQM) | BF_GPC_CNTR_GPCIRQM(v)))
// #endif
// //@}
// //-------------------------------------------------------------------------------------------
// // HW_GPC_PGR - GPC Power Gating Register
// //-------------------------------------------------------------------------------------------
// #ifndef __LANGUAGE_ASM__
// /*!
// * @brief HW_GPC_PGR - GPC Power Gating Register (RW)
// *
// * Reset value: 0x00000000
// */
// typedef union _hw_gpc_pgr
// {
// reg32_t U;
// struct _hw_gpc_pgr_bitfields
// {
// unsigned RESERVED0 : 29; //!< [28:0] Reserved
// unsigned DRCIC : 2; //!< [30:29] Debug ref cir in mux control
// unsigned RESERVED1 : 1; //!< [31] Reserved
// } B;
// } hw_gpc_pgr_t;
// #endif
// /*!
// * @name Constants and macros for entire GPC_PGR register
// */
// //@{
// #define HW_GPC_PGR_ADDR (REGS_GPC_BASE + 0x4)
// #ifndef __LANGUAGE_ASM__
// #define HW_GPC_PGR (*(volatile hw_gpc_pgr_t *) HW_GPC_PGR_ADDR)
// #define HW_GPC_PGR_RD() (HW_GPC_PGR.U)
// #define HW_GPC_PGR_WR(v) (HW_GPC_PGR.U = (v))
// #define HW_GPC_PGR_SET(v) (HW_GPC_PGR_WR(HW_GPC_PGR_RD() | (v)))
// #define HW_GPC_PGR_CLR(v) (HW_GPC_PGR_WR(HW_GPC_PGR_RD() & ~(v)))
// #define HW_GPC_PGR_TOG(v) (HW_GPC_PGR_WR(HW_GPC_PGR_RD() ^ (v)))
// #endif
// //@}
// /*
// * constants & macros for individual GPC_PGR bitfields
// */
// /*! @name Register GPC_PGR, field DRCIC[30:29] (RW)
// *
// * Debug ref cir in mux control
// *
// * Values:
// * - 00 - ccm_cosr_1_clk_in
// * - 01 - ccm_cosr_2_clk_in
// * - 10 - restricted
// * - 11 - restricted
// */
// //@{
// #define BP_GPC_PGR_DRCIC (29) //!< Bit position for GPC_PGR_DRCIC.
// #define BM_GPC_PGR_DRCIC (0x60000000) //!< Bit mask for GPC_PGR_DRCIC.
// //! @brief Get value of GPC_PGR_DRCIC from a register value.
// #define BG_GPC_PGR_DRCIC(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_GPC_PGR_DRCIC) >> BP_GPC_PGR_DRCIC)
// //! @brief Format value for bitfield GPC_PGR_DRCIC.
// #define BF_GPC_PGR_DRCIC(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_GPC_PGR_DRCIC) & BM_GPC_PGR_DRCIC)
// #ifndef __LANGUAGE_ASM__
// //! @brief Set the DRCIC field to a new value.
// #define BW_GPC_PGR_DRCIC(v) (HW_GPC_PGR_WR((HW_GPC_PGR_RD() & ~BM_GPC_PGR_DRCIC) | BF_GPC_PGR_DRCIC(v)))
// #endif
// //@}
// //-------------------------------------------------------------------------------------------
// // HW_GPC_IMR1 - IRQ masking register 1
// //-------------------------------------------------------------------------------------------
#ifndef __LANGUAGE_ASM__
/*!
* @brief HW_GPC_IMR1 - IRQ masking register 1 (RW)
*
* Reset value: 0x00000000
*
* IMR1 Register - masking of irq[63:32].
*/
typedef union _hw_gpc_imr1 {
reg32_t U;
struct _hw_gpc_imr1_bitfields {
unsigned IMR1 : 32; //!< [31:0] IRQ[63:32] masking bits: 1-irq masked, 0-irq is not masked
} B;
} hw_gpc_imr1_t;
#endif
/*!
* @name Constants and macros for entire GPC_IMR1 register
*/
//@{
#define HW_GPC_IMR1_ADDR (REGS_GPC_BASE + 0x8)
#ifndef __LANGUAGE_ASM__
#define HW_GPC_IMR1 (*(volatile hw_gpc_imr1_t*)HW_GPC_IMR1_ADDR)
#define HW_GPC_IMR1_RD() (HW_GPC_IMR1.U)
#define HW_GPC_IMR1_WR(v) (HW_GPC_IMR1.U = (v))
#define HW_GPC_IMR1_SET(v) (HW_GPC_IMR1_WR(HW_GPC_IMR1_RD() | (v)))
#define HW_GPC_IMR1_CLR(v) (HW_GPC_IMR1_WR(HW_GPC_IMR1_RD() & ~(v)))
#define HW_GPC_IMR1_TOG(v) (HW_GPC_IMR1_WR(HW_GPC_IMR1_RD() ^ (v)))
#endif
//@}
// /*
// * constants & macros for individual GPC_IMR1 bitfields
// */
// /*! @name Register GPC_IMR1, field IMR1[31:0] (RW)
// *
// * IRQ[63:32] masking bits: 1-irq masked, 0-irq is not masked
// */
// //@{
// #define BP_GPC_IMR1_IMR1 (0) //!< Bit position for GPC_IMR1_IMR1.
// #define BM_GPC_IMR1_IMR1 (0xffffffff) //!< Bit mask for GPC_IMR1_IMR1.
// //! @brief Get value of GPC_IMR1_IMR1 from a register value.
// #define BG_GPC_IMR1_IMR1(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_GPC_IMR1_IMR1) >> BP_GPC_IMR1_IMR1)
// //! @brief Format value for bitfield GPC_IMR1_IMR1.
// #define BF_GPC_IMR1_IMR1(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_GPC_IMR1_IMR1) & BM_GPC_IMR1_IMR1)
// #ifndef __LANGUAGE_ASM__
// //! @brief Set the IMR1 field to a new value.
// #define BW_GPC_IMR1_IMR1(v) (HW_GPC_IMR1_WR((HW_GPC_IMR1_RD() & ~BM_GPC_IMR1_IMR1) | BF_GPC_IMR1_IMR1(v)))
// #endif
// //@}
// //-------------------------------------------------------------------------------------------
// // HW_GPC_IMR2 - IRQ masking register 2
// //-------------------------------------------------------------------------------------------
#ifndef __LANGUAGE_ASM__
/*!
* @brief HW_GPC_IMR2 - IRQ masking register 2 (RW)
*
* Reset value: 0x00000000
*
* IMR2 Register - masking of irq[95:64].
*/
typedef union _hw_gpc_imr2 {
reg32_t U;
struct _hw_gpc_imr2_bitfields {
unsigned IMR2 : 32; //!< [31:0] IRQ[95:64] masking bits: 1-irq masked, 0-irq is not masked
} B;
} hw_gpc_imr2_t;
#endif
/*!
* @name Constants and macros for entire GPC_IMR2 register
*/
//@{
#define HW_GPC_IMR2_ADDR (REGS_GPC_BASE + 0xc)
#ifndef __LANGUAGE_ASM__
#define HW_GPC_IMR2 (*(volatile hw_gpc_imr2_t*)HW_GPC_IMR2_ADDR)
#define HW_GPC_IMR2_RD() (HW_GPC_IMR2.U)
#define HW_GPC_IMR2_WR(v) (HW_GPC_IMR2.U = (v))
#define HW_GPC_IMR2_SET(v) (HW_GPC_IMR2_WR(HW_GPC_IMR2_RD() | (v)))
#define HW_GPC_IMR2_CLR(v) (HW_GPC_IMR2_WR(HW_GPC_IMR2_RD() & ~(v)))
#define HW_GPC_IMR2_TOG(v) (HW_GPC_IMR2_WR(HW_GPC_IMR2_RD() ^ (v)))
#endif
//@}
// /*
// * constants & macros for individual GPC_IMR2 bitfields
// */
// /*! @name Register GPC_IMR2, field IMR2[31:0] (RW)
// *
// * IRQ[95:64] masking bits: 1-irq masked, 0-irq is not masked
// */
// //@{
// #define BP_GPC_IMR2_IMR2 (0) //!< Bit position for GPC_IMR2_IMR2.
// #define BM_GPC_IMR2_IMR2 (0xffffffff) //!< Bit mask for GPC_IMR2_IMR2.
// //! @brief Get value of GPC_IMR2_IMR2 from a register value.
// #define BG_GPC_IMR2_IMR2(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_GPC_IMR2_IMR2) >> BP_GPC_IMR2_IMR2)
// //! @brief Format value for bitfield GPC_IMR2_IMR2.
// #define BF_GPC_IMR2_IMR2(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_GPC_IMR2_IMR2) & BM_GPC_IMR2_IMR2)
// #ifndef __LANGUAGE_ASM__
// //! @brief Set the IMR2 field to a new value.
// #define BW_GPC_IMR2_IMR2(v) (HW_GPC_IMR2_WR((HW_GPC_IMR2_RD() & ~BM_GPC_IMR2_IMR2) | BF_GPC_IMR2_IMR2(v)))
// #endif
// //@}
// //-------------------------------------------------------------------------------------------
// // HW_GPC_IMR3 - IRQ masking register 3
// //-------------------------------------------------------------------------------------------
#ifndef __LANGUAGE_ASM__
/*!
* @brief HW_GPC_IMR3 - IRQ masking register 3 (RW)
*
* Reset value: 0x00000000
*
* IMR3 Register - masking of irq[127:96].
*/
typedef union _hw_gpc_imr3 {
reg32_t U;
struct _hw_gpc_imr3_bitfields {
unsigned IMR3 : 32; //!< [31:0] IRQ[127:96] masking bits: 1-irq masked, 0-irq is not masked
} B;
} hw_gpc_imr3_t;
#endif
/*!
* @name Constants and macros for entire GPC_IMR3 register
*/
//@{
#define HW_GPC_IMR3_ADDR (REGS_GPC_BASE + 0x10)
#ifndef __LANGUAGE_ASM__
#define HW_GPC_IMR3 (*(volatile hw_gpc_imr3_t*)HW_GPC_IMR3_ADDR)
#define HW_GPC_IMR3_RD() (HW_GPC_IMR3.U)
#define HW_GPC_IMR3_WR(v) (HW_GPC_IMR3.U = (v))
#define HW_GPC_IMR3_SET(v) (HW_GPC_IMR3_WR(HW_GPC_IMR3_RD() | (v)))
#define HW_GPC_IMR3_CLR(v) (HW_GPC_IMR3_WR(HW_GPC_IMR3_RD() & ~(v)))
#define HW_GPC_IMR3_TOG(v) (HW_GPC_IMR3_WR(HW_GPC_IMR3_RD() ^ (v)))
#endif
//@}
// /*
// * constants & macros for individual GPC_IMR3 bitfields
// */
// /*! @name Register GPC_IMR3, field IMR3[31:0] (RW)
// *
// * IRQ[127:96] masking bits: 1-irq masked, 0-irq is not masked
// */
// //@{
// #define BP_GPC_IMR3_IMR3 (0) //!< Bit position for GPC_IMR3_IMR3.
// #define BM_GPC_IMR3_IMR3 (0xffffffff) //!< Bit mask for GPC_IMR3_IMR3.
// //! @brief Get value of GPC_IMR3_IMR3 from a register value.
// #define BG_GPC_IMR3_IMR3(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_GPC_IMR3_IMR3) >> BP_GPC_IMR3_IMR3)
// //! @brief Format value for bitfield GPC_IMR3_IMR3.
// #define BF_GPC_IMR3_IMR3(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_GPC_IMR3_IMR3) & BM_GPC_IMR3_IMR3)
// #ifndef __LANGUAGE_ASM__
// //! @brief Set the IMR3 field to a new value.
// #define BW_GPC_IMR3_IMR3(v) (HW_GPC_IMR3_WR((HW_GPC_IMR3_RD() & ~BM_GPC_IMR3_IMR3) | BF_GPC_IMR3_IMR3(v)))
// #endif
// //@}
// //-------------------------------------------------------------------------------------------
// // HW_GPC_IMR4 - IRQ masking register 4
// //-------------------------------------------------------------------------------------------
#ifndef __LANGUAGE_ASM__
/*!
* @brief HW_GPC_IMR4 - IRQ masking register 4 (RW)
*
* Reset value: 0x00000000
*
* IMR4 Register - masking of irq[159:128].
*/
typedef union _hw_gpc_imr4 {
reg32_t U;
struct _hw_gpc_imr4_bitfields {
unsigned IMR4 : 32; //!< [31:0] IRQ[159:128] masking bits: 1-irq masked, 0-irq is not masked
} B;
} hw_gpc_imr4_t;
#endif
/*!
* @name Constants and macros for entire GPC_IMR4 register
*/
//@{
#define HW_GPC_IMR4_ADDR (REGS_GPC_BASE + 0x14)
#ifndef __LANGUAGE_ASM__
#define HW_GPC_IMR4 (*(volatile hw_gpc_imr4_t*)HW_GPC_IMR4_ADDR)
#define HW_GPC_IMR4_RD() (HW_GPC_IMR4.U)
#define HW_GPC_IMR4_WR(v) (HW_GPC_IMR4.U = (v))
#define HW_GPC_IMR4_SET(v) (HW_GPC_IMR4_WR(HW_GPC_IMR4_RD() | (v)))
#define HW_GPC_IMR4_CLR(v) (HW_GPC_IMR4_WR(HW_GPC_IMR4_RD() & ~(v)))
#define HW_GPC_IMR4_TOG(v) (HW_GPC_IMR4_WR(HW_GPC_IMR4_RD() ^ (v)))
#endif
//@}
// /*
// * constants & macros for individual GPC_IMR4 bitfields
// */
// /*! @name Register GPC_IMR4, field IMR4[31:0] (RW)
// *
// * IRQ[159:128] masking bits: 1-irq masked, 0-irq is not masked
// */
// //@{
// #define BP_GPC_IMR4_IMR4 (0) //!< Bit position for GPC_IMR4_IMR4.
// #define BM_GPC_IMR4_IMR4 (0xffffffff) //!< Bit mask for GPC_IMR4_IMR4.
// //! @brief Get value of GPC_IMR4_IMR4 from a register value.
// #define BG_GPC_IMR4_IMR4(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_GPC_IMR4_IMR4) >> BP_GPC_IMR4_IMR4)
// //! @brief Format value for bitfield GPC_IMR4_IMR4.
// #define BF_GPC_IMR4_IMR4(v) ((__REG_VALUE_TYPE((v), reg32_t) << BP_GPC_IMR4_IMR4) & BM_GPC_IMR4_IMR4)
// #ifndef __LANGUAGE_ASM__
// //! @brief Set the IMR4 field to a new value.
// #define BW_GPC_IMR4_IMR4(v) (HW_GPC_IMR4_WR((HW_GPC_IMR4_RD() & ~BM_GPC_IMR4_IMR4) | BF_GPC_IMR4_IMR4(v)))
// #endif
// //@}
// //-------------------------------------------------------------------------------------------
// // HW_GPC_ISR1 - IRQ status resister 1
// //-------------------------------------------------------------------------------------------
// #ifndef __LANGUAGE_ASM__
// /*!
// * @brief HW_GPC_ISR1 - IRQ status resister 1 (RO)
// *
// * Reset value: 0x00000000
// *
// * ISR1 Register - status of irq [63:32].
// */
// typedef union _hw_gpc_isr1
// {
// reg32_t U;
// struct _hw_gpc_isr1_bitfields
// {
// unsigned ISR1 : 32; //!< [31:0] IRQ[63:32] status, read only
// } B;
// } hw_gpc_isr1_t;
// #endif
// /*!
// * @name Constants and macros for entire GPC_ISR1 register
// */
// //@{
// #define HW_GPC_ISR1_ADDR (REGS_GPC_BASE + 0x18)
// #ifndef __LANGUAGE_ASM__
// #define HW_GPC_ISR1 (*(volatile hw_gpc_isr1_t *) HW_GPC_ISR1_ADDR)
// #define HW_GPC_ISR1_RD() (HW_GPC_ISR1.U)
// #endif
// //@}
// /*
// * constants & macros for individual GPC_ISR1 bitfields
// */
// /*! @name Register GPC_ISR1, field ISR1[31:0] (RO)
// *
// * IRQ[63:32] status, read only
// */
// //@{
// #define BP_GPC_ISR1_ISR1 (0) //!< Bit position for GPC_ISR1_ISR1.
// #define BM_GPC_ISR1_ISR1 (0xffffffff) //!< Bit mask for GPC_ISR1_ISR1.
// //! @brief Get value of GPC_ISR1_ISR1 from a register value.
// #define BG_GPC_ISR1_ISR1(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_GPC_ISR1_ISR1) >> BP_GPC_ISR1_ISR1)
// //@}
// //-------------------------------------------------------------------------------------------
// // HW_GPC_ISR2 - IRQ status resister 2
// //-------------------------------------------------------------------------------------------
// #ifndef __LANGUAGE_ASM__
// /*!
// * @brief HW_GPC_ISR2 - IRQ status resister 2 (RO)
// *
// * Reset value: 0x00000000
// *
// * ISR2 Register - status of irq [95:64].
// */
// typedef union _hw_gpc_isr2
// {
// reg32_t U;
// struct _hw_gpc_isr2_bitfields
// {
// unsigned ISR2 : 32; //!< [31:0] IRQ[95:64] status, read only
// } B;
// } hw_gpc_isr2_t;
// #endif
// /*!
// * @name Constants and macros for entire GPC_ISR2 register
// */
// //@{
// #define HW_GPC_ISR2_ADDR (REGS_GPC_BASE + 0x1c)
// #ifndef __LANGUAGE_ASM__
// #define HW_GPC_ISR2 (*(volatile hw_gpc_isr2_t *) HW_GPC_ISR2_ADDR)
// #define HW_GPC_ISR2_RD() (HW_GPC_ISR2.U)
// #endif
// //@}
// /*
// * constants & macros for individual GPC_ISR2 bitfields
// */
// /*! @name Register GPC_ISR2, field ISR2[31:0] (RO)
// *
// * IRQ[95:64] status, read only
// */
// //@{
// #define BP_GPC_ISR2_ISR2 (0) //!< Bit position for GPC_ISR2_ISR2.
// #define BM_GPC_ISR2_ISR2 (0xffffffff) //!< Bit mask for GPC_ISR2_ISR2.
// //! @brief Get value of GPC_ISR2_ISR2 from a register value.
// #define BG_GPC_ISR2_ISR2(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_GPC_ISR2_ISR2) >> BP_GPC_ISR2_ISR2)
// //@}
// //-------------------------------------------------------------------------------------------
// // HW_GPC_ISR3 - IRQ status resister 3
// //-------------------------------------------------------------------------------------------
// #ifndef __LANGUAGE_ASM__
// /*!
// * @brief HW_GPC_ISR3 - IRQ status resister 3 (RO)
// *
// * Reset value: 0x00000000
// *
// * ISR3 Register - status of irq [127:96].
// */
// typedef union _hw_gpc_isr3
// {
// reg32_t U;
// struct _hw_gpc_isr3_bitfields
// {
// unsigned ISR3 : 32; //!< [31:0] IRQ[127:96] status, read only
// } B;
// } hw_gpc_isr3_t;
// #endif
// /*!
// * @name Constants and macros for entire GPC_ISR3 register
// */
// //@{
// #define HW_GPC_ISR3_ADDR (REGS_GPC_BASE + 0x20)
// #ifndef __LANGUAGE_ASM__
// #define HW_GPC_ISR3 (*(volatile hw_gpc_isr3_t *) HW_GPC_ISR3_ADDR)
// #define HW_GPC_ISR3_RD() (HW_GPC_ISR3.U)
// #endif
// //@}
// /*
// * constants & macros for individual GPC_ISR3 bitfields
// */
// /*! @name Register GPC_ISR3, field ISR3[31:0] (RO)
// *
// * IRQ[127:96] status, read only
// */
// //@{
// #define BP_GPC_ISR3_ISR3 (0) //!< Bit position for GPC_ISR3_ISR3.
// #define BM_GPC_ISR3_ISR3 (0xffffffff) //!< Bit mask for GPC_ISR3_ISR3.
// //! @brief Get value of GPC_ISR3_ISR3 from a register value.
// #define BG_GPC_ISR3_ISR3(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_GPC_ISR3_ISR3) >> BP_GPC_ISR3_ISR3)
// //@}
// //-------------------------------------------------------------------------------------------
// // HW_GPC_ISR4 - IRQ status resister 4
// //-------------------------------------------------------------------------------------------
// #ifndef __LANGUAGE_ASM__
// /*!
// * @brief HW_GPC_ISR4 - IRQ status resister 4 (RO)
// *
// * Reset value: 0x00000000
// *
// * ISR4 Register - status of irq [159:128].
// */
// typedef union _hw_gpc_isr4
// {
// reg32_t U;
// struct _hw_gpc_isr4_bitfields
// {
// unsigned ISR4 : 32; //!< [31:0] IRQ[159:128] status, read only
// } B;
// } hw_gpc_isr4_t;
// #endif
// /*!
// * @name Constants and macros for entire GPC_ISR4 register
// */
// //@{
// #define HW_GPC_ISR4_ADDR (REGS_GPC_BASE + 0x24)
// #ifndef __LANGUAGE_ASM__
// #define HW_GPC_ISR4 (*(volatile hw_gpc_isr4_t *) HW_GPC_ISR4_ADDR)
// #define HW_GPC_ISR4_RD() (HW_GPC_ISR4.U)
// #endif
// //@}
// /*
// * constants & macros for individual GPC_ISR4 bitfields
// */
// /*! @name Register GPC_ISR4, field ISR4[31:0] (RO)
// *
// * IRQ[159:128] status, read only
// */
// //@{
// #define BP_GPC_ISR4_ISR4 (0) //!< Bit position for GPC_ISR4_ISR4.
// #define BM_GPC_ISR4_ISR4 (0xffffffff) //!< Bit mask for GPC_ISR4_ISR4.
// //! @brief Get value of GPC_ISR4_ISR4 from a register value.
// #define BG_GPC_ISR4_ISR4(r) ((__REG_VALUE_TYPE((r), reg32_t) & BM_GPC_ISR4_ISR4) >> BP_GPC_ISR4_ISR4)
// //@}
//-------------------------------------------------------------------------------------------
// hw_gpc_t - module struct
//-------------------------------------------------------------------------------------------
/*!
* @brief All GPC module registers.
*/
#ifndef __LANGUAGE_ASM__
#pragma pack(1)
// typedef struct _hw_gpc
// {
// volatile hw_gpc_cntr_t CNTR; //!< GPC Interface control register
// volatile hw_gpc_pgr_t PGR; //!< GPC Power Gating Register
// volatile hw_gpc_imr1_t IMR1; //!< IRQ masking register 1
// volatile hw_gpc_imr2_t IMR2; //!< IRQ masking register 2
// volatile hw_gpc_imr3_t IMR3; //!< IRQ masking register 3
// volatile hw_gpc_imr4_t IMR4; //!< IRQ masking register 4
// volatile hw_gpc_isr1_t ISR1; //!< IRQ status resister 1
// volatile hw_gpc_isr2_t ISR2; //!< IRQ status resister 2
// volatile hw_gpc_isr3_t ISR3; //!< IRQ status resister 3
// volatile hw_gpc_isr4_t ISR4; //!< IRQ status resister 4
// } hw_gpc_t;
// #pragma pack()
// //! @brief Macro to access all GPC registers.
// //! @return Reference (not a pointer) to the registers struct. To get a pointer to the struct,
// //! use the '&' operator, like <code>&HW_GPC</code>.
// #define HW_GPC (*(hw_gpc_t *) REGS_GPC_BASE)
#endif
#endif // __HW_GPC_REGISTERS_H__
// v18/121106/1.2.2
// EOF

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,120 @@
/*
* Copyright (c) 2008-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.
*/
#pragma once
//! @addtogroup sdk_common
//! @{
/*!
* @file sdk_types.h
* @brief Basic types used throughout the SDK.
*/
#include <stdarg.h>
#include <stdbool.h>
#include <stdint.h>
////////////////////////////////////////////////////////////////////////////////
// Definitions
////////////////////////////////////////////////////////////////////////////////
//! @name Alternate Boolean constants
//@{
#define TRUE 1
#define FALSE 0
//@}
//! @brief
#define NONE_CHAR (0xFF)
//! @brief A parameter was out of range or otherwise invalid.
#define INVALID_PARAMETER (-1)
//! @name Min/max macros
//@{
#if !defined(MIN)
#define MIN(a, b) ((a) < (b) ? (a) : (b))
#endif
#if !defined(MAX)
#define MAX(a, b) ((a) > (b) ? (a) : (b))
#endif
//@}
//! @brief Computes the number of elements in an array.
#define ARRAY_SIZE(x) (sizeof(x) / sizeof((x)[0]))
//! @brief Debug print utility.
//!
//! This print function will only output text when the @a DEBUG macro is defined.
static inline void debug_printf(const char* format, ...)
{
#if defined(DEBUG)
va_list args;
va_start(args, format);
vprintf(format, args);
va_end(args);
#endif
}
//! @name Test results
typedef enum _test_return {
TEST_NOT_STARTED = -3, // present in the menu, but not run
TEST_NOT_IMPLEMENTED = -2, // present in the menu, but not functional
TEST_FAILED = -1,
TEST_PASSED = 0,
TEST_BYPASSED = 2, // user elected to exit the test before it was run
TEST_NOT_PRESENT = 3, // not present in the menu.
TEST_CONTINUE = 4 // proceed with the test. opposite of TEST_BYPASSED
} test_return_t;
//! @name Return codes
//@{
#define SUCCESS (0)
#define FAIL (1)
#define ERROR_GENERIC (-1)
#define ERROR_OUT_OF_MEMORY (-2)
//@}
//! @brief Possible types of displays.
enum display_type {
DISP_DEV_NULL = 0,
DISP_DEV_TFTLCD,
DISP_DEV_LVDS,
DISP_DEV_VGA,
DISP_DEV_HDMI,
DISP_DEV_TV,
DISP_DEV_MIPI,
};
//! @}
////////////////////////////////////////////////////////////////////////////////
// EOF
////////////////////////////////////////////////////////////////////////////////

View File

@ -0,0 +1,236 @@
/*
* Copyright (c) 2011-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.
*/
#ifndef _SOC_MEMORY_MAP_H
#define _SOC_MEMORY_MAP_H
// clang-format off
#define BOARD_SABRE_LITE
#define CHIP_MX6DQ 1
#define BOARD_REV_A
#define DRIVER_MAPPING_OFFSET 0x50000000
#define USERLAND_MMIO_P2V(a) ((uintptr_t)DRIVER_MAPPING_OFFSET + (uintptr_t)a)
#define BAAD_STATUS 0xbaadbaad
#define GOOD_STATUS 0x900d900d
// CPU Memory Map
//#define MMDC1_BASE_ADDR 0x10000000
//#define MMDC1_END_ADDR 0x7FFFFFFF
//#define MMDC0_BASE_ADDR 0x80000000
//#define MMDC0_END_ADDR 0xFFFFFFFF
#define OCRAM_BASE_ADDR 0x00900000
#define OCRAM_END_ADDR 0x009FFFFF
#define IRAM_BASE_ADDR OCRAM_BASE_ADDR
#define PCIE_BASE_ADDR 0x01000000
#define PCIE_END_ADDR 0x01FFFFFF
#define ROMCP_ARB_BASE_ADDR 0x00000000
#define ROMCP_ARB_END_ADDR 0x000FFFFF
#define BOOT_ROM_BASE_ADDR ROMCP_ARB_BASE_ADDR
#define CAAM_SEC_RAM_START_ADDR 0x00100000
#define CAAM_SEC_RAM_END_ADDR 0x00103FFF
#define GPMI_BASE_ADDR 0x00112000
#define APBH_DMA_BASE_ADDR 0x00110000
#define APBH_DMA_END_ADDR 0x00117FFF
#define HDMI_BASE_ADDR 0x00120000
#define HDMI_END_ADDR 0x00128FFF
#define GPU_3D_BASE_ADDR 0x00130000
#define GPU_3D_END_ADDR 0x00133FFF
#define GPU_2D_BASE_ADDR 0x00134000
#define GPU_2D_END_ADDR 0x00137FFF
#define DTCP_BASE_ADDR 0x00138000
#define DTCP_END_ADDR 0x0013BFFF
#define GPU_MEM_BASE_ADDR GPU_3D_BASE_ADDR
#define GPV0_BASE_ADDR 0x00B00000
#define GPV1_BASE_ADDR 0x00C00000
#define GPV2_BASE_ADDR 0x00200000
#define GPV3_BASE_ADDR 0x00300000
#define GPV4_BASE_ADDR 0x00800000
#define AIPS1_ARB_PHY_BASE_ADDR 0x02000000
#define AIPS1_ARB_PHY_END_ADDR 0x020FFFFF
#define AIPS2_ARB_PHY_BASE_ADDR 0x02100000
#define AIPS2_ARB_PHY_END_ADDR 0x021FFFFF
#define AIPS1_ARB_BASE_ADDR USERLAND_MMIO_P2V(AIPS1_ARB_PHY_BASE_ADDR)
#define AIPS1_ARB_END_ADDR USERLAND_MMIO_P2V(AIPS1_ARB_PHY_END_ADDR)
#define AIPS2_ARB_BASE_ADDR USERLAND_MMIO_P2V(AIPS2_ARB_PHY_BASE_ADDR)
#define AIPS2_ARB_END_ADDR USERLAND_MMIO_P2V(AIPS2_ARB_PHY_END_ADDR)
#define SATA_BASE_ADDR 0x02200000
#define SATA_END_ADDR 0x02203FFF
#define OPENVG_BASE_ADDR 0x02204000
#define OPENVG_END_ADDR 0x02207FFF
#define HSI_BASE_ADDR 0x02208000
#define HSI_END_ADDR 0x0220BFFF
#define IPU1_BASE_ADDR 0x02400000
#define IPU1_END_ADDR 0x027FFFFF
#define IPU2_BASE_ADDR 0x02800000
#define IPU2_END_ADDR 0x02BFFFFF
#define WEIM_CS_BASE_ADDR 0x08000000
#define WEIM_CS_END_ADDR 0x0FFFFFFF
// CoreSight (ARM Debug)
#define DEBUG_ROM_BASE_ADDR 0x02140000
#define ETB_BASE_ADDR 0x02141000
#define EXT_CTI_BASE_ADDR 0x02142000
#define TPIU_BASE_ADDR 0x02143000
#define FUNNEL_BASE_ADDR 0x02144000
#define CORTEX_ROM_TABLE 0x0214F000
#define CORTEX_DEBUG_UNIT 0x02150000
#define CORE0_DEBUG_UNIT 0x02150000
#define PMU0_BASE_ADDR 0x02151000
#define CORE1_DEBUG_UNIT 0x02152000
#define PMU1_BASE_ADDR 0x02153000
#define CORE2_DEBUG_UNIT 0x02154000
#define PMU2_BASE_ADDR 0x02155000
#define CORE3_DEBUG_UNIT 0x02156000
#define PMU3_BASE_ADDR 0x02157000
#define CTI0_BASE_ADDR 0x02158000
#define CTI1_BASE_ADDR 0x02159000
#define CTI2_BASE_ADDR 0x0215A000
#define CTI3_BASE_ADDR 0x0215B000
#define PTM0_BASE_ADDR 0x0215C000
#define PTM_BASE_ADDR 0x0215C000
#define PTM1_BASE_ADDR 0x0215D000
#define PTM2_BASE_ADDR 0x0215E000
#define PTM3_BASE_ADDR 0x0215F000
#define AIPS_TZ1_BASE_ADDR AIPS1_ARB_BASE_ADDR
#define AIPS_TZ2_BASE_ADDR AIPS2_ARB_BASE_ADDR
#define SPDIF_BASE_ADDR (AIPS_TZ1_BASE_ADDR+0x04000) //slot 1
#define ECSPI1_BASE_ADDR (AIPS_TZ1_BASE_ADDR+0x08000) //slot 2
#define ECSPI2_BASE_ADDR (AIPS_TZ1_BASE_ADDR+0x0C000) //slot 3
#define ECSPI3_BASE_ADDR (AIPS_TZ1_BASE_ADDR+0x10000) //slot 4
#define ECSPI4_BASE_ADDR (AIPS_TZ1_BASE_ADDR+0x14000) //slot 5
#define ECSPI5_BASE_ADDR (AIPS_TZ1_BASE_ADDR+0x18000) //slot 6
#define UART1_BASE_ADDR (AIPS_TZ1_BASE_ADDR+0x20000) //slot 8
#define ESAI1_BASE_ADDR (AIPS_TZ1_BASE_ADDR+0x24000) //slot 9
#define SSI1_BASE_ADDR (AIPS_TZ1_BASE_ADDR+0x28000) //slot 10
#define SSI2_BASE_ADDR (AIPS_TZ1_BASE_ADDR+0x2C000) //slot 11
#define SSI3_BASE_ADDR (AIPS_TZ1_BASE_ADDR+0x30000) //slot 12
#define ASRC_BASE_ADDR (AIPS_TZ1_BASE_ADDR+0x34000) //slot 13
#define SPBA_BASE_ADDR (AIPS_TZ1_BASE_ADDR+0x3C000) //slot 15
#define VPU_BASE_ADDR (AIPS_TZ1_BASE_ADDR+0x40000) //slot 33, global en[1], til 0x7BFFF
#define AIPS1_ON_BASE_ADDR (AIPS_TZ1_BASE_ADDR+0x7C000)
#define AIPS1_OFF_BASE_ADDR (AIPS_TZ1_BASE_ADDR+0x80000)
#define PWM1_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x0000)
#define PWM2_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x4000)
#define PWM3_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x8000)
#define PWM4_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0xC000)
#define CAN1_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x10000)
#define CAN2_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x14000)
#define GPT_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x18000)
#define GPIO1_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x1C000)
#define GPIO2_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x20000)
#define GPIO3_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x24000)
#define GPIO4_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x28000)
#define GPIO5_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x2C000)
#define GPIO6_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x30000)
#define GPIO7_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x34000)
#define KPP_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x38000)
#define WDOG1_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x3C000)
#define WDOG2_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x40000)
#define CCM_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x44000)
#define IP2APB_USBPHY1_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x49000)
#define IP2APB_USBPHY2_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x4A000)
#define SNVS_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x4C000)
#define EPIT1_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x50000)
#define EPIT2_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x54000)
#define SRC_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x58000)
#define GPC_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x5C000)
#define IOMUXC_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x60000)
#define DCIC1_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x64000)
#define DCIC2_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x68000)
#define SDMA_BASE_ADDR (AIPS1_OFF_BASE_ADDR+0x6C000)
#define SDMA_IPS_HOST_BASE_ADDR SDMA_BASE_ADDR
#define AIPS2_ON_BASE_ADDR (AIPS_TZ2_BASE_ADDR+0x7C000)
#define AIPS2_OFF_BASE_ADDR (AIPS_TZ2_BASE_ADDR+0x80000)
#define AIPS1_BASE_ADDR AIPS1_ON_BASE_ADDR
#define AIPS2_BASE_ADDR AIPS2_ON_BASE_ADDR
#define CAAM_BASE_ADDR AIPS_TZ2_BASE_ADDR
#define ARM_IPS_BASE_ADDR (AIPS_TZ2_BASE_ADDR+0x40000)
#define USBOH3_PL301_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x0000)
#define USBOH3_USB_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x4000)
#define ENET_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x8000)
#define MLB_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0xC000)
#define USDHC1_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x10000)
#define USDHC2_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x14000)
#define USDHC3_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x18000)
#define USDHC4_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x1C000)
#define I2C1_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x20000)
#define I2C2_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x24000)
#define I2C3_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x28000)
#define ROMCP_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x2C000)
#define MMDC_P0_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x30000)
#define MMDC_P1_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x34000)
#define WEIM_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x38000)
#define OCOTP_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x3C000)
#define CSU_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x40000)
#define PERFMON1_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x44000)
#define PERFMON2_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x48000)
#define PERFMON3_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x4C000)
#define IP2APB_TZASC1_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x50000)
#define IP2APB_TZASC2_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x54000)
#define AUDMUX_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x58000)
#define MIPI_CSI2_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x5C000)
#define MIPI_DSI_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x60000)
#define VDOA_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x64000)
#define UART2_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x68000)
#define UART3_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x6C000)
#define UART4_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x70000)
#define UART5_BASE_ADDR (AIPS2_OFF_BASE_ADDR+0x74000)
// Cortex-A9 MPCore private memory region
#define ARM_PERIPHBASE 0x00A00000
#define SCU_BASE_ADDR ARM_PERIPHBASE
#define IC_INTERFACES_BASE_ADDR (ARM_PERIPHBASE+0x0100)
#define GLOBAL_TIMER_BASE_ADDR (ARM_PERIPHBASE+0x0200)
#define PRIVATE_TIMERS_WD_BASE_ADDR (ARM_PERIPHBASE+0x0600)
#define IC_DISTRIBUTOR_BASE_ADDR (ARM_PERIPHBASE+0x1000)
//Add from mx53 for ds90ur124.c
#define GPR_BASE_ADDR (IOMUXC_BASE_ADDR + 0x0)
#define OBSRV_BASE_ADDR (GPR_BASE_ADDR + 0x38)
#define SW_MUX_BASE_ADDR (OBSRV_BASE_ADDR + 0x14)
// clang-format
#endif //_SOC_MEMORY_MAP_H

View File

@ -0,0 +1,29 @@
ifeq ($(BOARD), imx6q-sabrelite)
toolchain ?= arm-none-eabi-
endif
ifeq ($(BOARD), zynq7000-zc702)
toolchain ?= arm-xilinx-eabi-
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 \
-I$(KERNEL_ROOT)/services/boards/$(BOARD) \
-I$(KERNEL_ROOT)/services/lib/serial \
-I$(KERNEL_ROOT)/services/drivers/$(BOARD)/include \
-I$(KERNEL_ROOT)/services/drivers/$(BOARD)/enet \
-I$(KERNEL_ROOT)/services/drivers/$(BOARD)/clock \
-I$(KERNEL_ROOT)/services/lib/usyscall \
-I$(KERNEL_ROOT)/services/lib/ipc
all: sabrelite_libtimer.o
@mv $^ $(KERNEL_ROOT)/services/app
%.o: %.c
@echo "cc $^"
@${cc} ${cflags} ${c_useropts} ${INC_DIR} -o $@ -c $^

View File

@ -0,0 +1,26 @@
/*
* 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 "sabrelite_timer.h"
IPC_INTERFACE(Ipc_delay_us, 1, usecs, sizeof(uint32_t));
int delay_us(struct Session* session, uint32_t usecs)
{
return IPC_CALL(Ipc_delay_us)(session, &usecs);
}
IPC_INTERFACE(Ipc_get_microseconds, 1, microsecs, sizeof(uint64_t));
uint64_t hello_string(struct Session* session)
{
uint64_t microsecs = 0;
int remote_ret = IPC_CALL(Ipc_get_microseconds)(session, &microsecs);
return microsecs;
}

View File

@ -0,0 +1,20 @@
/*
* 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"
IPC_SERVICES(IpcSabreliteTimer, Ipc_delay_us, Ipc_get_microseconds);
int delay_us(struct Session* session, uint32_t usecs);
uint64_t get_microseconds(struct Session* session);

View File

@ -1,7 +1,7 @@
ifeq ($(BOARD), imx6q-sabrelite) ifeq ($(BOARD), imx6q-sabrelite)
toolchain ?= arm-none-eabi- toolchain ?= arm-none-eabi-
user_ldflags = -N -Ttext 0 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 -no-pie 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
endif endif
ifeq ($(BOARD), zynq7000-zc702) ifeq ($(BOARD), zynq7000-zc702)
toolchain ?= arm-xilinx-eabi- toolchain ?= arm-xilinx-eabi-
@ -13,17 +13,19 @@ cc = ${toolchain}gcc
ld = ${toolchain}g++ ld = ${toolchain}g++
objdump = ${toolchain}objdump objdump = ${toolchain}objdump
c_useropts = -O0 c_useropts = -O2
INC_DIR = -I$(KERNEL_ROOT)/services/fs/libfs \ INC_DIR = -I$(KERNEL_ROOT)/services/fs/libfs \
-I$(KERNEL_ROOT)/services/fs/fs_server/include \ -I$(KERNEL_ROOT)/services/fs/fs_server/include \
-I$(KERNEL_ROOT)/services/lib/ipc \ -I$(KERNEL_ROOT)/services/lib/ipc \
-I$(KERNEL_ROOT)/services/lib/memory \ -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/boards/$(BOARD) \
-I$(KERNEL_ROOT)/services/app -I$(KERNEL_ROOT)/services/app
fs_server: fs_server.o fs.o block_io.o fs_server: fs_server.o fs.o block_io.o
@mv $^ ../../app @mv $^ $(KERNEL_ROOT)/services/app
%.o: %.c %.o: %.c
@echo "cc $^" @echo "cc $^"

View File

@ -57,7 +57,7 @@ static int InodeFreeRecursive(struct Inode* dp);
static char* PathElementExtract(char* path, char* name); static char* PathElementExtract(char* path, char* name);
static uint32_t InodeBlockMapping(struct Inode* inode, uint32_t block_num); static uint32_t InodeBlockMapping(struct Inode* inode, uint32_t block_num);
#define MAX_SUPPORT_FD 1024 #define MAX_SUPPORT_FD 2048
static struct FileDescriptor fd_table[MAX_SUPPORT_FD]; static struct FileDescriptor fd_table[MAX_SUPPORT_FD];
struct MemFsRange MemFsRange; struct MemFsRange MemFsRange;
@ -486,7 +486,7 @@ void FreeFileDescriptor(int fd)
printf("fd invlid.\n"); printf("fd invlid.\n");
return; return;
} }
fd_table[fd].data = 0; fd_table[fd].data = NULL;
return; return;
} }
@ -495,8 +495,9 @@ int AllocFileDescriptor(void)
int free_idx = -1; int free_idx = -1;
for (int i = 0; i < MAX_SUPPORT_FD; i++) { for (int i = 0; i < MAX_SUPPORT_FD; i++) {
// found free fd // found free fd
if (free_idx == -1 && fd_table[i].data == 0) { if (free_idx == -1 && fd_table[i].data == NULL) {
free_idx = i; free_idx = i;
break;
} }
} }
if (free_idx == -1) { if (free_idx == -1) {

View File

@ -23,7 +23,7 @@ struct CwdPair {
struct Inode* Inode; struct Inode* Inode;
}; };
#define MAX_SUPPORT_SESSION 1024 #define MAX_SUPPORT_SESSION 2048
static struct CwdPair session_cwd[MAX_SUPPORT_SESSION]; static struct CwdPair session_cwd[MAX_SUPPORT_SESSION];
static struct CwdPair* get_session_cwd(void) static struct CwdPair* get_session_cwd(void)
@ -357,7 +357,7 @@ int main(int argc, char* argv[])
MemFsInit((uintptr_t)FS_IMG_ADDR, (uint32_t)len); MemFsInit((uintptr_t)FS_IMG_ADDR, (uint32_t)len);
if (register_server("MemFS") < 0) { if (register_server("MemFS") < 0) {
printf("register server name: %s failed.\n", "SimpleServer"); printf("register server name: %s failed.\n", "MemFs");
exit(); exit();
} }
ipc_server_loop(&IpcFsServer); ipc_server_loop(&IpcFsServer);

View File

@ -51,8 +51,8 @@ Modification:
// [ block 0 ] [ block 1 ] [block 2] [...] [ block 28 ] [ ... ] // [ block 0 ] [ block 1 ] [block 2] [...] [ block 28 ] [ ... ]
// [ unused ] [super block] [Inode bit map] [block bit map] [data blocks] // [ unused ] [super block] [Inode bit map] [block bit map] [data blocks]
#define NR_DIRECT_BLOCKS 5 // direct block number #define NR_DIRECT_BLOCKS 4 // direct block number
#define NR_INDIRECT_BLOCKS 8 // indirect block number #define NR_INDIRECT_BLOCKS 25 // indirect block number
#define ROOT_INUM 1 // root inode number #define ROOT_INUM 1 // root inode number
#define MAX_INDIRECT_BLOCKS (BLOCK_SIZE / sizeof(uint32_t)) // Mmaximum number of indirect blocks mapped per block #define MAX_INDIRECT_BLOCKS (BLOCK_SIZE / sizeof(uint32_t)) // Mmaximum number of indirect blocks mapped per block
@ -88,7 +88,7 @@ struct Inode {
}; };
// directory entry // directory entry
#define DIR_NAME_SIZE 14 #define DIR_NAME_SIZE 30
struct DirectEntry { struct DirectEntry {
uint16_t inum; uint16_t inum;
char name[DIR_NAME_SIZE]; char name[DIR_NAME_SIZE];

View File

@ -1,7 +1,7 @@
ifeq ($(BOARD), imx6q-sabrelite) ifeq ($(BOARD), imx6q-sabrelite)
toolchain ?= arm-none-eabi- toolchain ?= arm-none-eabi-
user_ldflags = -N -Ttext 0 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 -no-pie 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
endif endif
ifeq ($(BOARD), zynq7000-zc702) ifeq ($(BOARD), zynq7000-zc702)
toolchain ?= arm-xilinx-eabi- toolchain ?= arm-xilinx-eabi-
@ -13,11 +13,13 @@ cc = ${toolchain}gcc
ld = ${toolchain}g++ ld = ${toolchain}g++
objdump = ${toolchain}objdump objdump = ${toolchain}objdump
c_useropts = -O0 c_useropts = -O2
INC_DIR = -I$(KERNEL_ROOT)/services/fs/libfs \ INC_DIR = -I$(KERNEL_ROOT)/services/fs/libfs \
-I$(KERNEL_ROOT)/services/lib/ipc \ -I$(KERNEL_ROOT)/services/lib/ipc \
-I$(KERNEL_ROOT)/services/lib/memory \ -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/boards/$(BOARD) \
-I$(KERNEL_ROOT)/services/app -I$(KERNEL_ROOT)/services/app

View File

@ -1,4 +1,4 @@
SRC_DIR := ipc memory SRC_DIR := ipc memory serial usyscall
include $(KERNEL_ROOT)/compiler.mk include $(KERNEL_ROOT)/compiler.mk

View File

@ -1,7 +1,7 @@
ifeq ($(BOARD), imx6q-sabrelite) ifeq ($(BOARD), imx6q-sabrelite)
toolchain ?= arm-none-eabi- toolchain ?= arm-none-eabi-
user_ldflags = -N -Ttext 0 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 -no-pie 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
endif endif
ifeq ($(BOARD), zynq7000-zc702) ifeq ($(BOARD), zynq7000-zc702)
toolchain ?= arm-xilinx-eabi- toolchain ?= arm-xilinx-eabi-
@ -13,10 +13,12 @@ cc = ${toolchain}gcc
ld = ${toolchain}g++ ld = ${toolchain}g++
objdump = ${toolchain}objdump objdump = ${toolchain}objdump
c_useropts = -O0 c_useropts = -O2
INC_DIR = -I$(KERNEL_ROOT)/services/lib/ipc \ INC_DIR = -I$(KERNEL_ROOT)/services/lib/ipc \
-I$(KERNEL_ROOT)/services/lib/memory \ -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/boards/$(BOARD) \
-I$(KERNEL_ROOT)/services/app -I$(KERNEL_ROOT)/services/app

View File

@ -156,6 +156,11 @@ void delay_session(void)
session_delayed = true; session_delayed = true;
} }
bool is_cur_session_delayed(void)
{
return session_delayed;
}
void ipc_server_loop(struct IpcNode* ipc_node) void ipc_server_loop(struct IpcNode* ipc_node)
{ {
struct Session session_list[NR_MAX_SESSION]; struct Session session_list[NR_MAX_SESSION];
@ -168,43 +173,49 @@ void ipc_server_loop(struct IpcNode* ipc_node)
*/ */
poll_session(session_list, NR_MAX_SESSION); poll_session(session_list, NR_MAX_SESSION);
/* handle each session */ /* handle each session */
for (int i = 0; i < NR_MAX_SESSION; i++) { bool has_delayed = true;
if (session_list[i].buf == NULL) { for (int repeat = 0; repeat <= 1 && has_delayed; repeat++) {
yield(SYS_TASK_YIELD_NO_REASON); has_delayed = false;
break; for (int i = 0; i < NR_MAX_SESSION; i++) {
} session_delayed = false;
cur_sess_id = session_list[i].id; if (session_list[i].buf == NULL) {
struct IpcMsg* msg = IPCSESSION_MSG(&session_list[i]); yield(SYS_TASK_YIELD_NO_REASON);
/* handle every message in current session
a session could be delay in case one of its message(current message) needs to wait for an interrupt message's arrival
interfaces[opcode] should explicitly call delay_session() and return to delay this session
*/
while (msg->header.magic == IPC_MSG_MAGIC && msg->header.valid == 1 && 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], msg->header.len) < 0) {
break; break;
} }
cur_sess_id = session_list[i].id;
// this is a message needs to handle struct IpcMsg* msg = IPCSESSION_MSG(&session_list[i]);
if (ipc_node->interfaces[msg->header.opcode]) { /* handle every message in current session
ipc_node->interfaces[msg->header.opcode](msg); a session could be delay in case one of its message(current message) needs to wait for an interrupt message's arrival
// check if this session is delayed by op handler, all messages after the delayed message in current session is blocked. interfaces[opcode] should explicitly call delay_session() and return to delay this session
if (session_delayed) { */
session_delayed = false; while (msg->header.magic == IPC_MSG_MAGIC && msg->header.valid == 1 && 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], msg->header.len) < 0) {
break; break;
} }
} else {
printf("Unsupport opcode(%d) for server: %s\n", msg->header.opcode, ipc_node->name); // this is a message needs to handle
if (ipc_node->interfaces[msg->header.opcode]) {
ipc_node->interfaces[msg->header.opcode](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()) {
msg->header.delayed = 1;
has_delayed = true;
break;
}
} else {
printf("Unsupport opcode(%d) for server: %s\n", msg->header.opcode, ipc_node->name);
}
// current msg is a message that needs to ignore
// finish this message in server's perspective
if (session_forward_head(&session_list[i], msg->header.len) < 0) {
break;
}
msg = IPCSESSION_MSG(&session_list[i]);
} }
// current msg is a message that needs to ignore // stop handle this session
// finish this message in server's perspective cur_sess_id = -1;
if (session_forward_head(&session_list[i], msg->header.len) < 0) {
break;
}
msg = IPCSESSION_MSG(&session_list[i]);
} }
// stop handle this session
cur_sess_id = -1;
} }
} }
} }

View File

@ -47,7 +47,7 @@ typedef struct {
uint64_t valid : 1; // for server to peek new msg uint64_t valid : 1; // for server to peek new msg
uint64_t done : 1; // for client to check request done uint64_t done : 1; // for client to check request done
uint64_t init : 1; // for client to check request done uint64_t init : 1; // for client to check request done
uint64_t reserved : 1; uint64_t delayed : 1;
uint64_t nr_args : 4; uint64_t nr_args : 4;
uint64_t opcode : 8; uint64_t opcode : 8;
uint64_t len : 16; uint64_t len : 16;
@ -60,13 +60,13 @@ typedef struct {
struct IpcArgInfo { struct IpcArgInfo {
uint16_t offset; uint16_t offset;
uint16_t len; uint16_t len;
}; } __attribute__((packed));
/* [header, ipc_arg_buffer_len[], ipc_arg_buffer[]] */ /* [header, ipc_arg_buffer_len[], ipc_arg_buffer[]] */
struct IpcMsg { struct IpcMsg {
ipc_msg_header header; ipc_msg_header header;
uintptr_t buf[]; uintptr_t buf[];
}; } __attribute__((packed));
enum { enum {
IPC_ARG_INFO_BASE_OFFSET = sizeof(ipc_msg_header), IPC_ARG_INFO_BASE_OFFSET = sizeof(ipc_msg_header),
}; };
@ -76,7 +76,7 @@ typedef int (*IpcInterface)(struct IpcMsg* msg);
struct IpcNode { struct IpcNode {
char* name; char* name;
IpcInterface interfaces[UINT8_MAX]; IpcInterface interfaces[UINT8_MAX];
}; } __attribute__((packed));
#define IPC_SERVER_LOOP(ipc_node_name) rpc_server_loop_##rpc_node_name #define IPC_SERVER_LOOP(ipc_node_name) rpc_server_loop_##rpc_node_name
#define IPC_SERVICES(ipc_node_name, ...) \ #define IPC_SERVICES(ipc_node_name, ...) \
@ -225,6 +225,7 @@ void ipc_server_loop(struct IpcNode* ipc_node);
return res; \ return res; \
} }
bool is_cur_session_delayed(void);
#define IPC_SERVER_INTERFACE(ipc_name, argc) \ #define IPC_SERVER_INTERFACE(ipc_name, argc) \
static int IPC_SERVE(ipc_name)(struct IpcMsg * msg) \ static int IPC_SERVE(ipc_name)(struct IpcMsg * msg) \
{ \ { \
@ -233,8 +234,10 @@ void ipc_server_loop(struct IpcNode* ipc_node);
argv[i] = ipc_msg_get_nth_arg_buf(msg, i); \ argv[i] = ipc_msg_get_nth_arg_buf(msg, i); \
} \ } \
int32_t _ret = IPC_DO_SERVE##argc(ipc_name); \ int32_t _ret = IPC_DO_SERVE##argc(ipc_name); \
ipc_msg_set_return(msg, &_ret); \ if (!is_cur_session_delayed()) { \
msg->header.done = 1; \ ipc_msg_set_return(msg, &_ret); \
msg->header.done = 1; \
} \
return 0; \ return 0; \
} }

View File

@ -10,12 +10,14 @@ objdump = ${toolchain}objdump
user_ldflags = -N -Ttext 0 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 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 = -O0 c_useropts = -O2
INC_DIR = -I$(KERNEL_ROOT)/services/app \ INC_DIR = -I$(KERNEL_ROOT)/services/app \
-I$(KERNEL_ROOT)/services/fs/libfs \ -I$(KERNEL_ROOT)/services/fs/libfs \
-I$(KERNEL_ROOT)/services/boards/$(BOARD) \ -I$(KERNEL_ROOT)/services/boards/$(BOARD) \
-I$(KERNEL_ROOT)/services/lib/memory \ -I$(KERNEL_ROOT)/services/lib/memory \
-I$(KERNEL_ROOT)/services/lib/serial \
-I$(KERNEL_ROOT)/services/lib/usyscall \
-I$(KERNEL_ROOT)/services/lib/ipc -I$(KERNEL_ROOT)/services/lib/ipc
all: libmem.o all: libmem.o

View File

@ -0,0 +1,28 @@
ifeq ($(BOARD), imx6q-sabrelite)
toolchain ?= arm-none-eabi-
endif
ifeq ($(BOARD), zynq7000-zc702)
toolchain ?= arm-xilinx-eabi-
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 \
-I$(KERNEL_ROOT)/services/fs/libfs \
-I$(KERNEL_ROOT)/services/boards/$(BOARD) \
-I$(KERNEL_ROOT)/services/lib/memory \
-I$(KERNEL_ROOT)/services/lib/serial \
-I$(KERNEL_ROOT)/services/lib/usyscall \
-I$(KERNEL_ROOT)/services/lib/ipc
all: printf.o
@mv $^ $(KERNEL_ROOT)/services/app
%.o: %.c
@echo "cc $^"
@${cc} ${cflags} ${c_useropts} ${INC_DIR} -o $@ -c $^

View File

@ -12,7 +12,10 @@
/// this file is only used for debug /// this file is only used for debug
#pragma once #pragma once
#include <stdbool.h>
void printf(char* fmt, ...); #include "printf.h"
bool init_uart_mmio();
void putc(char c);
char getc(); char getc();

View File

@ -0,0 +1,884 @@
///////////////////////////////////////////////////////////////////////////////
// \author (c) Marco Paland (info@paland.com)
// 2014-2019, PALANDesign Hannover, Germany
//
// \license The MIT License (MIT)
//
// 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.
//
// \brief Tiny printf, sprintf and (v)snprintf implementation, optimized for speed on
// embedded systems with a very limited resources. These routines are thread
// safe and reentrant!
// Use this instead of the bloated standard/newlib printf cause these use
// malloc for printf (and may not be thread safe).
//
///////////////////////////////////////////////////////////////////////////////
/**
* @file uart_common_ope.c
* @brief support uart common operation
* @version 3.0
* @author AIIT XUOS Lab
* @date 2023.11.20
*/
#include <stdbool.h>
#include <stdint.h>
#include "libserial.h"
#include "printf.h"
// 'ntoa' conversion buffer size, this must be big enough to hold one converted
// numeric number including padded zeros (dynamically created on stack)
// default: 32 byte
#define PRINTF_NTOA_BUFFER_SIZE 32U
#define PRINTF_FTOA_BUFFER_SIZE 32U
// support for the floating point type (%f)
// default: activated
#define PRINTF_SUPPORT_FLOAT
// support for exponential floating point notation (%e/%g)
// default: activated
#define PRINTF_SUPPORT_EXPONENTIAL
// define the default floating point precision
// default: 6 digits
#define PRINTF_DEFAULT_FLOAT_PRECISION 6U
// define the largest float suitable to print with %f
// default: 1e9
#define PRINTF_MAX_FLOAT 1e9
// support for the long long types (%llu or %p)
// default: activated
#define PRINTF_SUPPORT_LONG_LONG
// support for the ptrdiff_t type (%t)
// ptrdiff_t is normally defined in <stddef.h> as long or long long type
// default: activated
#define PRINTF_SUPPORT_PTRDIFF_T
#define _putchar putc
///////////////////////////////////////////////////////////////////////////////
// internal flag definitions
#define FLAGS_ZEROPAD (1U << 0U)
#define FLAGS_LEFT (1U << 1U)
#define FLAGS_PLUS (1U << 2U)
#define FLAGS_SPACE (1U << 3U)
#define FLAGS_HASH (1U << 4U)
#define FLAGS_UPPERCASE (1U << 5U)
#define FLAGS_CHAR (1U << 6U)
#define FLAGS_SHORT (1U << 7U)
#define FLAGS_LONG (1U << 8U)
#define FLAGS_LONG_LONG (1U << 9U)
#define FLAGS_PRECISION (1U << 10U)
#define FLAGS_ADAPT_EXP (1U << 11U)
// import float.h for DBL_MAX
#if defined(PRINTF_SUPPORT_FLOAT)
#include <float.h>
#endif
// output function type
typedef void (*out_fct_type)(char character, void* buffer, size_t idx, size_t maxlen);
// wrapper (used as buffer) for output function type
typedef struct {
void (*fct)(char character, void* arg);
void* arg;
} out_fct_wrap_type;
// internal buffer output
static inline void _out_buffer(char character, void* buffer, size_t idx, size_t maxlen)
{
if (idx < maxlen) {
((char*)buffer)[idx] = character;
}
}
// internal null output
static inline void _out_null(char character, void* buffer, size_t idx, size_t maxlen)
{
(void)character;
(void)buffer;
(void)idx;
(void)maxlen;
}
// internal _putchar wrapper
static inline void _out_char(char character, void* buffer, size_t idx, size_t maxlen)
{
(void)buffer;
(void)idx;
(void)maxlen;
if (character) {
_putchar(character);
}
}
// internal output function wrapper
static inline void _out_fct(char character, void* buffer, size_t idx, size_t maxlen)
{
(void)idx;
(void)maxlen;
if (character) {
// buffer is the output fct pointer
((out_fct_wrap_type*)buffer)->fct(character, ((out_fct_wrap_type*)buffer)->arg);
}
}
// internal secure strlen
// \return The length of the string (excluding the terminating 0) limited by 'maxsize'
static inline unsigned int _strnlen_s(const char* str, size_t maxsize)
{
const char* s;
for (s = str; *s && maxsize--; ++s)
;
return (unsigned int)(s - str);
}
// internal test if char is a digit (0-9)
// \return true if char is a digit
static inline bool _is_digit(char ch)
{
return (ch >= '0') && (ch <= '9');
}
// internal ASCII string to unsigned int conversion
static unsigned int _atoi(const char** str)
{
unsigned int i = 0U;
while (_is_digit(**str)) {
i = i * 10U + (unsigned int)(*((*str)++) - '0');
}
return i;
}
// output the specified string in reverse, taking care of any zero-padding
static size_t _out_rev(out_fct_type out, char* buffer, size_t idx, size_t maxlen, const char* buf, size_t len, unsigned int width, unsigned int flags)
{
const size_t start_idx = idx;
// pad spaces up to given width
if (!(flags & FLAGS_LEFT) && !(flags & FLAGS_ZEROPAD)) {
for (size_t i = len; i < width; i++) {
out(' ', buffer, idx++, maxlen);
}
}
// reverse string
while (len) {
out(buf[--len], buffer, idx++, maxlen);
}
// append pad spaces up to given width
if (flags & FLAGS_LEFT) {
while (idx - start_idx < width) {
out(' ', buffer, idx++, maxlen);
}
}
return idx;
}
// internal itoa format
static size_t _ntoa_format(out_fct_type out, char* buffer, size_t idx, size_t maxlen, char* buf, size_t len, bool negative, unsigned int base, unsigned int prec, unsigned int width, unsigned int flags)
{
// pad leading zeros
if (!(flags & FLAGS_LEFT)) {
if (width && (flags & FLAGS_ZEROPAD) && (negative || (flags & (FLAGS_PLUS | FLAGS_SPACE)))) {
width--;
}
while ((len < prec) && (len < PRINTF_NTOA_BUFFER_SIZE)) {
buf[len++] = '0';
}
while ((flags & FLAGS_ZEROPAD) && (len < width) && (len < PRINTF_NTOA_BUFFER_SIZE)) {
buf[len++] = '0';
}
}
// handle hash
if (flags & FLAGS_HASH) {
if (!(flags & FLAGS_PRECISION) && len && ((len == prec) || (len == width))) {
len--;
if (len && (base == 16U)) {
len--;
}
}
if ((base == 16U) && !(flags & FLAGS_UPPERCASE) && (len < PRINTF_NTOA_BUFFER_SIZE)) {
buf[len++] = 'x';
} else if ((base == 16U) && (flags & FLAGS_UPPERCASE) && (len < PRINTF_NTOA_BUFFER_SIZE)) {
buf[len++] = 'X';
} else if ((base == 2U) && (len < PRINTF_NTOA_BUFFER_SIZE)) {
buf[len++] = 'b';
}
if (len < PRINTF_NTOA_BUFFER_SIZE) {
buf[len++] = '0';
}
}
if (len < PRINTF_NTOA_BUFFER_SIZE) {
if (negative) {
buf[len++] = '-';
} else if (flags & FLAGS_PLUS) {
buf[len++] = '+'; // ignore the space if the '+' exists
} else if (flags & FLAGS_SPACE) {
buf[len++] = ' ';
}
}
return _out_rev(out, buffer, idx, maxlen, buf, len, width, flags);
}
// internal itoa for 'long' type
static size_t _ntoa_long(out_fct_type out, char* buffer, size_t idx, size_t maxlen, unsigned long value, bool negative, unsigned long base, unsigned int prec, unsigned int width, unsigned int flags)
{
char buf[PRINTF_NTOA_BUFFER_SIZE];
size_t len = 0U;
// no hash for 0 values
if (!value) {
flags &= ~FLAGS_HASH;
}
// write if precision != 0 and value is != 0
if (!(flags & FLAGS_PRECISION) || value) {
do {
const char digit = (char)(value % base);
buf[len++] = digit < 10 ? '0' + digit : (flags & FLAGS_UPPERCASE ? 'A' : 'a') + digit - 10;
value /= base;
} while (value && (len < PRINTF_NTOA_BUFFER_SIZE));
}
return _ntoa_format(out, buffer, idx, maxlen, buf, len, negative, (unsigned int)base, prec, width, flags);
}
// internal itoa for 'long long' type
#if defined(PRINTF_SUPPORT_LONG_LONG)
static size_t _ntoa_long_long(out_fct_type out, char* buffer, size_t idx, size_t maxlen, unsigned long long value, bool negative, unsigned long long base, unsigned int prec, unsigned int width, unsigned int flags)
{
char buf[PRINTF_NTOA_BUFFER_SIZE];
size_t len = 0U;
// no hash for 0 values
if (!value) {
flags &= ~FLAGS_HASH;
}
// write if precision != 0 and value is != 0
if (!(flags & FLAGS_PRECISION) || value) {
do {
const char digit = (char)(value % base);
buf[len++] = digit < 10 ? '0' + digit : (flags & FLAGS_UPPERCASE ? 'A' : 'a') + digit - 10;
value /= base;
} while (value && (len < PRINTF_NTOA_BUFFER_SIZE));
}
return _ntoa_format(out, buffer, idx, maxlen, buf, len, negative, (unsigned int)base, prec, width, flags);
}
#endif // PRINTF_SUPPORT_LONG_LONG
#if defined(PRINTF_SUPPORT_FLOAT)
#if defined(PRINTF_SUPPORT_EXPONENTIAL)
// forward declaration so that _ftoa can switch to exp notation for values > PRINTF_MAX_FLOAT
static size_t _etoa(out_fct_type out, char* buffer, size_t idx, size_t maxlen, double value, unsigned int prec, unsigned int width, unsigned int flags);
#endif
// internal ftoa for fixed decimal floating point
static size_t _ftoa(out_fct_type out, char* buffer, size_t idx, size_t maxlen, double value, unsigned int prec, unsigned int width, unsigned int flags)
{
char buf[PRINTF_FTOA_BUFFER_SIZE];
size_t len = 0U;
double diff = 0.0;
// powers of 10
static const double pow10[] = { 1, 10, 100, 1000, 10000, 100000, 1000000, 10000000, 100000000, 1000000000 };
// test for special values
if (value != value)
return _out_rev(out, buffer, idx, maxlen, "nan", 3, width, flags);
if (value < -DBL_MAX)
return _out_rev(out, buffer, idx, maxlen, "fni-", 4, width, flags);
if (value > DBL_MAX)
return _out_rev(out, buffer, idx, maxlen, (flags & FLAGS_PLUS) ? "fni+" : "fni", (flags & FLAGS_PLUS) ? 4U : 3U, width, flags);
// test for very large values
// standard printf behavior is to print EVERY whole number digit -- which could be 100s of characters overflowing your buffers == bad
if ((value > PRINTF_MAX_FLOAT) || (value < -PRINTF_MAX_FLOAT)) {
#if defined(PRINTF_SUPPORT_EXPONENTIAL)
return _etoa(out, buffer, idx, maxlen, value, prec, width, flags);
#else
return 0U;
#endif
}
// test for negative
bool negative = false;
if (value < 0) {
negative = true;
value = 0 - value;
}
// set default precision, if not set explicitly
if (!(flags & FLAGS_PRECISION)) {
prec = PRINTF_DEFAULT_FLOAT_PRECISION;
}
// limit precision to 9, cause a prec >= 10 can lead to overflow errors
while ((len < PRINTF_FTOA_BUFFER_SIZE) && (prec > 9U)) {
buf[len++] = '0';
prec--;
}
int whole = (int)value;
double tmp = (value - whole) * pow10[prec];
unsigned long frac = (unsigned long)tmp;
diff = tmp - frac;
if (diff > 0.5) {
++frac;
// handle rollover, e.g. case 0.99 with prec 1 is 1.0
if (frac >= pow10[prec]) {
frac = 0;
++whole;
}
} else if (diff < 0.5) {
} else if ((frac == 0U) || (frac & 1U)) {
// if halfway, round up if odd OR if last digit is 0
++frac;
}
if (prec == 0U) {
diff = value - (double)whole;
if ((!(diff < 0.5) || (diff > 0.5)) && (whole & 1)) {
// exactly 0.5 and ODD, then round up
// 1.5 -> 2, but 2.5 -> 2
++whole;
}
} else {
unsigned int count = prec;
// now do fractional part, as an unsigned number
while (len < PRINTF_FTOA_BUFFER_SIZE) {
--count;
buf[len++] = (char)(48U + (frac % 10U));
if (!(frac /= 10U)) {
break;
}
}
// add extra 0s
while ((len < PRINTF_FTOA_BUFFER_SIZE) && (count-- > 0U)) {
buf[len++] = '0';
}
if (len < PRINTF_FTOA_BUFFER_SIZE) {
// add decimal
buf[len++] = '.';
}
}
// do whole part, number is reversed
while (len < PRINTF_FTOA_BUFFER_SIZE) {
buf[len++] = (char)(48 + (whole % 10));
if (!(whole /= 10)) {
break;
}
}
// pad leading zeros
if (!(flags & FLAGS_LEFT) && (flags & FLAGS_ZEROPAD)) {
if (width && (negative || (flags & (FLAGS_PLUS | FLAGS_SPACE)))) {
width--;
}
while ((len < width) && (len < PRINTF_FTOA_BUFFER_SIZE)) {
buf[len++] = '0';
}
}
if (len < PRINTF_FTOA_BUFFER_SIZE) {
if (negative) {
buf[len++] = '-';
} else if (flags & FLAGS_PLUS) {
buf[len++] = '+'; // ignore the space if the '+' exists
} else if (flags & FLAGS_SPACE) {
buf[len++] = ' ';
}
}
return _out_rev(out, buffer, idx, maxlen, buf, len, width, flags);
}
#if defined(PRINTF_SUPPORT_EXPONENTIAL)
// internal ftoa variant for exponential floating-point type, contributed by Martijn Jasperse <m.jasperse@gmail.com>
static size_t _etoa(out_fct_type out, char* buffer, size_t idx, size_t maxlen, double value, unsigned int prec, unsigned int width, unsigned int flags)
{
// check for NaN and special values
if ((value != value) || (value > DBL_MAX) || (value < -DBL_MAX)) {
return _ftoa(out, buffer, idx, maxlen, value, prec, width, flags);
}
// determine the sign
const bool negative = value < 0;
if (negative) {
value = -value;
}
// default precision
if (!(flags & FLAGS_PRECISION)) {
prec = PRINTF_DEFAULT_FLOAT_PRECISION;
}
// determine the decimal exponent
// based on the algorithm by David Gay (https://www.ampl.com/netlib/fp/dtoa.c)
union {
uint64_t U;
double F;
} conv;
conv.F = value;
int exp2 = (int)((conv.U >> 52U) & 0x07FFU) - 1023; // effectively log2
conv.U = (conv.U & ((1ULL << 52U) - 1U)) | (1023ULL << 52U); // drop the exponent so conv.F is now in [1,2)
// now approximate log10 from the log2 integer part and an expansion of ln around 1.5
int expval = (int)(0.1760912590558 + exp2 * 0.301029995663981 + (conv.F - 1.5) * 0.289529654602168);
// now we want to compute 10^expval but we want to be sure it won't overflow
exp2 = (int)(expval * 3.321928094887362 + 0.5);
const double z = expval * 2.302585092994046 - exp2 * 0.6931471805599453;
const double z2 = z * z;
conv.U = (uint64_t)(exp2 + 1023) << 52U;
// compute exp(z) using continued fractions, see https://en.wikipedia.org/wiki/Exponential_function#Continued_fractions_for_ex
conv.F *= 1 + 2 * z / (2 - z + (z2 / (6 + (z2 / (10 + z2 / 14)))));
// correct for rounding errors
if (value < conv.F) {
expval--;
conv.F /= 10;
}
// the exponent format is "%+03d" and largest value is "307", so set aside 4-5 characters
unsigned int minwidth = ((expval < 100) && (expval > -100)) ? 4U : 5U;
// in "%g" mode, "prec" is the number of *significant figures* not decimals
if (flags & FLAGS_ADAPT_EXP) {
// do we want to fall-back to "%f" mode?
if ((value >= 1e-4) && (value < 1e6)) {
if ((int)prec > expval) {
prec = (unsigned)((int)prec - expval - 1);
} else {
prec = 0;
}
flags |= FLAGS_PRECISION; // make sure _ftoa respects precision
// no characters in exponent
minwidth = 0U;
expval = 0;
} else {
// we use one sigfig for the whole part
if ((prec > 0) && (flags & FLAGS_PRECISION)) {
--prec;
}
}
}
// will everything fit?
unsigned int fwidth = width;
if (width > minwidth) {
// we didn't fall-back so subtract the characters required for the exponent
fwidth -= minwidth;
} else {
// not enough characters, so go back to default sizing
fwidth = 0U;
}
if ((flags & FLAGS_LEFT) && minwidth) {
// if we're padding on the right, DON'T pad the floating part
fwidth = 0U;
}
// rescale the float value
if (expval) {
value /= conv.F;
}
// output the floating part
const size_t start_idx = idx;
idx = _ftoa(out, buffer, idx, maxlen, negative ? -value : value, prec, fwidth, flags & ~FLAGS_ADAPT_EXP);
// output the exponent part
if (minwidth) {
// output the exponential symbol
out((flags & FLAGS_UPPERCASE) ? 'E' : 'e', buffer, idx++, maxlen);
// output the exponent value
idx = _ntoa_long(out, buffer, idx, maxlen, (expval < 0) ? -expval : expval, expval < 0, 10, 0, minwidth - 1, FLAGS_ZEROPAD | FLAGS_PLUS);
// might need to right-pad spaces
if (flags & FLAGS_LEFT) {
while (idx - start_idx < width)
out(' ', buffer, idx++, maxlen);
}
}
return idx;
}
#endif // PRINTF_SUPPORT_EXPONENTIAL
#endif // PRINTF_SUPPORT_FLOAT
// internal vsnprintf
static int _vsnprintf(out_fct_type out, char* buffer, const size_t maxlen, const char* format, va_list va)
{
unsigned int flags, width, precision, n;
size_t idx = 0U;
if (!buffer) {
// use null output function
out = _out_null;
}
while (*format) {
// format specifier? %[flags][width][.precision][length]
if (*format != '%') {
// no
out(*format, buffer, idx++, maxlen);
format++;
continue;
} else {
// yes, evaluate it
format++;
}
// evaluate flags
flags = 0U;
do {
switch (*format) {
case '0':
flags |= FLAGS_ZEROPAD;
format++;
n = 1U;
break;
case '-':
flags |= FLAGS_LEFT;
format++;
n = 1U;
break;
case '+':
flags |= FLAGS_PLUS;
format++;
n = 1U;
break;
case ' ':
flags |= FLAGS_SPACE;
format++;
n = 1U;
break;
case '#':
flags |= FLAGS_HASH;
format++;
n = 1U;
break;
default:
n = 0U;
break;
}
} while (n);
// evaluate width field
width = 0U;
if (_is_digit(*format)) {
width = _atoi(&format);
} else if (*format == '*') {
const int w = va_arg(va, int);
if (w < 0) {
flags |= FLAGS_LEFT; // reverse padding
width = (unsigned int)-w;
} else {
width = (unsigned int)w;
}
format++;
}
// evaluate precision field
precision = 0U;
if (*format == '.') {
flags |= FLAGS_PRECISION;
format++;
if (_is_digit(*format)) {
precision = _atoi(&format);
} else if (*format == '*') {
const int prec = (int)va_arg(va, int);
precision = prec > 0 ? (unsigned int)prec : 0U;
format++;
}
}
// evaluate length field
switch (*format) {
case 'l':
flags |= FLAGS_LONG;
format++;
if (*format == 'l') {
flags |= FLAGS_LONG_LONG;
format++;
}
break;
case 'h':
flags |= FLAGS_SHORT;
format++;
if (*format == 'h') {
flags |= FLAGS_CHAR;
format++;
}
break;
#if defined(PRINTF_SUPPORT_PTRDIFF_T)
case 't':
flags |= (sizeof(ptrdiff_t) == sizeof(long) ? FLAGS_LONG : FLAGS_LONG_LONG);
format++;
break;
#endif
case 'j':
flags |= (sizeof(intmax_t) == sizeof(long) ? FLAGS_LONG : FLAGS_LONG_LONG);
format++;
break;
case 'z':
flags |= (sizeof(size_t) == sizeof(long) ? FLAGS_LONG : FLAGS_LONG_LONG);
format++;
break;
default:
break;
}
// evaluate specifier
switch (*format) {
case 'd':
case 'i':
case 'u':
case 'x':
case 'X':
case 'o':
case 'b': {
// set the base
unsigned int base;
if (*format == 'x' || *format == 'X') {
base = 16U;
} else if (*format == 'o') {
base = 8U;
} else if (*format == 'b') {
base = 2U;
} else {
base = 10U;
flags &= ~FLAGS_HASH; // no hash for dec format
}
// uppercase
if (*format == 'X') {
flags |= FLAGS_UPPERCASE;
}
// no plus or space flag for u, x, X, o, b
if ((*format != 'i') && (*format != 'd')) {
flags &= ~(FLAGS_PLUS | FLAGS_SPACE);
}
// ignore '0' flag when precision is given
if (flags & FLAGS_PRECISION) {
flags &= ~FLAGS_ZEROPAD;
}
// convert the integer
if ((*format == 'i') || (*format == 'd')) {
// signed
if (flags & FLAGS_LONG_LONG) {
#if defined(PRINTF_SUPPORT_LONG_LONG)
const long long value = va_arg(va, long long);
idx = _ntoa_long_long(out, buffer, idx, maxlen, (unsigned long long)(value > 0 ? value : 0 - value), value < 0, base, precision, width, flags);
#endif
} else if (flags & FLAGS_LONG) {
const long value = va_arg(va, long);
idx = _ntoa_long(out, buffer, idx, maxlen, (unsigned long)(value > 0 ? value : 0 - value), value < 0, base, precision, width, flags);
} else {
const int value = (flags & FLAGS_CHAR) ? (char)va_arg(va, int) : (flags & FLAGS_SHORT) ? (short int)va_arg(va, int)
: va_arg(va, int);
idx = _ntoa_long(out, buffer, idx, maxlen, (unsigned int)(value > 0 ? value : 0 - value), value < 0, base, precision, width, flags);
}
} else {
// unsigned
if (flags & FLAGS_LONG_LONG) {
#if defined(PRINTF_SUPPORT_LONG_LONG)
idx = _ntoa_long_long(out, buffer, idx, maxlen, va_arg(va, unsigned long long), false, base, precision, width, flags);
#endif
} else if (flags & FLAGS_LONG) {
idx = _ntoa_long(out, buffer, idx, maxlen, va_arg(va, unsigned long), false, base, precision, width, flags);
} else {
const unsigned int value = (flags & FLAGS_CHAR) ? (unsigned char)va_arg(va, unsigned int) : (flags & FLAGS_SHORT) ? (unsigned short int)va_arg(va, unsigned int)
: va_arg(va, unsigned int);
idx = _ntoa_long(out, buffer, idx, maxlen, value, false, base, precision, width, flags);
}
}
format++;
break;
}
#if defined(PRINTF_SUPPORT_FLOAT)
case 'f':
case 'F':
if (*format == 'F')
flags |= FLAGS_UPPERCASE;
idx = _ftoa(out, buffer, idx, maxlen, va_arg(va, double), precision, width, flags);
format++;
break;
#if defined(PRINTF_SUPPORT_EXPONENTIAL)
case 'e':
case 'E':
case 'g':
case 'G':
if ((*format == 'g') || (*format == 'G'))
flags |= FLAGS_ADAPT_EXP;
if ((*format == 'E') || (*format == 'G'))
flags |= FLAGS_UPPERCASE;
idx = _etoa(out, buffer, idx, maxlen, va_arg(va, double), precision, width, flags);
format++;
break;
#endif // PRINTF_SUPPORT_EXPONENTIAL
#endif // PRINTF_SUPPORT_FLOAT
case 'c': {
unsigned int l = 1U;
// pre padding
if (!(flags & FLAGS_LEFT)) {
while (l++ < width) {
out(' ', buffer, idx++, maxlen);
}
}
// char output
out((char)va_arg(va, int), buffer, idx++, maxlen);
// post padding
if (flags & FLAGS_LEFT) {
while (l++ < width) {
out(' ', buffer, idx++, maxlen);
}
}
format++;
break;
}
case 's': {
const char* p = va_arg(va, char*);
unsigned int l = _strnlen_s(p, precision ? precision : (size_t)-1);
// pre padding
if (flags & FLAGS_PRECISION) {
l = (l < precision ? l : precision);
}
if (!(flags & FLAGS_LEFT)) {
while (l++ < width) {
out(' ', buffer, idx++, maxlen);
}
}
// string output
while ((*p != 0) && (!(flags & FLAGS_PRECISION) || precision--)) {
out(*(p++), buffer, idx++, maxlen);
}
// post padding
if (flags & FLAGS_LEFT) {
while (l++ < width) {
out(' ', buffer, idx++, maxlen);
}
}
format++;
break;
}
case 'p': {
width = sizeof(void*) * 2U;
flags |= FLAGS_ZEROPAD | FLAGS_UPPERCASE;
#if defined(PRINTF_SUPPORT_LONG_LONG)
const bool is_ll = sizeof(uintptr_t) == sizeof(long long);
if (is_ll) {
idx = _ntoa_long_long(out, buffer, idx, maxlen, (uintptr_t)va_arg(va, void*), false, 16U, precision, width, flags);
} else {
#endif
idx = _ntoa_long(out, buffer, idx, maxlen, (unsigned long)((uintptr_t)va_arg(va, void*)), false, 16U, precision, width, flags);
#if defined(PRINTF_SUPPORT_LONG_LONG)
}
#endif
format++;
break;
}
case '%':
out('%', buffer, idx++, maxlen);
format++;
break;
default:
out(*format, buffer, idx++, maxlen);
format++;
break;
}
}
// termination
out((char)0, buffer, idx < maxlen ? idx : maxlen - 1U, maxlen);
// return written chars without terminating \0
return (int)idx;
}
///////////////////////////////////////////////////////////////////////////////
int printf(const char* format, ...)
{
if (!init_uart_mmio()) {
return -1;
}
va_list va;
va_start(va, format);
char buffer[1];
const int ret = _vsnprintf(_out_char, buffer, (size_t)-1, format, va);
va_end(va);
return ret;
}
int sprintf_(char* buffer, const char* format, ...)
{
va_list va;
va_start(va, format);
const int ret = _vsnprintf(_out_buffer, buffer, (size_t)-1, format, va);
va_end(va);
return ret;
}
int snprintf_(char* buffer, size_t count, const char* format, ...)
{
va_list va;
va_start(va, format);
const int ret = _vsnprintf(_out_buffer, buffer, count, format, va);
va_end(va);
return ret;
}
int vprintf_(const char* format, va_list va)
{
char buffer[1];
return _vsnprintf(_out_char, buffer, (size_t)-1, format, va);
}
int vsnprintf_(char* buffer, size_t count, const char* format, va_list va)
{
return _vsnprintf(_out_buffer, buffer, count, format, va);
}
int fctprintf(void (*out)(char character, void* arg), void* arg, const char* format, ...)
{
va_list va;
va_start(va, format);
const out_fct_wrap_type out_fct_wrap = { out, arg };
const int ret = _vsnprintf(_out_fct, (char*)(uintptr_t)&out_fct_wrap, (size_t)-1, format, va);
va_end(va);
return ret;
}

View File

@ -0,0 +1,100 @@
///////////////////////////////////////////////////////////////////////////////
// \author (c) Marco Paland (info@paland.com)
// 2014-2019, PALANDesign Hannover, Germany
//
// \license The MIT License (MIT)
//
// 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.
//
// \brief Tiny printf, sprintf and snprintf implementation, optimized for speed on
// embedded systems with a very limited resources.
// Use this instead of bloated standard/newlib printf.
// These routines are thread safe and reentrant.
//
///////////////////////////////////////////////////////////////////////////////
#ifndef _PRINTF_H_
#define _PRINTF_H_
#include <stdarg.h>
#include <stddef.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* Tiny printf implementation
* You have to implement _putchar if you use printf()
* To avoid conflicts with the regular printf() API it is overridden by macro defines
* and internal underscore-appended functions like printf_() are used
* \param format A string that specifies the format of the output
* \return The number of characters that are written into the array, not counting the terminating null character
*/
int printf(const char* format, ...);
/**
* Tiny sprintf implementation
* Due to security reasons (buffer overflow) YOU SHOULD CONSIDER USING (V)SNPRINTF INSTEAD!
* \param buffer A pointer to the buffer where to store the formatted string. MUST be big enough to store the output!
* \param format A string that specifies the format of the output
* \return The number of characters that are WRITTEN into the buffer, not counting the terminating null character
*/
#define sprintf sprintf_
int sprintf_(char* buffer, const char* format, ...);
/**
* Tiny snprintf/vsnprintf implementation
* \param buffer A pointer to the buffer where to store the formatted string
* \param count The maximum number of characters to store in the buffer, including a terminating null character
* \param format A string that specifies the format of the output
* \param va A value identifying a variable arguments list
* \return The number of characters that COULD have been written into the buffer, not counting the terminating
* null character. A value equal or larger than count indicates truncation. Only when the returned value
* is non-negative and less than count, the string has been completely written.
*/
#define snprintf snprintf_
#define vsnprintf vsnprintf_
int snprintf_(char* buffer, size_t count, const char* format, ...);
int vsnprintf_(char* buffer, size_t count, const char* format, va_list va);
/**
* Tiny vprintf implementation
* \param format A string that specifies the format of the output
* \param va A value identifying a variable arguments list
* \return The number of characters that are WRITTEN into the buffer, not counting the terminating null character
*/
#define vprintf vprintf_
int vprintf_(const char* format, va_list va);
/**
* printf with output function
* You may use this as dynamic alternative to printf() with its fixed _putchar() output
* \param out An output function which takes one character and an argument pointer
* \param arg An argument pointer for user data passed to output function
* \param format A string that specifies the format of the output
* \return The number of characters that are sent to the output function, not counting the terminating null character
*/
int fctprintf(void (*out)(char character, void* arg), void* arg, const char* format, ...);
#ifdef __cplusplus
}
#endif
#endif // _PRINTF_H_

View File

@ -0,0 +1,28 @@
ifeq ($(BOARD), imx6q-sabrelite)
toolchain ?= arm-none-eabi-
endif
ifeq ($(BOARD), zynq7000-zc702)
toolchain ?= arm-xilinx-eabi-
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 \
-I$(KERNEL_ROOT)/services/fs/libfs \
-I$(KERNEL_ROOT)/services/boards/$(BOARD) \
-I$(KERNEL_ROOT)/services/lib/memory \
-I$(KERNEL_ROOT)/services/lib/serial \
-I$(KERNEL_ROOT)/services/lib/usyscall \
-I$(KERNEL_ROOT)/services/lib/ipc
all: usyscall.o
@mv $^ ../../app
%.o: %.c
@echo "cc $^"
@${cc} ${cflags} ${c_useropts} ${INC_DIR} -o $@ -c $^

View File

@ -12,28 +12,6 @@
#include "usyscall.h" #include "usyscall.h"
#include "libmem.h" #include "libmem.h"
static int
syscall(int sys_num, intptr_t a1, intptr_t a2, intptr_t a3, intptr_t a4)
{
int ret = -1;
__asm__ volatile(
"mov r0, %1;\
mov r1, %2;\
mov r2, %3;\
mov r3, %4;\
mov r4, %5;\
swi 0;\
dsb;\
isb;\
mov %0, r0"
: "=r"(ret)
: "r"(sys_num), "r"(a1), "r"(a2), "r"(a3), "r"(a4)
: "memory", "r0", "r1", "r2", "r3", "r4");
return ret;
}
int spawn(struct Session* session, int fd, ipc_read_fn ipc_read, ipc_fsize_fn ipc_fsize, char* name, char** argv) int spawn(struct Session* session, int fd, ipc_read_fn ipc_read, ipc_fsize_fn ipc_fsize, char* name, char** argv)
{ {
int file_size = ipc_fsize(session, fd); int file_size = ipc_fsize(session, fd);

View File

@ -62,6 +62,8 @@ typedef int (*ipc_read_fn)(struct Session* session, int fd, char* dst, int offse
typedef int (*ipc_fsize_fn)(struct Session* session, int fd); typedef int (*ipc_fsize_fn)(struct Session* session, int fd);
typedef int (*ipc_write_fn)(struct Session* session, int fd, char* src, int offset, int len); typedef int (*ipc_write_fn)(struct Session* session, int fd, char* src, int offset, int len);
int syscall(int sys_num, intptr_t a1, intptr_t a2, intptr_t a3, intptr_t a4);
int spawn(struct Session* session, int fd, ipc_read_fn ipc_read, ipc_fsize_fn ipc_fsize, char* name, char** argv); int spawn(struct Session* session, int fd, ipc_read_fn ipc_read, ipc_fsize_fn ipc_fsize, char* name, char** argv);
int exit(); int exit();
int yield(task_yield_reason reason); int yield(task_yield_reason reason);

View File

@ -13,11 +13,13 @@ cc = ${toolchain}gcc
ld = ${toolchain}g++ ld = ${toolchain}g++
objdump = ${toolchain}objdump objdump = ${toolchain}objdump
c_useropts = -O0 c_useropts = -O2
INC_DIR = -I$(KERNEL_ROOT)/services/app \ INC_DIR = -I$(KERNEL_ROOT)/services/app \
-I$(KERNEL_ROOT)/services/fs/libfs \ -I$(KERNEL_ROOT)/services/fs/libfs \
-I$(KERNEL_ROOT)/services/lib/memory \ -I$(KERNEL_ROOT)/services/lib/memory \
-I$(KERNEL_ROOT)/services/lib/serial \
-I$(KERNEL_ROOT)/services/lib/usyscall \
-I$(KERNEL_ROOT)/services/lib/ipc \ -I$(KERNEL_ROOT)/services/lib/ipc \
-I$(KERNEL_ROOT)/services/boards/$(BOARD) -I$(KERNEL_ROOT)/services/boards/$(BOARD)

View File

@ -48,11 +48,11 @@ Modification:
#define ROOT_INUM 1 // root inode number #define ROOT_INUM 1 // root inode number
#define BLOCK_SIZE 512 // block size #define BLOCK_SIZE 512 // block size
#define nr_blocks_total 2048 // total number of blocks (including used blocks and free blocks) #define nr_blocks_total 8192 // total number of blocks (including used blocks and free blocks)
#define nr_inodes 200 // total number of inodes #define nr_inodes 200 // total number of inodes
#define NR_DIRECT_BLOCKS 5 #define NR_DIRECT_BLOCKS 4
#define NR_INDIRECT_BLOCKS 8 #define NR_INDIRECT_BLOCKS 25
#define MAX_INDIRECT_BLOCKS (BLOCK_SIZE / sizeof(uint)) #define MAX_INDIRECT_BLOCKS (BLOCK_SIZE / sizeof(uint))
#define MAX_FILE_SIZE (NR_DIRECT_BLOCKS + (NR_INDIRECT_BLOCKS * MAX_INDIRECT_BLOCKS)) #define MAX_FILE_SIZE (NR_DIRECT_BLOCKS + (NR_INDIRECT_BLOCKS * MAX_INDIRECT_BLOCKS))
@ -80,7 +80,7 @@ struct Inode {
}; };
// Directory is a file containing a sequence of DirEntry structures. // Directory is a file containing a sequence of DirEntry structures.
#define DIR_NAME_SIZE 14 #define DIR_NAME_SIZE 30
struct DirEntry { struct DirEntry {
ushort inum; ushort inum;
char name[DIR_NAME_SIZE]; char name[DIR_NAME_SIZE];

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