arch: convert to using newly introduced integer sized types

Convert code to use u{8,16,32,64}_t and s{8,16,32,64}_t instead of C99
integer types.  There are few places we dont convert over to the new
types because of compatiability with ext/HALs or for ease of transition
at this point.  Fixup a few of the PRI formatters so we build with newlib.

Jira: ZEP-2051

Change-Id: I7d2d3697cad04f20aaa8f6e77228f502cd9c8286
Signed-off-by: Kumar Gala <kumar.gala@linaro.org>
This commit is contained in:
Kumar Gala 2017-04-20 13:30:33 -05:00
commit bf53ebf2c8
85 changed files with 965 additions and 966 deletions

View file

@ -56,7 +56,7 @@ static int dcache_available(void)
return (val == 0)?0:1; return (val == 0)?0:1;
} }
static void dcache_dc_ctrl(uint32_t dcache_en_mask) static void dcache_dc_ctrl(u32_t dcache_en_mask)
{ {
if (!dcache_available()) if (!dcache_available())
return; return;
@ -85,9 +85,9 @@ static void dcache_enable(void)
* *
* @return N/A * @return N/A
*/ */
static void dcache_flush_mlines(uint32_t start_addr, uint32_t size) static void dcache_flush_mlines(u32_t start_addr, u32_t size)
{ {
uint32_t end_addr; u32_t end_addr;
unsigned int key; unsigned int key;
if (!dcache_available() || (size == 0)) { if (!dcache_available() || (size == 0)) {
@ -95,7 +95,7 @@ static void dcache_flush_mlines(uint32_t start_addr, uint32_t size)
} }
end_addr = start_addr + size - 1; end_addr = start_addr + size - 1;
start_addr &= (uint32_t)(~(DCACHE_LINE_SIZE - 1)); start_addr &= (u32_t)(~(DCACHE_LINE_SIZE - 1));
key = irq_lock(); /* --enter critical section-- */ key = irq_lock(); /* --enter critical section-- */
@ -137,7 +137,7 @@ static void dcache_flush_mlines(uint32_t start_addr, uint32_t size)
void sys_cache_flush(vaddr_t start_addr, size_t size) void sys_cache_flush(vaddr_t start_addr, size_t size)
{ {
dcache_flush_mlines((uint32_t)start_addr, (uint32_t)size); dcache_flush_mlines((u32_t)start_addr, (u32_t)size);
} }
@ -145,7 +145,7 @@ void sys_cache_flush(vaddr_t start_addr, size_t size)
size_t sys_cache_line_size; size_t sys_cache_line_size;
static void init_dcache_line_size(void) static void init_dcache_line_size(void)
{ {
uint32_t val; u32_t val;
val = _arc_v2_aux_reg_read(_ARC_V2_D_CACHE_BUILD); val = _arc_v2_aux_reg_read(_ARC_V2_D_CACHE_BUILD);
__ASSERT((val&0xff) != 0, "d-cache is not present"); __ASSERT((val&0xff) != 0, "d-cache is not present");

View file

@ -50,15 +50,14 @@ void _FaultDump(const NANO_ESF *esf, int fault)
ARG_UNUSED(fault); ARG_UNUSED(fault);
#ifdef CONFIG_PRINTK #ifdef CONFIG_PRINTK
uint32_t exc_addr = _arc_v2_aux_reg_read(_ARC_V2_EFA); u32_t exc_addr = _arc_v2_aux_reg_read(_ARC_V2_EFA);
uint32_t ecr = _arc_v2_aux_reg_read(_ARC_V2_ECR); u32_t ecr = _arc_v2_aux_reg_read(_ARC_V2_ECR);
PR_EXC("Exception vector: 0x%" PRIx32 ", cause code: 0x%" PRIx32 PR_EXC("Exception vector: 0x%x, cause code: 0x%x, parameter 0x%xn",
", parameter 0x%" PRIx32 "\n",
_ARC_V2_ECR_VECTOR(ecr), _ARC_V2_ECR_VECTOR(ecr),
_ARC_V2_ECR_CODE(ecr), _ARC_V2_ECR_CODE(ecr),
_ARC_V2_ECR_PARAMETER(ecr)); _ARC_V2_ECR_PARAMETER(ecr));
PR_EXC("Address 0x%" PRIx32 "\n", exc_addr); PR_EXC("Address 0x%x\n", exc_addr);
#endif #endif
} }
#endif /* CONFIG_FAULT_DUMP */ #endif /* CONFIG_FAULT_DUMP */
@ -75,7 +74,7 @@ void _FaultDump(const NANO_ESF *esf, int fault)
*/ */
void _Fault(void) void _Fault(void)
{ {
uint32_t ecr = _arc_v2_aux_reg_read(_ARC_V2_ECR); u32_t ecr = _arc_v2_aux_reg_read(_ARC_V2_ECR);
FAULT_DUMP(&_default_esf, ecr); FAULT_DUMP(&_default_esf, ecr);

View file

@ -21,12 +21,12 @@
#endif /* CONFIG_INIT_STACKS */ #endif /* CONFIG_INIT_STACKS */
/* initial stack frame */ /* initial stack frame */
struct init_stack_frame { struct init_stack_frame {
uint32_t pc; u32_t pc;
uint32_t status32; u32_t status32;
uint32_t r3; u32_t r3;
uint32_t r2; u32_t r2;
uint32_t r1; u32_t r1;
uint32_t r0; u32_t r0;
}; };
#if defined(CONFIG_THREAD_MONITOR) #if defined(CONFIG_THREAD_MONITOR)
@ -94,11 +94,11 @@ void _new_thread(char *pStackMem, size_t stackSize,
pInitCtx = (struct init_stack_frame *)(STACK_ROUND_DOWN(stackEnd) - pInitCtx = (struct init_stack_frame *)(STACK_ROUND_DOWN(stackEnd) -
sizeof(struct init_stack_frame)); sizeof(struct init_stack_frame));
pInitCtx->pc = ((uint32_t)_thread_entry_wrapper); pInitCtx->pc = ((u32_t)_thread_entry_wrapper);
pInitCtx->r0 = (uint32_t)pEntry; pInitCtx->r0 = (u32_t)pEntry;
pInitCtx->r1 = (uint32_t)parameter1; pInitCtx->r1 = (u32_t)parameter1;
pInitCtx->r2 = (uint32_t)parameter2; pInitCtx->r2 = (u32_t)parameter2;
pInitCtx->r3 = (uint32_t)parameter3; pInitCtx->r3 = (u32_t)parameter3;
/* /*
* For now set the interrupt priority to 15 * For now set the interrupt priority to 15
* we can leave interrupt enable flag set to 0 as * we can leave interrupt enable flag set to 0 as
@ -108,7 +108,7 @@ void _new_thread(char *pStackMem, size_t stackSize,
*/ */
#ifdef CONFIG_ARC_STACK_CHECKING #ifdef CONFIG_ARC_STACK_CHECKING
pInitCtx->status32 = _ARC_V2_STATUS32_SC | _ARC_V2_STATUS32_E(_ARC_V2_DEF_IRQ_LEVEL); pInitCtx->status32 = _ARC_V2_STATUS32_SC | _ARC_V2_STATUS32_E(_ARC_V2_DEF_IRQ_LEVEL);
thread->arch.stack_top = (uint32_t) stackEnd; thread->arch.stack_top = (u32_t) stackEnd;
#else #else
pInitCtx->status32 = _ARC_V2_STATUS32_E(_ARC_V2_DEF_IRQ_LEVEL); pInitCtx->status32 = _ARC_V2_STATUS32_E(_ARC_V2_DEF_IRQ_LEVEL);
#endif #endif
@ -142,7 +142,7 @@ void _new_thread(char *pStackMem, size_t stackSize,
thread->arch.intlock_key = 0x3F; thread->arch.intlock_key = 0x3F;
thread->arch.relinquish_cause = _CAUSE_COOP; thread->arch.relinquish_cause = _CAUSE_COOP;
thread->callee_saved.sp = thread->callee_saved.sp =
(uint32_t)pInitCtx - ___callee_saved_stack_t_SIZEOF; (u32_t)pInitCtx - ___callee_saved_stack_t_SIZEOF;
/* initial values in all other regs/k_thread entries are irrelevant */ /* initial values in all other regs/k_thread entries are irrelevant */

View file

@ -15,7 +15,7 @@
#include <toolchain.h> #include <toolchain.h>
#include <kernel_structs.h> #include <kernel_structs.h>
extern int64_t _sys_clock_tick_count; extern s64_t _sys_clock_tick_count;
extern int sys_clock_hw_cycles_per_tick; extern int sys_clock_hw_cycles_per_tick;
/* /*
@ -26,17 +26,17 @@ extern int sys_clock_hw_cycles_per_tick;
* *
* @return 64-bit time stamp value * @return 64-bit time stamp value
*/ */
uint64_t _tsc_read(void) u64_t _tsc_read(void)
{ {
unsigned int key; unsigned int key;
uint64_t t; u64_t t;
uint32_t count; u32_t count;
key = irq_lock(); key = irq_lock();
t = (uint64_t)_sys_clock_tick_count; t = (u64_t)_sys_clock_tick_count;
count = _arc_v2_aux_reg_read(_ARC_V2_TMR0_COUNT); count = _arc_v2_aux_reg_read(_ARC_V2_TMR0_COUNT);
irq_unlock(key); irq_unlock(key);
t *= (uint64_t)sys_clock_hw_cycles_per_tick; t *= (u64_t)sys_clock_hw_cycles_per_tick;
t += (uint64_t)count; t += (u64_t)count;
return t; return t;
} }

View file

@ -28,39 +28,39 @@
#include "vector_table.h" #include "vector_table.h"
struct vector_table { struct vector_table {
uint32_t reset; u32_t reset;
uint32_t memory_error; u32_t memory_error;
uint32_t instruction_error; u32_t instruction_error;
uint32_t ev_machine_check; u32_t ev_machine_check;
uint32_t ev_tlb_miss_i; u32_t ev_tlb_miss_i;
uint32_t ev_tlb_miss_d; u32_t ev_tlb_miss_d;
uint32_t ev_prot_v; u32_t ev_prot_v;
uint32_t ev_privilege_v; u32_t ev_privilege_v;
uint32_t ev_swi; u32_t ev_swi;
uint32_t ev_trap; u32_t ev_trap;
uint32_t ev_extension; u32_t ev_extension;
uint32_t ev_div_zero; u32_t ev_div_zero;
uint32_t ev_dc_error; u32_t ev_dc_error;
uint32_t ev_maligned; u32_t ev_maligned;
uint32_t unused_1; u32_t unused_1;
uint32_t unused_2; u32_t unused_2;
}; };
struct vector_table _VectorTable _GENERIC_SECTION(.exc_vector_table) = { struct vector_table _VectorTable _GENERIC_SECTION(.exc_vector_table) = {
(uint32_t)__reset, (u32_t)__reset,
(uint32_t)__memory_error, (u32_t)__memory_error,
(uint32_t)__instruction_error, (u32_t)__instruction_error,
(uint32_t)__ev_machine_check, (u32_t)__ev_machine_check,
(uint32_t)__ev_tlb_miss_i, (u32_t)__ev_tlb_miss_i,
(uint32_t)__ev_tlb_miss_d, (u32_t)__ev_tlb_miss_d,
(uint32_t)__ev_prot_v, (u32_t)__ev_prot_v,
(uint32_t)__ev_privilege_v, (u32_t)__ev_privilege_v,
(uint32_t)__ev_swi, (u32_t)__ev_swi,
(uint32_t)__ev_trap, (u32_t)__ev_trap,
(uint32_t)__ev_extension, (u32_t)__ev_extension,
(uint32_t)__ev_div_zero, (u32_t)__ev_div_zero,
(uint32_t)__ev_dc_error, (u32_t)__ev_dc_error,
(uint32_t)__ev_maligned, (u32_t)__ev_maligned,
0, 0,
0 0
}; };

View file

@ -49,65 +49,65 @@ struct _caller_saved {
typedef struct _caller_saved _caller_saved_t; typedef struct _caller_saved _caller_saved_t;
struct _irq_stack_frame { struct _irq_stack_frame {
uint32_t r0; u32_t r0;
uint32_t r1; u32_t r1;
uint32_t r2; u32_t r2;
uint32_t r3; u32_t r3;
uint32_t r4; u32_t r4;
uint32_t r5; u32_t r5;
uint32_t r6; u32_t r6;
uint32_t r7; u32_t r7;
uint32_t r8; u32_t r8;
uint32_t r9; u32_t r9;
uint32_t r10; u32_t r10;
uint32_t r11; u32_t r11;
uint32_t r12; u32_t r12;
uint32_t r13; u32_t r13;
uint32_t blink; u32_t blink;
uint32_t lp_end; u32_t lp_end;
uint32_t lp_start; u32_t lp_start;
uint32_t lp_count; u32_t lp_count;
#ifdef CONFIG_CODE_DENSITY #ifdef CONFIG_CODE_DENSITY
/* /*
* Currently unsupported. This is where those registers are * Currently unsupported. This is where those registers are
* automatically pushed on the stack by the CPU when taking a regular * automatically pushed on the stack by the CPU when taking a regular
* IRQ. * IRQ.
*/ */
uint32_t ei_base; u32_t ei_base;
uint32_t ldi_base; u32_t ldi_base;
uint32_t jli_base; u32_t jli_base;
#endif #endif
uint32_t pc; u32_t pc;
uint32_t status32; u32_t status32;
}; };
typedef struct _irq_stack_frame _isf_t; typedef struct _irq_stack_frame _isf_t;
struct _callee_saved { struct _callee_saved {
uint32_t sp; /* r28 */ u32_t sp; /* r28 */
}; };
typedef struct _callee_saved _callee_saved_t; typedef struct _callee_saved _callee_saved_t;
/* callee-saved registers pushed on the stack, not in k_thread */ /* callee-saved registers pushed on the stack, not in k_thread */
struct _callee_saved_stack { struct _callee_saved_stack {
uint32_t r13; u32_t r13;
uint32_t r14; u32_t r14;
uint32_t r15; u32_t r15;
uint32_t r16; u32_t r16;
uint32_t r17; u32_t r17;
uint32_t r18; u32_t r18;
uint32_t r19; u32_t r19;
uint32_t r20; u32_t r20;
uint32_t r21; u32_t r21;
uint32_t r22; u32_t r22;
uint32_t r23; u32_t r23;
uint32_t r24; u32_t r24;
uint32_t r25; u32_t r25;
uint32_t r26; u32_t r26;
uint32_t fp; /* r27 */ u32_t fp; /* r27 */
/* r28 is the stack pointer and saved separately */ /* r28 is the stack pointer and saved separately */
/* r29 is ILINK and does not need to be saved */ /* r29 is ILINK and does not need to be saved */
uint32_t r30; u32_t r30;
/* /*
* No need to save r31 (blink), it's either alread pushed as the pc or * No need to save r31 (blink), it's either alread pushed as the pc or
* blink on an irq stack frame. * blink on an irq stack frame.
@ -139,7 +139,7 @@ typedef struct _callee_saved_stack _callee_saved_stack_t;
struct _thread_arch { struct _thread_arch {
/* interrupt key when relinquishing control */ /* interrupt key when relinquishing control */
uint32_t intlock_key; u32_t intlock_key;
/* one of the _CAUSE_xxxx definitions above */ /* one of the _CAUSE_xxxx definitions above */
int relinquish_cause; int relinquish_cause;
@ -149,7 +149,7 @@ struct _thread_arch {
#ifdef CONFIG_ARC_STACK_CHECKING #ifdef CONFIG_ARC_STACK_CHECKING
/* top of stack for hardware stack checking */ /* top of stack for hardware stack checking */
uint32_t stack_top; u32_t stack_top;
#endif #endif
}; };

View file

@ -44,7 +44,7 @@ _set_thread_return_value(struct k_thread *thread, unsigned int value)
static ALWAYS_INLINE int _is_in_isr(void) static ALWAYS_INLINE int _is_in_isr(void)
{ {
uint32_t act = _arc_v2_aux_reg_read(_ARC_V2_AUX_IRQ_ACT); u32_t act = _arc_v2_aux_reg_read(_ARC_V2_AUX_IRQ_ACT);
#if CONFIG_IRQ_OFFLOAD #if CONFIG_IRQ_OFFLOAD
/* Check if we're in a TRAP_S exception as well */ /* Check if we're in a TRAP_S exception as well */
if (_arc_v2_aux_reg_read(_ARC_V2_STATUS32) & _ARC_V2_STATUS32_AE && if (_arc_v2_aux_reg_read(_ARC_V2_STATUS32) & _ARC_V2_STATUS32_AE &&
@ -65,7 +65,7 @@ static ALWAYS_INLINE int _is_in_isr(void)
*/ */
static ALWAYS_INLINE int _INTERRUPT_CAUSE(void) static ALWAYS_INLINE int _INTERRUPT_CAUSE(void)
{ {
uint32_t irq_num = _arc_v2_aux_reg_read(_ARC_V2_ICAUSE); u32_t irq_num = _arc_v2_aux_reg_read(_ARC_V2_ICAUSE);
return irq_num; return irq_num;
} }

View file

@ -36,11 +36,11 @@ extern "C" {
*/ */
static ALWAYS_INLINE void _icache_setup(void) static ALWAYS_INLINE void _icache_setup(void)
{ {
uint32_t icache_config = ( u32_t icache_config = (
IC_CACHE_DIRECT | /* direct mapping (one-way assoc.) */ IC_CACHE_DIRECT | /* direct mapping (one-way assoc.) */
IC_CACHE_ENABLE /* i-cache enabled */ IC_CACHE_ENABLE /* i-cache enabled */
); );
uint32_t val; u32_t val;
val = _arc_v2_aux_reg_read(_ARC_V2_I_CACHE_BUILD); val = _arc_v2_aux_reg_read(_ARC_V2_I_CACHE_BUILD);
val &= 0xff; val &= 0xff;

View file

@ -41,7 +41,7 @@ extern char _interrupt_stack[];
*/ */
static ALWAYS_INLINE void _irq_setup(void) static ALWAYS_INLINE void _irq_setup(void)
{ {
uint32_t aux_irq_ctrl_value = ( u32_t aux_irq_ctrl_value = (
_ARC_V2_AUX_IRQ_CTRL_LOOP_REGS | /* save lp_xxx registers */ _ARC_V2_AUX_IRQ_CTRL_LOOP_REGS | /* save lp_xxx registers */
_ARC_V2_AUX_IRQ_CTRL_BLINK | /* save blink */ _ARC_V2_AUX_IRQ_CTRL_BLINK | /* save blink */
_ARC_V2_AUX_IRQ_CTRL_14_REGS /* save r0 -> r13 (caller-saved) */ _ARC_V2_AUX_IRQ_CTRL_14_REGS /* save r0 -> r13 (caller-saved) */

View file

@ -70,7 +70,7 @@ void _sys_soc_set_power_state(enum power_states state)
void _sys_soc_power_state_post_ops(enum power_states state) void _sys_soc_power_state_post_ops(enum power_states state)
{ {
uint32_t limit; u32_t limit;
switch (state) { switch (state) {
case SYS_POWER_STATE_CPU_LPS: case SYS_POWER_STATE_CPU_LPS:

View file

@ -67,7 +67,7 @@ SECTION_FUNC(TEXT, _CpuIdleInit)
* *
* C function prototype: * C function prototype:
* *
* int32_t _NanoIdleValGet (void); * s32_t _NanoIdleValGet (void);
*/ */
SECTION_FUNC(TEXT, _NanoIdleValGet) SECTION_FUNC(TEXT, _NanoIdleValGet)

View file

@ -162,7 +162,7 @@ void _arch_isr_direct_pm(void)
#endif /* CONFIG_ARMV6_M */ #endif /* CONFIG_ARMV6_M */
if (_kernel.idle) { if (_kernel.idle) {
int32_t idle_val = _kernel.idle; s32_t idle_val = _kernel.idle;
_kernel.idle = 0; _kernel.idle = 0;
_sys_power_save_idle_exit(idle_val); _sys_power_save_idle_exit(idle_val);

View file

@ -75,7 +75,7 @@ void _new_thread(char *pStackMem, size_t stackSize,
{ {
_ASSERT_VALID_PRIO(priority, pEntry); _ASSERT_VALID_PRIO(priority, pEntry);
__ASSERT(!((uint32_t)pStackMem & (STACK_ALIGN - 1)), __ASSERT(!((u32_t)pStackMem & (STACK_ALIGN - 1)),
"stack is not aligned properly\n" "stack is not aligned properly\n"
"%d-byte alignment required\n", STACK_ALIGN); "%d-byte alignment required\n", STACK_ALIGN);
@ -92,11 +92,11 @@ void _new_thread(char *pStackMem, size_t stackSize,
pInitCtx = (struct __esf *)(STACK_ROUND_DOWN(stackEnd) - pInitCtx = (struct __esf *)(STACK_ROUND_DOWN(stackEnd) -
sizeof(struct __esf)); sizeof(struct __esf));
pInitCtx->pc = ((uint32_t)_thread_entry) & 0xfffffffe; pInitCtx->pc = ((u32_t)_thread_entry) & 0xfffffffe;
pInitCtx->a1 = (uint32_t)pEntry; pInitCtx->a1 = (u32_t)pEntry;
pInitCtx->a2 = (uint32_t)parameter1; pInitCtx->a2 = (u32_t)parameter1;
pInitCtx->a3 = (uint32_t)parameter2; pInitCtx->a3 = (u32_t)parameter2;
pInitCtx->a4 = (uint32_t)parameter3; pInitCtx->a4 = (u32_t)parameter3;
pInitCtx->xpsr = pInitCtx->xpsr =
0x01000000UL; /* clear all, thumb bit is 1, even if RO */ 0x01000000UL; /* clear all, thumb bit is 1, even if RO */
@ -120,7 +120,7 @@ void _new_thread(char *pStackMem, size_t stackSize,
thread->entry = (struct __thread_entry *)(pInitCtx); thread->entry = (struct __thread_entry *)(pInitCtx);
#endif #endif
thread->callee_saved.psp = (uint32_t)pInitCtx; thread->callee_saved.psp = (u32_t)pInitCtx;
thread->arch.basepri = 0; thread->arch.basepri = 0;
/* swap_return_value can contain garbage */ /* swap_return_value can contain garbage */

View file

@ -28,9 +28,9 @@ extern "C" {
* *
* @return the contents of the IPSR register * @return the contents of the IPSR register
*/ */
static ALWAYS_INLINE uint32_t _IpsrGet(void) static ALWAYS_INLINE u32_t _IpsrGet(void)
{ {
uint32_t vector; u32_t vector;
__asm__ volatile("mrs %0, IPSR\n\t" : "=r"(vector)); __asm__ volatile("mrs %0, IPSR\n\t" : "=r"(vector));
return vector; return vector;
@ -44,7 +44,7 @@ static ALWAYS_INLINE uint32_t _IpsrGet(void)
* *
* @return N/A * @return N/A
*/ */
static ALWAYS_INLINE void _MspSet(uint32_t msp /* value to store in MSP */ static ALWAYS_INLINE void _MspSet(u32_t msp /* value to store in MSP */
) )
{ {
__asm__ volatile("msr MSP, %0\n\t" : : "r"(msp)); __asm__ volatile("msr MSP, %0\n\t" : : "r"(msp));

View file

@ -42,7 +42,7 @@ extern "C" {
*/ */
static ALWAYS_INLINE int _IsInIsr(void) static ALWAYS_INLINE int _IsInIsr(void)
{ {
uint32_t vector = _IpsrGet(); u32_t vector = _IpsrGet();
/* /*
* IRQs + PendSV (14) + SVC (11) + SYSTICK (15) are interrupts. * IRQs + PendSV (14) + SVC (11) + SYSTICK (15) are interrupts.

View file

@ -46,7 +46,7 @@ extern char _interrupt_stack[CONFIG_ISR_STACK_SIZE];
*/ */
static ALWAYS_INLINE void _InterruptStackSetup(void) static ALWAYS_INLINE void _InterruptStackSetup(void)
{ {
uint32_t msp = (uint32_t)(_interrupt_stack + CONFIG_ISR_STACK_SIZE); u32_t msp = (u32_t)(_interrupt_stack + CONFIG_ISR_STACK_SIZE);
_MspSet(msp); _MspSet(msp);
} }

View file

@ -45,29 +45,29 @@ struct _caller_saved {
* *
* For Cortex-A, this may be: * For Cortex-A, this may be:
* *
* uint32_t a1; // r0 * u32_t a1; // r0
* uint32_t a2; // r1 * u32_t a2; // r1
* uint32_t a3; // r2 * u32_t a3; // r2
* uint32_t a4; // r3 * u32_t a4; // r3
* uint32_t ip; // r12 * u32_t ip; // r12
* uint32_t lr; // r14 * u32_t lr; // r14
* uint32_t pc; // r15 * u32_t pc; // r15
* uint32_t xpsr; * u32_t xpsr;
*/ */
}; };
typedef struct _caller_saved _caller_saved_t; typedef struct _caller_saved _caller_saved_t;
struct _callee_saved { struct _callee_saved {
uint32_t v1; /* r4 */ u32_t v1; /* r4 */
uint32_t v2; /* r5 */ u32_t v2; /* r5 */
uint32_t v3; /* r6 */ u32_t v3; /* r6 */
uint32_t v4; /* r7 */ u32_t v4; /* r7 */
uint32_t v5; /* r8 */ u32_t v5; /* r8 */
uint32_t v6; /* r9 */ u32_t v6; /* r9 */
uint32_t v7; /* r10 */ u32_t v7; /* r10 */
uint32_t v8; /* r11 */ u32_t v8; /* r11 */
uint32_t psp; /* r13 */ u32_t psp; /* r13 */
}; };
typedef struct _callee_saved _callee_saved_t; typedef struct _callee_saved _callee_saved_t;
@ -112,10 +112,10 @@ struct _preempt_float {
struct _thread_arch { struct _thread_arch {
/* interrupt locking key */ /* interrupt locking key */
uint32_t basepri; u32_t basepri;
/* r0 in stack frame cannot be written to reliably */ /* r0 in stack frame cannot be written to reliably */
uint32_t swap_return_value; u32_t swap_return_value;
#ifdef CONFIG_FLOAT #ifdef CONFIG_FLOAT
/* /*

View file

@ -32,7 +32,7 @@
*/ */
static int arm_beetle_init(struct device *arg) static int arm_beetle_init(struct device *arg)
{ {
uint32_t key; u32_t key;
ARG_UNUSED(arg); ARG_UNUSED(arg);

View file

@ -15,99 +15,99 @@
/* System Control Register (SYSCON) */ /* System Control Register (SYSCON) */
struct syscon { struct syscon {
/* Offset: 0x000 (r/w) remap control register */ /* Offset: 0x000 (r/w) remap control register */
volatile uint32_t remap; volatile u32_t remap;
/* Offset: 0x004 (r/w) pmu control register */ /* Offset: 0x004 (r/w) pmu control register */
volatile uint32_t pmuctrl; volatile u32_t pmuctrl;
/* Offset: 0x008 (r/w) reset option register */ /* Offset: 0x008 (r/w) reset option register */
volatile uint32_t resetop; volatile u32_t resetop;
/* Offset: 0x00c (r/w) emi control register */ /* Offset: 0x00c (r/w) emi control register */
volatile uint32_t emictrl; volatile u32_t emictrl;
/* Offset: 0x010 (r/w) reset information register */ /* Offset: 0x010 (r/w) reset information register */
volatile uint32_t rstinfo; volatile u32_t rstinfo;
volatile uint32_t reserved0[3]; volatile u32_t reserved0[3];
/* Offset: 0x020 (r/w)AHB peripheral access control set */ /* Offset: 0x020 (r/w)AHB peripheral access control set */
volatile uint32_t ahbper0set; volatile u32_t ahbper0set;
/* Offset: 0x024 (r/w)AHB peripheral access control clear */ /* Offset: 0x024 (r/w)AHB peripheral access control clear */
volatile uint32_t ahbper0clr; volatile u32_t ahbper0clr;
volatile uint32_t reserved1[2]; volatile u32_t reserved1[2];
/* Offset: 0x030 (r/w)APB peripheral access control set */ /* Offset: 0x030 (r/w)APB peripheral access control set */
volatile uint32_t apbper0set; volatile u32_t apbper0set;
/* Offset: 0x034 (r/w)APB peripheral access control clear */ /* Offset: 0x034 (r/w)APB peripheral access control clear */
volatile uint32_t apbper0clr; volatile u32_t apbper0clr;
volatile uint32_t reserved2[2]; volatile u32_t reserved2[2];
/* Offset: 0x040 (r/w) main clock control register */ /* Offset: 0x040 (r/w) main clock control register */
volatile uint32_t mainclk; volatile u32_t mainclk;
/* Offset: 0x044 (r/w) auxiliary / rtc control register */ /* Offset: 0x044 (r/w) auxiliary / rtc control register */
volatile uint32_t auxclk; volatile u32_t auxclk;
/* Offset: 0x048 (r/w) pll control register */ /* Offset: 0x048 (r/w) pll control register */
volatile uint32_t pllctrl; volatile u32_t pllctrl;
/* Offset: 0x04c (r/w) pll status register */ /* Offset: 0x04c (r/w) pll status register */
volatile uint32_t pllstatus; volatile u32_t pllstatus;
/* Offset: 0x050 (r/w) sleep control register */ /* Offset: 0x050 (r/w) sleep control register */
volatile uint32_t sleepcfg; volatile u32_t sleepcfg;
/* Offset: 0x054 (r/w) flash auxiliary settings control register */ /* Offset: 0x054 (r/w) flash auxiliary settings control register */
volatile uint32_t flashauxcfg; volatile u32_t flashauxcfg;
volatile uint32_t reserved3[10]; volatile u32_t reserved3[10];
/* Offset: 0x080 (r/w) AHB peripheral clock set in active state */ /* Offset: 0x080 (r/w) AHB peripheral clock set in active state */
volatile uint32_t ahbclkcfg0set; volatile u32_t ahbclkcfg0set;
/* Offset: 0x084 (r/w) AHB peripheral clock clear in active state */ /* Offset: 0x084 (r/w) AHB peripheral clock clear in active state */
volatile uint32_t ahbclkcfg0clr; volatile u32_t ahbclkcfg0clr;
/* Offset: 0x088 (r/w) AHB peripheral clock set in sleep state */ /* Offset: 0x088 (r/w) AHB peripheral clock set in sleep state */
volatile uint32_t ahbclkcfg1set; volatile u32_t ahbclkcfg1set;
/* Offset: 0x08c (r/w) AHB peripheral clock clear in sleep state */ /* Offset: 0x08c (r/w) AHB peripheral clock clear in sleep state */
volatile uint32_t ahbclkcfg1clr; volatile u32_t ahbclkcfg1clr;
/* Offset: 0x090 (r/w) AHB peripheral clock set in deep sleep state */ /* Offset: 0x090 (r/w) AHB peripheral clock set in deep sleep state */
volatile uint32_t ahbclkcfg2set; volatile u32_t ahbclkcfg2set;
/* Offset: 0x094 (r/w) AHB peripheral clock clear in deep sleep state */ /* Offset: 0x094 (r/w) AHB peripheral clock clear in deep sleep state */
volatile uint32_t ahbclkcfg2clr; volatile u32_t ahbclkcfg2clr;
volatile uint32_t reserved4[2]; volatile u32_t reserved4[2];
/* Offset: 0x0a0 (r/w) APB peripheral clock set in active state */ /* Offset: 0x0a0 (r/w) APB peripheral clock set in active state */
volatile uint32_t apbclkcfg0set; volatile u32_t apbclkcfg0set;
/* Offset: 0x0a4 (r/w) APB peripheral clock clear in active state */ /* Offset: 0x0a4 (r/w) APB peripheral clock clear in active state */
volatile uint32_t apbclkcfg0clr; volatile u32_t apbclkcfg0clr;
/* Offset: 0x0a8 (r/w) APB peripheral clock set in sleep state */ /* Offset: 0x0a8 (r/w) APB peripheral clock set in sleep state */
volatile uint32_t apbclkcfg1set; volatile u32_t apbclkcfg1set;
/* Offset: 0x0ac (r/w) APB peripheral clock clear in sleep state */ /* Offset: 0x0ac (r/w) APB peripheral clock clear in sleep state */
volatile uint32_t apbclkcfg1clr; volatile u32_t apbclkcfg1clr;
/* Offset: 0x0b0 (r/w) APB peripheral clock set in deep sleep state */ /* Offset: 0x0b0 (r/w) APB peripheral clock set in deep sleep state */
volatile uint32_t apbclkcfg2set; volatile u32_t apbclkcfg2set;
/* Offset: 0x0b4 (r/w) APB peripheral clock clear in deep sleep state */ /* Offset: 0x0b4 (r/w) APB peripheral clock clear in deep sleep state */
volatile uint32_t apbclkcfg2clr; volatile u32_t apbclkcfg2clr;
volatile uint32_t reserved5[2]; volatile u32_t reserved5[2];
/* Offset: 0x0c0 (r/w) AHB peripheral reset select set */ /* Offset: 0x0c0 (r/w) AHB peripheral reset select set */
volatile uint32_t ahbprst0set; volatile u32_t ahbprst0set;
/* Offset: 0x0c4 (r/w) AHB peripheral reset select clear */ /* Offset: 0x0c4 (r/w) AHB peripheral reset select clear */
volatile uint32_t ahbprst0clr; volatile u32_t ahbprst0clr;
/* Offset: 0x0c8 (r/w) APB peripheral reset select set */ /* Offset: 0x0c8 (r/w) APB peripheral reset select set */
volatile uint32_t apbprst0set; volatile u32_t apbprst0set;
/* Offset: 0x0cc (r/w) APB peripheral reset select clear */ /* Offset: 0x0cc (r/w) APB peripheral reset select clear */
volatile uint32_t apbprst0clr; volatile u32_t apbprst0clr;
/* Offset: 0x0d0 (r/w) AHB power down sleep wakeup source set */ /* Offset: 0x0d0 (r/w) AHB power down sleep wakeup source set */
volatile uint32_t pwrdncfg0set; volatile u32_t pwrdncfg0set;
/* Offset: 0x0d4 (r/w) AHB power down sleep wakeup source clear */ /* Offset: 0x0d4 (r/w) AHB power down sleep wakeup source clear */
volatile uint32_t pwrdncfg0clr; volatile u32_t pwrdncfg0clr;
/* Offset: 0x0d8 (r/w) APB power down sleep wakeup source set */ /* Offset: 0x0d8 (r/w) APB power down sleep wakeup source set */
volatile uint32_t pwrdncfg1set; volatile u32_t pwrdncfg1set;
/* Offset: 0x0dc (r/w) APB power down sleep wakeup source clear */ /* Offset: 0x0dc (r/w) APB power down sleep wakeup source clear */
volatile uint32_t pwrdncfg1clr; volatile u32_t pwrdncfg1clr;
/* Offset: 0x0e0 ( /w) rtc reset */ /* Offset: 0x0e0 ( /w) rtc reset */
volatile uint32_t rtcreset; volatile u32_t rtcreset;
/* Offset: 0x0e4 (r/w) event interface control register */ /* Offset: 0x0e4 (r/w) event interface control register */
volatile uint32_t eventcfg; volatile u32_t eventcfg;
volatile uint32_t reserved6[2]; volatile u32_t reserved6[2];
/* Offset: 0x0f0 (r/w) sram power control overide */ /* Offset: 0x0f0 (r/w) sram power control overide */
volatile uint32_t pwrovride0; volatile u32_t pwrovride0;
/* Offset: 0x0f4 (r/w) embedded flash power control overide */ /* Offset: 0x0f4 (r/w) embedded flash power control overide */
volatile uint32_t pwrovride1; volatile u32_t pwrovride1;
/* Offset: 0x0f8 (r/ ) memory status register */ /* Offset: 0x0f8 (r/ ) memory status register */
volatile uint32_t memorystatus; volatile u32_t memorystatus;
volatile uint32_t reserved7[1]; volatile u32_t reserved7[1];
/* Offset: 0x100 (r/w) io pad settings */ /* Offset: 0x100 (r/w) io pad settings */
volatile uint32_t gpiopadcfg0; volatile u32_t gpiopadcfg0;
/* Offset: 0x104 (r/w) io pad settings */ /* Offset: 0x104 (r/w) io pad settings */
volatile uint32_t gpiopadcfg1; volatile u32_t gpiopadcfg1;
/* Offset: 0x108 (r/w) testmode boot bypass */ /* Offset: 0x108 (r/w) testmode boot bypass */
volatile uint32_t testmodecfg; volatile u32_t testmodecfg;
}; };
#endif /* _ARM_BEETLE_SOC_REGS_H_ */ #endif /* _ARM_BEETLE_SOC_REGS_H_ */

View file

@ -18,41 +18,41 @@
/* System Control Register (SYSCON) */ /* System Control Register (SYSCON) */
struct mps2_syscon { struct mps2_syscon {
/* Offset: 0x000 (r/w) remap control register */ /* Offset: 0x000 (r/w) remap control register */
volatile uint32_t remap; volatile u32_t remap;
/* Offset: 0x004 (r/w) pmu control register */ /* Offset: 0x004 (r/w) pmu control register */
volatile uint32_t pmuctrl; volatile u32_t pmuctrl;
/* Offset: 0x008 (r/w) reset option register */ /* Offset: 0x008 (r/w) reset option register */
volatile uint32_t resetop; volatile u32_t resetop;
/* Offset: 0x00c (r/w) emi control register */ /* Offset: 0x00c (r/w) emi control register */
volatile uint32_t emictrl; volatile u32_t emictrl;
/* Offset: 0x010 (r/w) reset information register */ /* Offset: 0x010 (r/w) reset information register */
volatile uint32_t rstinfo; volatile u32_t rstinfo;
}; };
/* Registers in the FPGA system control block */ /* Registers in the FPGA system control block */
struct mps2_fpgaio { struct mps2_fpgaio {
/* Offset: 0x000 LED connections */ /* Offset: 0x000 LED connections */
volatile uint32_t led0; volatile u32_t led0;
/* Offset: 0x004 RESERVED */ /* Offset: 0x004 RESERVED */
volatile uint32_t reserved1; volatile u32_t reserved1;
/* Offset: 0x008 Buttons */ /* Offset: 0x008 Buttons */
volatile uint32_t button; volatile u32_t button;
/* Offset: 0x00c RESERVED */ /* Offset: 0x00c RESERVED */
volatile uint32_t reserved2; volatile u32_t reserved2;
/* Offset: 0x010 1Hz up counter */ /* Offset: 0x010 1Hz up counter */
volatile uint32_t clk1hz; volatile u32_t clk1hz;
/* Offset: 0x014 100Hz up counter */ /* Offset: 0x014 100Hz up counter */
volatile uint32_t clk100hz; volatile u32_t clk100hz;
/* Offset: 0x018 Cycle up counter */ /* Offset: 0x018 Cycle up counter */
volatile uint32_t counter; volatile u32_t counter;
/* Offset: 0x01c Reload value for prescale counter */ /* Offset: 0x01c Reload value for prescale counter */
volatile uint32_t prescale; volatile u32_t prescale;
/* Offset: 0x020 32-bit Prescale counter */ /* Offset: 0x020 32-bit Prescale counter */
volatile uint32_t pscntr; volatile u32_t pscntr;
/* Offset: 0x024 RESERVED */ /* Offset: 0x024 RESERVED */
volatile uint32_t reserved3[10]; volatile u32_t reserved3[10];
/* Offset: 0x04c Misc control */ /* Offset: 0x04c Misc control */
volatile uint32_t misc; volatile u32_t misc;
}; };
/* Defines for bits in fpgaio led0 register */ /* Defines for bits in fpgaio led0 register */

View file

@ -11,7 +11,7 @@
#include <misc/__assert.h> #include <misc/__assert.h>
#include "soc_gpio.h" #include "soc_gpio.h"
static void configure_common_attr(Pio *pio, uint32_t mask, uint32_t flags) static void configure_common_attr(Pio *pio, u32_t mask, u32_t flags)
{ {
/* Disable interrupts on the pin(s) */ /* Disable interrupts on the pin(s) */
pio->PIO_IDR = mask; pio->PIO_IDR = mask;
@ -38,7 +38,7 @@ static void configure_common_attr(Pio *pio, uint32_t mask, uint32_t flags)
} }
} }
static void configure_input_attr(Pio *pio, uint32_t mask, uint32_t flags) static void configure_input_attr(Pio *pio, u32_t mask, u32_t flags)
{ {
/* Configure input filter */ /* Configure input filter */
if ((flags & SOC_GPIO_IN_FILTER_MASK) != 0) { if ((flags & SOC_GPIO_IN_FILTER_MASK) != 0) {
@ -86,7 +86,7 @@ static void configure_input_attr(Pio *pio, uint32_t mask, uint32_t flags)
} }
} }
static void configure_output_attr(Pio *pio, uint32_t mask, uint32_t flags) static void configure_output_attr(Pio *pio, u32_t mask, u32_t flags)
{ {
/* Enable control of the I/O line by the PIO_ODSR register */ /* Enable control of the I/O line by the PIO_ODSR register */
pio->PIO_OWER = mask; pio->PIO_OWER = mask;
@ -94,11 +94,11 @@ static void configure_output_attr(Pio *pio, uint32_t mask, uint32_t flags)
void soc_gpio_configure(const struct soc_gpio_pin *pin) void soc_gpio_configure(const struct soc_gpio_pin *pin)
{ {
uint32_t mask = pin->mask; u32_t mask = pin->mask;
Pio *pio = pin->regs; Pio *pio = pin->regs;
uint8_t periph_id = pin->periph_id; u8_t periph_id = pin->periph_id;
uint32_t flags = pin->flags; u32_t flags = pin->flags;
uint32_t type = pin->flags & SOC_GPIO_FUNC_MASK; u32_t type = pin->flags & SOC_GPIO_FUNC_MASK;
/* Configure pin attributes common to all functions */ /* Configure pin attributes common to all functions */
configure_common_attr(pio, mask, flags); configure_common_attr(pio, mask, flags);

View file

@ -70,10 +70,10 @@
#define SOC_GPIO_FUNC_OUT_1 (6 << SOC_GPIO_FUNC_POS) #define SOC_GPIO_FUNC_OUT_1 (6 << SOC_GPIO_FUNC_POS)
struct soc_gpio_pin { struct soc_gpio_pin {
uint32_t mask; /** pin(s) bit mask */ u32_t mask; /** pin(s) bit mask */
Pio *regs; /** pointer to registers of the PIO controller */ Pio *regs; /** pointer to registers of the PIO controller */
uint8_t periph_id; /** peripheral ID of the PIO controller */ u8_t periph_id; /** peripheral ID of the PIO controller */
uint32_t flags; /** pin flags/attributes */ u32_t flags; /** pin flags/attributes */
}; };
/** /**
@ -148,7 +148,7 @@ static inline void soc_gpio_clear(const struct soc_gpio_pin *pin)
* @return pin(s) value. To assess value of a specific pin the pin's bit * @return pin(s) value. To assess value of a specific pin the pin's bit
* field has to be read. * field has to be read.
*/ */
static inline uint32_t soc_gpio_get(const struct soc_gpio_pin *pin) static inline u32_t soc_gpio_get(const struct soc_gpio_pin *pin)
{ {
return pin->regs->PIO_PDSR & pin->mask; return pin->regs->PIO_PDSR & pin->mask;
} }
@ -173,7 +173,7 @@ static inline uint32_t soc_gpio_get(const struct soc_gpio_pin *pin)
* @param div slow clock divider, valid values: from 0 to 2^14 - 1 * @param div slow clock divider, valid values: from 0 to 2^14 - 1
*/ */
static inline void soc_gpio_debounce_length_set(const struct soc_gpio_pin *pin, static inline void soc_gpio_debounce_length_set(const struct soc_gpio_pin *pin,
uint32_t div) u32_t div)
{ {
pin->regs->PIO_SCDR = PIO_SCDR_DIV(div); pin->regs->PIO_SCDR = PIO_SCDR_DIV(div);
} }

View file

@ -16,7 +16,7 @@
#error "Unsupported SoC, update soc_pmc.c functions" #error "Unsupported SoC, update soc_pmc.c functions"
#endif #endif
void soc_pmc_peripheral_enable(uint32_t id) void soc_pmc_peripheral_enable(u32_t id)
{ {
__ASSERT(id < ID_PERIPH_COUNT, "Invalid peripheral id"); __ASSERT(id < ID_PERIPH_COUNT, "Invalid peripheral id");
@ -29,7 +29,7 @@ void soc_pmc_peripheral_enable(uint32_t id)
} }
} }
void soc_pmc_peripheral_disable(uint32_t id) void soc_pmc_peripheral_disable(u32_t id)
{ {
__ASSERT(id < ID_PERIPH_COUNT, "Invalid peripheral id"); __ASSERT(id < ID_PERIPH_COUNT, "Invalid peripheral id");
@ -42,7 +42,7 @@ void soc_pmc_peripheral_disable(uint32_t id)
} }
} }
uint32_t soc_pmc_peripheral_is_enabled(uint32_t id) u32_t soc_pmc_peripheral_is_enabled(u32_t id)
{ {
__ASSERT(id < ID_PERIPH_COUNT, "Invalid peripheral id"); __ASSERT(id < ID_PERIPH_COUNT, "Invalid peripheral id");

View file

@ -18,14 +18,14 @@
* *
* @param id peripheral module id, as defined in data sheet. * @param id peripheral module id, as defined in data sheet.
*/ */
void soc_pmc_peripheral_enable(uint32_t id); void soc_pmc_peripheral_enable(u32_t id);
/** /**
* @brief Disable the clock of specified peripheral module. * @brief Disable the clock of specified peripheral module.
* *
* @param id peripheral module id, as defined in data sheet. * @param id peripheral module id, as defined in data sheet.
*/ */
void soc_pmc_peripheral_disable(uint32_t id); void soc_pmc_peripheral_disable(u32_t id);
/** /**
* @brief Check if specified peripheral module is enabled. * @brief Check if specified peripheral module is enabled.
@ -33,6 +33,6 @@ void soc_pmc_peripheral_disable(uint32_t id);
* @param id peripheral module id, as defined in data sheet. * @param id peripheral module id, as defined in data sheet.
* @return 1 if peripheral is enabled, 0 otherwise * @return 1 if peripheral is enabled, 0 otherwise
*/ */
uint32_t soc_pmc_peripheral_is_enabled(uint32_t id); u32_t soc_pmc_peripheral_is_enabled(u32_t id);
#endif /* _ATMEL_SAM_SOC_PMC_H_ */ #endif /* _ATMEL_SAM_SOC_PMC_H_ */

View file

@ -53,7 +53,7 @@
*/ */
static ALWAYS_INLINE void clock_init(void) static ALWAYS_INLINE void clock_init(void)
{ {
uint32_t reg_val; u32_t reg_val;
#ifdef CONFIG_SOC_ATMEL_SAME70_EXT_SLCK #ifdef CONFIG_SOC_ATMEL_SAME70_EXT_SLCK
/* Switch slow clock to the external 32 kHz crystal oscillator */ /* Switch slow clock to the external 32 kHz crystal oscillator */
@ -217,7 +217,7 @@ static ALWAYS_INLINE void clock_init(void)
*/ */
static int atmel_same70_init(struct device *arg) static int atmel_same70_init(struct device *arg)
{ {
uint32_t key; u32_t key;
ARG_UNUSED(arg); ARG_UNUSED(arg);

View file

@ -31,7 +31,7 @@
*/ */
static ALWAYS_INLINE void clock_init(void) static ALWAYS_INLINE void clock_init(void)
{ {
uint32_t tmp; u32_t tmp;
/* Note: /* Note:
* Magic numbers below are obtained by reading the registers * Magic numbers below are obtained by reading the registers
@ -141,7 +141,7 @@ static ALWAYS_INLINE void clock_init(void)
*/ */
static int atmel_sam3_init(struct device *arg) static int atmel_sam3_init(struct device *arg)
{ {
uint32_t key; u32_t key;
ARG_UNUSED(arg); ARG_UNUSED(arg);

View file

@ -21,215 +21,215 @@
* Starts at offset 0x100. * Starts at offset 0x100.
*/ */
struct __pdc { struct __pdc {
uint32_t rpr; /* 0x100 Receive Pointer */ u32_t rpr; /* 0x100 Receive Pointer */
uint32_t rcr; /* 0x104 Receive Counter */ u32_t rcr; /* 0x104 Receive Counter */
uint32_t tpr; /* 0x108 Transmit Pointer */ u32_t tpr; /* 0x108 Transmit Pointer */
uint32_t tcr; /* 0x10C Transmit Counter */ u32_t tcr; /* 0x10C Transmit Counter */
uint32_t rnpr; /* 0x110 Receive Next Pointer */ u32_t rnpr; /* 0x110 Receive Next Pointer */
uint32_t rncr; /* 0x114 Receive Next Counter */ u32_t rncr; /* 0x114 Receive Next Counter */
uint32_t tnpr; /* 0x118 Transmit Next Pointer */ u32_t tnpr; /* 0x118 Transmit Next Pointer */
uint32_t tncr; /* 0x11C Transmit Next Counter */ u32_t tncr; /* 0x11C Transmit Next Counter */
uint32_t ptcr; /* 0x120 Transfer Control */ u32_t ptcr; /* 0x120 Transfer Control */
uint32_t ptsr; /* 0x124 Transfer Status */ u32_t ptsr; /* 0x124 Transfer Status */
}; };
/* Enhanced Embedded Flash Controller */ /* Enhanced Embedded Flash Controller */
struct __eefc { struct __eefc {
uint32_t fmr; /* 0x00 Flash Mode Register */ u32_t fmr; /* 0x00 Flash Mode Register */
uint32_t fcr; /* 0x04 Flash Command Register */ u32_t fcr; /* 0x04 Flash Command Register */
uint32_t fsr; /* 0x08 Flash Status Register */ u32_t fsr; /* 0x08 Flash Status Register */
uint32_t frr; /* 0x0C Flash Result Register */ u32_t frr; /* 0x0C Flash Result Register */
}; };
/* PIO Controller */ /* PIO Controller */
struct __pio { struct __pio {
uint32_t per; /* 0x00 Enable */ u32_t per; /* 0x00 Enable */
uint32_t pdr; /* 0x04 Disable */ u32_t pdr; /* 0x04 Disable */
uint32_t psr; /* 0x08 Status */ u32_t psr; /* 0x08 Status */
uint32_t res0; /* 0x0C reserved */ u32_t res0; /* 0x0C reserved */
uint32_t oer; /* 0x10 Output Enable */ u32_t oer; /* 0x10 Output Enable */
uint32_t odr; /* 0x14 Output Disable */ u32_t odr; /* 0x14 Output Disable */
uint32_t osr; /* 0x18 Output Status */ u32_t osr; /* 0x18 Output Status */
uint32_t res1; /* 0x1C reserved */ u32_t res1; /* 0x1C reserved */
uint32_t ifer; /* 0x20 Glitch Input Filter Enable */ u32_t ifer; /* 0x20 Glitch Input Filter Enable */
uint32_t ifdr; /* 0x24 Glitch Input Filter Disable */ u32_t ifdr; /* 0x24 Glitch Input Filter Disable */
uint32_t ifsr; /* 0x28 Glitch Input Fitler Status */ u32_t ifsr; /* 0x28 Glitch Input Fitler Status */
uint32_t res2; /* 0x2C reserved */ u32_t res2; /* 0x2C reserved */
uint32_t sodr; /* 0x30 Set Output Data */ u32_t sodr; /* 0x30 Set Output Data */
uint32_t codr; /* 0x34 Clear Output Data */ u32_t codr; /* 0x34 Clear Output Data */
uint32_t odsr; /* 0x38 Output Data Status */ u32_t odsr; /* 0x38 Output Data Status */
uint32_t pdsr; /* 0x3C Pin Data Status */ u32_t pdsr; /* 0x3C Pin Data Status */
uint32_t ier; /* 0x40 Interrupt Enable */ u32_t ier; /* 0x40 Interrupt Enable */
uint32_t idr; /* 0x44 Interrupt Disable */ u32_t idr; /* 0x44 Interrupt Disable */
uint32_t imr; /* 0x48 Interrupt Mask */ u32_t imr; /* 0x48 Interrupt Mask */
uint32_t isr; /* 0x4C Interrupt Status */ u32_t isr; /* 0x4C Interrupt Status */
uint32_t mder; /* 0x50 Multi-driver Enable */ u32_t mder; /* 0x50 Multi-driver Enable */
uint32_t mddr; /* 0x54 Multi-driver Disable */ u32_t mddr; /* 0x54 Multi-driver Disable */
uint32_t mdsr; /* 0x58 Multi-driver Status */ u32_t mdsr; /* 0x58 Multi-driver Status */
uint32_t res3; /* 0x5C reserved */ u32_t res3; /* 0x5C reserved */
uint32_t pudr; /* 0x60 Pull-up Disable */ u32_t pudr; /* 0x60 Pull-up Disable */
uint32_t puer; /* 0x64 Pull-up Enable */ u32_t puer; /* 0x64 Pull-up Enable */
uint32_t pusr; /* 0x68 Pad Pull-up Status */ u32_t pusr; /* 0x68 Pad Pull-up Status */
uint32_t res4; /* 0x6C reserved */ u32_t res4; /* 0x6C reserved */
uint32_t absr; /* 0x70 Peripheral AB Select */ u32_t absr; /* 0x70 Peripheral AB Select */
uint32_t res5[3]; /* 0x74-0x7C reserved */ u32_t res5[3]; /* 0x74-0x7C reserved */
uint32_t scifsr; /* 0x80 System Clock Glitch Input */ u32_t scifsr; /* 0x80 System Clock Glitch Input */
/* Filter Select */ /* Filter Select */
uint32_t difsr; /* 0x84 Debouncing Input Filter */ u32_t difsr; /* 0x84 Debouncing Input Filter */
/* Select */ /* Select */
uint32_t ifdgsr; /* 0x88 Glitch or Debouncing Input */ u32_t ifdgsr; /* 0x88 Glitch or Debouncing Input */
/* Filter Clock Selection */ /* Filter Clock Selection */
/* Status */ /* Status */
uint32_t scdr; /* 0x8C Slow Clock Divider Debounce */ u32_t scdr; /* 0x8C Slow Clock Divider Debounce */
uint32_t res6[4]; /* 0x90-0x9C reserved */ u32_t res6[4]; /* 0x90-0x9C reserved */
uint32_t ower; /* 0xA0 Output Write Enable */ u32_t ower; /* 0xA0 Output Write Enable */
uint32_t owdr; /* 0xA4 Output Write Disable */ u32_t owdr; /* 0xA4 Output Write Disable */
uint32_t owsr; /* 0xA8 Output Write Status */ u32_t owsr; /* 0xA8 Output Write Status */
uint32_t res7; /* 0xAC reserved */ u32_t res7; /* 0xAC reserved */
uint32_t aimer; /* 0xB0 Additional Interrupt Modes */ u32_t aimer; /* 0xB0 Additional Interrupt Modes */
/* Enable */ /* Enable */
uint32_t aimdr; /* 0xB4 Additional Interrupt Modes */ u32_t aimdr; /* 0xB4 Additional Interrupt Modes */
/* Disable */ /* Disable */
uint32_t aimmr; /* 0xB8 Additional Interrupt Modes */ u32_t aimmr; /* 0xB8 Additional Interrupt Modes */
/* Mask */ /* Mask */
uint32_t res8; /* 0xBC reserved */ u32_t res8; /* 0xBC reserved */
uint32_t esr; /* 0xC0 Edge Select */ u32_t esr; /* 0xC0 Edge Select */
uint32_t lsr; /* 0xC4 Level Select */ u32_t lsr; /* 0xC4 Level Select */
uint32_t elsr; /* 0xC8 Edge/Level Status */ u32_t elsr; /* 0xC8 Edge/Level Status */
uint32_t res9; /* 0xCC reserved */ u32_t res9; /* 0xCC reserved */
uint32_t fellsr; /* 0xD0 Falling Edge/Low Level Sel */ u32_t fellsr; /* 0xD0 Falling Edge/Low Level Sel */
uint32_t rehlsr; /* 0xD4 Rising Edge/High Level Sel */ u32_t rehlsr; /* 0xD4 Rising Edge/High Level Sel */
uint32_t frlhsr; /* 0xD8 Fall/Rise - Low/High Status */ u32_t frlhsr; /* 0xD8 Fall/Rise - Low/High Status */
uint32_t res10; /* 0xDC reserved */ u32_t res10; /* 0xDC reserved */
uint32_t locksr; /* 0xE0 Lock Status */ u32_t locksr; /* 0xE0 Lock Status */
uint32_t wpmr; /* 0xE4 Write Protect Mode */ u32_t wpmr; /* 0xE4 Write Protect Mode */
uint32_t wpsr; /* 0xE8 Write Protect Status */ u32_t wpsr; /* 0xE8 Write Protect Status */
}; };
/* Power Management Controller */ /* Power Management Controller */
struct __pmc { struct __pmc {
uint32_t scer; /* 0x00 System Clock Enable */ u32_t scer; /* 0x00 System Clock Enable */
uint32_t scdr; /* 0x04 System Clock Disable */ u32_t scdr; /* 0x04 System Clock Disable */
uint32_t scsr; /* 0x08 System Clock Status */ u32_t scsr; /* 0x08 System Clock Status */
uint32_t res0; /* 0x0C reserved */ u32_t res0; /* 0x0C reserved */
uint32_t pcer0; /* 0x10 Peripheral Clock Enable 0 */ u32_t pcer0; /* 0x10 Peripheral Clock Enable 0 */
uint32_t pcdr0; /* 0x14 Peripheral Clock Disable 0 */ u32_t pcdr0; /* 0x14 Peripheral Clock Disable 0 */
uint32_t pcsr0; /* 0x18 Peripheral Clock Status 0 */ u32_t pcsr0; /* 0x18 Peripheral Clock Status 0 */
uint32_t ckgr_uckr; /* 0x1C UTMI Clock */ u32_t ckgr_uckr; /* 0x1C UTMI Clock */
uint32_t ckgr_mor; /* 0x20 Main Oscillator */ u32_t ckgr_mor; /* 0x20 Main Oscillator */
uint32_t ckgr_mcfr; /* 0x24 Main Clock Freq. */ u32_t ckgr_mcfr; /* 0x24 Main Clock Freq. */
uint32_t ckgr_pllar; /* 0x28 PLLA */ u32_t ckgr_pllar; /* 0x28 PLLA */
uint32_t res1; /* 0x2C reserved */ u32_t res1; /* 0x2C reserved */
uint32_t mckr; /* 0x30 Master Clock */ u32_t mckr; /* 0x30 Master Clock */
uint32_t res2; /* 0x34 reserved */ u32_t res2; /* 0x34 reserved */
uint32_t usb; /* 0x38 USB Clock */ u32_t usb; /* 0x38 USB Clock */
uint32_t res3; /* 0x3C reserved */ u32_t res3; /* 0x3C reserved */
uint32_t pck0; /* 0x40 Programmable Clock 0 */ u32_t pck0; /* 0x40 Programmable Clock 0 */
uint32_t pck1; /* 0x44 Programmable Clock 1 */ u32_t pck1; /* 0x44 Programmable Clock 1 */
uint32_t pck2; /* 0x48 Programmable Clock 2 */ u32_t pck2; /* 0x48 Programmable Clock 2 */
uint32_t res4[5]; /* 0x4C-0x5C reserved */ u32_t res4[5]; /* 0x4C-0x5C reserved */
uint32_t ier; /* 0x60 Interrupt Enable */ u32_t ier; /* 0x60 Interrupt Enable */
uint32_t idr; /* 0x64 Interrupt Disable */ u32_t idr; /* 0x64 Interrupt Disable */
uint32_t sr; /* 0x68 Status */ u32_t sr; /* 0x68 Status */
uint32_t imr; /* 0x6C Interrupt Mask */ u32_t imr; /* 0x6C Interrupt Mask */
uint32_t fsmr; /* 0x70 Fast Startup Mode */ u32_t fsmr; /* 0x70 Fast Startup Mode */
uint32_t fspr; /* 0x74 Fast Startup Polarity */ u32_t fspr; /* 0x74 Fast Startup Polarity */
uint32_t focr; /* 0x78 Fault Outpu Clear */ u32_t focr; /* 0x78 Fault Outpu Clear */
uint32_t res5[26]; /* 0x7C-0xE0 reserved */ u32_t res5[26]; /* 0x7C-0xE0 reserved */
uint32_t wpmr; /* 0xE4 Write Protect Mode */ u32_t wpmr; /* 0xE4 Write Protect Mode */
uint32_t wpsr; /* 0xE8 Write Protect Status */ u32_t wpsr; /* 0xE8 Write Protect Status */
uint32_t res6[5]; /* 0xEC-0xFC reserved */ u32_t res6[5]; /* 0xEC-0xFC reserved */
uint32_t pcer1; /* 0x100 Peripheral Clock Enable 1 */ u32_t pcer1; /* 0x100 Peripheral Clock Enable 1 */
uint32_t pcdr1; /* 0x104 Peripheral Clock Disable 1 */ u32_t pcdr1; /* 0x104 Peripheral Clock Disable 1 */
uint32_t pcsr1; /* 0x108 Peripheral Clock Status 1 */ u32_t pcsr1; /* 0x108 Peripheral Clock Status 1 */
uint32_t pcr; /* 0x10C Peripheral Control */ u32_t pcr; /* 0x10C Peripheral Control */
}; };
/* Supply Controller (SUPC) */ /* Supply Controller (SUPC) */
struct __supc { struct __supc {
uint32_t cr; /* 0x00 Control */ u32_t cr; /* 0x00 Control */
uint32_t smmr; /* 0x04 Supply Monitor Mode */ u32_t smmr; /* 0x04 Supply Monitor Mode */
uint32_t mr; /* 0x08 Mode */ u32_t mr; /* 0x08 Mode */
uint32_t wumr; /* 0x0C Wake Up Mode */ u32_t wumr; /* 0x0C Wake Up Mode */
uint32_t wuir; /* 0x10 Wake Up Inputs */ u32_t wuir; /* 0x10 Wake Up Inputs */
uint32_t sr; /* 0x14 Status */ u32_t sr; /* 0x14 Status */
}; };
/* Two-wire Interface (TWI), aka I2C */ /* Two-wire Interface (TWI), aka I2C */
struct __twi { struct __twi {
uint32_t cr; /* 0x00 Control */ u32_t cr; /* 0x00 Control */
uint32_t mmr; /* 0x04 Master Mode */ u32_t mmr; /* 0x04 Master Mode */
uint32_t smr; /* 0x08 Slave Mode */ u32_t smr; /* 0x08 Slave Mode */
uint32_t iadr; /* 0x0C Internal Address */ u32_t iadr; /* 0x0C Internal Address */
uint32_t cwgr; /* 0x10 Clock Waveform Generator */ u32_t cwgr; /* 0x10 Clock Waveform Generator */
uint32_t rev0[3]; /* 0x14-0x1C reserved */ u32_t rev0[3]; /* 0x14-0x1C reserved */
uint32_t sr; /* 0x20 Status */ u32_t sr; /* 0x20 Status */
uint32_t ier; /* 0x24 Interrupt Enable */ u32_t ier; /* 0x24 Interrupt Enable */
uint32_t idr; /* 0x28 Interrupt Disable */ u32_t idr; /* 0x28 Interrupt Disable */
uint32_t imr; /* 0x2C Interrupt Mask */ u32_t imr; /* 0x2C Interrupt Mask */
uint32_t rhr; /* 0x30 Receive Holding */ u32_t rhr; /* 0x30 Receive Holding */
uint32_t thr; /* 0x34 Transmit Holding */ u32_t thr; /* 0x34 Transmit Holding */
uint32_t rev1[50]; /* 0x38-0xFC Reserved */ u32_t rev1[50]; /* 0x38-0xFC Reserved */
struct __pdc pdc; /* 0x100 - 0x124 PDC */ struct __pdc pdc; /* 0x100 - 0x124 PDC */
}; };
/* Watchdog timer (WDT) */ /* Watchdog timer (WDT) */
struct __wdt { struct __wdt {
uint32_t cr; /* 0x00 Control Register */ u32_t cr; /* 0x00 Control Register */
uint32_t mr; /* 0x04 Mode Register */ u32_t mr; /* 0x04 Mode Register */
uint32_t sr; /* 0x08 Status Register */ u32_t sr; /* 0x08 Status Register */
}; };
#endif /* _ATMEL_SAM3_SOC_REGS_H_ */ #endif /* _ATMEL_SAM3_SOC_REGS_H_ */

View file

@ -36,7 +36,7 @@ uint32_t SystemCoreClock __used = __SYSTEM_CLOCK;
static int nordicsemi_nrf51_init(struct device *arg) static int nordicsemi_nrf51_init(struct device *arg)
{ {
uint32_t key; u32_t key;
ARG_UNUSED(arg); ARG_UNUSED(arg);
@ -57,8 +57,8 @@ static int nordicsemi_nrf51_init(struct device *arg)
* will not be available. * will not be available.
*/ */
if (ftpan_26()) { if (ftpan_26()) {
*(volatile uint32_t *)0x40000504 = 0xC007FFDF; *(volatile u32_t *)0x40000504 = 0xC007FFDF;
*(volatile uint32_t *)0x40006C18 = 0x00008000; *(volatile u32_t *)0x40006C18 = 0x00008000;
} }
/* Disable PROTENSET registers under debug, as indicated by PAN 59 /* Disable PROTENSET registers under debug, as indicated by PAN 59
@ -84,18 +84,18 @@ static int nordicsemi_nrf51_init(struct device *arg)
static bool ftpan_26(void) static bool ftpan_26(void)
{ {
if ((((*(uint32_t *)0xF0000FE0) & 0x000000FF) == 0x1) && if ((((*(u32_t *)0xF0000FE0) & 0x000000FF) == 0x1) &&
(((*(uint32_t *)0xF0000FE4) & 0x0000000F) == 0x0)) { (((*(u32_t *)0xF0000FE4) & 0x0000000F) == 0x0)) {
if ((((*(uint32_t *)0xF0000FE8) & 0x000000F0) == 0x00) && if ((((*(u32_t *)0xF0000FE8) & 0x000000F0) == 0x00) &&
(((*(uint32_t *)0xF0000FEC) & 0x000000F0) == 0x0)) { (((*(u32_t *)0xF0000FEC) & 0x000000F0) == 0x0)) {
return true; return true;
} }
if ((((*(uint32_t *)0xF0000FE8) & 0x000000F0) == 0x10) && if ((((*(u32_t *)0xF0000FE8) & 0x000000F0) == 0x10) &&
(((*(uint32_t *)0xF0000FEC) & 0x000000F0) == 0x0)) { (((*(u32_t *)0xF0000FEC) & 0x000000F0) == 0x0)) {
return true; return true;
} }
if ((((*(uint32_t *)0xF0000FE8) & 0x000000F0) == 0x30) && if ((((*(u32_t *)0xF0000FE8) & 0x000000F0) == 0x30) &&
(((*(uint32_t *)0xF0000FEC) & 0x000000F0) == 0x0)) { (((*(u32_t *)0xF0000FEC) & 0x000000F0) == 0x0)) {
return true; return true;
} }
} }
@ -105,10 +105,10 @@ static bool ftpan_26(void)
static bool ftpan_59(void) static bool ftpan_59(void)
{ {
if ((((*(uint32_t *)0xF0000FE0) & 0x000000FF) == 0x1) && if ((((*(u32_t *)0xF0000FE0) & 0x000000FF) == 0x1) &&
(((*(uint32_t *)0xF0000FE4) & 0x0000000F) == 0x0)) { (((*(u32_t *)0xF0000FE4) & 0x0000000F) == 0x0)) {
if ((((*(uint32_t *)0xF0000FE8) & 0x000000F0) == 0x40) && if ((((*(u32_t *)0xF0000FE8) & 0x000000F0) == 0x40) &&
(((*(uint32_t *)0xF0000FEC) & 0x000000F0) == 0x0)) { (((*(u32_t *)0xF0000FEC) & 0x000000F0) == 0x0)) {
return true; return true;
} }
} }

View file

@ -32,10 +32,10 @@ extern void _NmiInit(void);
#ifdef CONFIG_SOC_NRF52832 #ifdef CONFIG_SOC_NRF52832
static bool ftpan_32(void) static bool ftpan_32(void)
{ {
if ((((*(uint32_t *)0xF0000FE0) & 0x000000FF) == 0x6) && if ((((*(u32_t *)0xF0000FE0) & 0x000000FF) == 0x6) &&
(((*(uint32_t *)0xF0000FE4) & 0x0000000F) == 0x0)) { (((*(u32_t *)0xF0000FE4) & 0x0000000F) == 0x0)) {
if ((((*(uint32_t *)0xF0000FE8) & 0x000000F0) == 0x30) && if ((((*(u32_t *)0xF0000FE8) & 0x000000F0) == 0x30) &&
(((*(uint32_t *)0xF0000FEC) & 0x000000F0) == 0x0)) { (((*(u32_t *)0xF0000FEC) & 0x000000F0) == 0x0)) {
return true; return true;
} }
} }
@ -45,10 +45,10 @@ static bool ftpan_32(void)
static bool ftpan_37(void) static bool ftpan_37(void)
{ {
if ((((*(uint32_t *)0xF0000FE0) & 0x000000FF) == 0x6) && if ((((*(u32_t *)0xF0000FE0) & 0x000000FF) == 0x6) &&
(((*(uint32_t *)0xF0000FE4) & 0x0000000F) == 0x0)) { (((*(u32_t *)0xF0000FE4) & 0x0000000F) == 0x0)) {
if ((((*(uint32_t *)0xF0000FE8) & 0x000000F0) == 0x30) && if ((((*(u32_t *)0xF0000FE8) & 0x000000F0) == 0x30) &&
(((*(uint32_t *)0xF0000FEC) & 0x000000F0) == 0x0)) { (((*(u32_t *)0xF0000FEC) & 0x000000F0) == 0x0)) {
return true; return true;
} }
} }
@ -58,10 +58,10 @@ static bool ftpan_37(void)
static bool ftpan_36(void) static bool ftpan_36(void)
{ {
if ((((*(uint32_t *)0xF0000FE0) & 0x000000FF) == 0x6) && if ((((*(u32_t *)0xF0000FE0) & 0x000000FF) == 0x6) &&
(((*(uint32_t *)0xF0000FE4) & 0x0000000F) == 0x0)) { (((*(u32_t *)0xF0000FE4) & 0x0000000F) == 0x0)) {
if ((((*(uint32_t *)0xF0000FE8) & 0x000000F0) == 0x30) && if ((((*(u32_t *)0xF0000FE8) & 0x000000F0) == 0x30) &&
(((*(uint32_t *)0xF0000FEC) & 0x000000F0) == 0x0)) { (((*(u32_t *)0xF0000FEC) & 0x000000F0) == 0x0)) {
return true; return true;
} }
} }
@ -84,7 +84,7 @@ static void nordicsemi_nrf52832_init(void)
* for your device located at https://www.nordicsemi.com/ * for your device located at https://www.nordicsemi.com/
*/ */
if (ftpan_37()) { if (ftpan_37()) {
*(volatile uint32_t *)0x400005A0 = 0x3; *(volatile u32_t *)0x400005A0 = 0x3;
} }
/* Workaround for FTPAN-36 "CLOCK: Some registers are not /* Workaround for FTPAN-36 "CLOCK: Some registers are not
@ -152,8 +152,8 @@ static void nordicsemi_nrf52832_init(void)
#ifdef CONFIG_SOC_NRF52840 #ifdef CONFIG_SOC_NRF52840
static bool errata_36(void) static bool errata_36(void)
{ {
if ((*(uint32_t *)0x10000130ul == 0x8ul) && if ((*(u32_t *)0x10000130ul == 0x8ul) &&
(*(uint32_t *)0x10000134ul == 0x0ul)) { (*(u32_t *)0x10000134ul == 0x0ul)) {
return true; return true;
} }
@ -163,8 +163,8 @@ static bool errata_36(void)
static bool errata_98(void) static bool errata_98(void)
{ {
if ((*(uint32_t *)0x10000130ul == 0x8ul) && if ((*(u32_t *)0x10000130ul == 0x8ul) &&
(*(uint32_t *)0x10000134ul == 0x0ul)) { (*(u32_t *)0x10000134ul == 0x0ul)) {
return true; return true;
} }
@ -174,8 +174,8 @@ static bool errata_98(void)
static bool errata_103(void) static bool errata_103(void)
{ {
if ((*(uint32_t *)0x10000130ul == 0x8ul) && if ((*(u32_t *)0x10000130ul == 0x8ul) &&
(*(uint32_t *)0x10000134ul == 0x0ul)) { (*(u32_t *)0x10000134ul == 0x0ul)) {
return true; return true;
} }
@ -185,8 +185,8 @@ static bool errata_103(void)
static bool errata_115(void) static bool errata_115(void)
{ {
if ((*(uint32_t *)0x10000130ul == 0x8ul) && if ((*(u32_t *)0x10000130ul == 0x8ul) &&
(*(uint32_t *)0x10000134ul == 0x0ul)) { (*(u32_t *)0x10000134ul == 0x0ul)) {
return true; return true;
} }
@ -196,8 +196,8 @@ static bool errata_115(void)
static bool errata_120(void) static bool errata_120(void)
{ {
if ((*(uint32_t *)0x10000130ul == 0x8ul) && if ((*(u32_t *)0x10000130ul == 0x8ul) &&
(*(uint32_t *)0x10000134ul == 0x0ul)) { (*(u32_t *)0x10000134ul == 0x0ul)) {
return true; return true;
} }
@ -221,7 +221,7 @@ static void nordicsemi_nrf52840_init(void)
* https://infocenter.nordicsemi.com/ * https://infocenter.nordicsemi.com/
*/ */
if (errata_98()) { if (errata_98()) {
*(volatile uint32_t *)0x4000568Cul = 0x00038148ul; *(volatile u32_t *)0x4000568Cul = 0x00038148ul;
} }
/* Workaround for Errata 103 "CCM: Wrong reset value of CCM /* Workaround for Errata 103 "CCM: Wrong reset value of CCM
@ -238,9 +238,9 @@ static void nordicsemi_nrf52840_init(void)
* https://infocenter.nordicsemi.com/ * https://infocenter.nordicsemi.com/
*/ */
if (errata_115()) { if (errata_115()) {
*(volatile uint32_t *)0x40000EE4 = *(volatile u32_t *)0x40000EE4 =
(*(volatile uint32_t *) 0x40000EE4 & 0xFFFFFFF0) | (*(volatile u32_t *) 0x40000EE4 & 0xFFFFFFF0) |
(*(uint32_t *)0x10000258 & 0x0000000F); (*(u32_t *)0x10000258 & 0x0000000F);
} }
/* Workaround for Errata 120 "QSPI: Data read or written is corrupted" /* Workaround for Errata 120 "QSPI: Data read or written is corrupted"
@ -248,7 +248,7 @@ static void nordicsemi_nrf52840_init(void)
* https://infocenter.nordicsemi.com/ * https://infocenter.nordicsemi.com/
*/ */
if (errata_120()) { if (errata_120()) {
*(volatile uint32_t *)0x40029640ul = 0x200ul; *(volatile u32_t *)0x40029640ul = 0x200ul;
} }
/* Configure GPIO pads as pPin Reset pin if Pin Reset capabilities /* Configure GPIO pads as pPin Reset pin if Pin Reset capabilities
@ -329,7 +329,7 @@ static void clock_init(void)
static int nordicsemi_nrf52_init(struct device *arg) static int nordicsemi_nrf52_init(struct device *arg)
{ {
uint32_t key; u32_t key;
ARG_UNUSED(arg); ARG_UNUSED(arg);

View file

@ -49,7 +49,7 @@
* -Reserved, 1 byte, (EEPROM protection byte for FlexNVM) * -Reserved, 1 byte, (EEPROM protection byte for FlexNVM)
* *
*/ */
uint8_t __kinetis_flash_config_section __kinetis_flash_config[] = { u8_t __kinetis_flash_config_section __kinetis_flash_config[] = {
/* Backdoor Comparison Key (unused) */ /* Backdoor Comparison Key (unused) */
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
/* Program flash protection; 1 bit/region - 0=protected, 1=unprotected /* Program flash protection; 1 bit/region - 0=protected, 1=unprotected
@ -153,7 +153,7 @@ static int fsl_frdm_k64f_init(struct device *arg)
ARG_UNUSED(arg); ARG_UNUSED(arg);
int oldLevel; /* old interrupt lock level */ int oldLevel; /* old interrupt lock level */
uint32_t temp_reg; u32_t temp_reg;
/* disable interrupts */ /* disable interrupts */
oldLevel = irq_lock(); oldLevel = irq_lock();

View file

@ -32,7 +32,7 @@
* -Reserved, 1 byte, (EEPROM protection byte for FlexNVM) * -Reserved, 1 byte, (EEPROM protection byte for FlexNVM)
* *
*/ */
uint8_t __kinetis_flash_config_section __kinetis_flash_config[] = { u8_t __kinetis_flash_config_section __kinetis_flash_config[] = {
/* Backdoor Comparison Key (unused) */ /* Backdoor Comparison Key (unused) */
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
/* Program flash protection; 1 bit/region - 0=protected, 1=unprotected /* Program flash protection; 1 bit/region - 0=protected, 1=unprotected

View file

@ -37,7 +37,7 @@
* -Reserved, 1 byte, (EEPROM protection byte for FlexNVM) * -Reserved, 1 byte, (EEPROM protection byte for FlexNVM)
* *
*/ */
uint8_t __kinetis_flash_config_section __kinetis_flash_config[] = { u8_t __kinetis_flash_config_section __kinetis_flash_config[] = {
/* Backdoor Comparison Key (unused) */ /* Backdoor Comparison Key (unused) */
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
/* Program flash protection; 1 bit/region - 0=protected, 1=unprotected /* Program flash protection; 1 bit/region - 0=protected, 1=unprotected
@ -77,7 +77,7 @@ static const sim_clock_config_t simConfig = {
*/ */
static void CLOCK_SYS_FllStableDelay(void) static void CLOCK_SYS_FllStableDelay(void)
{ {
uint32_t i = 30000U; u32_t i = 30000U;
while (i--) { while (i--) {
__NOP(); __NOP();
} }

View file

@ -25,27 +25,27 @@ enum {
/* 3.3.3 FLASH_ACR */ /* 3.3.3 FLASH_ACR */
union __ef_acr { union __ef_acr {
uint32_t val; u32_t val;
struct { struct {
uint32_t latency :3 __packed; u32_t latency :3 __packed;
uint32_t hlfcya :1 __packed; u32_t hlfcya :1 __packed;
uint32_t prftbe :1 __packed; u32_t prftbe :1 __packed;
uint32_t prftbs :1 __packed; u32_t prftbs :1 __packed;
uint32_t rsvd__6_31 :26 __packed; u32_t rsvd__6_31 :26 __packed;
} bit; } bit;
}; };
/* 3.3.3 Embedded flash registers */ /* 3.3.3 Embedded flash registers */
struct stm32f10x_flash { struct stm32f10x_flash {
union __ef_acr acr; union __ef_acr acr;
uint32_t keyr; u32_t keyr;
uint32_t optkeyr; u32_t optkeyr;
uint32_t sr; u32_t sr;
uint32_t cr; u32_t cr;
uint32_t ar; u32_t ar;
uint32_t rsvd; u32_t rsvd;
uint32_t obr; u32_t obr;
uint32_t wrpr; u32_t wrpr;
}; };
#endif /* _STM32F10X_FLASHREGISTERS_H_ */ #endif /* _STM32F10X_FLASHREGISTERS_H_ */

View file

@ -20,74 +20,74 @@
/* 9.2 GPIO registers - each GPIO port controls 16 pins */ /* 9.2 GPIO registers - each GPIO port controls 16 pins */
struct stm32f10x_gpio { struct stm32f10x_gpio {
uint32_t crl; u32_t crl;
uint32_t crh; u32_t crh;
uint32_t idr; u32_t idr;
uint32_t odr; u32_t odr;
uint32_t bsrr; u32_t bsrr;
uint32_t brr; u32_t brr;
uint32_t lckr; u32_t lckr;
}; };
/* 9.4.1 AFIO_EVCR */ /* 9.4.1 AFIO_EVCR */
union __afio_evcr { union __afio_evcr {
uint32_t val; u32_t val;
struct { struct {
uint32_t pin :4 __packed; u32_t pin :4 __packed;
uint32_t port :3 __packed; u32_t port :3 __packed;
uint32_t evoe :1 __packed; u32_t evoe :1 __packed;
uint32_t rsvd__8_31 :24 __packed; u32_t rsvd__8_31 :24 __packed;
} bit; } bit;
}; };
/* 9.4.2 AFIO_MAPR */ /* 9.4.2 AFIO_MAPR */
/* TODO: support connectivity line devices */ /* TODO: support connectivity line devices */
union __afio_mapr { union __afio_mapr {
uint32_t val; u32_t val;
struct { struct {
uint32_t spi1_remap :1 __packed; u32_t spi1_remap :1 __packed;
uint32_t i2c1_remap :1 __packed; u32_t i2c1_remap :1 __packed;
uint32_t usart1_remap :1 __packed; u32_t usart1_remap :1 __packed;
uint32_t usart2_remap :1 __packed; u32_t usart2_remap :1 __packed;
uint32_t usart3_remap :2 __packed; u32_t usart3_remap :2 __packed;
uint32_t tim1_remap :2 __packed; u32_t tim1_remap :2 __packed;
uint32_t tim2_remap :2 __packed; u32_t tim2_remap :2 __packed;
uint32_t tim3_remap :2 __packed; u32_t tim3_remap :2 __packed;
uint32_t tim4_remap :1 __packed; u32_t tim4_remap :1 __packed;
uint32_t can_remap :2 __packed; u32_t can_remap :2 __packed;
uint32_t pd01_remap :1 __packed; u32_t pd01_remap :1 __packed;
uint32_t tim5ch4_iremap :1 __packed; u32_t tim5ch4_iremap :1 __packed;
uint32_t adc1_etrginj_remap :1 __packed; u32_t adc1_etrginj_remap :1 __packed;
uint32_t adc1_etrgreg_remap :1 __packed; u32_t adc1_etrgreg_remap :1 __packed;
uint32_t adc2_etrginj_remap :1 __packed; u32_t adc2_etrginj_remap :1 __packed;
uint32_t adc2_etrgreg_remap :1 __packed; u32_t adc2_etrgreg_remap :1 __packed;
uint32_t rsvd__21_23 :3 __packed; u32_t rsvd__21_23 :3 __packed;
uint32_t swj_cfg :3 __packed; u32_t swj_cfg :3 __packed;
uint32_t rsvd__27_31 :5 __packed; u32_t rsvd__27_31 :5 __packed;
} bit; } bit;
}; };
/* 9.4.{3,4,5,6} AFIO_EXTICRx */ /* 9.4.{3,4,5,6} AFIO_EXTICRx */
union __afio_exticr { union __afio_exticr {
uint32_t val; u32_t val;
struct { struct {
uint16_t rsvd__16_31; u16_t rsvd__16_31;
uint16_t exti; u16_t exti;
} bit; } bit;
}; };
/* 9.4.7 AFIO_MAPR2 */ /* 9.4.7 AFIO_MAPR2 */
union __afio_mapr2 { union __afio_mapr2 {
uint32_t val; u32_t val;
struct { struct {
uint32_t rsvd__0_4 :5 __packed; u32_t rsvd__0_4 :5 __packed;
uint32_t tim9_remap :1 __packed; u32_t tim9_remap :1 __packed;
uint32_t tim10_remap :1 __packed; u32_t tim10_remap :1 __packed;
uint32_t tim11_remap :1 __packed; u32_t tim11_remap :1 __packed;
uint32_t tim13_remap :1 __packed; u32_t tim13_remap :1 __packed;
uint32_t tim14_remap :1 __packed; u32_t tim14_remap :1 __packed;
uint32_t fsmc_nadv :1 __packed; u32_t fsmc_nadv :1 __packed;
uint32_t rsvd__11_31 :21 __packed; u32_t rsvd__11_31 :21 __packed;
} bit; } bit;
}; };

View file

@ -95,78 +95,78 @@ enum {
*/ */
union __rcc_cr { union __rcc_cr {
uint32_t val; u32_t val;
struct { struct {
uint32_t hsion :1 __packed; u32_t hsion :1 __packed;
uint32_t hsirdy :1 __packed; u32_t hsirdy :1 __packed;
uint32_t rsvd__2 :1 __packed; u32_t rsvd__2 :1 __packed;
uint32_t hsitrim :5 __packed; u32_t hsitrim :5 __packed;
uint32_t hsical :8 __packed; u32_t hsical :8 __packed;
uint32_t hseon :1 __packed; u32_t hseon :1 __packed;
uint32_t hserdy :1 __packed; u32_t hserdy :1 __packed;
uint32_t hsebyp :1 __packed; u32_t hsebyp :1 __packed;
uint32_t csson :1 __packed; u32_t csson :1 __packed;
uint32_t rsvd__20_23 :4 __packed; u32_t rsvd__20_23 :4 __packed;
uint32_t pllon :1 __packed; u32_t pllon :1 __packed;
uint32_t pllrdy :1 __packed; u32_t pllrdy :1 __packed;
#if CONFIG_SOC_STM32F10X_DENSITY_DEVICE #if CONFIG_SOC_STM32F10X_DENSITY_DEVICE
uint32_t rsvd__26_31 :6 __packed; u32_t rsvd__26_31 :6 __packed;
#elif CONFIG_SOC_STM32F10X_CONNECTIVITY_LINE_DEVICE #elif CONFIG_SOC_STM32F10X_CONNECTIVITY_LINE_DEVICE
uint32_t pll2on :1 __packed; u32_t pll2on :1 __packed;
uint32_t pll2rdy :1 __packed; u32_t pll2rdy :1 __packed;
uint32_t pll3on :1 __packed; u32_t pll3on :1 __packed;
uint32_t pll3rdy :1 __packed; u32_t pll3rdy :1 __packed;
uint32_t rsvd__30_31 :2 __packed; u32_t rsvd__30_31 :2 __packed;
#endif #endif
} bit; } bit;
}; };
union __rcc_cfgr { union __rcc_cfgr {
uint32_t val; u32_t val;
struct { struct {
uint32_t sw :2 __packed; u32_t sw :2 __packed;
uint32_t sws :2 __packed; u32_t sws :2 __packed;
uint32_t hpre :4 __packed; u32_t hpre :4 __packed;
uint32_t ppre1 :3 __packed; u32_t ppre1 :3 __packed;
uint32_t ppre2 :3 __packed; u32_t ppre2 :3 __packed;
uint32_t adcpre :2 __packed; u32_t adcpre :2 __packed;
uint32_t pllsrc :1 __packed; u32_t pllsrc :1 __packed;
uint32_t pllxtpre :1 __packed; u32_t pllxtpre :1 __packed;
uint32_t pllmul :4 __packed; u32_t pllmul :4 __packed;
uint32_t usbpre :1 __packed; u32_t usbpre :1 __packed;
uint32_t rsvd__23 :1 __packed; u32_t rsvd__23 :1 __packed;
uint32_t mco :3 __packed; u32_t mco :3 __packed;
uint32_t rsvd__27_31 :5 __packed; u32_t rsvd__27_31 :5 __packed;
} bit; } bit;
}; };
union __rcc_cfgr2 { union __rcc_cfgr2 {
uint32_t val; u32_t val;
struct { struct {
uint32_t prediv1 :4 __packed; u32_t prediv1 :4 __packed;
uint32_t prediv2 :4 __packed; u32_t prediv2 :4 __packed;
uint32_t pll2mul :4 __packed; u32_t pll2mul :4 __packed;
uint32_t pll3mul :4 __packed; u32_t pll3mul :4 __packed;
uint32_t prediv1src :1 __packed; u32_t prediv1src :1 __packed;
uint32_t i2s2sr :1 __packed; u32_t i2s2sr :1 __packed;
uint32_t i2s3sr :1 __packed; u32_t i2s3sr :1 __packed;
uint32_t rsvd__19_31 :13 __packed; u32_t rsvd__19_31 :13 __packed;
} bit; } bit;
}; };
struct stm32f10x_rcc { struct stm32f10x_rcc {
union __rcc_cr cr; union __rcc_cr cr;
union __rcc_cfgr cfgr; union __rcc_cfgr cfgr;
uint32_t cir; u32_t cir;
uint32_t apb2rstr; u32_t apb2rstr;
uint32_t apb1rstr; u32_t apb1rstr;
uint32_t ahbenr; u32_t ahbenr;
uint32_t apb2enr; u32_t apb2enr;
uint32_t apb1enr; u32_t apb1enr;
uint32_t bdcr; u32_t bdcr;
uint32_t csr; u32_t csr;
#ifdef CONFIG_SOC_STM32F10X_CONNECTIVITY_LINE_DEVICE #ifdef CONFIG_SOC_STM32F10X_CONNECTIVITY_LINE_DEVICE
uint32_t ahbrstr; u32_t ahbrstr;
union __rcc_cfgr2 cfgr2; union __rcc_cfgr2 cfgr2;
#endif #endif
}; };

View file

@ -37,7 +37,7 @@ uint32_t HAL_GetTick(void)
*/ */
static int stm32f1_init(struct device *arg) static int stm32f1_init(struct device *arg)
{ {
uint32_t key; u32_t key;
ARG_UNUSED(arg); ARG_UNUSED(arg);

View file

@ -26,7 +26,7 @@
/** /**
* @brief map pin function to MODE register value * @brief map pin function to MODE register value
*/ */
static uint32_t __func_to_mode(int func) static u32_t __func_to_mode(int func)
{ {
switch (func) { switch (func) {
case STM32F10X_PIN_CONFIG_ANALOG: case STM32F10X_PIN_CONFIG_ANALOG:
@ -46,7 +46,7 @@ static uint32_t __func_to_mode(int func)
/** /**
* @brief map pin function to CNF register value * @brief map pin function to CNF register value
*/ */
static uint32_t __func_to_cnf(int func) static u32_t __func_to_cnf(int func)
{ {
switch (func) { switch (func) {
case STM32F10X_PIN_CONFIG_ANALOG: case STM32F10X_PIN_CONFIG_ANALOG:
@ -97,7 +97,7 @@ int stm32_gpio_flags_to_conf(int flags, int *pincfg)
return 0; return 0;
} }
int stm32_gpio_configure(uint32_t *base_addr, int pin, int conf, int altf) int stm32_gpio_configure(u32_t *base_addr, int pin, int conf, int altf)
{ {
volatile struct stm32f10x_gpio *gpio = volatile struct stm32f10x_gpio *gpio =
(struct stm32f10x_gpio *)(base_addr); (struct stm32f10x_gpio *)(base_addr);
@ -107,7 +107,7 @@ int stm32_gpio_configure(uint32_t *base_addr, int pin, int conf, int altf)
/* pins are configured in CRL (0-7) and CRH (8-15) /* pins are configured in CRL (0-7) and CRH (8-15)
* registers * registers
*/ */
volatile uint32_t *reg = &gpio->crl; volatile u32_t *reg = &gpio->crl;
ARG_UNUSED(altf); ARG_UNUSED(altf);
@ -144,7 +144,7 @@ int stm32_gpio_configure(uint32_t *base_addr, int pin, int conf, int altf)
return 0; return 0;
} }
int stm32_gpio_set(uint32_t *base, int pin, int value) int stm32_gpio_set(u32_t *base, int pin, int value)
{ {
struct stm32f10x_gpio *gpio = (struct stm32f10x_gpio *)base; struct stm32f10x_gpio *gpio = (struct stm32f10x_gpio *)base;
@ -159,7 +159,7 @@ int stm32_gpio_set(uint32_t *base, int pin, int value)
return 0; return 0;
} }
int stm32_gpio_get(uint32_t *base, int pin) int stm32_gpio_get(u32_t *base, int pin)
{ {
struct stm32f10x_gpio *gpio = (struct stm32f10x_gpio *)base; struct stm32f10x_gpio *gpio = (struct stm32f10x_gpio *)base;

View file

@ -29,27 +29,27 @@ enum {
/* 3.3.3 FLASH_ACR */ /* 3.3.3 FLASH_ACR */
union ef_acr { union ef_acr {
uint32_t val; u32_t val;
struct { struct {
uint32_t latency :3 __packed; u32_t latency :3 __packed;
uint32_t hlfcya :1 __packed; u32_t hlfcya :1 __packed;
uint32_t prftbe :1 __packed; u32_t prftbe :1 __packed;
uint32_t prftbs :1 __packed; u32_t prftbs :1 __packed;
uint32_t rsvd__6_31 :26 __packed; u32_t rsvd__6_31 :26 __packed;
} bit; } bit;
}; };
/* 3.3.3 Embedded flash registers */ /* 3.3.3 Embedded flash registers */
struct stm32_flash { struct stm32_flash {
union ef_acr acr; union ef_acr acr;
uint32_t keyr; u32_t keyr;
uint32_t optkeyr; u32_t optkeyr;
uint32_t sr; u32_t sr;
uint32_t cr; u32_t cr;
uint32_t ar; u32_t ar;
uint32_t rsvd; u32_t rsvd;
uint32_t obr; u32_t obr;
uint32_t wrpr; u32_t wrpr;
}; };
/* list of device commands */ /* list of device commands */

View file

@ -18,60 +18,60 @@
*/ */
struct stm32f3x_gpio { struct stm32f3x_gpio {
uint32_t moder; u32_t moder;
uint32_t otyper; u32_t otyper;
uint32_t ospeedr; u32_t ospeedr;
uint32_t pupdr; u32_t pupdr;
uint32_t idr; u32_t idr;
uint32_t odr; u32_t odr;
uint32_t bsrr; u32_t bsrr;
uint32_t lckr; u32_t lckr;
uint32_t afrl; u32_t afrl;
uint32_t afrh; u32_t afrh;
uint32_t brr; u32_t brr;
}; };
union syscfg_cfgr1 { union syscfg_cfgr1 {
uint32_t val; u32_t val;
struct { struct {
uint32_t mem_mode :2 __packed; u32_t mem_mode :2 __packed;
uint32_t rsvd__2_5 :4 __packed; u32_t rsvd__2_5 :4 __packed;
uint32_t tim1_itr3_rmo :1 __packed; u32_t tim1_itr3_rmo :1 __packed;
uint32_t dac_trig_rmp :1 __packed; u32_t dac_trig_rmp :1 __packed;
uint32_t rsvd__8_10 :3 __packed; u32_t rsvd__8_10 :3 __packed;
uint32_t tim16_dma_rmp :1 __packed; u32_t tim16_dma_rmp :1 __packed;
uint32_t tim17_dma_rmp :1 __packed; u32_t tim17_dma_rmp :1 __packed;
uint32_t tim16_dac1_dma_rmp :1 __packed; u32_t tim16_dac1_dma_rmp :1 __packed;
uint32_t tim17_dac2_dma_rmp :1 __packed; u32_t tim17_dac2_dma_rmp :1 __packed;
uint32_t dac2_ch1_dma_rmp :1 __packed; u32_t dac2_ch1_dma_rmp :1 __packed;
uint32_t i2c_pb6_fmp :1 __packed; u32_t i2c_pb6_fmp :1 __packed;
uint32_t i2c_pb7_fmp :1 __packed; u32_t i2c_pb7_fmp :1 __packed;
uint32_t i2c_pb8_fmp :1 __packed; u32_t i2c_pb8_fmp :1 __packed;
uint32_t i2c_pb9_fmp :1 __packed; u32_t i2c_pb9_fmp :1 __packed;
uint32_t i2c1_fmp :1 __packed; u32_t i2c1_fmp :1 __packed;
uint32_t rsvd__21 :1 __packed; u32_t rsvd__21 :1 __packed;
uint32_t encoder_mode :2 __packed; u32_t encoder_mode :2 __packed;
uint32_t rsvd__24_25 :2 __packed; u32_t rsvd__24_25 :2 __packed;
uint32_t fpu_ie :6 __packed; u32_t fpu_ie :6 __packed;
} bit; } bit;
}; };
union syscfg_rcr { union syscfg_rcr {
uint32_t val; u32_t val;
struct { struct {
uint32_t page0_wp :1 __packed; u32_t page0_wp :1 __packed;
uint32_t page1_wp :1 __packed; u32_t page1_wp :1 __packed;
uint32_t page2_wp :1 __packed; u32_t page2_wp :1 __packed;
uint32_t page3_wp :1 __packed; u32_t page3_wp :1 __packed;
uint32_t rsvd__4_31 :28 __packed; u32_t rsvd__4_31 :28 __packed;
} bit; } bit;
}; };
union syscfg__exticr { union syscfg__exticr {
uint32_t val; u32_t val;
struct { struct {
uint16_t exti; u16_t exti;
uint16_t rsvd__16_31; u16_t rsvd__16_31;
} bit; } bit;
}; };
@ -82,21 +82,21 @@ struct stm32f3x_syscfg {
union syscfg__exticr exticr2; union syscfg__exticr exticr2;
union syscfg__exticr exticr3; union syscfg__exticr exticr3;
union syscfg__exticr exticr4; union syscfg__exticr exticr4;
uint32_t cfgr2; u32_t cfgr2;
uint32_t rsvd_0x1C; u32_t rsvd_0x1C;
uint32_t rsvd_0x20; u32_t rsvd_0x20;
uint32_t rsvd_0x24; u32_t rsvd_0x24;
uint32_t rsvd_0x28; u32_t rsvd_0x28;
uint32_t rsvd_0x2C; u32_t rsvd_0x2C;
uint32_t rsvd_0x30; u32_t rsvd_0x30;
uint32_t rsvd_0x34; u32_t rsvd_0x34;
uint32_t rsvd_0x38; u32_t rsvd_0x38;
uint32_t rsvd_0x3C; u32_t rsvd_0x3C;
uint32_t rsvd_0x40; u32_t rsvd_0x40;
uint32_t rsvd_0x44; u32_t rsvd_0x44;
uint32_t rsvd_0x48; u32_t rsvd_0x48;
uint32_t rsvd_0x4C; u32_t rsvd_0x4C;
uint32_t cfgr3; u32_t cfgr3;
}; };
#endif /* _STM32F3X_GPIO_REGISTERS_H_ */ #endif /* _STM32F3X_GPIO_REGISTERS_H_ */

View file

@ -37,7 +37,7 @@ uint32_t HAL_GetTick(void)
*/ */
static int stm32f3_init(struct device *arg) static int stm32f3_init(struct device *arg)
{ {
uint32_t key; u32_t key;
ARG_UNUSED(arg); ARG_UNUSED(arg);

View file

@ -25,7 +25,7 @@
/** /**
* @brief map pin function to MODE register value * @brief map pin function to MODE register value
*/ */
static uint32_t func_to_mode(int func) static u32_t func_to_mode(int func)
{ {
switch (func) { switch (func) {
case STM32F3X_PIN_CONFIG_ANALOG: case STM32F3X_PIN_CONFIG_ANALOG:
@ -95,7 +95,7 @@ int stm32_gpio_flags_to_conf(int flags, int *pincfg)
return 0; return 0;
} }
int stm32_gpio_configure(uint32_t *base_addr, int pin, int conf, int altf) int stm32_gpio_configure(u32_t *base_addr, int pin, int conf, int altf)
{ {
volatile struct stm32f3x_gpio *gpio = volatile struct stm32f3x_gpio *gpio =
(struct stm32f3x_gpio *)(base_addr); (struct stm32f3x_gpio *)(base_addr);
@ -112,7 +112,7 @@ int stm32_gpio_configure(uint32_t *base_addr, int pin, int conf, int altf)
if (cmode == STM32F3X_PIN_CONFIG_AF) { if (cmode == STM32F3X_PIN_CONFIG_AF) {
/* alternate function setup */ /* alternate function setup */
int af = STM32_AF(conf); int af = STM32_AF(conf);
volatile uint32_t *afr = &gpio->afrl; volatile u32_t *afr = &gpio->afrl;
int crpin = pin; int crpin = pin;
if (crpin > 7) { if (crpin > 7) {
@ -156,7 +156,7 @@ int stm32_gpio_configure(uint32_t *base_addr, int pin, int conf, int altf)
return 0; return 0;
} }
int stm32_gpio_set(uint32_t *base, int pin, int value) int stm32_gpio_set(u32_t *base, int pin, int value)
{ {
struct stm32f3x_gpio *gpio = (struct stm32f3x_gpio *)base; struct stm32f3x_gpio *gpio = (struct stm32f3x_gpio *)base;
@ -171,7 +171,7 @@ int stm32_gpio_set(uint32_t *base, int pin, int value)
return 0; return 0;
} }
int stm32_gpio_get(uint32_t *base, int pin) int stm32_gpio_get(u32_t *base, int pin)
{ {
struct stm32f3x_gpio *gpio = (struct stm32f3x_gpio *)base; struct stm32f3x_gpio *gpio = (struct stm32f3x_gpio *)base;

View file

@ -34,8 +34,8 @@ struct stm32f4x_flash_sector stm32f4xx_sectors[] = {
#endif #endif
}; };
#define STM32F4X_FLASH_TIMEOUT ((uint32_t) 0x000B0000) #define STM32F4X_FLASH_TIMEOUT ((u32_t) 0x000B0000)
#define STM32F4X_SECTOR_MASK ((uint32_t) 0xFFFFFF07) #define STM32F4X_SECTOR_MASK ((u32_t) 0xFFFFFF07)
#define STM32F4X_SECTORS ARRAY_SIZE(stm32f4xx_sectors) #define STM32F4X_SECTORS ARRAY_SIZE(stm32f4xx_sectors)
#define STM32F4X_FLASH_END \ #define STM32F4X_FLASH_END \

View file

@ -25,27 +25,27 @@ enum {
}; };
union __flash_acr { union __flash_acr {
uint32_t val; u32_t val;
struct { struct {
uint32_t latency :4 __packed; u32_t latency :4 __packed;
uint32_t rsvd__4_7 :4 __packed; u32_t rsvd__4_7 :4 __packed;
uint32_t prften :1 __packed; u32_t prften :1 __packed;
uint32_t icen :1 __packed; u32_t icen :1 __packed;
uint32_t dcen :1 __packed; u32_t dcen :1 __packed;
uint32_t icrst :1 __packed; u32_t icrst :1 __packed;
uint32_t dcrst :1 __packed; u32_t dcrst :1 __packed;
uint32_t rsvd__13_31 :19 __packed; u32_t rsvd__13_31 :19 __packed;
} bit; } bit;
}; };
/* 3.8.7 Embedded flash registers */ /* 3.8.7 Embedded flash registers */
struct stm32f4x_flash { struct stm32f4x_flash {
volatile union __flash_acr acr; volatile union __flash_acr acr;
volatile uint32_t key; volatile u32_t key;
volatile uint32_t optkey; volatile u32_t optkey;
volatile uint32_t status; volatile u32_t status;
volatile uint32_t ctrl; volatile u32_t ctrl;
volatile uint32_t optctrl; volatile u32_t optctrl;
}; };
/** /**
@ -56,7 +56,7 @@ struct stm32f4x_flash {
static inline void __setup_flash(void) static inline void __setup_flash(void)
{ {
volatile struct stm32f4x_flash *regs; volatile struct stm32f4x_flash *regs;
uint32_t tmpreg = 0; u32_t tmpreg = 0;
regs = (struct stm32f4x_flash *) FLASH_R_BASE; regs = (struct stm32f4x_flash *) FLASH_R_BASE;

View file

@ -19,34 +19,34 @@
/* 8.4 GPIO registers - each GPIO port controls 16 pins */ /* 8.4 GPIO registers - each GPIO port controls 16 pins */
struct stm32f4x_gpio { struct stm32f4x_gpio {
uint32_t mode; u32_t mode;
uint32_t otype; u32_t otype;
uint32_t ospeed; u32_t ospeed;
uint32_t pupdr; u32_t pupdr;
uint32_t idr; u32_t idr;
uint32_t odr; u32_t odr;
uint32_t bsr; u32_t bsr;
uint32_t lck; u32_t lck;
uint32_t afr[2]; u32_t afr[2];
}; };
union syscfg_exticr { union syscfg_exticr {
uint32_t val; u32_t val;
struct { struct {
uint16_t rsvd__16_31; u16_t rsvd__16_31;
uint16_t exti; u16_t exti;
} bit; } bit;
}; };
/* 7.2 SYSCFG registers */ /* 7.2 SYSCFG registers */
struct stm32f4x_syscfg { struct stm32f4x_syscfg {
uint32_t memrmp; u32_t memrmp;
uint32_t pmc; u32_t pmc;
union syscfg_exticr exticr1; union syscfg_exticr exticr1;
union syscfg_exticr exticr2; union syscfg_exticr exticr2;
union syscfg_exticr exticr3; union syscfg_exticr exticr3;
union syscfg_exticr exticr4; union syscfg_exticr exticr4;
uint32_t cmpcr; u32_t cmpcr;
}; };
#endif /* _STM32F4X_GPIO_REGISTERS_H_ */ #endif /* _STM32F4X_GPIO_REGISTERS_H_ */

View file

@ -66,58 +66,58 @@ enum {
}; };
union __rcc_cr { union __rcc_cr {
uint32_t val; u32_t val;
struct { struct {
uint32_t hsion :1 __packed; u32_t hsion :1 __packed;
uint32_t hsirdy :1 __packed; u32_t hsirdy :1 __packed;
uint32_t rsvd__2 :1 __packed; u32_t rsvd__2 :1 __packed;
uint32_t hsitrim :5 __packed; u32_t hsitrim :5 __packed;
uint32_t hsical :8 __packed; u32_t hsical :8 __packed;
uint32_t hseon :1 __packed; u32_t hseon :1 __packed;
uint32_t hserdy :1 __packed; u32_t hserdy :1 __packed;
uint32_t hsebyp :1 __packed; u32_t hsebyp :1 __packed;
uint32_t csson :1 __packed; u32_t csson :1 __packed;
uint32_t rsvd__20_23 :4 __packed; u32_t rsvd__20_23 :4 __packed;
uint32_t pllon :1 __packed; u32_t pllon :1 __packed;
uint32_t pllrdy :1 __packed; u32_t pllrdy :1 __packed;
uint32_t plli2son :1 __packed; u32_t plli2son :1 __packed;
uint32_t plli2srdy :1 __packed; u32_t plli2srdy :1 __packed;
uint32_t pllsaion :1 __packed; u32_t pllsaion :1 __packed;
uint32_t pllsairdy :1 __packed; u32_t pllsairdy :1 __packed;
uint32_t rsvd__30_31 :2 __packed; u32_t rsvd__30_31 :2 __packed;
} bit; } bit;
}; };
union __rcc_pllcfgr { union __rcc_pllcfgr {
uint32_t val; u32_t val;
struct { struct {
uint32_t pllm :6 __packed; u32_t pllm :6 __packed;
uint32_t plln :9 __packed; u32_t plln :9 __packed;
uint32_t rsvd__15 :1 __packed; u32_t rsvd__15 :1 __packed;
uint32_t pllp :2 __packed; u32_t pllp :2 __packed;
uint32_t rsvd__18_21 :4 __packed; u32_t rsvd__18_21 :4 __packed;
uint32_t pllsrc :1 __packed; u32_t pllsrc :1 __packed;
uint32_t rsvd__23 :1 __packed; u32_t rsvd__23 :1 __packed;
uint32_t pllq :4 __packed; u32_t pllq :4 __packed;
uint32_t rsvd__28_31 :4 __packed; u32_t rsvd__28_31 :4 __packed;
} bit; } bit;
}; };
union __rcc_cfgr { union __rcc_cfgr {
uint32_t val; u32_t val;
struct { struct {
uint32_t sw :2 __packed; u32_t sw :2 __packed;
uint32_t sws :2 __packed; u32_t sws :2 __packed;
uint32_t hpre :4 __packed; u32_t hpre :4 __packed;
uint32_t rsvd__8_9 :2 __packed; u32_t rsvd__8_9 :2 __packed;
uint32_t ppre1 :3 __packed; u32_t ppre1 :3 __packed;
uint32_t ppre2 :3 __packed; u32_t ppre2 :3 __packed;
uint32_t rtcpre :5 __packed; u32_t rtcpre :5 __packed;
uint32_t mco1 :2 __packed; u32_t mco1 :2 __packed;
uint32_t i2sscr :1 __packed; u32_t i2sscr :1 __packed;
uint32_t mco1pre :3 __packed; u32_t mco1pre :3 __packed;
uint32_t mco2pre :3 __packed; u32_t mco2pre :3 __packed;
uint32_t mco2 :2 __packed; u32_t mco2 :2 __packed;
} bit; } bit;
}; };
@ -125,35 +125,35 @@ struct stm32f4x_rcc {
union __rcc_cr cr; union __rcc_cr cr;
union __rcc_pllcfgr pllcfgr; union __rcc_pllcfgr pllcfgr;
union __rcc_cfgr cfgr; union __rcc_cfgr cfgr;
uint32_t cir; u32_t cir;
uint32_t ahb1rstr; u32_t ahb1rstr;
uint32_t ahb2rstr; u32_t ahb2rstr;
uint32_t ahb3rstr; u32_t ahb3rstr;
uint32_t rsvd0; u32_t rsvd0;
uint32_t apb1rstr; u32_t apb1rstr;
uint32_t apb2rstr; u32_t apb2rstr;
uint32_t rsvd1[2]; u32_t rsvd1[2];
uint32_t ahb1enr; u32_t ahb1enr;
uint32_t ahb2enr; u32_t ahb2enr;
uint32_t ahb3enr; u32_t ahb3enr;
uint32_t rsvd2; u32_t rsvd2;
uint32_t apb1enr; u32_t apb1enr;
uint32_t apb2enr; u32_t apb2enr;
uint32_t rsvd3[2]; u32_t rsvd3[2];
uint32_t ahb1lpenr; u32_t ahb1lpenr;
uint32_t ahb2lpenr; u32_t ahb2lpenr;
uint32_t ahb3lpenr; u32_t ahb3lpenr;
uint32_t rsvd4; u32_t rsvd4;
uint32_t apb1lpenr; u32_t apb1lpenr;
uint32_t apb2lpenr; u32_t apb2lpenr;
uint32_t rsvd5[2]; u32_t rsvd5[2];
uint32_t bdcr; u32_t bdcr;
uint32_t csr; u32_t csr;
uint32_t rsvd6[2]; u32_t rsvd6[2];
uint32_t sscgr; u32_t sscgr;
uint32_t plli2scfgr; u32_t plli2scfgr;
uint32_t rsvd7; u32_t rsvd7;
uint32_t dckcfgr; u32_t dckcfgr;
}; };
#endif /* _STM32F4X_CLOCK_H_ */ #endif /* _STM32F4X_CLOCK_H_ */

View file

@ -38,7 +38,7 @@ uint32_t HAL_GetTick(void)
*/ */
static int st_stm32f4_init(struct device *arg) static int st_stm32f4_init(struct device *arg)
{ {
uint32_t key; u32_t key;
ARG_UNUSED(arg); ARG_UNUSED(arg);

View file

@ -25,7 +25,7 @@
/** /**
* @brief map pin function to MODE register value * @brief map pin function to MODE register value
*/ */
static uint32_t __func_to_mode(int func) static u32_t __func_to_mode(int func)
{ {
switch (func) { switch (func) {
case STM32F4X_PIN_CONFIG_BIAS_HIGH_IMPEDANCE: case STM32F4X_PIN_CONFIG_BIAS_HIGH_IMPEDANCE:
@ -56,7 +56,7 @@ static uint32_t __func_to_mode(int func)
/** /**
* @brief map pin function to OTYPE register value * @brief map pin function to OTYPE register value
*/ */
static uint32_t __func_to_otype(int func) static u32_t __func_to_otype(int func)
{ {
switch (func) { switch (func) {
case STM32F4X_PIN_CONFIG_DRIVE_OPEN_DRAIN: case STM32F4X_PIN_CONFIG_DRIVE_OPEN_DRAIN:
@ -74,7 +74,7 @@ static uint32_t __func_to_otype(int func)
/** /**
* @brief map pin function to OSPEED register value * @brief map pin function to OSPEED register value
*/ */
static uint32_t __func_to_ospeed(int func) static u32_t __func_to_ospeed(int func)
{ {
switch (func) { switch (func) {
case STM32F4X_PIN_CONFIG_DRIVE_PUSH_PULL: case STM32F4X_PIN_CONFIG_DRIVE_PUSH_PULL:
@ -99,7 +99,7 @@ static uint32_t __func_to_ospeed(int func)
/** /**
* @brief map pin function to PUPD register value * @brief map pin function to PUPD register value
*/ */
static uint32_t __func_to_pupd(int func) static u32_t __func_to_pupd(int func)
{ {
switch (func) { switch (func) {
case STM32F4X_PIN_CONFIG_DRIVE_PUSH_PULL: case STM32F4X_PIN_CONFIG_DRIVE_PUSH_PULL:
@ -159,15 +159,15 @@ int stm32_gpio_flags_to_conf(int flags, int *pincfg)
return 0; return 0;
} }
int stm32_gpio_configure(uint32_t *base_addr, int pin, int conf, int altf) int stm32_gpio_configure(u32_t *base_addr, int pin, int conf, int altf)
{ {
volatile struct stm32f4x_gpio *gpio = volatile struct stm32f4x_gpio *gpio =
(struct stm32f4x_gpio *)(base_addr); (struct stm32f4x_gpio *)(base_addr);
uint32_t mode = __func_to_mode(conf); u32_t mode = __func_to_mode(conf);
uint32_t otype = __func_to_otype(conf); u32_t otype = __func_to_otype(conf);
uint32_t ospeed = __func_to_ospeed(conf); u32_t ospeed = __func_to_ospeed(conf);
uint32_t pupd = __func_to_pupd(conf); u32_t pupd = __func_to_pupd(conf);
uint32_t tmpreg = 0; u32_t tmpreg = 0;
/* TODO: validate if indeed alternate */ /* TODO: validate if indeed alternate */
if (altf) { if (altf) {
@ -206,7 +206,7 @@ int stm32_gpio_configure(uint32_t *base_addr, int pin, int conf, int altf)
return 0; return 0;
} }
int stm32_gpio_set(uint32_t *base, int pin, int value) int stm32_gpio_set(u32_t *base, int pin, int value)
{ {
struct stm32f4x_gpio *gpio = (struct stm32f4x_gpio *)base; struct stm32f4x_gpio *gpio = (struct stm32f4x_gpio *)base;
@ -221,7 +221,7 @@ int stm32_gpio_set(uint32_t *base, int pin, int value)
return 0; return 0;
} }
int stm32_gpio_get(uint32_t *base, int pin) int stm32_gpio_get(u32_t *base, int pin)
{ {
struct stm32f4x_gpio *gpio = (struct stm32f4x_gpio *)base; struct stm32f4x_gpio *gpio = (struct stm32f4x_gpio *)base;

View file

@ -18,46 +18,46 @@ enum {
/* 3.7.1 FLASH_ACR */ /* 3.7.1 FLASH_ACR */
union __ef_acr { union __ef_acr {
uint32_t val; u32_t val;
struct { struct {
uint32_t latency :3 __packed; u32_t latency :3 __packed;
uint32_t rsvd__3_7 :5 __packed; u32_t rsvd__3_7 :5 __packed;
uint32_t prften :1 __packed; u32_t prften :1 __packed;
uint32_t icen :1 __packed; u32_t icen :1 __packed;
uint32_t dcen :1 __packed; u32_t dcen :1 __packed;
uint32_t icrst :1 __packed; u32_t icrst :1 __packed;
uint32_t dcrst :1 __packed; u32_t dcrst :1 __packed;
uint32_t run_pd :1 __packed; u32_t run_pd :1 __packed;
uint32_t sleep_pd :1 __packed; u32_t sleep_pd :1 __packed;
uint32_t rsvd__16_31 :17 __packed; u32_t rsvd__16_31 :17 __packed;
} bit; } bit;
}; };
/* FLASH register map */ /* FLASH register map */
struct stm32l4x_flash { struct stm32l4x_flash {
union __ef_acr acr; union __ef_acr acr;
uint32_t pdkeyr; u32_t pdkeyr;
uint32_t keyr; u32_t keyr;
uint32_t optkeyr; u32_t optkeyr;
uint32_t sr; u32_t sr;
uint32_t cr; u32_t cr;
uint32_t eccr; u32_t eccr;
uint32_t rsvd_0; u32_t rsvd_0;
uint32_t optr; u32_t optr;
uint32_t pcrop1sr; u32_t pcrop1sr;
uint32_t pcrop1er; u32_t pcrop1er;
uint32_t wrp1ar; u32_t wrp1ar;
uint32_t wrp1br; u32_t wrp1br;
uint32_t rsvd_2[4]; u32_t rsvd_2[4];
/* /*
* The registers below are only present on STM32L4x2, STM32L4x5, * The registers below are only present on STM32L4x2, STM32L4x5,
* STM32L4x6. * STM32L4x6.
*/ */
uint32_t pcrop2sr; u32_t pcrop2sr;
uint32_t pcrop2er; u32_t pcrop2er;
uint32_t wrp2ar; u32_t wrp2ar;
uint32_t wrp2br; u32_t wrp2br;
}; };
#endif /* _STM32L4X_FLASH_REGISTERS_H_ */ #endif /* _STM32L4X_FLASH_REGISTERS_H_ */

View file

@ -38,7 +38,7 @@ uint32_t HAL_GetTick(void)
*/ */
static int stm32l4_init(struct device *arg) static int stm32l4_init(struct device *arg)
{ {
uint32_t key; u32_t key;
ARG_UNUSED(arg); ARG_UNUSED(arg);

View file

@ -57,23 +57,23 @@ enum {
/* GPIO registers - each GPIO port controls 16 pins */ /* GPIO registers - each GPIO port controls 16 pins */
struct stm32l4x_gpio { struct stm32l4x_gpio {
uint32_t moder; u32_t moder;
uint32_t otyper; u32_t otyper;
uint32_t ospeedr; u32_t ospeedr;
uint32_t pupdr; u32_t pupdr;
uint32_t idr; u32_t idr;
uint32_t odr; u32_t odr;
uint32_t bsrr; u32_t bsrr;
uint32_t lckr; u32_t lckr;
uint32_t afr[2]; u32_t afr[2];
uint32_t brr; u32_t brr;
uint32_t ascr; /* Only present on STM32L4x1, STM32L4x5, STM32L4x6 */ u32_t ascr; /* Only present on STM32L4x1, STM32L4x5, STM32L4x6 */
}; };
/** /**
* @brief map pin function to MODE register value * @brief map pin function to MODE register value
*/ */
static uint32_t func_to_mode(int conf, unsigned int afnum) static u32_t func_to_mode(int conf, unsigned int afnum)
{ {
/* If an alternate function is specified */ /* If an alternate function is specified */
if (afnum) { if (afnum) {
@ -94,7 +94,7 @@ static uint32_t func_to_mode(int conf, unsigned int afnum)
return STM32L4X_MODER_INPUT_MODE; return STM32L4X_MODER_INPUT_MODE;
} }
static uint32_t func_to_otype(int conf) static u32_t func_to_otype(int conf)
{ {
switch (conf) { switch (conf) {
case STM32L4X_PIN_CONFIG_OPEN_DRAIN: case STM32L4X_PIN_CONFIG_OPEN_DRAIN:
@ -108,7 +108,7 @@ static uint32_t func_to_otype(int conf)
return STM32L4X_OTYPER_PUSH_PULL; return STM32L4X_OTYPER_PUSH_PULL;
} }
static uint32_t func_to_pupd(int conf) static u32_t func_to_pupd(int conf)
{ {
switch (conf) { switch (conf) {
case STM32L4X_PIN_CONFIG_ANALOG: case STM32L4X_PIN_CONFIG_ANALOG:
@ -158,7 +158,7 @@ int stm32_gpio_flags_to_conf(int flags, int *pincfg)
return 0; return 0;
} }
int stm32_gpio_configure(uint32_t *base_addr, int pin, int pinconf, int afnum) int stm32_gpio_configure(u32_t *base_addr, int pin, int pinconf, int afnum)
{ {
volatile struct stm32l4x_gpio *gpio = volatile struct stm32l4x_gpio *gpio =
(struct stm32l4x_gpio *)(base_addr); (struct stm32l4x_gpio *)(base_addr);
@ -166,7 +166,7 @@ int stm32_gpio_configure(uint32_t *base_addr, int pin, int pinconf, int afnum)
unsigned int pin_shift = pin << 1; unsigned int pin_shift = pin << 1;
unsigned int afr_bank = pin / 8; unsigned int afr_bank = pin / 8;
unsigned int afr_shift = (pin % 8) << 2; unsigned int afr_shift = (pin % 8) << 2;
uint32_t scratch; u32_t scratch;
mode = func_to_mode(pinconf, afnum); mode = func_to_mode(pinconf, afnum);
otype = func_to_otype(pinconf); otype = func_to_otype(pinconf);
@ -187,7 +187,7 @@ int stm32_gpio_configure(uint32_t *base_addr, int pin, int pinconf, int afnum)
return 0; return 0;
} }
int stm32_gpio_set(uint32_t *base, int pin, int value) int stm32_gpio_set(u32_t *base, int pin, int value)
{ {
struct stm32l4x_gpio *gpio = (struct stm32l4x_gpio *)base; struct stm32l4x_gpio *gpio = (struct stm32l4x_gpio *)base;
int pval = 1 << (pin & 0xf); int pval = 1 << (pin & 0xf);
@ -201,7 +201,7 @@ int stm32_gpio_set(uint32_t *base, int pin, int value)
return 0; return 0;
} }
int stm32_gpio_get(uint32_t *base, int pin) int stm32_gpio_get(u32_t *base, int pin)
{ {
struct stm32l4x_gpio *gpio = (struct stm32l4x_gpio *)base; struct stm32l4x_gpio *gpio = (struct stm32l4x_gpio *)base;
@ -212,7 +212,7 @@ int stm32_gpio_enable_int(int port, int pin)
{ {
struct stm32l4x_syscfg *syscfg = (struct stm32l4x_syscfg *)SYSCFG_BASE; struct stm32l4x_syscfg *syscfg = (struct stm32l4x_syscfg *)SYSCFG_BASE;
struct device *clk = device_get_binding(STM32_CLOCK_CONTROL_NAME); struct device *clk = device_get_binding(STM32_CLOCK_CONTROL_NAME);
uint32_t *reg; u32_t *reg;
/* Enable SYSCFG clock */ /* Enable SYSCFG clock */
struct stm32_pclken pclken = { struct stm32_pclken pclken = {

View file

@ -11,16 +11,16 @@
/* SYSCFG registers */ /* SYSCFG registers */
struct stm32l4x_syscfg { struct stm32l4x_syscfg {
uint32_t memrmp; u32_t memrmp;
uint32_t cfgr1; u32_t cfgr1;
uint32_t exticr1; u32_t exticr1;
uint32_t exticr2; u32_t exticr2;
uint32_t exticr3; u32_t exticr3;
uint32_t exticr4; u32_t exticr4;
uint32_t scsr; u32_t scsr;
uint32_t cfgr2; u32_t cfgr2;
uint32_t swpr; u32_t swpr;
uint32_t skr; u32_t skr;
}; };
#endif /* _STM32L4X_SYSCFG_REGISTERS_H_ */ #endif /* _STM32L4X_SYSCFG_REGISTERS_H_ */

View file

@ -57,99 +57,99 @@ extern "C" {
#define _SCP_CRYSTAL_8_192MHZ 15 #define _SCP_CRYSTAL_8_192MHZ 15
union __rcc { union __rcc {
uint32_t value; u32_t value;
struct { struct {
uint32_t moscdis : 1 __packed; u32_t moscdis : 1 __packed;
uint32_t ioscdis : 1 __packed; u32_t ioscdis : 1 __packed;
uint32_t rsvd__2_3 : 2 __packed; u32_t rsvd__2_3 : 2 __packed;
uint32_t oscsrc : 2 __packed; u32_t oscsrc : 2 __packed;
uint32_t xtal : 4 __packed; u32_t xtal : 4 __packed;
uint32_t rsvd__10 : 1 __packed; u32_t rsvd__10 : 1 __packed;
uint32_t bypass : 1 __packed; u32_t bypass : 1 __packed;
uint32_t rsvd__12 : 1 __packed; u32_t rsvd__12 : 1 __packed;
uint32_t pwrdn : 1 __packed; u32_t pwrdn : 1 __packed;
uint32_t rsvd__14_16 : 3 __packed; u32_t rsvd__14_16 : 3 __packed;
uint32_t pwmdiv : 3 __packed; /* 2**(n+1) */ u32_t pwmdiv : 3 __packed; /* 2**(n+1) */
uint32_t usepwmdiv : 1 __packed; u32_t usepwmdiv : 1 __packed;
uint32_t rsvd__21 : 1 __packed; u32_t rsvd__21 : 1 __packed;
uint32_t usesysdiv : 1 __packed; u32_t usesysdiv : 1 __packed;
uint32_t sysdiv : 4 __packed; u32_t sysdiv : 4 __packed;
uint32_t acg : 1 __packed; u32_t acg : 1 __packed;
uint32_t rsvd__28_31 : 4 __packed; u32_t rsvd__28_31 : 4 __packed;
} bit; } bit;
}; };
union __rcc2 { union __rcc2 {
uint32_t value; u32_t value;
struct { struct {
uint8_t rsvd__0_3 : 4 __packed; u8_t rsvd__0_3 : 4 __packed;
uint8_t oscsrc2 : 3 __packed; u8_t oscsrc2 : 3 __packed;
uint16_t rsvd__7_10 : 4 __packed; u16_t rsvd__7_10 : 4 __packed;
uint8_t bypass2 : 1 __packed; u8_t bypass2 : 1 __packed;
uint8_t rsvd__12 : 1 __packed; u8_t rsvd__12 : 1 __packed;
uint8_t pwrdn2 : 1 __packed; u8_t pwrdn2 : 1 __packed;
uint16_t rsvd__14_22 : 9 __packed; u16_t rsvd__14_22 : 9 __packed;
uint16_t sysdiv2 : 6 __packed; u16_t sysdiv2 : 6 __packed;
uint8_t rsvd__29_30 : 2 __packed; u8_t rsvd__29_30 : 2 __packed;
uint8_t usercc2 : 1 __packed; u8_t usercc2 : 1 __packed;
} bit; } bit;
}; };
struct __scp { struct __scp {
uint32_t did0; /* 0x000 RO Device ID*/ u32_t did0; /* 0x000 RO Device ID*/
uint32_t did1; /* 0x004 RO Device ID*/ u32_t did1; /* 0x004 RO Device ID*/
uint32_t dc0; /* 0x008 RO Device Capabilities */ u32_t dc0; /* 0x008 RO Device Capabilities */
uint32_t dc1; /* 0x00c RO Device Capabilities */ u32_t dc1; /* 0x00c RO Device Capabilities */
uint32_t dc2; /* 0x010 RO Device Capabilities */ u32_t dc2; /* 0x010 RO Device Capabilities */
uint32_t dc3; /* 0x014 RO Device Capabilities */ u32_t dc3; /* 0x014 RO Device Capabilities */
uint32_t dc4; /* 0x018 RO Device capabilities */ u32_t dc4; /* 0x018 RO Device capabilities */
uint32_t rsvd__01c_02f[(0x30 - 0x1c) / 4]; u32_t rsvd__01c_02f[(0x30 - 0x1c) / 4];
uint32_t pborctl; /* 0x030 RW Brown-Out Reset ConTroL */ u32_t pborctl; /* 0x030 RW Brown-Out Reset ConTroL */
uint32_t ldopctl; /* 0x034 RW LDO Power ConTroL */ u32_t ldopctl; /* 0x034 RW LDO Power ConTroL */
uint32_t rsvd__038_03f[(0x40 - 0x38) / 4]; u32_t rsvd__038_03f[(0x40 - 0x38) / 4];
uint32_t srcr0; /* 0x040 RW Software Reset Control Register */ u32_t srcr0; /* 0x040 RW Software Reset Control Register */
uint32_t srcr1; /* 0x044 RW Software Reset Control Register */ u32_t srcr1; /* 0x044 RW Software Reset Control Register */
uint32_t srcr2; /* 0x048 RW Software Reset Control Register */ u32_t srcr2; /* 0x048 RW Software Reset Control Register */
uint32_t rsvd__04c_04f; u32_t rsvd__04c_04f;
uint32_t ris; /* 0x050 RO Raw Interrupt Status */ u32_t ris; /* 0x050 RO Raw Interrupt Status */
uint32_t imc; /* 0x054 RW Interrupt Mask Control */ u32_t imc; /* 0x054 RW Interrupt Mask Control */
uint32_t misc; /* 0x058 RW1C Masked Int. Status & Clear */ u32_t misc; /* 0x058 RW1C Masked Int. Status & Clear */
uint32_t resc; /* 0x05C RW RESet Cause */ u32_t resc; /* 0x05C RW RESet Cause */
struct { struct {
union __rcc rcc; /* 0x060 RW Run-mode Clock Configuration */ union __rcc rcc; /* 0x060 RW Run-mode Clock Configuration */
uint32_t pllcfg; /* 0x064 RW xtal-to-pll translation */ u32_t pllcfg; /* 0x064 RW xtal-to-pll translation */
uint32_t rsvd__068_06f[(0x70 - 0x068) / 4]; u32_t rsvd__068_06f[(0x70 - 0x068) / 4];
union __rcc2 rcc2; /* 0x070 RW Run-mode Clock Configuration */ union __rcc2 rcc2; /* 0x070 RW Run-mode Clock Configuration */
uint32_t rsvd__074_0ff[(0x100 - 0x074) / 4]; u32_t rsvd__074_0ff[(0x100 - 0x074) / 4];
uint32_t rcgc0; /* 0x100 RW Run-mode Clock Gating */ u32_t rcgc0; /* 0x100 RW Run-mode Clock Gating */
uint32_t rcgc1; /* 0x104 RW Run-mode Clock Gating */ u32_t rcgc1; /* 0x104 RW Run-mode Clock Gating */
uint32_t rcgc2; /* 0x108 RW Run-mode Clock Gating */ u32_t rcgc2; /* 0x108 RW Run-mode Clock Gating */
uint32_t rsvd__10c_10f; u32_t rsvd__10c_10f;
uint32_t scgc0; /* 0x110 RW Sleep-mode Clock Gating */ u32_t scgc0; /* 0x110 RW Sleep-mode Clock Gating */
uint32_t scgc1; /* 0x114 RW Sleep-mode Clock Gating */ u32_t scgc1; /* 0x114 RW Sleep-mode Clock Gating */
uint32_t scgc2; /* 0x118 RW Sleep-mode Clock Gating */ u32_t scgc2; /* 0x118 RW Sleep-mode Clock Gating */
uint32_t rsvd__11c_11f; u32_t rsvd__11c_11f;
uint32_t dcgc0; /* 0x120 RW Deep sleep mode Clock Gating */ u32_t dcgc0; /* 0x120 RW Deep sleep mode Clock Gating */
uint32_t dcgc1; /* 0x124 RW Deep sleep mode Clock Gating */ u32_t dcgc1; /* 0x124 RW Deep sleep mode Clock Gating */
uint32_t dcgc2; /* 0x128 RW Deep sleep mode Clock Gating */ u32_t dcgc2; /* 0x128 RW Deep sleep mode Clock Gating */
uint32_t rsvd__12c_143[(0x144 - 0x12c) / 4]; u32_t rsvd__12c_143[(0x144 - 0x12c) / 4];
uint32_t u32_t
dslpclkcfg; /* 0x144 RW Deep SLeeP CLocK ConFiGuration dslpclkcfg; /* 0x144 RW Deep SLeeP CLocK ConFiGuration
*/ */
} clock; } clock;

View file

@ -18,7 +18,7 @@
#ifdef CONFIG_UART_STELLARIS #ifdef CONFIG_UART_STELLARIS
#include <uart.h> #include <uart.h>
#define RCGC1 (*((volatile uint32_t *)0x400FE104)) #define RCGC1 (*((volatile u32_t *)0x400FE104))
#define RCGC1_UART0_EN 0x00000001 #define RCGC1_UART0_EN 0x00000001
#define RCGC1_UART1_EN 0x00000002 #define RCGC1_UART1_EN 0x00000002

View file

@ -34,8 +34,8 @@ def read_intlist(intlist_path):
struct { struct {
void * spurious_irq_handler; void * spurious_irq_handler;
void * sw_irq_handler; void * sw_irq_handler;
uint32_t num_isrs; u32_t num_isrs;
uint32_t num_vectors; <- typically CONFIG_NUM_IRQS u32_t num_vectors; <- typically CONFIG_NUM_IRQS
struct _isr_list isrs[]; <- of size num_isrs struct _isr_list isrs[]; <- of size num_isrs
} }
@ -44,9 +44,9 @@ def read_intlist(intlist_path):
struct _isr_list { struct _isr_list {
/** IRQ line number */ /** IRQ line number */
int32_t irq; s32_t irq;
/** Flags for this IRQ, see ISR_FLAG_* definitions */ /** Flags for this IRQ, see ISR_FLAG_* definitions */
int32_t flags; s32_t flags;
/** ISR to call */ /** ISR to call */
void *func; void *func;
/** Parameter for non-direct IRQs */ /** Parameter for non-direct IRQs */
@ -129,7 +129,7 @@ def write_source_file(fp, vt, swt, intlist):
nv = intlist["num_vectors"] nv = intlist["num_vectors"]
if vt: if vt:
fp.write("uint32_t __irq_vector_table _irq_vector_table[%d] = {\n" % nv) fp.write("u32_t __irq_vector_table _irq_vector_table[%d] = {\n" % nv)
for i in range(nv): for i in range(nv):
fp.write("\t0x%x,\n" % vt[i]) fp.write("\t0x%x,\n" % vt[i])
fp.write("};\n") fp.write("};\n")

View file

@ -21,8 +21,8 @@
struct int_list_header { struct int_list_header {
void *spurious_ptr; void *spurious_ptr;
void *handler_ptr; void *handler_ptr;
uint32_t table_size; u32_t table_size;
uint32_t offset; u32_t offset;
}; };
/* These values are not included in the resulting binary, but instead form the /* These values are not included in the resulting binary, but instead form the
@ -44,7 +44,7 @@ _GENERIC_SECTION(.irq_info) struct int_list_header _iheader = {
* point for all interrupts. Don't generate a table in this case. * point for all interrupts. Don't generate a table in this case.
*/ */
#ifdef CONFIG_GEN_IRQ_VECTOR_TABLE #ifdef CONFIG_GEN_IRQ_VECTOR_TABLE
uint32_t __irq_vector_table _irq_vector_table[IRQ_TABLE_SIZE] = { u32_t __irq_vector_table _irq_vector_table[IRQ_TABLE_SIZE] = {
[0 ...(IRQ_TABLE_SIZE - 1)] = 0xabababab, [0 ...(IRQ_TABLE_SIZE - 1)] = 0xabababab,
}; };
#endif #endif

View file

@ -24,7 +24,7 @@
#if ALT_CPU_ICACHE_SIZE > 0 #if ALT_CPU_ICACHE_SIZE > 0
void _nios2_icache_flush_all(void) void _nios2_icache_flush_all(void)
{ {
uint32_t i; u32_t i;
for (i = 0; i < ALT_CPU_ICACHE_SIZE; i += ALT_CPU_ICACHE_LINE_SIZE) { for (i = 0; i < ALT_CPU_ICACHE_SIZE; i += ALT_CPU_ICACHE_LINE_SIZE) {
_nios2_icache_flush(i); _nios2_icache_flush(i);
@ -53,7 +53,7 @@ void _nios2_icache_flush_all(void)
#if ALT_CPU_DCACHE_SIZE > 0 #if ALT_CPU_DCACHE_SIZE > 0
void _nios2_dcache_flush_all(void) void _nios2_dcache_flush_all(void)
{ {
uint32_t i; u32_t i;
for (i = 0; i < ALT_CPU_DCACHE_SIZE; i += ALT_CPU_DCACHE_LINE_SIZE) { for (i = 0; i < ALT_CPU_DCACHE_SIZE; i += ALT_CPU_DCACHE_LINE_SIZE) {
_nios2_dcache_flush(i); _nios2_dcache_flush(i);

View file

@ -112,7 +112,7 @@ SECTION_FUNC(TEXT, __start)
ori r3, r3, 0xaaaa ori r3, r3, 0xaaaa
1: 1:
/* Loop through the _interrupt_stack treating it as an array of /* Loop through the _interrupt_stack treating it as an array of
* uint32_t, setting each element to r3 */ * u32_t, setting each element to r3 */
stw r3, (r1) stw r3, (r1)
subi r2, r2, 4 subi r2, r2, 4
addi r1, r1, 4 addi r1, r1, 4

View file

@ -100,7 +100,7 @@ FUNC_NORETURN void _NanoFatalErrorHandler(unsigned int reason,
#if defined(CONFIG_EXTRA_EXCEPTION_INFO) && defined(CONFIG_PRINTK) \ #if defined(CONFIG_EXTRA_EXCEPTION_INFO) && defined(CONFIG_PRINTK) \
&& defined(ALT_CPU_HAS_EXTRA_EXCEPTION_INFO) && defined(ALT_CPU_HAS_EXTRA_EXCEPTION_INFO)
static char *cause_str(uint32_t cause_code) static char *cause_str(u32_t cause_code)
{ {
switch (cause_code) { switch (cause_code) {
case 0: case 0:
@ -164,7 +164,7 @@ FUNC_NORETURN void _Fault(const NANO_ESF *esf)
#ifdef CONFIG_PRINTK #ifdef CONFIG_PRINTK
/* Unfortunately, completely unavailable on Nios II/e cores */ /* Unfortunately, completely unavailable on Nios II/e cores */
#ifdef ALT_CPU_HAS_EXTRA_EXCEPTION_INFO #ifdef ALT_CPU_HAS_EXTRA_EXCEPTION_INFO
uint32_t exc_reg, badaddr_reg, eccftl; u32_t exc_reg, badaddr_reg, eccftl;
enum nios2_exception_cause cause; enum nios2_exception_cause cause;
exc_reg = _nios2_creg_read(NIOS2_CR_EXCEPTION); exc_reg = _nios2_creg_read(NIOS2_CR_EXCEPTION);
@ -176,13 +176,13 @@ FUNC_NORETURN void _Fault(const NANO_ESF *esf)
cause = (exc_reg & NIOS2_EXCEPTION_REG_CAUSE_MASK) cause = (exc_reg & NIOS2_EXCEPTION_REG_CAUSE_MASK)
>> NIOS2_EXCEPTION_REG_CAUSE_OFST; >> NIOS2_EXCEPTION_REG_CAUSE_OFST;
printk("Exception cause: %d ECCFTL: 0x%" PRIu32 "\n", cause, eccftl); printk("Exception cause: %d ECCFTL: 0x%x\n", cause, eccftl);
#if CONFIG_EXTRA_EXCEPTION_INFO #if CONFIG_EXTRA_EXCEPTION_INFO
printk("reason: %s\n", cause_str(cause)); printk("reason: %s\n", cause_str(cause));
#endif #endif
if (BIT(cause) & NIOS2_BADADDR_CAUSE_MASK) { if (BIT(cause) & NIOS2_BADADDR_CAUSE_MASK) {
badaddr_reg = _nios2_creg_read(NIOS2_CR_BADADDR); badaddr_reg = _nios2_creg_read(NIOS2_CR_BADADDR);
printk("Badaddr: 0x%" PRIx32 "\n", badaddr_reg); printk("Badaddr: 0x%x\n", badaddr_reg);
} }
#endif /* ALT_CPU_HAS_EXTRA_EXCEPTION_INFO */ #endif /* ALT_CPU_HAS_EXTRA_EXCEPTION_INFO */
#endif /* CONFIG_PRINTK */ #endif /* CONFIG_PRINTK */

View file

@ -30,7 +30,7 @@ void _irq_spurious(void *unused)
void _arch_irq_enable(unsigned int irq) void _arch_irq_enable(unsigned int irq)
{ {
uint32_t ienable; u32_t ienable;
int key; int key;
key = irq_lock(); key = irq_lock();
@ -46,7 +46,7 @@ void _arch_irq_enable(unsigned int irq)
void _arch_irq_disable(unsigned int irq) void _arch_irq_disable(unsigned int irq)
{ {
uint32_t ienable; u32_t ienable;
int key; int key;
key = irq_lock(); key = irq_lock();
@ -66,7 +66,7 @@ void _arch_irq_disable(unsigned int irq)
* *
* @param ipending Bitfield of interrupts * @param ipending Bitfield of interrupts
*/ */
void _enter_irq(uint32_t ipending) void _enter_irq(u32_t ipending)
{ {
int index; int index;

View file

@ -86,8 +86,8 @@ void _new_thread(char *stack_memory, size_t stack_size,
/* Initialize custom data field (value is opaque to kernel) */ /* Initialize custom data field (value is opaque to kernel) */
thread->custom_data = NULL; thread->custom_data = NULL;
#endif #endif
thread->callee_saved.sp = (uint32_t)iframe; thread->callee_saved.sp = (u32_t)iframe;
thread->callee_saved.ra = (uint32_t)_thread_entry_wrapper; thread->callee_saved.ra = (u32_t)_thread_entry_wrapper;
thread->callee_saved.key = NIOS2_STATUS_PIE_MSK; thread->callee_saved.key = NIOS2_STATUS_PIE_MSK;
/* Leave the rest of thread->callee_saved junk */ /* Leave the rest of thread->callee_saved junk */

View file

@ -57,31 +57,31 @@ typedef struct _caller_saved _caller_saved_t;
struct _callee_saved { struct _callee_saved {
/* General purpose callee-saved registers */ /* General purpose callee-saved registers */
uint32_t r16; u32_t r16;
uint32_t r17; u32_t r17;
uint32_t r18; u32_t r18;
uint32_t r19; u32_t r19;
uint32_t r20; u32_t r20;
uint32_t r21; u32_t r21;
uint32_t r22; u32_t r22;
uint32_t r23; u32_t r23;
/* Normally used for the frame pointer but also a general purpose /* Normally used for the frame pointer but also a general purpose
* register if frame pointers omitted * register if frame pointers omitted
*/ */
uint32_t r28; u32_t r28;
/* Return address */ /* Return address */
uint32_t ra; u32_t ra;
/* Stack pointer */ /* Stack pointer */
uint32_t sp; u32_t sp;
/* IRQ status before irq_lock() and call to _Swap() */ /* IRQ status before irq_lock() and call to _Swap() */
uint32_t key; u32_t key;
/* Return value of _Swap() */ /* Return value of _Swap() */
uint32_t retval; u32_t retval;
}; };
typedef struct _callee_saved _callee_saved_t; typedef struct _callee_saved _callee_saved_t;

View file

@ -28,7 +28,7 @@ extern "C" {
*/ */
static inline int _sys_current_irq_key_get(void) static inline int _sys_current_irq_key_get(void)
{ {
uint32_t ipending; u32_t ipending;
ipending = _nios2_creg_read(NIOS2_CR_IPENDING); ipending = _nios2_creg_read(NIOS2_CR_IPENDING);
return find_lsb_set(ipending) - 1; return find_lsb_set(ipending) - 1;

View file

@ -164,7 +164,7 @@ void _SysFatalErrorHandler(unsigned int reason, const NANO_ESF *esf)
#ifdef CONFIG_PRINTK #ifdef CONFIG_PRINTK
static char *cause_str(uint32_t cause) static char *cause_str(u32_t cause)
{ {
switch (cause) { switch (cause) {
case 0: case 0:
@ -188,7 +188,7 @@ static char *cause_str(uint32_t cause)
FUNC_NORETURN void _Fault(const NANO_ESF *esf) FUNC_NORETURN void _Fault(const NANO_ESF *esf)
{ {
uint32_t mcause; u32_t mcause;
__asm__ volatile("csrr %0, mcause" : "=r" (mcause)); __asm__ volatile("csrr %0, mcause" : "=r" (mcause));

View file

@ -10,7 +10,7 @@
void _irq_spurious(void *unused) void _irq_spurious(void *unused)
{ {
uint32_t mcause; u32_t mcause;
ARG_UNUSED(unused); ARG_UNUSED(unused);

View file

@ -53,10 +53,10 @@ void _new_thread(char *stack_memory, size_t stack_size,
stack_size - sizeof(struct __esf)); stack_size - sizeof(struct __esf));
/* Setup the initial stack frame */ /* Setup the initial stack frame */
stack_init->a0 = (uint32_t)thread_func; stack_init->a0 = (u32_t)thread_func;
stack_init->a1 = (uint32_t)arg1; stack_init->a1 = (u32_t)arg1;
stack_init->a2 = (uint32_t)arg2; stack_init->a2 = (u32_t)arg2;
stack_init->a3 = (uint32_t)arg3; stack_init->a3 = (u32_t)arg3;
/* /*
* Following the RISC-V architecture, * Following the RISC-V architecture,
* the MSTATUS register (used to globally enable/disable interrupt), * the MSTATUS register (used to globally enable/disable interrupt),
@ -81,7 +81,7 @@ void _new_thread(char *stack_memory, size_t stack_size,
* thread stack. * thread stack.
*/ */
stack_init->mstatus = SOC_MSTATUS_DEF_RESTORE; stack_init->mstatus = SOC_MSTATUS_DEF_RESTORE;
stack_init->mepc = (uint32_t)_thread_entry_wrapper; stack_init->mepc = (u32_t)_thread_entry_wrapper;
/* Initialize various struct k_thread members */ /* Initialize various struct k_thread members */
thread = (struct k_thread *)stack_memory; thread = (struct k_thread *)stack_memory;
@ -97,7 +97,7 @@ void _new_thread(char *stack_memory, size_t stack_size,
thread->custom_data = NULL; thread->custom_data = NULL;
#endif #endif
thread->callee_saved.sp = (uint32_t)stack_init; thread->callee_saved.sp = (u32_t)stack_init;
thread_monitor_init(thread); thread_monitor_init(thread);
} }

View file

@ -35,20 +35,20 @@ extern "C" {
* saved/restored when a cooperative context switch occurs. * saved/restored when a cooperative context switch occurs.
*/ */
struct _callee_saved { struct _callee_saved {
uint32_t sp; /* Stack pointer, (x2 register) */ u32_t sp; /* Stack pointer, (x2 register) */
uint32_t s0; /* saved register/frame pointer */ u32_t s0; /* saved register/frame pointer */
uint32_t s1; /* saved register */ u32_t s1; /* saved register */
uint32_t s2; /* saved register */ u32_t s2; /* saved register */
uint32_t s3; /* saved register */ u32_t s3; /* saved register */
uint32_t s4; /* saved register */ u32_t s4; /* saved register */
uint32_t s5; /* saved register */ u32_t s5; /* saved register */
uint32_t s6; /* saved register */ u32_t s6; /* saved register */
uint32_t s7; /* saved register */ u32_t s7; /* saved register */
uint32_t s8; /* saved register */ u32_t s8; /* saved register */
uint32_t s9; /* saved register */ u32_t s9; /* saved register */
uint32_t s10; /* saved register */ u32_t s10; /* saved register */
uint32_t s11; /* saved register */ u32_t s11; /* saved register */
}; };
typedef struct _callee_saved _callee_saved_t; typedef struct _callee_saved _callee_saved_t;
@ -62,7 +62,7 @@ struct _caller_saved {
typedef struct _caller_saved _caller_saved_t; typedef struct _caller_saved _caller_saved_t;
struct _thread_arch { struct _thread_arch {
uint32_t swap_return_value; /* Return value of _Swap() */ u32_t swap_return_value; /* Return value of _Swap() */
}; };
typedef struct _thread_arch _thread_arch_t; typedef struct _thread_arch _thread_arch_t;

View file

@ -28,7 +28,7 @@ extern "C" {
*/ */
static inline int _sys_current_irq_key_get(void) static inline int _sys_current_irq_key_get(void)
{ {
uint32_t mcause; u32_t mcause;
__asm__ volatile("csrr %0, mcause" : "=r" (mcause)); __asm__ volatile("csrr %0, mcause" : "=r" (mcause));

View file

@ -60,10 +60,10 @@ void soc_interrupt_init(void);
#endif #endif
#if defined(CONFIG_RISCV_HAS_PLIC) #if defined(CONFIG_RISCV_HAS_PLIC)
void riscv_plic_irq_enable(uint32_t irq); void riscv_plic_irq_enable(u32_t irq);
void riscv_plic_irq_disable(uint32_t irq); void riscv_plic_irq_disable(u32_t irq);
int riscv_plic_irq_is_enabled(uint32_t irq); int riscv_plic_irq_is_enabled(u32_t irq);
void riscv_plic_set_priority(uint32_t irq, uint32_t priority); void riscv_plic_set_priority(u32_t irq, u32_t priority);
int riscv_plic_get_irq(void); int riscv_plic_get_irq(void);
#endif #endif

View file

@ -13,7 +13,7 @@
void _arch_irq_enable(unsigned int irq) void _arch_irq_enable(unsigned int irq)
{ {
uint32_t mie; u32_t mie;
#if defined(CONFIG_RISCV_HAS_PLIC) #if defined(CONFIG_RISCV_HAS_PLIC)
if (irq > RISCV_MAX_GENERIC_IRQ) { if (irq > RISCV_MAX_GENERIC_IRQ) {
@ -33,7 +33,7 @@ void _arch_irq_enable(unsigned int irq)
void _arch_irq_disable(unsigned int irq) void _arch_irq_disable(unsigned int irq)
{ {
uint32_t mie; u32_t mie;
#if defined(CONFIG_RISCV_HAS_PLIC) #if defined(CONFIG_RISCV_HAS_PLIC)
if (irq > RISCV_MAX_GENERIC_IRQ) { if (irq > RISCV_MAX_GENERIC_IRQ) {
@ -53,7 +53,7 @@ void _arch_irq_disable(unsigned int irq)
int _arch_irq_is_enabled(unsigned int irq) int _arch_irq_is_enabled(unsigned int irq)
{ {
uint32_t mie; u32_t mie;
#if defined(CONFIG_RISCV_HAS_PLIC) #if defined(CONFIG_RISCV_HAS_PLIC)
if (irq > RISCV_MAX_GENERIC_IRQ) if (irq > RISCV_MAX_GENERIC_IRQ)

View file

@ -28,7 +28,7 @@
#include <arch/cpu.h> #include <arch/cpu.h>
#ifdef CONFIG_BOOT_TIME_MEASUREMENT #ifdef CONFIG_BOOT_TIME_MEASUREMENT
extern uint64_t __idle_tsc; /* timestamp when CPU went idle */ extern u64_t __idle_tsc; /* timestamp when CPU went idle */
#endif #endif
/** /**

View file

@ -47,7 +47,7 @@
* *
* C function prototype: * C function prototype:
* *
* void _exception_enter(uint32_t error_code, void *handler) * void _exception_enter(u32_t error_code, void *handler)
* *
*/ */

View file

@ -184,13 +184,13 @@ EXC_FUNC_NOCODE(IV_MACHINE_CHECK);
FUNC_NORETURN void page_fault_handler(const NANO_ESF *pEsf) FUNC_NORETURN void page_fault_handler(const NANO_ESF *pEsf)
{ {
uint32_t err, cr2; u32_t err, cr2;
/* See Section 6.15 of the IA32 Software Developer's Manual vol 3 */ /* See Section 6.15 of the IA32 Software Developer's Manual vol 3 */
__asm__ ("mov %%cr2, %0" : "=r" (cr2)); __asm__ ("mov %%cr2, %0" : "=r" (cr2));
err = pEsf->errorCode; err = pEsf->errorCode;
printk("***** CPU Page Fault (error code 0x%08" PRIx32 ")\n", err); printk("***** CPU Page Fault (error code 0x%08x)\n", err);
printk("%s thread %s address 0x%08" PRIx32 "\n", printk("%s thread %s address 0x%08" PRIx32 "\n",
err & US ? "User" : "Supervisor", err & US ? "User" : "Supervisor",

View file

@ -48,7 +48,7 @@
#ifdef CONFIG_FP_SHARING #ifdef CONFIG_FP_SHARING
/* SSE control/status register default value (used by assembler code) */ /* SSE control/status register default value (used by assembler code) */
extern uint32_t _sse_mxcsr_default_value; extern u32_t _sse_mxcsr_default_value;
/* /*
* Save a thread's floating point context information. * Save a thread's floating point context information.
@ -104,7 +104,7 @@ void k_float_enable(struct tcs *tcs, unsigned int options)
/* Indicate thread requires floating point context saving */ /* Indicate thread requires floating point context saving */
tcs->base.user_options |= (uint8_t)options; tcs->base.user_options |= (u8_t)options;
/* /*
* The current thread might not allow FP instructions, so clear CR0[TS] * The current thread might not allow FP instructions, so clear CR0[TS]

View file

@ -62,7 +62,7 @@ void *__attribute__((section(".spurNoErrIsr")))
void _arch_irq_direct_pm(void) void _arch_irq_direct_pm(void)
{ {
if (_kernel.idle) { if (_kernel.idle) {
int32_t idle_val = _kernel.idle; s32_t idle_val = _kernel.idle;
_kernel.idle = 0; _kernel.idle = 0;
_sys_power_save_idle_exit(idle_val); _sys_power_save_idle_exit(idle_val);

View file

@ -29,7 +29,7 @@
* *
* @return N/A * @return N/A
*/ */
void _MsrWrite(unsigned int msr, uint64_t msr_data) void _MsrWrite(unsigned int msr, u64_t msr_data)
{ {
__asm__ volatile ( __asm__ volatile (
"movl %[msr], %%ecx\n\t" "movl %[msr], %%ecx\n\t"
@ -38,8 +38,8 @@ void _MsrWrite(unsigned int msr, uint64_t msr_data)
"wrmsr" "wrmsr"
: :
: [msr] "m" (msr), : [msr] "m" (msr),
[data_lo] "rm" ((uint32_t)(msr_data & 0xFFFFFFFF)), [data_lo] "rm" ((u32_t)(msr_data & 0xFFFFFFFF)),
[data_hi] "rm" ((uint32_t)(msr_data >> 32)) [data_hi] "rm" ((u32_t)(msr_data >> 32))
: "eax", "ecx", "edx"); : "eax", "ecx", "edx");
} }
@ -62,9 +62,9 @@ void _MsrWrite(unsigned int msr, uint64_t msr_data)
* *
* @return N/A * @return N/A
*/ */
uint64_t _MsrRead(unsigned int msr) u64_t _MsrRead(unsigned int msr)
{ {
uint64_t ret; u64_t ret;
__asm__ volatile ( __asm__ volatile (
"movl %[msr], %%ecx\n\t" "movl %[msr], %%ecx\n\t"

View file

@ -15,7 +15,7 @@
static inline void cold_reboot(void) static inline void cold_reboot(void)
{ {
uint8_t reset_value = SYS_X86_RST_CNT_CPU_RST | SYS_X86_RST_CNT_SYS_RST | u8_t reset_value = SYS_X86_RST_CNT_CPU_RST | SYS_X86_RST_CNT_SYS_RST |
SYS_X86_RST_CNT_FULL_RST; SYS_X86_RST_CNT_FULL_RST;
sys_out8(reset_value, SYS_X86_RST_CNT_REG); sys_out8(reset_value, SYS_X86_RST_CNT_REG);
} }

View file

@ -149,27 +149,27 @@ void gdb_arch_regs_to_isf(struct gdb_reg_set *regs, NANO_ISF *isf)
void gdb_arch_regs_get(struct gdb_reg_set *regs, char *buffer) void gdb_arch_regs_get(struct gdb_reg_set *regs, char *buffer)
{ {
*((uint32_t *) buffer) = regs->regs.eax; *((u32_t *) buffer) = regs->regs.eax;
buffer += 4; buffer += 4;
*((uint32_t *) buffer) = regs->regs.ecx; *((u32_t *) buffer) = regs->regs.ecx;
buffer += 4; buffer += 4;
*((uint32_t *) buffer) = regs->regs.edx; *((u32_t *) buffer) = regs->regs.edx;
buffer += 4; buffer += 4;
*((uint32_t *) buffer) = regs->regs.ebx; *((u32_t *) buffer) = regs->regs.ebx;
buffer += 4; buffer += 4;
*((uint32_t *) buffer) = regs->regs.esp; *((u32_t *) buffer) = regs->regs.esp;
buffer += 4; buffer += 4;
*((uint32_t *) buffer) = regs->regs.ebp; *((u32_t *) buffer) = regs->regs.ebp;
buffer += 4; buffer += 4;
*((uint32_t *) buffer) = regs->regs.esi; *((u32_t *) buffer) = regs->regs.esi;
buffer += 4; buffer += 4;
*((uint32_t *) buffer) = regs->regs.edi; *((u32_t *) buffer) = regs->regs.edi;
buffer += 4; buffer += 4;
*((uint32_t *) buffer) = (uint32_t) regs->regs.eip; *((u32_t *) buffer) = (u32_t) regs->regs.eip;
buffer += 4; buffer += 4;
*((uint32_t *) buffer) = regs->regs.eflags; *((u32_t *) buffer) = regs->regs.eflags;
buffer += 4; buffer += 4;
*((uint32_t *) buffer) = regs->regs.cs; *((u32_t *) buffer) = regs->regs.cs;
} }
/** /**
@ -187,27 +187,27 @@ void gdb_arch_regs_get(struct gdb_reg_set *regs, char *buffer)
void gdb_arch_regs_set(struct gdb_reg_set *regs, char *buffer) void gdb_arch_regs_set(struct gdb_reg_set *regs, char *buffer)
{ {
regs->regs.eax = *((uint32_t *)buffer); regs->regs.eax = *((u32_t *)buffer);
buffer += 4; buffer += 4;
regs->regs.ecx = *((uint32_t *)buffer); regs->regs.ecx = *((u32_t *)buffer);
buffer += 4; buffer += 4;
regs->regs.edx = *((uint32_t *)buffer); regs->regs.edx = *((u32_t *)buffer);
buffer += 4; buffer += 4;
regs->regs.ebx = *((uint32_t *)buffer); regs->regs.ebx = *((u32_t *)buffer);
buffer += 4; buffer += 4;
regs->regs.esp = *((uint32_t *)buffer); regs->regs.esp = *((u32_t *)buffer);
buffer += 4; buffer += 4;
regs->regs.ebp = *((uint32_t *)buffer); regs->regs.ebp = *((u32_t *)buffer);
buffer += 4; buffer += 4;
regs->regs.esi = *((uint32_t *)buffer); regs->regs.esi = *((u32_t *)buffer);
buffer += 4; buffer += 4;
regs->regs.edi = *((uint32_t *)buffer); regs->regs.edi = *((u32_t *)buffer);
buffer += 4; buffer += 4;
regs->regs.eip = *((uint32_t *)buffer); regs->regs.eip = *((u32_t *)buffer);
buffer += 4; buffer += 4;
regs->regs.eflags = *((uint32_t *)buffer); regs->regs.eflags = *((u32_t *)buffer);
buffer += 4; buffer += 4;
regs->regs.cs = *((uint32_t *)buffer); regs->regs.cs = *((u32_t *)buffer);
} }
/** /**

View file

@ -84,8 +84,8 @@ _set_thread_return_value(struct k_thread *thread, unsigned int value)
extern void k_cpu_atomic_idle(unsigned int imask); extern void k_cpu_atomic_idle(unsigned int imask);
extern void _MsrWrite(unsigned int msr, uint64_t msrData); extern void _MsrWrite(unsigned int msr, u64_t msrData);
extern uint64_t _MsrRead(unsigned int msr); extern u64_t _MsrRead(unsigned int msr);
/* /*
* _IntLibInit() is called from the non-arch specific function, * _IntLibInit() is called from the non-arch specific function,

View file

@ -13,21 +13,21 @@
#include "power_states.h" #include "power_states.h"
#define _REG_TIMER_ICR ((volatile uint32_t *) \ #define _REG_TIMER_ICR ((volatile u32_t *) \
(CONFIG_LOAPIC_BASE_ADDRESS + LOAPIC_TIMER_ICR)) (CONFIG_LOAPIC_BASE_ADDRESS + LOAPIC_TIMER_ICR))
/* Variables used to save CPU state */ /* Variables used to save CPU state */
uint64_t _pm_save_gdtr; u64_t _pm_save_gdtr;
uint64_t _pm_save_idtr; u64_t _pm_save_idtr;
uint32_t _pm_save_esp; u32_t _pm_save_esp;
extern void _power_soc_sleep(void); extern void _power_soc_sleep(void);
extern void _power_restore_cpu_context(void); extern void _power_restore_cpu_context(void);
extern void _power_soc_deep_sleep(void); extern void _power_soc_deep_sleep(void);
#if (defined(CONFIG_SYS_POWER_DEEP_SLEEP)) #if (defined(CONFIG_SYS_POWER_DEEP_SLEEP))
static uint32_t *__x86_restore_info = static u32_t *__x86_restore_info =
(uint32_t *)CONFIG_BSP_SHARED_RESTORE_INFO_RAM_ADDR; (u32_t *)CONFIG_BSP_SHARED_RESTORE_INFO_RAM_ADDR;
static void _deep_sleep(enum power_states state) static void _deep_sleep(enum power_states state)
{ {

View file

@ -11,8 +11,8 @@
#define SHARED_ADDR_START 0xA8000000 #define SHARED_ADDR_START 0xA8000000
struct shared_mem { struct shared_mem {
uint32_t arc_start; u32_t arc_start;
uint32_t flags; u32_t flags;
}; };
#define ARC_READY (1 << 0) #define ARC_READY (1 << 0)

View file

@ -24,7 +24,7 @@
#ifdef CONFIG_ARC_INIT #ifdef CONFIG_ARC_INIT
#define SCSS_REG_VAL(offset) \ #define SCSS_REG_VAL(offset) \
(*((volatile uint32_t *)(SCSS_REGISTER_BASE+offset))) (*((volatile u32_t *)(SCSS_REGISTER_BASE+offset)))
#define SYS_LOG_LEVEL CONFIG_SYS_LOG_ARC_INIT_LEVEL #define SYS_LOG_LEVEL CONFIG_SYS_LOG_ARC_INIT_LEVEL
#include <logging/sys_log.h> #include <logging/sys_log.h>
@ -40,7 +40,7 @@
/* This function is also called at deep sleep resume. */ /* This function is also called at deep sleep resume. */
int _arc_init(struct device *arg) int _arc_init(struct device *arg)
{ {
uint32_t *reset_vector; u32_t *reset_vector;
ARG_UNUSED(arg); ARG_UNUSED(arg);
@ -53,7 +53,7 @@ int _arc_init(struct device *arg)
/* Address of ARC side __reset stored in the first 4 bytes of arc.bin, /* Address of ARC side __reset stored in the first 4 bytes of arc.bin,
* we read the value and stick it in shared_mem->arc_start which is * we read the value and stick it in shared_mem->arc_start which is
* the beginning of the address space at 0xA8000000 */ * the beginning of the address space at 0xA8000000 */
reset_vector = (uint32_t *)RESET_VECTOR; reset_vector = (u32_t *)RESET_VECTOR;
SYS_LOG_DBG("Reset vector address: %x", *reset_vector); SYS_LOG_DBG("Reset vector address: %x", *reset_vector);
shared_data->arc_start = *reset_vector; shared_data->arc_start = *reset_vector;
shared_data->flags = 0; shared_data->flags = 0;

View file

@ -40,7 +40,7 @@ QUARK_SE_IPM_DEFINE(quark_se_ipm4, 4, QUARK_SE_IPM_INBOUND);
#define QUARK_SE_IPM_CONSOLE_LINE_BUF_SIZE 80 #define QUARK_SE_IPM_CONSOLE_LINE_BUF_SIZE 80
static uint32_t ipm_console_ring_buf_data[CONFIG_QUARK_SE_IPM_CONSOLE_RING_BUF_SIZE32]; static u32_t ipm_console_ring_buf_data[CONFIG_QUARK_SE_IPM_CONSOLE_RING_BUF_SIZE32];
static char __stack ipm_console_thread_stack[CONFIG_IPM_CONSOLE_STACK_SIZE]; static char __stack ipm_console_thread_stack[CONFIG_IPM_CONSOLE_STACK_SIZE];
static char ipm_console_line_buf[QUARK_SE_IPM_CONSOLE_LINE_BUF_SIZE]; static char ipm_console_line_buf[QUARK_SE_IPM_CONSOLE_LINE_BUF_SIZE];

View file

@ -27,7 +27,7 @@
* @return N/A * @return N/A
*/ */
void _irq_priority_set(unsigned int irq, unsigned int prio, uint32_t flags) void _irq_priority_set(unsigned int irq, unsigned int prio, u32_t flags)
{ {
__ASSERT(prio < XCHAL_EXCM_LEVEL + 1, __ASSERT(prio < XCHAL_EXCM_LEVEL + 1,
"invalid priority %d! values must be less than %d\n", "invalid priority %d! values must be less than %d\n",

View file

@ -88,7 +88,7 @@ void _new_thread(char *pStack, size_t stackSize,
*/ */
struct k_thread *thread = (struct k_thread *)(pStack); struct k_thread *thread = (struct k_thread *)(pStack);
#if XCHAL_CP_NUM > 0 #if XCHAL_CP_NUM > 0
uint32_t *cpSA; u32_t *cpSA;
char *cpStack; char *cpStack;
#endif #endif
@ -104,7 +104,7 @@ void _new_thread(char *pStack, size_t stackSize,
cpStack = thread->arch.preempCoprocReg.cpStack; /* short hand alias */ cpStack = thread->arch.preempCoprocReg.cpStack; /* short hand alias */
memset(cpStack, 0, XT_CP_ASA); /* Set to zero to avoid bad surprises */ memset(cpStack, 0, XT_CP_ASA); /* Set to zero to avoid bad surprises */
/* Coprocessor's stack is allocated just after the k_thread */ /* Coprocessor's stack is allocated just after the k_thread */
cpSA = (uint32_t *)(thread->arch.preempCoprocReg.cpStack + XT_CP_ASA); cpSA = (u32_t *)(thread->arch.preempCoprocReg.cpStack + XT_CP_ASA);
/* Coprocessor's save area alignment is at leat 16 bytes */ /* Coprocessor's save area alignment is at leat 16 bytes */
*cpSA = ROUND_UP(cpSA + 1, *cpSA = ROUND_UP(cpSA + 1,
(XCHAL_TOTAL_SA_ALIGN < 16 ? 16 : XCHAL_TOTAL_SA_ALIGN)); (XCHAL_TOTAL_SA_ALIGN < 16 ? 16 : XCHAL_TOTAL_SA_ALIGN));
@ -125,31 +125,31 @@ void _new_thread(char *pStack, size_t stackSize,
/* Explicitly initialize certain saved registers */ /* Explicitly initialize certain saved registers */
/* task entrypoint */ /* task entrypoint */
pInitCtx->pc = (uint32_t)_thread_entry; pInitCtx->pc = (u32_t)_thread_entry;
/* physical top of stack frame */ /* physical top of stack frame */
pInitCtx->a1 = (uint32_t)pInitCtx + XT_STK_FRMSZ; pInitCtx->a1 = (u32_t)pInitCtx + XT_STK_FRMSZ;
/* user exception exit dispatcher */ /* user exception exit dispatcher */
pInitCtx->exit = (uint32_t)_xt_user_exit; pInitCtx->exit = (u32_t)_xt_user_exit;
/* Set initial PS to int level 0, EXCM disabled, user mode. /* Set initial PS to int level 0, EXCM disabled, user mode.
* Also set entry point argument arg. * Also set entry point argument arg.
*/ */
#ifdef __XTENSA_CALL0_ABI__ #ifdef __XTENSA_CALL0_ABI__
pInitCtx->a2 = (uint32_t)pEntry; pInitCtx->a2 = (u32_t)pEntry;
pInitCtx->a3 = (uint32_t)p1; pInitCtx->a3 = (u32_t)p1;
pInitCtx->a4 = (uint32_t)p2; pInitCtx->a4 = (u32_t)p2;
pInitCtx->a5 = (uint32_t)p3; pInitCtx->a5 = (u32_t)p3;
pInitCtx->ps = PS_UM | PS_EXCM; pInitCtx->ps = PS_UM | PS_EXCM;
#else #else
/* For windowed ABI set also WOE and CALLINC /* For windowed ABI set also WOE and CALLINC
* (pretend task is 'call4') * (pretend task is 'call4')
*/ */
pInitCtx->a6 = (uint32_t)pEntry; pInitCtx->a6 = (u32_t)pEntry;
pInitCtx->a7 = (uint32_t)p1; pInitCtx->a7 = (u32_t)p1;
pInitCtx->a8 = (uint32_t)p2; pInitCtx->a8 = (u32_t)p2;
pInitCtx->a9 = (uint32_t)p3; pInitCtx->a9 = (u32_t)p3;
pInitCtx->ps = PS_UM | PS_EXCM | PS_WOE | PS_CALLINC(1); pInitCtx->ps = PS_UM | PS_EXCM | PS_WOE | PS_CALLINC(1);
#endif #endif
thread->callee_saved.topOfStack = pInitCtx; thread->callee_saved.topOfStack = pInitCtx;

View file

@ -79,7 +79,7 @@ struct _callee_saved {
* callee-saved, but their values are pushed onto the stack rather than * callee-saved, but their values are pushed onto the stack rather than
* stored in the k_thread structure: * stored in the k_thread structure:
*/ */
uint32_t retval; /* a2 */ u32_t retval; /* a2 */
XtExcFrame *topOfStack; /* a1 = sp */ XtExcFrame *topOfStack; /* a1 = sp */
}; };
@ -129,7 +129,7 @@ struct _thread_arch {
* before any #ifdef'ed fields since the host tools currently use a * before any #ifdef'ed fields since the host tools currently use a
* fixed offset to read the 'flags' field. * fixed offset to read the 'flags' field.
*/ */
uint32_t flags; u32_t flags;
#ifdef CONFIG_THREAD_CUSTOM_DATA #ifdef CONFIG_THREAD_CUSTOM_DATA
void *custom_data; /* available for custom use */ void *custom_data; /* available for custom use */
#endif #endif