This patch series implements SMP boot for arch/arm, as far as getting all CPUs up and running the idle loop. The first few patches are semi-independent cleanups and improvements, most of which are needed for the SMP patches later. Cheers, Tim.
# HG changeset patch # User Tim Deegan <tim@xen.org> # Date 1330018799 0 # Node ID 4a7c1420913135fbeba361cd9603e748c074cdac # Parent 0c3d19f40ab145d101de84051c3e00eef17fa1cb arm: strip xen binary The symbols in it are wrong anyway and will only confuse people who ought to be looking at xen-syms. Signed-off-by: Tim Deegan <tim@xen.org> diff -r 0c3d19f40ab1 -r 4a7c14209131 xen/arch/arm/Makefile --- a/xen/arch/arm/Makefile Mon Feb 20 22:16:32 2012 +0100 +++ b/xen/arch/arm/Makefile Thu Feb 23 17:39:59 2012 +0000 @@ -40,7 +40,7 @@ ALL_OBJS := head.o $(ALL_OBJS) # XXX: VE model loads by VMA so instead of # making a proper ELF we link with LMA == VMA and adjust crudely $(OBJCOPY) --change-addresses +0x80000000 $< $@ - # XXX strip it + $(STRIP) $@ #$(TARGET): $(TARGET)-syms $(efi-y) boot/mkelf32 # ./boot/mkelf32 $(TARGET)-syms $(TARGET) 0x100000 \
# HG changeset patch
# User Tim Deegan <tim@xen.org>
# Date 1330018799 0
# Node ID ec051056db2b6d37344629e2f01d17240099d5ec
# Parent 4a7c1420913135fbeba361cd9603e748c074cdac
arm: implement udelay()
Signed-off-by: Tim Deegan <tim@xen.org>
diff -r 4a7c14209131 -r ec051056db2b xen/arch/arm/dummy.S
--- a/xen/arch/arm/dummy.S Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/arch/arm/dummy.S Thu Feb 23 17:39:59 2012 +0000
@@ -62,5 +62,4 @@ DUMMY(gmfn_to_mfn);
DUMMY(hypercall_create_continuation);
DUMMY(send_timer_event);
DUMMY(share_xen_page_with_privileged_guests);
-DUMMY(__udelay);
DUMMY(wallclock_time);
diff -r 4a7c14209131 -r ec051056db2b xen/arch/arm/time.c
--- a/xen/arch/arm/time.c Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/arch/arm/time.c Thu Feb 23 17:39:59 2012 +0000
@@ -171,6 +171,16 @@ void __cpuinit init_timer_interrupt(void
request_irq(30, timer_interrupt, 0, "phytimer", NULL);
}
+/* Wait a set number of microseconds */
+void udelay(unsigned long usecs)
+{
+ s_time_t deadline = get_s_time() + 1000 * (s_time_t) usecs;
+ do {
+ dsb();
+ isb();
+ } while ( get_s_time() - deadline < 0 );
+}
+
/*
* Local variables:
* mode: C
diff -r 4a7c14209131 -r ec051056db2b xen/include/asm-arm/delay.h
--- a/xen/include/asm-arm/delay.h Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/include/asm-arm/delay.h Thu Feb 23 17:39:59 2012 +0000
@@ -1,8 +1,7 @@
#ifndef _ARM_DELAY_H
#define _ARM_DELAY_H
-extern void __udelay(unsigned long usecs);
-#define udelay(n) __udelay(n)
+extern void udelay(unsigned long usecs);
#endif /* defined(_ARM_DELAY_H) */
/*
Tim Deegan
2012-Feb-23 17:40 UTC
[PATCH 03 of 10] arm: Move some GIC distributor init out of the per-CPU init function
# HG changeset patch
# User Tim Deegan <tim@xen.org>
# Date 1330018799 0
# Node ID 437ad1207a175c9ad376871f3f4c075dbcd5b6e6
# Parent ec051056db2b6d37344629e2f01d17240099d5ec
arm: Move some GIC distributor init out of the per-CPU init function
Signed-off-by: Tim Deegan <tim@xen.org>
diff -r ec051056db2b -r 437ad1207a17 xen/arch/arm/gic.c
--- a/xen/arch/arm/gic.c Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/arch/arm/gic.c Thu Feb 23 17:39:59 2012 +0000
@@ -216,14 +216,6 @@ static void __init gic_dist_init(void)
for ( i = 32; i < gic.lines; i += 32 )
GICD[GICD_ICENABLER + i / 32] = ~0ul;
- /* Turn on the distributor */
- GICD[GICD_CTLR] = GICD_CTL_ENABLE;
-}
-
-static void __cpuinit gic_cpu_init(void)
-{
- int i;
-
/* Disable all PPI and enable all SGI */
GICD[GICD_ICENABLER] = 0xffff0000; /* Disable all PPI */
GICD[GICD_ISENABLER] = 0x0000ffff; /* Enable all SGI */
@@ -231,6 +223,12 @@ static void __cpuinit gic_cpu_init(void)
for (i = 0; i < 32; i += 4)
GICD[GICD_IPRIORITYR + i / 4] = 0xa0a0a0a0;
+ /* Turn on the distributor */
+ GICD[GICD_CTLR] = GICD_CTL_ENABLE;
+}
+
+static void __cpuinit gic_cpu_init(void)
+{
/* Local settings: interface controller */
GICC[GICC_PMR] = 0xff; /* Don''t mask by priority */
GICC[GICC_BPR] = 0; /* Finest granularity of priority */
# HG changeset patch # User Tim Deegan <tim@xen.org> # Date 1330018799 0 # Node ID 8f322ab538572e1a12c8ed716ddd5cb4c122e9ed # Parent 437ad1207a175c9ad376871f3f4c075dbcd5b6e6 arm: Handle booting on SMP platforms Make all non-boot CPUs wait forever instead of trying to boot in parallel. Signed-off-by: Tim Deegan <tim@xen.org> diff -r 437ad1207a17 -r 8f322ab53857 xen/arch/arm/head.S --- a/xen/arch/arm/head.S Thu Feb 23 17:39:59 2012 +0000 +++ b/xen/arch/arm/head.S Thu Feb 23 17:39:59 2012 +0000 @@ -61,6 +61,19 @@ start: add r8, r10 /* r8 := paddr(DTB) */ #endif + /* Are we the boot CPU? */ + mrc CP32(r0, MPIDR) + tst r0, #(1<<31) /* Multiprocessor extension supported? */ + beq boot_cpu + tst r0, #(1<<30) /* Uniprocessor system? */ + bne boot_cpu + bics r0, r0, #(0xff << 24) /* Ignore flags */ + beq boot_cpu /* If all other fields are 0, we win */ + +1: wfi + b 1b + +boot_cpu: #ifdef EARLY_UART_ADDRESS /* Say hello */ ldr r11, =EARLY_UART_ADDRESS /* r11 := UART base address */ diff -r 437ad1207a17 -r 8f322ab53857 xen/include/asm-arm/cpregs.h --- a/xen/include/asm-arm/cpregs.h Thu Feb 23 17:39:59 2012 +0000 +++ b/xen/include/asm-arm/cpregs.h Thu Feb 23 17:39:59 2012 +0000 @@ -91,6 +91,7 @@ /* Coprocessor 15 */ /* CP15 CR0: CPUID and Cache Type Registers */ +#define MPIDR p15,0,c0,c0,5 /* Multiprocessor Affinity Register */ #define ID_PFR0 p15,0,c0,c1,0 /* Processor Feature Register 0 */ #define ID_PFR1 p15,0,c0,c1,1 /* Processor Feature Register 1 */ #define ID_DFR0 p15,0,c0,c1,2 /* Debug Feature Register 0 */
# HG changeset patch
# User Tim Deegan <tim@xen.org>
# Date 1330018799 0
# Node ID 1e9c6bd7cc99d1af0107aa927ee2ba03721449b7
# Parent 8f322ab538572e1a12c8ed716ddd5cb4c122e9ed
arm: More SMP bringup
Bring non-boot CPUs up as far as running on the relocated pagetables,
one at a time, before the non-relocated copy of Xen gets reused for
general memory pools.
Don''t yet bring them up into C; that will happen later when stacks are
allocated.
Signed-off-by: Tim Deegan <tim@xen.org>
diff -r 8f322ab53857 -r 1e9c6bd7cc99 xen/arch/arm/gic.c
--- a/xen/arch/arm/gic.c Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/arch/arm/gic.c Thu Feb 23 17:39:59 2012 +0000
@@ -248,7 +248,7 @@ static void __cpuinit gic_hyp_init(void)
}
/* Set up the GIC */
-void gic_init(void)
+int __init gic_init(void)
{
/* XXX FIXME get this from devicetree */
gic.dbase = GIC_BASE_ADDRESS + GIC_DR_OFFSET;
@@ -270,6 +270,8 @@ void gic_init(void)
gic_hyp_init();
spin_unlock(&gic.lock);
+
+ return gic.cpus;
}
void gic_route_irqs(void)
diff -r 8f322ab53857 -r 1e9c6bd7cc99 xen/arch/arm/gic.h
--- a/xen/arch/arm/gic.h Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/arch/arm/gic.h Thu Feb 23 17:39:59 2012 +0000
@@ -138,8 +138,8 @@ extern int gic_route_irq_to_guest(struct
/* Accept an interrupt from the GIC and dispatch its handler */
extern void gic_interrupt(struct cpu_user_regs *regs, int is_fiq);
-/* Bring up the interrupt controller */
-extern void gic_init(void);
+/* Bring up the interrupt controller, and report # cpus attached */
+extern int gic_init(void);
/* setup the gic virtual interface for a guest */
extern void gicv_setup(struct domain *d);
#endif
diff -r 8f322ab53857 -r 1e9c6bd7cc99 xen/arch/arm/head.S
--- a/xen/arch/arm/head.S Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/arch/arm/head.S Thu Feb 23 17:39:59 2012 +0000
@@ -62,22 +62,36 @@ start:
#endif
/* Are we the boot CPU? */
+ mov r12, #0 /* r12 := CPU ID */
mrc CP32(r0, MPIDR)
tst r0, #(1<<31) /* Multiprocessor extension supported? */
beq boot_cpu
tst r0, #(1<<30) /* Uniprocessor system? */
bne boot_cpu
- bics r0, r0, #(0xff << 24) /* Ignore flags */
- beq boot_cpu /* If all other fields are 0, we win */
+ bics r12, r0, #(0xff << 24) /* Mask out flags to get CPU ID */
+ beq boot_cpu /* If we''re CPU 0, boot now */
-1: wfi
- b 1b
-
+ /* Non-boot CPUs wait here to be woken up one at a time.
+ * This is basically an open-coded spin-lock to serialize. */
+ ldr r0, =boot_gate /* VA of gate */
+ add r0, r0, r10 /* PA of gate */
+ mov r1, #1 /* (1 == locked) */
+1: wfe
+ ldrex r2, [r0] /* Linked read of current value */
+ teq r2, #0 /* (0 == unlocked) */
+ strexeq r2, r1, [r0] /* Matching update -> locked */
+ teq r2, #0 /* (0 == succeeded) */
+ bne 1b
+
boot_cpu:
#ifdef EARLY_UART_ADDRESS
- /* Say hello */
ldr r11, =EARLY_UART_ADDRESS /* r11 := UART base address */
- bl init_uart
+ teq r12, #0 /* CPU 0 sets up the UART too */
+ bleq init_uart
+ PRINT("- CPU ")
+ mov r0, r12
+ bl putn
+ PRINT(" booting -\r\n")
#endif
/* Check that this CPU has Hyp mode */
@@ -85,7 +99,6 @@ boot_cpu:
and r0, r0, #0xf000 /* Bits 12-15 define virt extensions */
teq r0, #0x1000 /* Must == 0x1 or may be incompatible */
beq 1f
- bl putn
PRINT("- CPU doesn''t support the virtualization extensions
-\r\n")
b fail
1:
@@ -185,6 +198,10 @@ hyp:
mov r5, #0 /* r4:r5 is paddr (xen_pagetable) */
mcrr CP64(r4, r5, HTTBR)
+ /* Non-boot CPUs don''t need to rebuild the pagetable */
+ teq r12, #0
+ bne pt_ready
+
/* Build the baseline idle pagetable''s first-level entries */
ldr r1, =xen_second
add r1, r1, r10 /* r1 := paddr (xen_second) */
@@ -226,6 +243,7 @@ hyp:
add r4, r4, #8
strd r2, r3, [r1, r4] /* Map it in the early boot slot */
+pt_ready:
PRINT("- Turning on paging -\r\n")
ldr r1, =paging /* Explicit vaddr, not RIP-relative */
@@ -238,7 +256,7 @@ hyp:
paging:
#ifdef EARLY_UART_ADDRESS
- /* Recover the UART address in the new address space */
+ /* Recover the UART address in the new address space. */
lsl r11, #11
lsr r11, #11 /* UART base''s offset from 2MB base */
adr r0, start
@@ -246,14 +264,57 @@ paging:
add r11, r11, r0 /* r11 := vaddr (UART base address) */
#endif
- PRINT("- Entering C -\r\n")
+ PRINT("- Ready -\r\n")
+ /* The boot CPU should go straight into C now */
+ teq r12, #0
+ beq launch
+
+ /* Signal the next non-boot CPU to come and join us here */
+ ldr r0, =boot_gate /* VA of gate */
+ add r0, r0, r10 /* PA of gate */
+ mov r1, #0 /* (0 == unlocked) */
+ str r1, [r0]
+ dsb
+ isb
+ sev
+
+ /* Move on to the relocated pagetables */
+ mov r0, #0
+ ldr r4, =boot_httbr /* VA of HTTBR value stashed by CPU 0 */
+ add r4, r4, r10 /* PA of it */
+ ldrd r4, r5, [r4] /* Actual value */
+ mcrr CP64(r4, r5, HTTBR)
+ mcr CP32(r0, TLBIALLH) /* Flush hypervisor TLB */
+ mcr CP32(r0, BPIALL) /* Flush branch predictor */
+ dsb /* Ensure completion of TLB+BP flush */
+ isb
+ /* Now, the UART is in its proper fixmap address */
+ ldrne r11, =FIXMAP_ADDR(FIXMAP_CONSOLE)
+
+ /* Non-boot CPUs report that they''ve got this far */
+ ldr r0, =ready_cpus
+ ldr r1, [r0] /* Read count of ready CPUs */
+ add r1, r1, #1 /* ++ */
+ str r1, [r0] /* Writeback */
+ dsb
+
+ /* Here, the non-boot CPUs must wait again -- they''re now running on
+ * the boot CPU''s pagetables so it''s safe for the boot CPU
to
+ * overwrite the non-relocated copy of Xen. Once it''s done that,
+ * and brought up the memory allocator, non-boot CPUs can get their
+ * own stacks and enter C. */
+1: wfe
+ b 1b
+
+launch:
ldr sp, =init_stack /* Supply a stack */
add sp, #STACK_SIZE /* (which grows down from the top). */
sub sp, #CPUINFO_sizeof /* Make room for CPU save record */
mov r0, r10 /* Marshal args: - phys_offset */
mov r1, r7 /* - machine type */
mov r2, r8 /* - ATAG address */
+ mov r3, r12 /* - CPU ID */
b start_xen /* and disappear into the land of C */
/* Fail-stop
@@ -288,7 +349,7 @@ puts:
tst r2, #0x8 /* Check BUSY bit */
bne puts /* Wait for the UART to be ready */
ldrb r2, [r0], #1 /* Load next char */
- teq r2, #0 /* Exit on nul*/
+ teq r2, #0 /* Exit on nul */
moveq pc, lr
str r2, [r11] /* -> UARTDR (Data Register) */
b puts
@@ -308,10 +369,8 @@ 1: ldr r2, [r11, #0x18] /* <- UA
lsl r0, #4 /* Roll it through one nybble at a time */
subs r3, r3, #1
bne 1b
- adr r0, crlf /* Finish with a newline */
- b puts
+ mov pc, lr
-crlf: .asciz "\r\n"
hex: .ascii "0123456789abcdef"
.align 2
diff -r 8f322ab53857 -r 1e9c6bd7cc99 xen/arch/arm/mm.c
--- a/xen/arch/arm/mm.c Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/arch/arm/mm.c Thu Feb 23 17:39:59 2012 +0000
@@ -36,6 +36,9 @@ lpae_t xen_second[LPAE_ENTRIES*4] __attr
static lpae_t xen_fixmap[LPAE_ENTRIES] __attribute__((__aligned__(4096)));
static lpae_t xen_xenmap[LPAE_ENTRIES] __attribute__((__aligned__(4096)));
+/* Non-boot CPUs use this to find the correct pagetables. */
+uint64_t boot_httbr;
+
/* Limits of the Xen heap */
unsigned long xenheap_mfn_start, xenheap_mfn_end;
unsigned long xenheap_virt_end;
@@ -156,14 +159,6 @@ void __init setup_pagetables(unsigned lo
lpae_t pte, *p;
int i;
- if ( boot_phys_offset != 0 )
- {
- /* Remove the old identity mapping of the boot paddr */
- pte.bits = 0;
- dest_va = (unsigned long)_start + boot_phys_offset;
- write_pte(xen_second + second_linear_offset(dest_va), pte);
- }
-
xen_paddr = device_tree_get_xen_paddr();
/* Map the destination in the boot misc area. */
@@ -186,11 +181,19 @@ void __init setup_pagetables(unsigned lo
for ( i = 0; i < 4; i++)
p[i].pt.base += (phys_offset - boot_phys_offset) >> PAGE_SHIFT;
p = (void *) xen_second + dest_va - (unsigned long) _start;
+ if ( boot_phys_offset != 0 )
+ {
+ /* Remove the old identity mapping of the boot paddr */
+ pte.bits = 0;
+ dest_va = (unsigned long)_start + boot_phys_offset;
+ p[second_linear_offset(dest_va)] = pte;
+ }
for ( i = 0; i < 4 * LPAE_ENTRIES; i++)
if ( p[i].pt.valid )
p[i].pt.base += (phys_offset - boot_phys_offset) >>
PAGE_SHIFT;
/* Change pagetables to the copy in the relocated Xen */
+ boot_httbr = (unsigned long) xen_pgtable + phys_offset;
asm volatile (
STORE_CP64(0, HTTBR) /* Change translation base */
"dsb;" /* Ensure visibility of HTTBR
update */
@@ -198,7 +201,7 @@ void __init setup_pagetables(unsigned lo
STORE_CP32(0, BPIALL) /* Flush branch predictor */
"dsb;" /* Ensure completion of TLB+BP
flush */
"isb;"
- : : "r" ((unsigned long) xen_pgtable + phys_offset) :
"memory");
+ : : "r" (boot_httbr) : "memory");
/* Undo the temporary map */
pte.bits = 0;
diff -r 8f322ab53857 -r 1e9c6bd7cc99 xen/arch/arm/setup.c
--- a/xen/arch/arm/setup.c Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/arch/arm/setup.c Thu Feb 23 17:39:59 2012 +0000
@@ -44,7 +44,12 @@ static unsigned int __initdata max_cpus
/* Xen stack for bringing up the first CPU. */
unsigned char __initdata init_stack[STACK_SIZE]
__attribute__((__aligned__(STACK_SIZE)));
-extern char __init_begin[], __init_end[], __bss_start[];
+extern const char __init_begin[], __init_end[], __bss_start[];
+
+/* Spinlock for serializing CPU bringup */
+unsigned long __initdata boot_gate = 1;
+/* Number of non-boot CPUs ready to enter C */
+unsigned long __initdata ready_cpus = 0;
static __attribute_used__ void init_done(void)
{
@@ -151,14 +156,17 @@ static void __init setup_mm(unsigned lon
end_boot_allocator();
}
+/* C entry point for boot CPU */
void __init start_xen(unsigned long boot_phys_offset,
unsigned long arm_type,
- unsigned long atag_paddr)
-
+ unsigned long atag_paddr,
+ unsigned long cpuid)
{
void *fdt;
size_t fdt_size;
- int i;
+ int cpus, i;
+ paddr_t gate_pa;
+ unsigned long *gate;
fdt = (void *)BOOT_MISC_VIRT_START
+ (atag_paddr & ((1 << SECOND_SHIFT) - 1));
@@ -174,6 +182,22 @@ void __init start_xen(unsigned long boot
console_init_preirq();
#endif
+ cpus = gic_init();
+
+ printk("Waiting for %i other CPUs to be ready\n", cpus - 1);
+ /* Bring the other CPUs up to paging before the original
+ * copy of .text gets overwritten. We need to use the unrelocated
+ * copy of boot_gate as that''s the one the others can see. */
+ gate_pa = ((unsigned long) &boot_gate) + boot_phys_offset;
+ gate = map_domain_page(gate_pa >> PAGE_SHIFT) + (gate_pa &
~PAGE_MASK);
+ *gate = 0;
+ unmap_domain_page(gate);
+ /* Now send an event to wake the first non-boot CPU */
+ asm volatile("dsb; isb; sev");
+ /* And wait for them all to be ready. */
+ while ( ready_cpus + 1 < cpus )
+ smp_rmb();
+
__set_current((struct vcpu *)0xfffff000); /* debug sanity */
idle_vcpu[0] = current;
set_processor_id(0); /* needed early, for smp_processor_id() */
@@ -208,8 +232,6 @@ void __init start_xen(unsigned long boot
init_IRQ();
- gic_init();
-
gic_route_irqs();
init_maintenance_interrupt();
# HG changeset patch
# User Tim Deegan <tim@xen.org>
# Date 1330018799 0
# Node ID 3b1d7a91a2596baca178e8b5610b3cbc299fa5ea
# Parent 1e9c6bd7cc99d1af0107aa927ee2ba03721449b7
arm: per-cpu areas
Signed-off-by: Tim Deegan <tim@xen.org>
diff -r 1e9c6bd7cc99 -r 3b1d7a91a259 xen/arch/arm/Makefile
--- a/xen/arch/arm/Makefile Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/arch/arm/Makefile Thu Feb 23 17:39:59 2012 +0000
@@ -13,6 +13,7 @@ obj-y += irq.o
obj-y += kernel.o
obj-y += mm.o
obj-y += p2m.o
+obj-y += percpu.o
obj-y += guestcopy.o
obj-y += setup.o
obj-y += time.o
diff -r 1e9c6bd7cc99 -r 3b1d7a91a259 xen/arch/arm/dummy.S
--- a/xen/arch/arm/dummy.S Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/arch/arm/dummy.S Thu Feb 23 17:39:59 2012 +0000
@@ -14,7 +14,6 @@ DUMMY(per_cpu__cpu_core_mask);
DUMMY(per_cpu__cpu_sibling_mask);
DUMMY(node_online_map);
DUMMY(smp_send_state_dump);
-DUMMY(__per_cpu_offset);
/* PIRQ support */
DUMMY(alloc_pirq_struct);
diff -r 1e9c6bd7cc99 -r 3b1d7a91a259 xen/arch/arm/percpu.c
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/xen/arch/arm/percpu.c Thu Feb 23 17:39:59 2012 +0000
@@ -0,0 +1,85 @@
+#include <xen/config.h>
+#include <xen/percpu.h>
+#include <xen/cpu.h>
+#include <xen/init.h>
+#include <xen/mm.h>
+#include <xen/rcupdate.h>
+
+unsigned long __per_cpu_offset[NR_CPUS];
+#define INVALID_PERCPU_AREA (-(long)__per_cpu_start)
+#define PERCPU_ORDER (get_order_from_bytes(__per_cpu_data_end-__per_cpu_start))
+
+void __init percpu_init_areas(void)
+{
+ unsigned int cpu;
+ for ( cpu = 1; cpu < NR_CPUS; cpu++ )
+ __per_cpu_offset[cpu] = INVALID_PERCPU_AREA;
+}
+
+static int init_percpu_area(unsigned int cpu)
+{
+ char *p;
+ if ( __per_cpu_offset[cpu] != INVALID_PERCPU_AREA )
+ return -EBUSY;
+ if ( (p = alloc_xenheap_pages(PERCPU_ORDER, 0)) == NULL )
+ return -ENOMEM;
+ memset(p, 0, __per_cpu_data_end - __per_cpu_start);
+ __per_cpu_offset[cpu] = p - __per_cpu_start;
+ return 0;
+}
+
+struct free_info {
+ unsigned int cpu;
+ struct rcu_head rcu;
+};
+static DEFINE_PER_CPU(struct free_info, free_info);
+
+static void _free_percpu_area(struct rcu_head *head)
+{
+ struct free_info *info = container_of(head, struct free_info, rcu);
+ unsigned int cpu = info->cpu;
+ char *p = __per_cpu_start + __per_cpu_offset[cpu];
+ free_xenheap_pages(p, PERCPU_ORDER);
+ __per_cpu_offset[cpu] = INVALID_PERCPU_AREA;
+}
+
+static void free_percpu_area(unsigned int cpu)
+{
+ struct free_info *info = &per_cpu(free_info, cpu);
+ info->cpu = cpu;
+ call_rcu(&info->rcu, _free_percpu_area);
+}
+
+static int cpu_percpu_callback(
+ struct notifier_block *nfb, unsigned long action, void *hcpu)
+{
+ unsigned int cpu = (unsigned long)hcpu;
+ int rc = 0;
+
+ switch ( action )
+ {
+ case CPU_UP_PREPARE:
+ rc = init_percpu_area(cpu);
+ break;
+ case CPU_UP_CANCELED:
+ case CPU_DEAD:
+ free_percpu_area(cpu);
+ break;
+ default:
+ break;
+ }
+
+ return !rc ? NOTIFY_DONE : notifier_from_errno(rc);
+}
+
+static struct notifier_block cpu_percpu_nfb = {
+ .notifier_call = cpu_percpu_callback,
+ .priority = 100 /* highest priority */
+};
+
+static int __init percpu_presmp_init(void)
+{
+ register_cpu_notifier(&cpu_percpu_nfb);
+ return 0;
+}
+presmp_initcall(percpu_presmp_init);
diff -r 1e9c6bd7cc99 -r 3b1d7a91a259 xen/include/asm-arm/percpu.h
--- a/xen/include/asm-arm/percpu.h Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/include/asm-arm/percpu.h Thu Feb 23 17:39:59 2012 +0000
@@ -12,8 +12,11 @@ void percpu_init_areas(void);
__attribute__((__section__(".bss.percpu" #suffix))) \
__typeof__(type) per_cpu_##name
-#define per_cpu(var, cpu) ((&per_cpu__##var)[cpu?0:0])
-#define __get_cpu_var(var) per_cpu__##var
+
+#define per_cpu(var, cpu) \
+ (*RELOC_HIDE(&per_cpu__##var, __per_cpu_offset[cpu]))
+#define __get_cpu_var(var) \
+ (*RELOC_HIDE(&per_cpu__##var, get_cpu_info()->per_cpu_offset))
#define DECLARE_PER_CPU(type, name) extern __typeof__(type) per_cpu__##name
# HG changeset patch
# User Tim Deegan <tim@xen.org>
# Date 1330018799 0
# Node ID fd78d23ba19de4129e21cdc7303848b105057227
# Parent 3b1d7a91a2596baca178e8b5610b3cbc299fa5ea
arm: start plumbing in SMP bringup in C
Still a noop, but no longer just a dummy symbol.
Signed-off-by: Tim Deegan <tim@xen.org>
diff -r 3b1d7a91a259 -r fd78d23ba19d xen/arch/arm/dummy.S
--- a/xen/arch/arm/dummy.S Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/arch/arm/dummy.S Thu Feb 23 17:39:59 2012 +0000
@@ -7,9 +7,6 @@ x: .word 0xe7f000f0 /* Undefined instruc
x: mov pc, lr
/* SMP support */
-DUMMY(__cpu_die);
-DUMMY(__cpu_disable);
-DUMMY(__cpu_up);
DUMMY(per_cpu__cpu_core_mask);
DUMMY(per_cpu__cpu_sibling_mask);
DUMMY(node_online_map);
diff -r 3b1d7a91a259 -r fd78d23ba19d xen/arch/arm/setup.c
--- a/xen/arch/arm/setup.c Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/arch/arm/setup.c Thu Feb 23 17:39:59 2012 +0000
@@ -38,9 +38,6 @@
#include <asm/setup.h>
#include "gic.h"
-/* maxcpus: maximum number of CPUs to activate. */
-static unsigned int __initdata max_cpus = NR_CPUS;
-
/* Xen stack for bringing up the first CPU. */
unsigned char __initdata init_stack[STACK_SIZE]
__attribute__((__aligned__(STACK_SIZE)));
@@ -206,7 +203,7 @@ void __init start_xen(unsigned long boot
cpumask_set_cpu(smp_processor_id(), &cpu_online_map);
cpumask_set_cpu(smp_processor_id(), &cpu_present_map);
- smp_prepare_cpus(max_cpus);
+ smp_prepare_cpus(cpus);
init_xen_time();
@@ -253,7 +250,7 @@ void __init start_xen(unsigned long boot
for_each_present_cpu ( i )
{
- if ( (num_online_cpus() < max_cpus) && !cpu_online(i) )
+ if ( (num_online_cpus() < cpus) && !cpu_online(i) )
{
int ret = cpu_up(i);
if ( ret != 0 )
diff -r 3b1d7a91a259 -r fd78d23ba19d xen/arch/arm/smpboot.c
--- a/xen/arch/arm/smpboot.c Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/arch/arm/smpboot.c Thu Feb 23 17:39:59 2012 +0000
@@ -19,6 +19,7 @@
#include <xen/cpumask.h>
#include <xen/smp.h>
#include <xen/init.h>
+#include <xen/errno.h>
cpumask_t cpu_online_map;
EXPORT_SYMBOL(cpu_online_map);
@@ -30,16 +31,40 @@ EXPORT_SYMBOL(cpu_possible_map);
void __init
smp_prepare_cpus (unsigned int max_cpus)
{
- set_processor_id(0); /* needed early, for smp_processor_id() */
+ int i;
+ set_processor_id(0); /* needed early, for smp_processor_id() */
- cpumask_clear(&cpu_online_map);
- cpumask_clear(&cpu_present_map);
- cpumask_clear(&cpu_possible_map);
- cpumask_set_cpu(0, &cpu_online_map);
- cpumask_set_cpu(0, &cpu_present_map);
- cpumask_set_cpu(0, &cpu_possible_map);
- return;
+ cpumask_clear(&cpu_online_map);
+ cpumask_set_cpu(0, &cpu_online_map);
+
+ cpumask_clear(&cpu_possible_map);
+ for ( i = 0; i < max_cpus; i++ )
+ cpumask_set_cpu(i, &cpu_possible_map);
+ cpumask_copy(&cpu_present_map, &cpu_possible_map);
}
+
+/* Bring up a non-boot CPU */
+int __cpu_up(unsigned int cpu)
+{
+ /* Not yet... */
+ return -ENODEV;
+}
+
+/* Shut down the current CPU */
+void __cpu_disable(void)
+{
+ /* TODO: take down timers, GIC, &c. */
+ BUG();
+}
+
+/* Wait for a remote CPU to die */
+void __cpu_die(unsigned int cpu)
+{
+ /* TODO: interlock with __cpu_disable */
+ BUG();
+}
+
+
/*
* Local variables:
* mode: C
# HG changeset patch
# User Tim Deegan <tim@xen.org>
# Date 1330018799 0
# Node ID d35b52e5fde829dfbaf3da73e0716d004faded2f
# Parent fd78d23ba19de4129e21cdc7303848b105057227
arm: Boot secondary CPUs into C
Signed-off-by: Tim Deegan <tim@xen.org>
diff -r fd78d23ba19d -r d35b52e5fde8 xen/arch/arm/gic.c
--- a/xen/arch/arm/gic.c Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/arch/arm/gic.c Thu Feb 23 17:39:59 2012 +0000
@@ -241,7 +241,6 @@ static void __cpuinit gic_hyp_init(void)
vtr = GICH[GICH_VTR];
nr_lrs = (vtr & GICH_VTR_NRLRGS) + 1;
- printk("GICH: %d list registers available\n", nr_lrs);
GICH[GICH_HCR] = GICH_HCR_EN;
GICH[GICH_MISR] = GICH_MISR_EOI;
@@ -274,6 +273,15 @@ int __init gic_init(void)
return gic.cpus;
}
+/* Set up the per-CPU parts of the GIC for a secondary CPU */
+void __cpuinit gic_init_secondary_cpu(void)
+{
+ spin_lock(&gic.lock);
+ gic_cpu_init();
+ gic_hyp_init();
+ spin_unlock(&gic.lock);
+}
+
void gic_route_irqs(void)
{
/* XXX should get these from DT */
diff -r fd78d23ba19d -r d35b52e5fde8 xen/arch/arm/gic.h
--- a/xen/arch/arm/gic.h Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/arch/arm/gic.h Thu Feb 23 17:39:59 2012 +0000
@@ -140,6 +140,8 @@ extern int gic_route_irq_to_guest(struct
extern void gic_interrupt(struct cpu_user_regs *regs, int is_fiq);
/* Bring up the interrupt controller, and report # cpus attached */
extern int gic_init(void);
+/* Bring up a secondary CPU''s per-CPU GIC interface */
+extern void gic_init_secondary_cpu(void);
/* setup the gic virtual interface for a guest */
extern void gicv_setup(struct domain *d);
#endif
diff -r fd78d23ba19d -r d35b52e5fde8 xen/arch/arm/head.S
--- a/xen/arch/arm/head.S Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/arch/arm/head.S Thu Feb 23 17:39:59 2012 +0000
@@ -305,17 +305,23 @@ paging:
* and brought up the memory allocator, non-boot CPUs can get their
* own stacks and enter C. */
1: wfe
- b 1b
+ dsb
+ ldr r0, =smp_up_cpu
+ ldr r1, [r0] /* Which CPU is being booted? */
+ teq r1, r12 /* Is it us? */
+ bne 1b
launch:
- ldr sp, =init_stack /* Supply a stack */
+ ldr r0, =init_stacks /* Find the boot-time stack */
+ ldr sp, [r0, r12, lsl #2] /* (the one for this CPU) */
add sp, #STACK_SIZE /* (which grows down from the top). */
sub sp, #CPUINFO_sizeof /* Make room for CPU save record */
mov r0, r10 /* Marshal args: - phys_offset */
mov r1, r7 /* - machine type */
mov r2, r8 /* - ATAG address */
- mov r3, r12 /* - CPU ID */
- b start_xen /* and disappear into the land of C */
+ movs r3, r12 /* - CPU ID */
+ beq start_xen /* and disappear into the land of C */
+ b start_secondary /* (to the appropriate entry point) */
/* Fail-stop
* r0: string explaining why */
diff -r fd78d23ba19d -r d35b52e5fde8 xen/arch/arm/setup.c
--- a/xen/arch/arm/setup.c Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/arch/arm/setup.c Thu Feb 23 17:39:59 2012 +0000
@@ -38,9 +38,6 @@
#include <asm/setup.h>
#include "gic.h"
-/* Xen stack for bringing up the first CPU. */
-unsigned char __initdata init_stack[STACK_SIZE]
__attribute__((__aligned__(STACK_SIZE)));
-
extern const char __init_begin[], __init_end[], __bss_start[];
/* Spinlock for serializing CPU bringup */
@@ -179,6 +176,8 @@ void __init start_xen(unsigned long boot
console_init_preirq();
#endif
+ percpu_init_areas();
+
cpus = gic_init();
printk("Waiting for %i other CPUs to be ready\n", cpus - 1);
diff -r fd78d23ba19d -r d35b52e5fde8 xen/arch/arm/smpboot.c
--- a/xen/arch/arm/smpboot.c Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/arch/arm/smpboot.c Thu Feb 23 17:39:59 2012 +0000
@@ -16,10 +16,15 @@
* GNU General Public License for more details.
*/
+#include <xen/cpu.h>
#include <xen/cpumask.h>
+#include <xen/errno.h>
+#include <xen/init.h>
+#include <xen/mm.h>
+#include <xen/sched.h>
#include <xen/smp.h>
-#include <xen/init.h>
-#include <xen/errno.h>
+#include <xen/softirq.h>
+#include "gic.h"
cpumask_t cpu_online_map;
EXPORT_SYMBOL(cpu_online_map);
@@ -28,6 +33,14 @@ EXPORT_SYMBOL(cpu_online_map);
cpumask_t cpu_possible_map;
EXPORT_SYMBOL(cpu_possible_map);
+/* Xen stack for bringing up the first CPU. */
+static unsigned char cpu0_stack[STACK_SIZE]
+ __attribute__((__aligned__(STACK_SIZE)));
+
+/* Remember where the boot-time stacks live */
+/* TODO: overhaul this, and get_processor_id(), for per-vcpu stacks */
+unsigned char *init_stacks[NR_CPUS] = { cpu0_stack, 0 };
+
void __init
smp_prepare_cpus (unsigned int max_cpus)
{
@@ -43,11 +56,43 @@ smp_prepare_cpus (unsigned int max_cpus)
cpumask_copy(&cpu_present_map, &cpu_possible_map);
}
-/* Bring up a non-boot CPU */
-int __cpu_up(unsigned int cpu)
+/* Shared state for coordinating CPU bringup */
+unsigned long smp_up_cpu = 0;
+
+/* Boot the current CPU */
+void __cpuinit start_secondary(unsigned long boot_phys_offset,
+ unsigned long arm_type,
+ unsigned long atag_paddr,
+ unsigned long cpuid)
{
- /* Not yet... */
- return -ENODEV;
+ memset(get_cpu_info(), 0, sizeof (struct cpu_info));
+
+ /* TODO: handle boards where CPUIDs are not contiguous */
+ set_processor_id(cpuid);
+
+ /* Setup Hyp vector base */
+ WRITE_CP32((uint32_t) hyp_traps_vector, HVBAR);
+
+ dprintk(XENLOG_DEBUG, "CPU %li awake.\n", cpuid);
+
+ gic_init_secondary_cpu();
+
+ set_current(idle_vcpu[cpuid]);
+ this_cpu(curr_vcpu) = current;
+
+ /* Run local notifiers */
+ notify_cpu_starting(cpuid);
+ wmb();
+
+ /* Now report this CPU is up */
+ cpumask_set_cpu(cpuid, &cpu_online_map);
+ wmb();
+
+ local_irq_enable();
+
+ dprintk(XENLOG_DEBUG, "CPU %li booted.\n", cpuid);
+
+ startup_cpu_idle_loop();
}
/* Shut down the current CPU */
@@ -57,6 +102,32 @@ void __cpu_disable(void)
BUG();
}
+/* Bring up a remote CPU */
+int __cpu_up(unsigned int cpu)
+{
+ unsigned char *stack;
+
+ /* Remote CPU needs a stack to boot on. */
+ stack = alloc_xenheap_pages(STACK_ORDER, 0);
+ if ( !stack )
+ return -ENOMEM;
+ ASSERT(init_stacks[cpu] == NULL);
+ init_stacks[cpu] = stack;
+
+ /* Unblock the CPU. It should be waiting in the loop in head.S
+ * for an event to arrive when smp_up_cpu matches its cpuid. */
+ smp_up_cpu = cpu;
+ asm volatile("dsb; isb; sev");
+
+ while ( !cpu_online(cpu) )
+ {
+ cpu_relax();
+ process_pending_softirqs();
+ }
+
+ return 0;
+}
+
/* Wait for a remote CPU to die */
void __cpu_die(unsigned int cpu)
{
# HG changeset patch
# User Tim Deegan <tim@xen.org>
# Date 1330018799 0
# Node ID a78bc9b8421492e0545c6d52c7a32b9de9737d61
# Parent d35b52e5fde829dfbaf3da73e0716d004faded2f
arm: SMP CPU shutdown
For completeness, also implelent the CPU shutdown path.
Signed-off-by: TIm Deegan <tim@xen.org>
diff -r d35b52e5fde8 -r a78bc9b84214 xen/arch/arm/domain.c
--- a/xen/arch/arm/domain.c Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/arch/arm/domain.c Thu Feb 23 17:39:59 2012 +0000
@@ -31,12 +31,10 @@ void idle_loop(void)
{
for ( ; ; )
{
- /* TODO
- if ( cpu_is_offline(smp_processor_id()) )
- play_dead();
- (*pm_idle)();
- BUG();
- */
+ if ( cpu_is_offline(smp_processor_id()) )
+ stop_cpu();
+
+ /* TODO: (*pm_idle)(); */
do_tasklet();
do_softirq();
}
diff -r d35b52e5fde8 -r a78bc9b84214 xen/arch/arm/gic.c
--- a/xen/arch/arm/gic.c Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/arch/arm/gic.c Thu Feb 23 17:39:59 2012 +0000
@@ -235,6 +235,11 @@ static void __cpuinit gic_cpu_init(void)
GICC[GICC_CTLR] = GICC_CTL_ENABLE|GICC_CTL_EOI; /* Turn on delivery */
}
+static void gic_cpu_disable(void)
+{
+ GICC[GICC_CTLR] = 0;
+}
+
static void __cpuinit gic_hyp_init(void)
{
uint32_t vtr;
@@ -246,6 +251,11 @@ static void __cpuinit gic_hyp_init(void)
GICH[GICH_MISR] = GICH_MISR_EOI;
}
+static void __cpuinit gic_hyp_disable(void)
+{
+ GICH[GICH_HCR] = 0;
+}
+
/* Set up the GIC */
int __init gic_init(void)
{
@@ -282,6 +292,15 @@ void __cpuinit gic_init_secondary_cpu(vo
spin_unlock(&gic.lock);
}
+/* Shut down the per-CPU GIC interface */
+void gic_disable_cpu(void)
+{
+ spin_lock(&gic.lock);
+ gic_cpu_disable();
+ gic_hyp_disable();
+ spin_unlock(&gic.lock);
+}
+
void gic_route_irqs(void)
{
/* XXX should get these from DT */
diff -r d35b52e5fde8 -r a78bc9b84214 xen/arch/arm/gic.h
--- a/xen/arch/arm/gic.h Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/arch/arm/gic.h Thu Feb 23 17:39:59 2012 +0000
@@ -142,6 +142,8 @@ extern void gic_interrupt(struct cpu_use
extern int gic_init(void);
/* Bring up a secondary CPU''s per-CPU GIC interface */
extern void gic_init_secondary_cpu(void);
+/* Take down a CPU''s per-CPU GIC interface */
+extern void gic_disable_cpu(void);
/* setup the gic virtual interface for a guest */
extern void gicv_setup(struct domain *d);
#endif
diff -r d35b52e5fde8 -r a78bc9b84214 xen/arch/arm/smpboot.c
--- a/xen/arch/arm/smpboot.c Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/arch/arm/smpboot.c Thu Feb 23 17:39:59 2012 +0000
@@ -18,6 +18,7 @@
#include <xen/cpu.h>
#include <xen/cpumask.h>
+#include <xen/delay.h>
#include <xen/errno.h>
#include <xen/init.h>
#include <xen/mm.h>
@@ -58,6 +59,7 @@ smp_prepare_cpus (unsigned int max_cpus)
/* Shared state for coordinating CPU bringup */
unsigned long smp_up_cpu = 0;
+static bool_t cpu_is_dead = 0;
/* Boot the current CPU */
void __cpuinit start_secondary(unsigned long boot_phys_offset,
@@ -98,8 +100,35 @@ void __cpuinit start_secondary(unsigned
/* Shut down the current CPU */
void __cpu_disable(void)
{
- /* TODO: take down timers, GIC, &c. */
- BUG();
+ unsigned int cpu = get_processor_id();
+
+ local_irq_disable();
+ gic_disable_cpu();
+ /* Allow any queued timer interrupts to get serviced */
+ local_irq_enable();
+ mdelay(1);
+ local_irq_disable();
+
+ /* It''s now safe to remove this processor from the online map */
+ cpumask_clear_cpu(cpu, &cpu_online_map);
+
+ if ( cpu_disable_scheduler(cpu) )
+ BUG();
+ mb();
+
+ /* Return to caller; eventually the IPI mecahnism will unwind and the
+ * scheduler will drop to the idle loop, which will call stop_cpu(). */
+}
+
+void stop_cpu(void)
+{
+ local_irq_disable();
+ cpu_is_dead = 1;
+ /* Make sure the write happens before we sleep forever */
+ dsb();
+ isb();
+ while ( 1 )
+ asm volatile("wfi");
}
/* Bring up a remote CPU */
@@ -131,8 +160,19 @@ int __cpu_up(unsigned int cpu)
/* Wait for a remote CPU to die */
void __cpu_die(unsigned int cpu)
{
- /* TODO: interlock with __cpu_disable */
- BUG();
+ unsigned int i = 0;
+
+ while ( !cpu_is_dead )
+ {
+ mdelay(100);
+ cpu_relax();
+ process_pending_softirqs();
+ if ( (++i % 10) == 0 )
+ printk(KERN_ERR "CPU %u still not dead...\n", cpu);
+ mb();
+ }
+ cpu_is_dead = 0;
+ mb();
}
diff -r d35b52e5fde8 -r a78bc9b84214 xen/include/asm-arm/smp.h
--- a/xen/include/asm-arm/smp.h Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/include/asm-arm/smp.h Thu Feb 23 17:39:59 2012 +0000
@@ -14,6 +14,8 @@ DECLARE_PER_CPU(cpumask_var_t, cpu_core_
#define raw_smp_processor_id() (get_processor_id())
+extern void stop_cpu(void);
+
#endif
/*
* Local variables:
# HG changeset patch
# User Tim Deegan <tim@xen.org>
# Date 1330018799 0
# Node ID 8a2d38ab67ccaf8637e223feb0d0678433974e93
# Parent a78bc9b8421492e0545c6d52c7a32b9de9737d61
arm: Shutdown and reboot
Reboot runes grabbed from linux''s SP810 reset function.
Doesn''t seem to work on the model, though.
Signed-off-by: Tim Deegan <tim@xen.org>
diff -r a78bc9b84214 -r 8a2d38ab67cc xen/arch/arm/shutdown.c
--- a/xen/arch/arm/shutdown.c Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/arch/arm/shutdown.c Thu Feb 23 17:39:59 2012 +0000
@@ -1,18 +1,63 @@
#include <xen/config.h>
+#include <xen/console.h>
+#include <xen/cpu.h>
+#include <xen/delay.h>
#include <xen/lib.h>
+#include <xen/mm.h>
+#include <xen/smp.h>
+
+static void raw_machine_reset(void)
+{
+#ifdef SP810_ADDRESS
+ /* Use the SP810 system controller to force a reset */
+ volatile uint32_t *sp810;
+ set_fixmap(FIXMAP_MISC, SP810_ADDRESS >> PAGE_SHIFT, DEV_SHARED);
+ sp810 = ((uint32_t *)
+ (FIXMAP_ADDR(FIXMAP_MISC) + (SP810_ADDRESS & ~PAGE_MASK)));
+ sp810[0] = 0x3; /* switch to slow mode */
+ dsb(); isb();
+ sp810[1] = 0x1; /* writing any value to SCSYSSTAT reg will reset system */
+ dsb(); isb();
+ clear_fixmap(FIXMAP_MISC);
+#endif
+}
+
+static void halt_this_cpu(void *arg)
+{
+ __cpu_disable();
+ stop_cpu();
+}
void machine_halt(void)
{
- /* TODO: halt */
- while(1) ;
+ watchdog_disable();
+ console_start_sync();
+ local_irq_enable();
+ smp_call_function(halt_this_cpu, NULL, 0);
+ halt_this_cpu(NULL);
}
void machine_restart(unsigned int delay_millisecs)
{
- /* TODO: restart */
- printk("Cannot restart yet\n");
- while(1);
+ int timeout = 10;
+
+ local_irq_enable();
+ smp_call_function(halt_this_cpu, NULL, 0);
+ local_irq_disable();
+
+ mdelay(delay_millisecs);
+
+ /* Wait at most another 10ms for all other CPUs to go offline. */
+ while ( (num_online_cpus() > 1) && (timeout-- > 0) )
+ mdelay(1);
+
+ while ( 1 )
+ {
+ raw_machine_reset();
+ mdelay(100);
+ }
}
+
/*
* Local variables:
* mode: C
diff -r a78bc9b84214 -r 8a2d38ab67cc xen/include/asm-arm/config.h
--- a/xen/include/asm-arm/config.h Thu Feb 23 17:39:59 2012 +0000
+++ b/xen/include/asm-arm/config.h Thu Feb 23 17:39:59 2012 +0000
@@ -119,6 +119,9 @@ extern unsigned long frametable_virt_end
#define GIC_CR_OFFSET 0x2000
#define GIC_HR_OFFSET 0x4000 /* Guess work
http://lists.infradead.org/pipermail/linux-arm-kernel/2011-September/064219.html
*/
#define GIC_VR_OFFSET 0x6000 /* Virtual Machine CPU interface) */
+/* Board-specific: base address of system controller */
+#define SP810_ADDRESS 0x1C020000
+
#endif /* __ARM_CONFIG_H__ */
/*
On 23/02/12 17:40, Tim Deegan wrote:> arm: implement udelay() > > Signed-off-by: Tim Deegan <tim@xen.org> >[...]> diff -r 4a7c14209131 -r ec051056db2b xen/arch/arm/time.c > --- a/xen/arch/arm/time.c Thu Feb 23 17:39:59 2012 +0000 > +++ b/xen/arch/arm/time.c Thu Feb 23 17:39:59 2012 +0000 > @@ -171,6 +171,16 @@ void __cpuinit init_timer_interrupt(void > request_irq(30, timer_interrupt, 0, "phytimer", NULL); > } > > +/* Wait a set number of microseconds */ > +void udelay(unsigned long usecs) > +{ > + s_time_t deadline = get_s_time() + 1000 * (s_time_t) usecs; > + do { > + dsb(); > + isb();What are these barriers for? David> + } while ( get_s_time() - deadline < 0 ); > +} > + > /* > * Local variables: > * mode: C
On Thu, 2012-02-23 at 17:40 +0000, Tim Deegan wrote: [...]> + /* Signal the next non-boot CPU to come and join us here */ > + ldr r0, =boot_gate /* VA of gate */ > + add r0, r0, r10 /* PA of gate */ > + mov r1, #0 /* (0 == unlocked) */ > + str r1, [r0] > + dsb > + isb > + sevHere we have released the next CPU from the holding pen... [...]> + /* Non-boot CPUs report that they''ve got this far */ > + ldr r0, =ready_cpus > + ldr r1, [r0] /* Read count of ready CPUs */ > + add r1, r1, #1 /* ++ */ > + str r1, [r0] /* Writeback */ > + dsb... and here we do a non-atomic update of a shared variable. What prevents the following CPU from catching us up and conflicting here? Would we be better signalling the next CPU after the increment instead? Ian.
Ian Campbell
2012-Feb-27 17:32 UTC
Re: [PATCH 03 of 10] arm: Move some GIC distributor init out of the per-CPU init function
On Thu, 2012-02-23 at 17:40 +0000, Tim Deegan wrote:> # HG changeset patch > # User Tim Deegan <tim@xen.org> > # Date 1330018799 0 > # Node ID 437ad1207a175c9ad376871f3f4c075dbcd5b6e6 > # Parent ec051056db2b6d37344629e2f01d17240099d5ec > arm: Move some GIC distributor init out of the per-CPU init function > > Signed-off-by: Tim Deegan <tim@xen.org> > > diff -r ec051056db2b -r 437ad1207a17 xen/arch/arm/gic.c > --- a/xen/arch/arm/gic.c Thu Feb 23 17:39:59 2012 +0000 > +++ b/xen/arch/arm/gic.c Thu Feb 23 17:39:59 2012 +0000 > @@ -216,14 +216,6 @@ static void __init gic_dist_init(void) > for ( i = 32; i < gic.lines; i += 32 ) > GICD[GICD_ICENABLER + i / 32] = ~0ul; > > - /* Turn on the distributor */ > - GICD[GICD_CTLR] = GICD_CTL_ENABLE; > -} > - > -static void __cpuinit gic_cpu_init(void) > -{ > - int i; > - > /* Disable all PPI and enable all SGI */ > GICD[GICD_ICENABLER] = 0xffff0000; /* Disable all PPI */ > GICD[GICD_ISENABLER] = 0x0000ffff; /* Enable all SGI */PPIs and SGIs are per physical-CPU and therefore, I think, the GICD registers of various sorts which refer to the first 32 interrupts are per physical-CPU as well. IOW moving these from gic_cpu_init to gic_dist_init is wrong?> @@ -231,6 +223,12 @@ static void __cpuinit gic_cpu_init(void) > for (i = 0; i < 32; i += 4) > GICD[GICD_IPRIORITYR + i / 4] = 0xa0a0a0a0; > > + /* Turn on the distributor */ > + GICD[GICD_CTLR] = GICD_CTL_ENABLE; > +} > + > +static void __cpuinit gic_cpu_init(void) > +{ > /* Local settings: interface controller */ > GICC[GICC_PMR] = 0xff; /* Don''t mask by priority */ > GICC[GICC_BPR] = 0; /* Finest granularity of priority */
At 19:03 +0000 on 23 Feb (1330023834), David Vrabel wrote:> On 23/02/12 17:40, Tim Deegan wrote: > > arm: implement udelay() > > > > Signed-off-by: Tim Deegan <tim@xen.org> > > > [...] > > diff -r 4a7c14209131 -r ec051056db2b xen/arch/arm/time.c > > --- a/xen/arch/arm/time.c Thu Feb 23 17:39:59 2012 +0000 > > +++ b/xen/arch/arm/time.c Thu Feb 23 17:39:59 2012 +0000 > > @@ -171,6 +171,16 @@ void __cpuinit init_timer_interrupt(void > > request_irq(30, timer_interrupt, 0, "phytimer", NULL); > > } > > > > +/* Wait a set number of microseconds */ > > +void udelay(unsigned long usecs) > > +{ > > + s_time_t deadline = get_s_time() + 1000 * (s_time_t) usecs; > > + do { > > + dsb(); > > + isb(); > > What are these barriers for?To make sure the CPU doesn''t hoist any instructions past the wait loop. :) They don''t really have to be inside the loop body; I can change that if you like. Tim.
At 19:16 +0000 on 23 Feb (1330024560), Ian Campbell wrote:> On Thu, 2012-02-23 at 17:40 +0000, Tim Deegan wrote: > [...] > > + /* Signal the next non-boot CPU to come and join us here */ > > + ldr r0, =boot_gate /* VA of gate */ > > + add r0, r0, r10 /* PA of gate */ > > + mov r1, #0 /* (0 == unlocked) */ > > + str r1, [r0] > > + dsb > > + isb > > + sev > > Here we have released the next CPU from the holding pen... > > [...] > > + /* Non-boot CPUs report that they''ve got this far */ > > + ldr r0, =ready_cpus > > + ldr r1, [r0] /* Read count of ready CPUs */ > > + add r1, r1, #1 /* ++ */ > > + str r1, [r0] /* Writeback */ > > + dsb > > ... and here we do a non-atomic update of a shared variable. > > What prevents the following CPU from catching us up and conflicting > here? > > Would we be better signalling the next CPU after the increment instead?Yes, we would. I''ll fix that. Tim.
Tim Deegan
2012-Feb-27 19:30 UTC
Re: [PATCH 03 of 10] arm: Move some GIC distributor init out of the per-CPU init function
At 17:32 +0000 on 27 Feb (1330363933), Ian Campbell wrote:> On Thu, 2012-02-23 at 17:40 +0000, Tim Deegan wrote: > > # HG changeset patch > > # User Tim Deegan <tim@xen.org> > > # Date 1330018799 0 > > # Node ID 437ad1207a175c9ad376871f3f4c075dbcd5b6e6 > > # Parent ec051056db2b6d37344629e2f01d17240099d5ec > > arm: Move some GIC distributor init out of the per-CPU init function > > > > Signed-off-by: Tim Deegan <tim@xen.org> > > > > diff -r ec051056db2b -r 437ad1207a17 xen/arch/arm/gic.c > > --- a/xen/arch/arm/gic.c Thu Feb 23 17:39:59 2012 +0000 > > +++ b/xen/arch/arm/gic.c Thu Feb 23 17:39:59 2012 +0000 > > @@ -216,14 +216,6 @@ static void __init gic_dist_init(void) > > for ( i = 32; i < gic.lines; i += 32 ) > > GICD[GICD_ICENABLER + i / 32] = ~0ul; > > > > - /* Turn on the distributor */ > > - GICD[GICD_CTLR] = GICD_CTL_ENABLE; > > -} > > - > > -static void __cpuinit gic_cpu_init(void) > > -{ > > - int i; > > - > > /* Disable all PPI and enable all SGI */ > > GICD[GICD_ICENABLER] = 0xffff0000; /* Disable all PPI */ > > GICD[GICD_ISENABLER] = 0x0000ffff; /* Enable all SGI */ > > PPIs and SGIs are per physical-CPU and therefore, I think, the GICD > registers of various sorts which refer to the first 32 interrupts are > per physical-CPU as well. IOW moving these from gic_cpu_init to > gic_dist_init is wrong?Yep, you''re right ISENABLER0 and ICENABLER0 are banked. I''ll replace this with a comment explaining that. Cheers, Tim.
On Thu, 2012-02-23 at 17:40 +0000, Tim Deegan wrote:> This patch series implements SMP boot for arch/arm, as far as getting > all CPUs up and running the idle loop. > > The first few patches are semi-independent cleanups and improvements, > most of which are needed for the SMP patches later.I have applied: 01: arm: strip xen binary 04: arm: Handle booting on SMP platforms I looked at taking a few others but they had dependencies on things which I or others have commented on. I''ll go through and ack them as appropriate now. Ian.
Ian Campbell
2012-Feb-28 10:24 UTC
Re: [PATCH 03 of 10] arm: Move some GIC distributor init out of the per-CPU init function
On Mon, 2012-02-27 at 19:30 +0000, Tim Deegan wrote:> At 17:32 +0000 on 27 Feb (1330363933), Ian Campbell wrote: > > On Thu, 2012-02-23 at 17:40 +0000, Tim Deegan wrote: > > > # HG changeset patch > > > # User Tim Deegan <tim@xen.org> > > > # Date 1330018799 0 > > > # Node ID 437ad1207a175c9ad376871f3f4c075dbcd5b6e6 > > > # Parent ec051056db2b6d37344629e2f01d17240099d5ec > > > arm: Move some GIC distributor init out of the per-CPU init function > > > > > > Signed-off-by: Tim Deegan <tim@xen.org> > > > > > > diff -r ec051056db2b -r 437ad1207a17 xen/arch/arm/gic.c > > > --- a/xen/arch/arm/gic.c Thu Feb 23 17:39:59 2012 +0000 > > > +++ b/xen/arch/arm/gic.c Thu Feb 23 17:39:59 2012 +0000 > > > @@ -216,14 +216,6 @@ static void __init gic_dist_init(void) > > > for ( i = 32; i < gic.lines; i += 32 ) > > > GICD[GICD_ICENABLER + i / 32] = ~0ul; > > > > > > - /* Turn on the distributor */ > > > - GICD[GICD_CTLR] = GICD_CTL_ENABLE; > > > -} > > > - > > > -static void __cpuinit gic_cpu_init(void) > > > -{ > > > - int i; > > > - > > > /* Disable all PPI and enable all SGI */ > > > GICD[GICD_ICENABLER] = 0xffff0000; /* Disable all PPI */ > > > GICD[GICD_ISENABLER] = 0x0000ffff; /* Enable all SGI */ > > > > PPIs and SGIs are per physical-CPU and therefore, I think, the GICD > > registers of various sorts which refer to the first 32 interrupts are > > per physical-CPU as well. IOW moving these from gic_cpu_init to > > gic_dist_init is wrong? > > Yep, you''re right ISENABLER0 and ICENABLER0 are banked.BTW so are GICD_IPRIORITYR0..4 which are initialised just outside the context here. More generally all the per-IRQ registers are banked for the first few which cover the PPIs and SGIs.> I''ll replace this with a comment explaining that.Thanks.
On Thu, 2012-02-23 at 17:40 +0000, Tim Deegan wrote:> # HG changeset patch > # User Tim Deegan <tim@xen.org> > # Date 1330018799 0 > # Node ID 3b1d7a91a2596baca178e8b5610b3cbc299fa5ea > # Parent 1e9c6bd7cc99d1af0107aa927ee2ba03721449b7 > arm: per-cpu areas > > Signed-off-by: Tim Deegan <tim@xen.org>I tried to apply this along with #1 and #4 but the result hung at just after freeing initial memory. I expect that''s due to missing #2,#3 or #5 rather than a bug here. With that in mind: Acked-by: Ian Campbell <ian.campbell@citrix.com>> > diff -r 1e9c6bd7cc99 -r 3b1d7a91a259 xen/arch/arm/Makefile > --- a/xen/arch/arm/Makefile Thu Feb 23 17:39:59 2012 +0000 > +++ b/xen/arch/arm/Makefile Thu Feb 23 17:39:59 2012 +0000 > @@ -13,6 +13,7 @@ obj-y += irq.o > obj-y += kernel.o > obj-y += mm.o > obj-y += p2m.o > +obj-y += percpu.o > obj-y += guestcopy.o > obj-y += setup.o > obj-y += time.o > diff -r 1e9c6bd7cc99 -r 3b1d7a91a259 xen/arch/arm/dummy.S > --- a/xen/arch/arm/dummy.S Thu Feb 23 17:39:59 2012 +0000 > +++ b/xen/arch/arm/dummy.S Thu Feb 23 17:39:59 2012 +0000 > @@ -14,7 +14,6 @@ DUMMY(per_cpu__cpu_core_mask); > DUMMY(per_cpu__cpu_sibling_mask); > DUMMY(node_online_map); > DUMMY(smp_send_state_dump); > -DUMMY(__per_cpu_offset); > > /* PIRQ support */ > DUMMY(alloc_pirq_struct); > diff -r 1e9c6bd7cc99 -r 3b1d7a91a259 xen/arch/arm/percpu.c > --- /dev/null Thu Jan 01 00:00:00 1970 +0000 > +++ b/xen/arch/arm/percpu.c Thu Feb 23 17:39:59 2012 +0000 > @@ -0,0 +1,85 @@ > +#include <xen/config.h> > +#include <xen/percpu.h> > +#include <xen/cpu.h> > +#include <xen/init.h> > +#include <xen/mm.h> > +#include <xen/rcupdate.h> > + > +unsigned long __per_cpu_offset[NR_CPUS]; > +#define INVALID_PERCPU_AREA (-(long)__per_cpu_start) > +#define PERCPU_ORDER (get_order_from_bytes(__per_cpu_data_end-__per_cpu_start)) > + > +void __init percpu_init_areas(void) > +{ > + unsigned int cpu; > + for ( cpu = 1; cpu < NR_CPUS; cpu++ ) > + __per_cpu_offset[cpu] = INVALID_PERCPU_AREA; > +} > + > +static int init_percpu_area(unsigned int cpu) > +{ > + char *p; > + if ( __per_cpu_offset[cpu] != INVALID_PERCPU_AREA ) > + return -EBUSY; > + if ( (p = alloc_xenheap_pages(PERCPU_ORDER, 0)) == NULL ) > + return -ENOMEM; > + memset(p, 0, __per_cpu_data_end - __per_cpu_start); > + __per_cpu_offset[cpu] = p - __per_cpu_start; > + return 0; > +} > + > +struct free_info { > + unsigned int cpu; > + struct rcu_head rcu; > +}; > +static DEFINE_PER_CPU(struct free_info, free_info); > + > +static void _free_percpu_area(struct rcu_head *head) > +{ > + struct free_info *info = container_of(head, struct free_info, rcu); > + unsigned int cpu = info->cpu; > + char *p = __per_cpu_start + __per_cpu_offset[cpu]; > + free_xenheap_pages(p, PERCPU_ORDER); > + __per_cpu_offset[cpu] = INVALID_PERCPU_AREA; > +} > + > +static void free_percpu_area(unsigned int cpu) > +{ > + struct free_info *info = &per_cpu(free_info, cpu); > + info->cpu = cpu; > + call_rcu(&info->rcu, _free_percpu_area); > +} > + > +static int cpu_percpu_callback( > + struct notifier_block *nfb, unsigned long action, void *hcpu) > +{ > + unsigned int cpu = (unsigned long)hcpu; > + int rc = 0; > + > + switch ( action ) > + { > + case CPU_UP_PREPARE: > + rc = init_percpu_area(cpu); > + break; > + case CPU_UP_CANCELED: > + case CPU_DEAD: > + free_percpu_area(cpu); > + break; > + default: > + break; > + } > + > + return !rc ? NOTIFY_DONE : notifier_from_errno(rc); > +} > + > +static struct notifier_block cpu_percpu_nfb = { > + .notifier_call = cpu_percpu_callback, > + .priority = 100 /* highest priority */ > +}; > + > +static int __init percpu_presmp_init(void) > +{ > + register_cpu_notifier(&cpu_percpu_nfb); > + return 0; > +} > +presmp_initcall(percpu_presmp_init); > diff -r 1e9c6bd7cc99 -r 3b1d7a91a259 xen/include/asm-arm/percpu.h > --- a/xen/include/asm-arm/percpu.h Thu Feb 23 17:39:59 2012 +0000 > +++ b/xen/include/asm-arm/percpu.h Thu Feb 23 17:39:59 2012 +0000 > @@ -12,8 +12,11 @@ void percpu_init_areas(void); > __attribute__((__section__(".bss.percpu" #suffix))) \ > __typeof__(type) per_cpu_##name > > -#define per_cpu(var, cpu) ((&per_cpu__##var)[cpu?0:0]) > -#define __get_cpu_var(var) per_cpu__##var > + > +#define per_cpu(var, cpu) \ > + (*RELOC_HIDE(&per_cpu__##var, __per_cpu_offset[cpu])) > +#define __get_cpu_var(var) \ > + (*RELOC_HIDE(&per_cpu__##var, get_cpu_info()->per_cpu_offset)) > > #define DECLARE_PER_CPU(type, name) extern __typeof__(type) per_cpu__##name >
Ian Campbell
2012-Feb-28 10:27 UTC
Re: [PATCH 07 of 10] arm: start plumbing in SMP bringup in C
On Thu, 2012-02-23 at 17:40 +0000, Tim Deegan wrote:> # HG changeset patch > # User Tim Deegan <tim@xen.org> > # Date 1330018799 0 > # Node ID fd78d23ba19de4129e21cdc7303848b105057227 > # Parent 3b1d7a91a2596baca178e8b5610b3cbc299fa5ea > arm: start plumbing in SMP bringup in C > > Still a noop, but no longer just a dummy symbol. > > Signed-off-by: Tim Deegan <tim@xen.org>Acked-by: Ian Campbell <ian.campbell@citrix.com>> diff -r 3b1d7a91a259 -r fd78d23ba19d xen/arch/arm/dummy.S > --- a/xen/arch/arm/dummy.S Thu Feb 23 17:39:59 2012 +0000 > +++ b/xen/arch/arm/dummy.S Thu Feb 23 17:39:59 2012 +0000 > @@ -7,9 +7,6 @@ x: .word 0xe7f000f0 /* Undefined instruc > x: mov pc, lr > > /* SMP support */ > -DUMMY(__cpu_die); > -DUMMY(__cpu_disable); > -DUMMY(__cpu_up); > DUMMY(per_cpu__cpu_core_mask); > DUMMY(per_cpu__cpu_sibling_mask); > DUMMY(node_online_map); > diff -r 3b1d7a91a259 -r fd78d23ba19d xen/arch/arm/setup.c > --- a/xen/arch/arm/setup.c Thu Feb 23 17:39:59 2012 +0000 > +++ b/xen/arch/arm/setup.c Thu Feb 23 17:39:59 2012 +0000 > @@ -38,9 +38,6 @@ > #include <asm/setup.h> > #include "gic.h" > > -/* maxcpus: maximum number of CPUs to activate. */ > -static unsigned int __initdata max_cpus = NR_CPUS; > - > /* Xen stack for bringing up the first CPU. */ > unsigned char __initdata init_stack[STACK_SIZE] __attribute__((__aligned__(STACK_SIZE))); > > @@ -206,7 +203,7 @@ void __init start_xen(unsigned long boot > cpumask_set_cpu(smp_processor_id(), &cpu_online_map); > cpumask_set_cpu(smp_processor_id(), &cpu_present_map); > > - smp_prepare_cpus(max_cpus); > + smp_prepare_cpus(cpus); > > init_xen_time(); > > @@ -253,7 +250,7 @@ void __init start_xen(unsigned long boot > > for_each_present_cpu ( i ) > { > - if ( (num_online_cpus() < max_cpus) && !cpu_online(i) ) > + if ( (num_online_cpus() < cpus) && !cpu_online(i) ) > { > int ret = cpu_up(i); > if ( ret != 0 ) > diff -r 3b1d7a91a259 -r fd78d23ba19d xen/arch/arm/smpboot.c > --- a/xen/arch/arm/smpboot.c Thu Feb 23 17:39:59 2012 +0000 > +++ b/xen/arch/arm/smpboot.c Thu Feb 23 17:39:59 2012 +0000 > @@ -19,6 +19,7 @@ > #include <xen/cpumask.h> > #include <xen/smp.h> > #include <xen/init.h> > +#include <xen/errno.h> > > cpumask_t cpu_online_map; > EXPORT_SYMBOL(cpu_online_map); > @@ -30,16 +31,40 @@ EXPORT_SYMBOL(cpu_possible_map); > void __init > smp_prepare_cpus (unsigned int max_cpus) > { > - set_processor_id(0); /* needed early, for smp_processor_id() */ > + int i; > + set_processor_id(0); /* needed early, for smp_processor_id() */ > > - cpumask_clear(&cpu_online_map); > - cpumask_clear(&cpu_present_map); > - cpumask_clear(&cpu_possible_map); > - cpumask_set_cpu(0, &cpu_online_map); > - cpumask_set_cpu(0, &cpu_present_map); > - cpumask_set_cpu(0, &cpu_possible_map); > - return; > + cpumask_clear(&cpu_online_map); > + cpumask_set_cpu(0, &cpu_online_map); > + > + cpumask_clear(&cpu_possible_map); > + for ( i = 0; i < max_cpus; i++ ) > + cpumask_set_cpu(i, &cpu_possible_map); > + cpumask_copy(&cpu_present_map, &cpu_possible_map); > } > + > +/* Bring up a non-boot CPU */ > +int __cpu_up(unsigned int cpu) > +{ > + /* Not yet... */ > + return -ENODEV; > +} > + > +/* Shut down the current CPU */ > +void __cpu_disable(void) > +{ > + /* TODO: take down timers, GIC, &c. */ > + BUG(); > +} > + > +/* Wait for a remote CPU to die */ > +void __cpu_die(unsigned int cpu) > +{ > + /* TODO: interlock with __cpu_disable */ > + BUG(); > +} > + > + > /* > * Local variables: > * mode: C
On Thu, 2012-02-23 at 17:40 +0000, Tim Deegan wrote:> # HG changeset patch > # User Tim Deegan <tim@xen.org> > # Date 1330018799 0 > # Node ID d35b52e5fde829dfbaf3da73e0716d004faded2f > # Parent fd78d23ba19de4129e21cdc7303848b105057227 > arm: Boot secondary CPUs into C > > Signed-off-by: Tim Deegan <tim@xen.org>I think this need rebasing a bit past the per-vcpu stacks changes so I wont'' ack just yet although I like the general shape of it.> @@ -28,6 +33,14 @@ EXPORT_SYMBOL(cpu_online_map); > cpumask_t cpu_possible_map; > EXPORT_SYMBOL(cpu_possible_map); > > +/* Xen stack for bringing up the first CPU. */ > +static unsigned char cpu0_stack[STACK_SIZE] > + __attribute__((__aligned__(STACK_SIZE))); > + > +/* Remember where the boot-time stacks live */ > +/* TODO: overhaul this, and get_processor_id(), for per-vcpu stacks */ > +unsigned char *init_stacks[NR_CPUS] = { cpu0_stack, 0 };Do we need to track the per-CPU idle stacks after the CPUs have been brought up? We are already serialized due to the use of the shared smp_up_cpu so could we get away with a single "smp_bringup_args" area and avoid the NR_CPUS array? Ian.
On Thu, 2012-02-23 at 17:40 +0000, Tim Deegan wrote:> # HG changeset patch > # User Tim Deegan <tim@xen.org> > # Date 1330018799 0 > # Node ID a78bc9b8421492e0545c6d52c7a32b9de9737d61 > # Parent d35b52e5fde829dfbaf3da73e0716d004faded2f > arm: SMP CPU shutdown > > For completeness, also implelent the CPU shutdown path.Does something free the init_stack for a CPU as it goes down? Alternatively the bring up path could reuse it if the CPU came back but we don''t seem to do that either.> Signed-off-by: TIm Deegan <tim@xen.org>Typo here. [...]> + /* It''s now safe to remove this processor from the online map */ > + cpumask_clear_cpu(cpu, &cpu_online_map); > + > + if ( cpu_disable_scheduler(cpu) ) > + BUG(); > + mb(); > + > + /* Return to caller; eventually the IPI mecahnism will unwind and themechanism> + * scheduler will drop to the idle loop, which will call stop_cpu(). */ > +} > + > +void stop_cpu(void) > +{ > + local_irq_disable(); > + cpu_is_dead = 1;Do we lock this variable? What stops multiple CPUs coming down at once?> + /* Make sure the write happens before we sleep forever */ > + dsb(); > + isb(); > + while ( 1 ) > + asm volatile("wfi"); > } > > /* Bring up a remote CPU */Ian.
On Thu, 2012-02-23 at 17:40 +0000, Tim Deegan wrote:> # HG changeset patch > # User Tim Deegan <tim@xen.org> > # Date 1330018799 0 > # Node ID 8a2d38ab67ccaf8637e223feb0d0678433974e93 > # Parent a78bc9b8421492e0545c6d52c7a32b9de9737d61 > arm: Shutdown and reboot > > Reboot runes grabbed from linux''s SP810 reset function. > Doesn''t seem to work on the model, though. > > Signed-off-by: Tim Deegan <tim@xen.org>Acked-by: Ian Campbell <ian.campbell@citrix.com> But please add an "XXX get this from device tree" somewhere appropriate ;-)> > diff -r a78bc9b84214 -r 8a2d38ab67cc xen/arch/arm/shutdown.c > --- a/xen/arch/arm/shutdown.c Thu Feb 23 17:39:59 2012 +0000 > +++ b/xen/arch/arm/shutdown.c Thu Feb 23 17:39:59 2012 +0000 > @@ -1,18 +1,63 @@ > #include <xen/config.h> > +#include <xen/console.h> > +#include <xen/cpu.h> > +#include <xen/delay.h> > #include <xen/lib.h> > +#include <xen/mm.h> > +#include <xen/smp.h> > + > +static void raw_machine_reset(void) > +{ > +#ifdef SP810_ADDRESS > + /* Use the SP810 system controller to force a reset */ > + volatile uint32_t *sp810; > + set_fixmap(FIXMAP_MISC, SP810_ADDRESS >> PAGE_SHIFT, DEV_SHARED); > + sp810 = ((uint32_t *) > + (FIXMAP_ADDR(FIXMAP_MISC) + (SP810_ADDRESS & ~PAGE_MASK))); > + sp810[0] = 0x3; /* switch to slow mode */ > + dsb(); isb(); > + sp810[1] = 0x1; /* writing any value to SCSYSSTAT reg will reset system */ > + dsb(); isb(); > + clear_fixmap(FIXMAP_MISC); > +#endif > +} > + > +static void halt_this_cpu(void *arg) > +{ > + __cpu_disable(); > + stop_cpu(); > +} > > void machine_halt(void) > { > - /* TODO: halt */ > - while(1) ; > + watchdog_disable(); > + console_start_sync(); > + local_irq_enable(); > + smp_call_function(halt_this_cpu, NULL, 0); > + halt_this_cpu(NULL); > } > > void machine_restart(unsigned int delay_millisecs) > { > - /* TODO: restart */ > - printk("Cannot restart yet\n"); > - while(1); > + int timeout = 10; > + > + local_irq_enable(); > + smp_call_function(halt_this_cpu, NULL, 0); > + local_irq_disable(); > + > + mdelay(delay_millisecs); > + > + /* Wait at most another 10ms for all other CPUs to go offline. */ > + while ( (num_online_cpus() > 1) && (timeout-- > 0) ) > + mdelay(1); > + > + while ( 1 ) > + { > + raw_machine_reset(); > + mdelay(100); > + } > } > + > /* > * Local variables: > * mode: C > diff -r a78bc9b84214 -r 8a2d38ab67cc xen/include/asm-arm/config.h > --- a/xen/include/asm-arm/config.h Thu Feb 23 17:39:59 2012 +0000 > +++ b/xen/include/asm-arm/config.h Thu Feb 23 17:39:59 2012 +0000 > @@ -119,6 +119,9 @@ extern unsigned long frametable_virt_end > #define GIC_CR_OFFSET 0x2000 > #define GIC_HR_OFFSET 0x4000 /* Guess work http://lists.infradead.org/pipermail/linux-arm-kernel/2011-September/064219.html */ > #define GIC_VR_OFFSET 0x6000 /* Virtual Machine CPU interface) */ > +/* Board-specific: base address of system controller */ > +#define SP810_ADDRESS 0x1C020000 > + > > #endif /* __ARM_CONFIG_H__ */ > /*
At 10:38 +0000 on 28 Feb (1330425518), Ian Campbell wrote:> On Thu, 2012-02-23 at 17:40 +0000, Tim Deegan wrote: > > # HG changeset patch > > # User Tim Deegan <tim@xen.org> > > # Date 1330018799 0 > > # Node ID a78bc9b8421492e0545c6d52c7a32b9de9737d61 > > # Parent d35b52e5fde829dfbaf3da73e0716d004faded2f > > arm: SMP CPU shutdown > > > > For completeness, also implelent the CPU shutdown path. > > Does something free the init_stack for a CPU as it goes down?Er, no. :)> Alternatively the bring up path could reuse it if the CPU came back but > we don''t seem to do that either.I''ll make it so.> > Signed-off-by: TIm Deegan <tim@xen.org> > > Typo here.WHat TYpo? I ALways SIgn MY NAme THat WAy.> [...] > > + /* It''s now safe to remove this processor from the online map */ > > + cpumask_clear_cpu(cpu, &cpu_online_map); > > + > > + if ( cpu_disable_scheduler(cpu) ) > > + BUG(); > > + mb(); > > + > > + /* Return to caller; eventually the IPI mecahnism will unwind and the > > mechanismta.> > + * scheduler will drop to the idle loop, which will call stop_cpu(). */ > > +} > > + > > +void stop_cpu(void) > > +{ > > + local_irq_disable(); > > + cpu_is_dead = 1; > > Do we lock this variable? What stops multiple CPUs coming down at once?IIRC that''s serialized at a higher level, and the x86 equivalent similarly uses static variables for signalling. Will double-check before I re-send this series (probably next week). Cheers, Tim.
On Thu, 2012-02-23 at 17:40 +0000, Tim Deegan wrote:> This patch series implements SMP boot for arch/arm, as far as getting > all CPUs up and running the idle loop.What additional steps are needed when building the model to get an SMP system? Ideally this would eventually be documented in http://wiki.xen.org/wiki/Xen_ARMv7_with_Virtualization_Extensions/FastModels but it is probably a bit premature for that right now. I think it is sufficient to do the following after opening the project ("sgcanvas <SGPROJ>") and before clicking the "Build" button. * Right click the header of the "cluster" in the diagram (the top bit of the box which says "cluster" in it) * Select "Object Properties" from the context menu * In the "Parameters" tab update the "num_cores" variable, e.g. to "0x4" * Click build and continue as usual. Do that sound about right? It appears to work for me at least. I''ve not applied all your patches so I can''t see how many processors there really are. Ian.
At 14:36 +0000 on 29 Feb (1330526182), Ian Campbell wrote:> On Thu, 2012-02-23 at 17:40 +0000, Tim Deegan wrote: > > This patch series implements SMP boot for arch/arm, as far as getting > > all CPUs up and running the idle loop. > > What additional steps are needed when building the model to get an SMP > system? > > Ideally this would eventually be documented in > http://wiki.xen.org/wiki/Xen_ARMv7_with_Virtualization_Extensions/FastModels but it is probably a bit premature for that right now. > > I think it is sufficient to do the following after opening the project > ("sgcanvas <SGPROJ>") and before clicking the "Build" button. > > * Right click the header of the "cluster" in the diagram (the top > bit of the box which says "cluster" in it) > * Select "Object Properties" from the context menu > * In the "Parameters" tab update the "num_cores" variable, e.g. to > "0x4" > * Click build and continue as usual.Yes, that is exactly what I did. Tim.