소스 검색

[bsp/raspberry-pico] add: SMP (#6888)

螺丝松掉的人 2 년 전
부모
커밋
6d00b28425

+ 20 - 2
bsp/raspberry-pico/board/board.c

@@ -1,11 +1,12 @@
 /*
 /*
- * Copyright (c) 2006-2021, RT-Thread Development Team
+ * Copyright (c) 2006-2023, RT-Thread Development Team
  *
  *
  * SPDX-License-Identifier: Apache-2.0
  * SPDX-License-Identifier: Apache-2.0
  *
  *
  * Change Logs:
  * Change Logs:
  * Date           Author         Notes
  * Date           Author         Notes
  * 2021-01-28     flybreak       first version
  * 2021-01-28     flybreak       first version
+ * 2023-01-22     rose_man       add RT_USING_SMP
  */
  */
 
 
 #include <rthw.h>
 #include <rthw.h>
@@ -21,12 +22,16 @@
 void isr_systick(void)
 void isr_systick(void)
 {
 {
     /* enter interrupt */
     /* enter interrupt */
+#ifndef RT_USING_SMP
     rt_interrupt_enter();
     rt_interrupt_enter();
+#endif
 
 
     rt_tick_increase();
     rt_tick_increase();
 
 
     /* leave interrupt */
     /* leave interrupt */
+#ifndef RT_USING_SMP
     rt_interrupt_leave();
     rt_interrupt_leave();
+#endif
 }
 }
 
 
 uint32_t systick_config(uint32_t ticks)
 uint32_t systick_config(uint32_t ticks)
@@ -47,7 +52,14 @@ void rt_hw_board_init()
 {
 {
     set_sys_clock_khz(PLL_SYS_KHZ, true);
     set_sys_clock_khz(PLL_SYS_KHZ, true);
 
 
+#ifdef RT_USING_HEAP
     rt_system_heap_init(HEAP_BEGIN, HEAP_END);
     rt_system_heap_init(HEAP_BEGIN, HEAP_END);
+#endif
+
+#ifdef RT_USING_SMP
+    extern rt_hw_spinlock_t _cpus_lock;
+    rt_hw_spin_lock_init(&_cpus_lock);
+#endif
 
 
     alarm_pool_init_default();
     alarm_pool_init_default();
 
 
@@ -64,10 +76,16 @@ void rt_hw_board_init()
     }
     }
 
 
     /* Configure the SysTick */
     /* Configure the SysTick */
-    systick_config(frequency_count_khz(CLOCKS_FC0_SRC_VALUE_PLL_SYS_CLKSRC_PRIMARY) * 1000 / RT_TICK_PER_SECOND);
+    systick_config(frequency_count_khz(CLOCKS_FC0_SRC_VALUE_ROSC_CLKSRC)*10000/RT_TICK_PER_SECOND);
+
+#ifdef RT_USING_COMPONENTS_INIT
+    rt_components_board_init();
+#endif
 
 
+#ifdef RT_USING_SERIAL
     stdio_init_all();
     stdio_init_all();
     rt_hw_uart_init();
     rt_hw_uart_init();
+#endif
 
 
 #ifdef RT_USING_CONSOLE
 #ifdef RT_USING_CONSOLE
    rt_console_set_device(RT_CONSOLE_DEVICE_NAME);
    rt_console_set_device(RT_CONSOLE_DEVICE_NAME);

+ 1 - 1
bsp/raspberry-pico/board/board.h

@@ -1,5 +1,5 @@
 /*
 /*
- * Copyright (c) 2006-2021, RT-Thread Development Team
+ * Copyright (c) 2006-2023, RT-Thread Development Team
  *
  *
  * SPDX-License-Identifier: Apache-2.0
  * SPDX-License-Identifier: Apache-2.0
  *
  *

+ 23 - 0
bsp/raspberry-pico/libcpu/SConscript

@@ -0,0 +1,23 @@
+# RT-Thread building script for component
+
+from building import *
+
+Import('rtconfig')
+
+cwd     = GetCurrentDir()
+src     = Glob('*.c') + Glob('*.cpp')
+CPPPATH = [cwd]
+
+if rtconfig.PLATFORM in ['armcc', 'armclang']:
+    src += Glob('*_rvds.S')
+
+if rtconfig.PLATFORM in ['gcc']:
+    src += Glob('*_init.S')
+    src += Glob('*_gcc.S')
+
+if rtconfig.PLATFORM in ['iccarm']:
+    src += Glob('*_iar.S')
+
+group = DefineGroup('CPU', src, depend = [''], CPPPATH = CPPPATH)
+
+Return('group')

+ 265 - 0
bsp/raspberry-pico/libcpu/context_gcc.S

@@ -0,0 +1,265 @@
+/*
+ * Copyright (c) 2006-2022, RT-Thread Development Team
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Change Logs:
+ * Date         Author    Notes
+ * 2010-01-25   Bernard      first version
+ * 2012-06-01   aozima       set pendsv priority to 0xFF.
+ * 2012-08-17   aozima       fixed bug: store r8 - r11.
+ * 2013-02-20   aozima       port to gcc.
+ * 2013-06-18   aozima       add restore MSP feature.
+ * 2013-11-04   bright       fixed hardfault bug for gcc.
+ */
+
+    .cpu    cortex-m0
+    .fpu    softvfp
+    .syntax unified
+    .thumb
+    .text
+
+    .equ    SCB_VTOR, 0xE000ED08            /* Vector Table Offset Register */
+    .equ    NVIC_INT_CTRL, 0xE000ED04       /* interrupt control state register */
+    .equ    NVIC_SHPR3, 0xE000ED20          /* system priority register (3) */
+    .equ    NVIC_PENDSV_PRI, 0xFFFF0000     /* PendSV and SysTick priority value (lowest) */
+    .equ    NVIC_PENDSVSET, 0x10000000      /* value to trigger PendSV exception */
+
+#include "../rtconfig.h"
+
+#ifdef RT_USING_SMP
+    .equ    SIO_CPUID, 0xd0000000 /* CPUID */
+    #define rt_hw_interrupt_disable rt_hw_local_irq_disable
+    #define rt_hw_interrupt_enable  rt_hw_local_irq_enable
+#endif
+
+/*
+ * rt_base_t rt_hw_interrupt_disable();
+ */
+    .global rt_hw_interrupt_disable
+    .type rt_hw_interrupt_disable, %function
+rt_hw_interrupt_disable:
+    MRS     R0, PRIMASK
+    CPSID   I
+    BX      LR
+
+/*
+ * void rt_hw_interrupt_enable(rt_base_t level);
+ */
+    .global rt_hw_interrupt_enable
+    .type rt_hw_interrupt_enable, %function
+rt_hw_interrupt_enable:
+    MSR     PRIMASK, R0
+    BX      LR
+
+/*
+ * void rt_hw_context_switch(rt_uint32 from, rt_uint32 to);
+ * R0 --> from
+ * R1 --> to
+ */
+    .global rt_hw_context_switch_interrupt
+    .type rt_hw_context_switch_interrupt, %function
+    .global rt_hw_context_switch
+    .type rt_hw_context_switch, %function
+rt_hw_context_switch_interrupt:
+rt_hw_context_switch:
+#ifndef RT_USING_SMP
+    /* set rt_thread_switch_interrupt_flag to 1 */
+    LDR     R2, =rt_thread_switch_interrupt_flag
+    LDR     R3, [R2]
+    CMP     R3, #1
+    BEQ     _reswitch
+    MOVS    R3, #1
+    STR     R3, [R2]
+
+    LDR     R2, =rt_interrupt_from_thread   /* set rt_interrupt_from_thread */
+    STR     R0, [R2]
+
+_reswitch:
+    LDR     R2, =rt_interrupt_to_thread     /* set rt_interrupt_to_thread */
+    STR     R1, [R2]
+#else
+    /* context_switch_to smp */
+    PUSH    {LR}
+    BL      __rt_cpu_switch
+    POP     {R2}
+#endif
+
+    LDR     R0, =NVIC_INT_CTRL           /* trigger the PendSV exception (causes context switch) */
+    LDR     R1, =NVIC_PENDSVSET
+    STR     R1, [R0]
+#ifndef RT_USING_SMP
+    BX      LR
+#else
+    BX      R2
+#endif
+
+/* R0 --> switch from thread stack
+ * R1 --> switch to thread stack
+ * psr, pc, LR, R12, R3, R2, R1, R0 are pushed into [from] stack
+ */
+    .global PendSV_Handler
+    .type PendSV_Handler, %function
+PendSV_Handler:
+    /* disable interrupt to protect context switch */
+    MRS     R2, PRIMASK
+    CPSID   I
+
+#ifndef RT_USING_SMP
+    /* get rt_thread_switch_interrupt_flag */
+    LDR     R0, =rt_thread_switch_interrupt_flag
+#else
+    LDR     R0, =SIO_CPUID
+    LDR     R1, [R0]
+    LDR     R3, =rt_thread_switch_array
+    CMP     R1, #0
+    BEQ     cpu0_info
+    ADDS    R3, #12
+cpu0_info:
+    MOV     R0, R3
+#endif
+    LDR     R1, [R0]
+
+    CMP     R1, #0x00
+    BEQ     pendsv_exit     /* pendsv already handled */
+
+    /* clear rt_thread_switch_interrupt_flag to 0 */
+    MOVS    R1, #0
+    STR     R1, [R0]
+
+#ifndef RT_USING_SMP
+    LDR     R0, =rt_interrupt_from_thread
+#else
+    ADDS    R0, #4
+#endif
+    LDR     R1, [R0]
+
+    CMP     R1, #0x00
+    BEQ     switch_to_thread    /* skip register save at the first time */
+
+    MRS     R1, PSP                 /* get from thread stack pointer */
+
+    SUBS    R1, R1, #0x20           /* space for {R4 - R7} and {R8 - R11} */
+    LDR     R0, [R0]
+    STR     R1, [R0]                /* update from thread stack pointer */
+
+    STMIA   R1!, {R4 - R7}          /* push thread {R4 - R7} register to thread stack */
+
+    MOV     R4, R8                  /* mov thread {R8 - R11} to {R4 - R7} */
+    MOV     R5, R9
+    MOV     R6, R10
+    MOV     R7, R11
+    STMIA   R1!, {R4 - R7}          /* push thread {R8 - R11} high register to thread stack */
+switch_to_thread:
+
+#ifndef RT_USING_SMP
+    LDR     R1, =rt_interrupt_to_thread
+#else
+    MOV     R1, R3
+    ADDS    R1, #8
+#endif
+    LDR     R1, [R1]
+
+    LDR     R1, [R1]                /* load thread stack pointer */
+
+    LDMIA   R1!, {R4 - R7}          /* pop thread {R4 - R7} register from thread stack */
+    PUSH    {R4 - R7}               /* push {R4 - R7} to MSP for copy {R8 - R11} */
+
+    LDMIA   R1!, {R4 - R7}          /* pop thread {R8 - R11} high register from thread stack to {R4 - R7} */
+    MOV     R8,  R4                 /* mov {R4 - R7} to {R8 - R11} */
+    MOV     R9,  R5
+    MOV     R10, R6
+    MOV     R11, R7
+
+    POP     {R4 - R7}               /* pop {R4 - R7} from MSP */
+
+    MSR     PSP, R1                 /* update stack pointer */
+
+pendsv_exit:
+    /* restore interrupt */
+    MSR     PRIMASK, R2
+
+    MOVS    R0, #0x03
+    RSBS    R0, R0, #0x00
+    BX      R0
+/*
+ * void rt_hw_context_switch_to(rt_uint32 to);
+ * R0 --> to
+ */
+    .global rt_hw_context_switch_to
+    .type rt_hw_context_switch_to, %function
+rt_hw_context_switch_to:
+#ifndef RT_USING_SMP
+    LDR     R1, =rt_interrupt_to_thread
+    STR     R0, [R1]
+
+    /* set from thread to 0 */
+    LDR     R1, =rt_interrupt_from_thread
+    MOVS    R0, #0
+    STR     R0, [R1]
+
+    /* set interrupt flag to 1 */
+    LDR     R1, =rt_thread_switch_interrupt_flag
+    MOVS    R0, #1
+    STR     R0, [R1]
+#else
+    /* context_switch_to smp */
+    MOV     R2,R1
+    MOV     R1,R0
+    MOVS    R0,#0
+    BL      __rt_cpu_switch
+#endif
+
+    /* set the PendSV and SysTick exception priority */
+    LDR     R0, =NVIC_SHPR3
+    LDR     R1, =NVIC_PENDSV_PRI
+    LDR     R2, [R0,#0x00]       /* read */
+    ORRS    R1, R1, R2             /* modify */
+    STR     R1, [R0]             /* write-back */
+
+    LDR     R0, =NVIC_INT_CTRL               /* trigger the PendSV exception (causes context switch) */
+    LDR     R1, =NVIC_PENDSVSET
+    STR     R1, [R0]
+    NOP
+    /* restore MSP */
+    LDR     R0, =SCB_VTOR
+    LDR     R0, [R0]
+    LDR     R0, [R0]
+    NOP
+    MSR     MSP, R0
+
+    /* enable interrupts at processor level */
+    CPSIE   I
+
+    /* ensure PendSV exception taken place before subsequent operation */
+    DSB
+    ISB
+
+    /* never reach here! */
+
+/* compatible with old version */
+    .global rt_hw_interrupt_thread_switch
+    .type rt_hw_interrupt_thread_switch, %function
+rt_hw_interrupt_thread_switch:
+    BX      LR
+    NOP
+
+    .global HardFault_Handler
+    .type HardFault_Handler, %function
+HardFault_Handler:
+    /* get current context */
+    MRS     R0, PSP                 /* get fault thread stack pointer */
+    PUSH    {LR}
+    BL      rt_hw_hard_fault_exception
+    POP     {PC}
+
+
+/*
+ * rt_uint32_t rt_hw_interrupt_check(void);
+ * R0 --> state
+ */
+    .global rt_hw_interrupt_check
+    .type rt_hw_interrupt_check, %function
+rt_hw_interrupt_check:
+    MRS     R0, IPSR
+    BX      LR

+ 284 - 0
bsp/raspberry-pico/libcpu/cpuport.c

@@ -0,0 +1,284 @@
+/*
+ * Copyright (c) 2006-2023, RT-Thread Development Team
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Change Logs:
+ * Date           Author       Notes
+ * 2010-01-25     Bernard      first version
+ * 2012-05-31     aozima       Merge all of the C source code into cpuport.c
+ * 2012-08-17     aozima       fixed bug: store r8 - r11.
+ * 2012-12-23     aozima       stack addr align to 8byte.
+ * 2023-01-22     rose_man     add RT_USING_SMP
+ */
+
+#include <rtthread.h>
+#include <rthw.h>
+#include <rtthread.h>
+#include <stdint.h>
+
+#include "board.h"
+
+#ifdef RT_USING_SMP
+
+#include "hardware/structs/sio.h"
+#include "hardware/irq.h"
+#include "pico/sync.h"
+#include "pico/multicore.h"
+
+int rt_hw_cpu_id(void)
+{
+    return sio_hw->cpuid;
+}
+
+void rt_hw_spin_lock_init(rt_hw_spinlock_t *lock)
+{
+    static uint8_t spin_cnt = 0;
+
+    if ( spin_cnt < 32)
+    {
+        lock->slock = (rt_uint32_t)spin_lock_instance(spin_cnt);
+        spin_cnt = spin_cnt + 1;
+    }
+    else
+    {
+        lock->slock = 0;
+    }
+}
+
+void rt_hw_spin_lock(rt_hw_spinlock_t *lock)
+{
+    if ( lock->slock != 0 )
+    {
+        spin_lock_unsafe_blocking((spin_lock_t*)lock->slock);
+    }
+}
+
+void rt_hw_spin_unlock(rt_hw_spinlock_t *lock)
+{
+    if ( lock->slock != 0 )
+    {
+        spin_unlock_unsafe((spin_lock_t*)lock->slock);
+    }
+}
+
+void secondary_cpu_c_start(void)
+{
+    irq_set_enabled(SIO_IRQ_PROC1,RT_TRUE);
+
+    extern uint32_t systick_config(uint32_t ticks);
+    systick_config(frequency_count_khz(CLOCKS_FC0_SRC_VALUE_ROSC_CLKSRC)*10000/RT_TICK_PER_SECOND);
+
+    rt_hw_spin_lock(&_cpus_lock);
+
+    rt_system_scheduler_start();
+}
+
+void rt_hw_secondary_cpu_up(void)
+{
+    multicore_launch_core1(secondary_cpu_c_start);
+
+    irq_set_enabled(SIO_IRQ_PROC0,RT_TRUE);
+}
+
+void rt_hw_secondary_cpu_idle_exec(void)
+{
+    asm volatile ("wfi");
+}
+
+#define IPI_MAGIC 0x5a5a
+
+void rt_hw_ipi_send(int ipi_vector, unsigned int cpu_mask)
+{
+    sio_hw->fifo_wr = IPI_MAGIC;
+}
+
+void rt_hw_ipi_handler(void)
+{
+    uint32_t status = sio_hw->fifo_st;
+
+    if ( status & (SIO_FIFO_ST_ROE_BITS | SIO_FIFO_ST_WOF_BITS) )
+    {
+        sio_hw->fifo_st = 0;
+    }
+
+    if ( status & SIO_FIFO_ST_VLD_BITS )
+    {
+        if ( sio_hw->fifo_rd == IPI_MAGIC )
+        {
+            //rt_schedule();
+        }
+    }
+}
+
+void isr_irq15(void)
+{
+    rt_hw_ipi_handler();
+}
+
+void isr_irq16(void)
+{
+    rt_hw_ipi_handler();
+}
+struct __rt_thread_switch_array
+{
+    rt_ubase_t flag;
+    rt_ubase_t from;
+    rt_ubase_t to;
+};
+struct __rt_thread_switch_array rt_thread_switch_array[2] = { {0,0,0}, {0,0,0} };
+
+void __rt_cpu_switch(rt_ubase_t from, rt_ubase_t to, struct rt_thread *thread)
+{
+    struct rt_cpu* pcpu = rt_cpu_self();
+    rt_uint32_t   cpuid = rt_hw_cpu_id();
+
+    if ( rt_thread_switch_array[cpuid].flag != 1)
+    {
+        rt_thread_switch_array[cpuid].flag  = 1;
+        rt_thread_switch_array[cpuid].from = from;
+    }
+    rt_thread_switch_array[cpuid].to = to;
+
+    if ( pcpu->current_thread != RT_NULL )
+    {
+        thread->cpus_lock_nest      = pcpu->current_thread->cpus_lock_nest;
+        thread->critical_lock_nest  = pcpu->current_thread->critical_lock_nest;
+        thread->scheduler_lock_nest = pcpu->current_thread->scheduler_lock_nest;
+    }
+
+    pcpu->current_thread = thread;
+    if (!thread->cpus_lock_nest)
+    {
+        rt_hw_spin_unlock(&_cpus_lock);
+    }
+}
+
+#endif /*RT_USING_SMP*/
+
+struct exception_stack_frame
+{
+    rt_uint32_t r0;
+    rt_uint32_t r1;
+    rt_uint32_t r2;
+    rt_uint32_t r3;
+    rt_uint32_t r12;
+    rt_uint32_t lr;
+    rt_uint32_t pc;
+    rt_uint32_t psr;
+};
+
+struct stack_frame
+{
+    /* r4 ~ r7 low register */
+    rt_uint32_t r4;
+    rt_uint32_t r5;
+    rt_uint32_t r6;
+    rt_uint32_t r7;
+
+    /* r8 ~ r11 high register */
+    rt_uint32_t r8;
+    rt_uint32_t r9;
+    rt_uint32_t r10;
+    rt_uint32_t r11;
+
+    struct exception_stack_frame exception_stack_frame;
+};
+
+/* flag in interrupt handling */
+rt_uint32_t rt_interrupt_from_thread, rt_interrupt_to_thread;
+rt_uint32_t rt_thread_switch_interrupt_flag;
+
+/**
+ * This function will initialize thread stack
+ *
+ * @param tentry the entry of thread
+ * @param parameter the parameter of entry
+ * @param stack_addr the beginning stack address
+ * @param texit the function will be called when thread exit
+ *
+ * @return stack address
+ */
+rt_uint8_t *rt_hw_stack_init(void       *tentry,
+                             void       *parameter,
+                             rt_uint8_t *stack_addr,
+                             void       *texit)
+{
+    struct stack_frame *stack_frame;
+    rt_uint8_t         *stk;
+    unsigned long       i;
+
+    stk  = stack_addr + sizeof(rt_uint32_t);
+    stk  = (rt_uint8_t *)RT_ALIGN_DOWN((rt_uint32_t)stk, 8);
+    stk -= sizeof(struct stack_frame);
+
+    stack_frame = (struct stack_frame *)stk;
+
+    /* init all register */
+    for (i = 0; i < sizeof(struct stack_frame) / sizeof(rt_uint32_t); i ++)
+    {
+        ((rt_uint32_t *)stack_frame)[i] = 0xdeadbeef;
+    }
+
+    stack_frame->exception_stack_frame.r0  = (unsigned long)parameter; /* r0 : argument */
+    stack_frame->exception_stack_frame.r1  = 0;                        /* r1 */
+    stack_frame->exception_stack_frame.r2  = 0;                        /* r2 */
+    stack_frame->exception_stack_frame.r3  = 0;                        /* r3 */
+    stack_frame->exception_stack_frame.r12 = 0;                        /* r12 */
+    stack_frame->exception_stack_frame.lr  = (unsigned long)texit;     /* lr */
+    stack_frame->exception_stack_frame.pc  = (unsigned long)tentry;    /* entry point, pc */
+    stack_frame->exception_stack_frame.psr = 0x01000000L;              /* PSR */
+
+    /* return task's current stack address */
+    return stk;
+}
+
+#if defined(RT_USING_FINSH) && defined(MSH_USING_BUILT_IN_COMMANDS)
+extern long list_thread(void);
+#endif
+extern rt_thread_t rt_current_thread;
+/**
+ * fault exception handling
+ */
+void rt_hw_hard_fault_exception(struct exception_stack_frame *contex)
+{
+    rt_kprintf("psr: 0x%08x\n", contex->psr);
+    rt_kprintf(" pc: 0x%08x\n", contex->pc);
+    rt_kprintf(" lr: 0x%08x\n", contex->lr);
+    rt_kprintf("r12: 0x%08x\n", contex->r12);
+    rt_kprintf("r03: 0x%08x\n", contex->r3);
+    rt_kprintf("r02: 0x%08x\n", contex->r2);
+    rt_kprintf("r01: 0x%08x\n", contex->r1);
+    rt_kprintf("r00: 0x%08x\n", contex->r0);
+
+#ifdef RT_USING_SMP
+    rt_thread_t rt_current_thread = rt_thread_self();
+    rt_kprintf("hard fault on cpu : %d on thread: %s\n", rt_current_thread->oncpu, rt_current_thread->name);
+#else
+    rt_kprintf("hard fault on thread: %s\n", rt_current_thread->name);
+#endif
+#if defined(RT_USING_FINSH) && defined(MSH_USING_BUILT_IN_COMMANDS)
+    list_thread();
+#endif
+
+    while (1);
+}
+
+#define SCB_CFSR        (*(volatile const unsigned *)0xE000ED28) /* Configurable Fault Status Register */
+#define SCB_HFSR        (*(volatile const unsigned *)0xE000ED2C) /* HardFault Status Register */
+#define SCB_MMAR        (*(volatile const unsigned *)0xE000ED34) /* MemManage Fault Address register */
+#define SCB_BFAR        (*(volatile const unsigned *)0xE000ED38) /* Bus Fault Address Register */
+#define SCB_AIRCR       (*(volatile unsigned long *)0xE000ED0C)  /* Reset control Address Register */
+#define SCB_RESET_VALUE 0x05FA0004                               /* Reset value, write to SCB_AIRCR can reset cpu */
+
+#define SCB_CFSR_MFSR   (*(volatile const unsigned char*)0xE000ED28)  /* Memory-management Fault Status Register */
+#define SCB_CFSR_BFSR   (*(volatile const unsigned char*)0xE000ED29)  /* Bus Fault Status Register */
+#define SCB_CFSR_UFSR   (*(volatile const unsigned short*)0xE000ED2A) /* Usage Fault Status Register */
+
+/**
+ * reset CPU
+ */
+rt_weak void rt_hw_cpu_reset(void)
+{
+    SCB_AIRCR  = SCB_RESET_VALUE;//((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) |SCB_AIRCR_SYSRESETREQ_Msk);
+}

+ 22 - 0
bsp/raspberry-pico/libcpu/cpuport.h

@@ -0,0 +1,22 @@
+/*
+ * Copyright (c) 2006-2023, RT-Thread Development Team
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Change Logs:
+ * Date           Author       Notes
+ * 2023-01-22     rose_man     add RT_USING_SMP
+ */
+
+#ifndef  CPUPORT_H__
+#define  CPUPORT_H__
+
+typedef union {
+    unsigned long slock;
+    struct __arch_tickets {
+        unsigned short owner;
+        unsigned short next;
+    } tickets;
+} rt_hw_spinlock_t;
+
+#endif  /*CPUPORT_H__*/

+ 4 - 0
bsp/raspberry-pico/libraries/SConscript

@@ -7,6 +7,8 @@ cwd = GetCurrentDir()
 
 
 # The set of source files associated with this SConscript file.
 # The set of source files associated with this SConscript file.
 src = Split("""
 src = Split("""
+pico-sdk/src/rp2_common/hardware_flash/flash.c
+pico-sdk/src/rp2_common/pico_multicore/multicore.c
 pico-sdk/src/rp2_common/pico_stdlib/stdlib.c
 pico-sdk/src/rp2_common/pico_stdlib/stdlib.c
 pico-sdk/src/rp2_common/hardware_gpio/gpio.c
 pico-sdk/src/rp2_common/hardware_gpio/gpio.c
 pico-sdk/src/rp2_common/hardware_claim/claim.c
 pico-sdk/src/rp2_common/hardware_claim/claim.c
@@ -59,6 +61,8 @@ generated/bs2_default_padded_checksummed.S
 """)
 """)
 
 
 path = [
 path = [
+    cwd + '/pico-sdk/src/rp2_common/hardware_flash/include',
+    cwd + '/pico-sdk/src/rp2_common/pico_multicore/include',
     cwd + '/pico-sdk/src/common/pico_stdlib/include',
     cwd + '/pico-sdk/src/common/pico_stdlib/include',
     cwd + '/pico-sdk/src/rp2_common/hardware_gpio/include',
     cwd + '/pico-sdk/src/rp2_common/hardware_gpio/include',
     cwd + '/pico-sdk/src/common/pico_base/include',
     cwd + '/pico-sdk/src/common/pico_base/include',

+ 1 - 1
bsp/raspberry-pico/rtconfig.py

@@ -3,7 +3,7 @@ import sys
 
 
 # toolchains options
 # toolchains options
 ARCH='arm'
 ARCH='arm'
-CPU='cortex-m0'
+CPU='cortex-m0-dual'
 CROSS_TOOL='gcc'
 CROSS_TOOL='gcc'
 
 
 # bsp lib config
 # bsp lib config