Skip to content

Commit

Permalink
[merge] Merge remote-tracking branch 'pr/rpi3'
Browse files Browse the repository at this point in the history
  • Loading branch information
travisg committed Aug 26, 2016
2 parents d0b90c2 + 173046e commit f2c9072
Show file tree
Hide file tree
Showing 17 changed files with 500 additions and 77 deletions.
10 changes: 5 additions & 5 deletions arch/arm/arm/mp.c
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,9 @@

#if WITH_DEV_INTERRUPT_ARM_GIC
#include <dev/interrupt/arm_gic.h>
#elif PLATFORM_BCM2835
/* bcm2835 has a weird custom interrupt controller for MP */
extern void bcm2835_send_ipi(uint irq, uint cpu_mask);
#elif PLATFORM_BCM28XX
/* bcm28xx has a weird custom interrupt controller for MP */
extern void bcm28xx_send_ipi(uint irq, uint cpu_mask);
#else
#error need other implementation of interrupt controller that can ipi
#endif
Expand All @@ -58,11 +58,11 @@ status_t arch_mp_send_ipi(mp_cpu_mask_t target, mp_ipi_t ipi)
#endif
arm_gic_sgi(gic_ipi_num, flags, target);
}
#elif PLATFORM_BCM2835
#elif PLATFORM_BCM28XX
/* filter out targets outside of the range of cpus we care about */
target &= ((1UL << SMP_MAX_CPUS) - 1);
if (target != 0) {
bcm2835_send_ipi(ipi, target);
bcm28xx_send_ipi(ipi, target);
}
#endif

Expand Down
55 changes: 55 additions & 0 deletions arch/arm64/asm.S
Original file line number Diff line number Diff line change
Expand Up @@ -83,5 +83,60 @@ FUNCTION(arm64_el3_to_el1)

eret

FUNCTION(arm64_elX_to_el1)
mrs x4, CurrentEL

cmp x4, #(0b01 << 2)
bne .notEL1
/* Already in EL1 */
ret

.notEL1:
cmp x4, #(0b10 << 2)
beq .inEL2


/* set EL2 to 64bit */
mrs x4, scr_el3
orr x4, x4, #(1<<10)
msr scr_el3, x4


adr x4, .Ltarget
msr elr_el3, x4

mov x4, #((0b1111 << 6) | (0b0101)) /* EL1h runlevel */
msr spsr_el3, x4
b .confEL1

.inEL2:
adr x4, .Ltarget
msr elr_el2, x4
mov x4, #((0b1111 << 6) | (0b0101)) /* EL1h runlevel */
msr spsr_el2, x4



.confEL1:
/* disable EL2 coprocessor traps */
mov x0, #0x33ff
msr cptr_el2, x0

/* set EL1 to 64bit */
mov x0, #(1<<31)
msr hcr_el2, x0

/* disable EL1 FPU traps */
mov x0, #(0b11<<20)
msr cpacr_el1, x0

/* set up the EL1 bounce interrupt */
mov x0, sp
msr sp_el1, x0

isb
eret


.Ltarget:
ret
2 changes: 1 addition & 1 deletion arch/arm64/mmu.c
Original file line number Diff line number Diff line change
Expand Up @@ -650,7 +650,7 @@ void arch_mmu_context_switch(arch_aspace_t *aspace)

if (TRACE_CONTEXT_SWITCH)
TRACEF("ttbr 0x%llx, tcr 0x%llx\n", ttbr, tcr);
ARM64_TLBI(aside1, MMU_ARM64_USER_ASID << 48);
ARM64_TLBI(aside1, (uint64_t)MMU_ARM64_USER_ASID << 48);
} else {
tcr = MMU_TCR_FLAGS_KERNEL;

Expand Down
9 changes: 9 additions & 0 deletions arch/arm64/mp.c
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,9 @@

#if WITH_DEV_INTERRUPT_ARM_GIC
#include <dev/interrupt/arm_gic.h>
#elif PLATFORM_BCM28XX
/* bcm28xx has a weird custom interrupt controller for MP */
extern void bcm28xx_send_ipi(uint irq, uint cpu_mask);
#else
#error need other implementation of interrupt controller that can ipi
#endif
Expand All @@ -51,6 +54,12 @@ status_t arch_mp_send_ipi(mp_cpu_mask_t target, mp_ipi_t ipi)
LTRACEF("target 0x%x, gic_ipi %u\n", target, gic_ipi_num);
arm_gic_sgi(gic_ipi_num, ARM_GIC_SGI_FLAG_NS, target);
}
#elif PLATFORM_BCM28XX
/* filter out targets outside of the range of cpus we care about */
target &= ((1UL << SMP_MAX_CPUS) - 1);
if (target != 0) {
bcm28xx_send_ipi(ipi, target);
}
#endif

return NO_ERROR;
Expand Down
46 changes: 40 additions & 6 deletions arch/arm64/start.S
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,10 @@ attr .req x27

.section .text.boot
FUNCTION(_start)
.globl arm_reset
arm_reset:
bl arm64_elX_to_el1

#if WITH_KERNEL_VM
/* enable caches so atomics and spinlocks work */
mrs tmp, sctlr_el1
Expand Down Expand Up @@ -69,6 +73,7 @@ FUNCTION(_start)
add mmu_initial_mapping, mmu_initial_mapping, #:lo12:mmu_initial_mappings

.Linitial_mapping_loop:
/* Read entry of mmu_initial_mappings (likely defined in platform.c) */
ldp paddr, vaddr, [mmu_initial_mapping, #__MMU_INITIAL_MAPPING_PHYS_OFFSET]
ldp size, tmp, [mmu_initial_mapping, #__MMU_INITIAL_MAPPING_SIZE_OFFSET]

Expand All @@ -79,21 +84,44 @@ FUNCTION(_start)
str size, [mmu_initial_mapping, #__MMU_INITIAL_MAPPING_SIZE_OFFSET]

.Lnot_dynamic:
/* if size == 0, end of list */
/* if size == 0, end of list, done with initial mapping */
cbz size, .Linitial_mapping_done
mov mapping_size, size

/* set up the flags */
tbzmask tmp, MMU_INITIAL_MAPPING_FLAG_UNCACHED, .Lnot_uncached
ldr attr, =MMU_INITIAL_MAP_STRONGLY_ORDERED
b .Lmem_type_done

.Lnot_uncached:
/* is this memory mapped to device/peripherals? */
tbzmask tmp, MMU_INITIAL_MAPPING_FLAG_DEVICE, .Lnot_device
ldr attr, =MMU_INITIAL_MAP_DEVICE
b .Lmem_type_done
.Lnot_device:

/* Determine the segment in which the memory resides and set appropriate
* attributes. In order to handle offset kernels, the following rules are
* implemented below:
* KERNEL_BASE to __code_start -read/write (see note below)
* __code_start to __rodata_start (.text) -read only
* __rodata_start to __data_start (.rodata) -read only, execute never
* __data_start to ..... (.data) -read/write
*
* The space below __code_start is presently left as read/write (same as .data)
* mainly as a workaround for the raspberry pi boot process. Boot vectors for
* secondary CPUs are in this area and need to be updated by cpu0 once the system
* is ready to boot the secondary processors.
* TODO: handle this via mmu_initial_mapping entries, which may need to be
* extended with additional flag types
*/
.Lmapping_size_loop:
ldr attr, =MMU_PTE_KERNEL_DATA_FLAGS
ldr tmp, =__code_start
subs size, tmp, vaddr
/* If page is below the entry point (_start) mark as kernel data */
b.hi .Lmem_type_done

ldr attr, =MMU_PTE_KERNEL_RO_FLAGS
ldr tmp, =__rodata_start
subs size, tmp, vaddr
Expand Down Expand Up @@ -134,6 +162,10 @@ FUNCTION(_start)

lsr index, vaddr, index_shift


/* determine the type of page table entry to use given alignment and size
* of the chunk of memory we are mapping
*/
.Lmap_range_one_table_loop:
/* Check if current level allow block descriptors */
cmp index_shift, #MMU_PTE_DESCRIPTOR_BLOCK_MAX_SHIFT
Expand Down Expand Up @@ -234,12 +266,14 @@ FUNCTION(_start)
str tmp2, [page_table0, tmp, lsl #3] /* tt_trampoline[paddr index] = pt entry */

#if WITH_SMP
adr tmp, page_tables_not_ready
adrp tmp, page_tables_not_ready
add tmp, tmp, #:lo12:page_tables_not_ready
str wzr, [tmp]
b .Lpage_tables_ready

.Lmmu_enable_secondary:
adr tmp, page_tables_not_ready
adrp tmp, page_tables_not_ready
add tmp, tmp, #:lo12:page_tables_not_ready
.Lpage_tables_not_ready:
ldr wtmp2, [tmp]
cbnz wtmp2, .Lpage_tables_not_ready
Expand Down Expand Up @@ -307,9 +341,9 @@ FUNCTION(_start)

/* clear bss */
.L__do_bss:
/* clear out the bss */
/* NOTE: relies on __bss_start and __bss_end being 8 byte aligned */
ldr tmp, =__bss_start
/* clear out the bss excluding the stack and kernel translation table */
/* NOTE: relies on __post_prebss_bss_start and __bss_end being 8 byte aligned */
ldr tmp, =__post_prebss_bss_start
ldr tmp2, =__bss_end
sub tmp2, tmp2, tmp
cbz tmp2, .L__bss_loop_done
Expand Down
15 changes: 11 additions & 4 deletions arch/arm64/system-onesegment.ld
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ SECTIONS
/* text/read-only data */
/* set the load address to physical MEMBASE */
.text : AT(%MEMBASE% + %KERNEL_LOAD_OFFSET%) {
__code_start = .;
KEEP(*(.text.boot))
KEEP(*(.text.boot.vectab))
*(.text* .sram.text.glue_7* .gnu.linkonce.t.*)
Expand Down Expand Up @@ -46,6 +47,10 @@ SECTIONS
.ARM.exidx : { *(.ARM.exidx* .gnu.linkonce.armexidx.*) }
__exidx_end = .;

.dummy_post_text : {
__code_end = .;
}

.rodata : ALIGN(4096) {
__rodata_start = .;
__fault_handler_table_start = .;
Expand Down Expand Up @@ -93,19 +98,21 @@ SECTIONS
__data_end = .;
}

/* uninitialized data (in same segment as writable data) */
.bss : ALIGN(8) {
/* unintialized data (in same segment as writable data) */
.bss : ALIGN(4096) {
__bss_start = .;
KEEP(*(.bss.prebss.*))
. = ALIGN(8);
__bss_start = .;
__post_prebss_bss_start = .;
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
. = ALIGN(8);
__bss_end = .;
}

. = ALIGN(8);
/* Align the end to ensure anything after the kernel ends up on its own pages */
. = ALIGN(4096);
_end = .;

. = %KERNEL_BASE% + %MEMSIZE%;
Expand Down
31 changes: 0 additions & 31 deletions platform/bcm2835/include/platform/gic.h

This file was deleted.

2 changes: 1 addition & 1 deletion platform/bcm2835/gpio.c → platform/bcm28xx/gpio.c
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
*/
#include <dev/gpio.h>
#include <errno.h>
#include <platform/bcm2835.h>
#include <platform/bcm28xx.h>
#include <reg.h>

#define NUM_PINS 54
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,10 +23,18 @@
#pragma once

#define SDRAM_BASE 0

/* Note: BCM2836/BCM2837 use different peripheral base than BCM2835 */
#define BCM_PERIPH_BASE_PHYS (0x3f000000U)
#define BCM_PERIPH_SIZE (0x01100000U)

#if BCM2836
#define BCM_PERIPH_BASE_VIRT (0xe0000000U)
#elif BCM2837
#define BCM_PERIPH_BASE_VIRT (0xffffffffc0000000ULL)
#define MEMORY_APERTURE_SIZE (1024 * 1024 * 1024)
#else
#error Unknown BCM28XX Variant
#endif

/* pointer to 'local' peripherals at 0x40000000 */
#define BCM_LOCAL_PERIPH_BASE_VIRT (BCM_PERIPH_BASE_VIRT + 0x01000000)
Expand All @@ -45,7 +53,8 @@
#define I2S_BASE (BCM_PERIPH_BASE_VIRT + 0x203000)
#define SPI0_BASE (BCM_PERIPH_BASE_VIRT + 0x204000)
#define BSC0_BASE (BCM_PERIPH_BASE_VIRT + 0x205000)
#define UART1_BASE (BCM_PERIPH_BASE_VIRT + 0x215000)
#define AUX_BASE (BCM_PERIPH_BASE_VIRT + 0x215000)
#define MINIUART_BASE (BCM_PERIPH_BASE_VIRT + 0x215040)
#define EMMC_BASE (BCM_PERIPH_BASE_VIRT + 0x300000)
#define SMI_BASE (BCM_PERIPH_BASE_VIRT + 0x600000)
#define BSC1_BASE (BCM_PERIPH_BASE_VIRT + 0x804000)
Expand Down
20 changes: 15 additions & 5 deletions platform/bcm2835/intc.c → platform/bcm28xx/intc.c
Original file line number Diff line number Diff line change
Expand Up @@ -24,12 +24,22 @@
#include <assert.h>
#include <err.h>
#include <bits.h>
#include <arch/arm.h>
#include <kernel/spinlock.h>
#include <kernel/thread.h>
#include <kernel/mp.h>
#include <platform/interrupts.h>
#include <platform/bcm2835.h>
#include <platform/bcm28xx.h>

#if defined (BCM2836)
#include <arch/arm.h>
typedef struct arm_iframe arm_platform_iframe_t;
#elif defined (BCM2837)
#include <arch/arm64.h>
typedef struct arm64_iframe_long arm_platform_iframe_t;
#else
#error Unknown BCM28XX Variant
#endif


#define LOCAL_TRACE 0

Expand Down Expand Up @@ -167,7 +177,7 @@ void register_int_handler(unsigned int vector, int_handler handler, void *arg)
spin_unlock_irqrestore(&lock, state);
}

enum handler_return platform_irq(struct arm_iframe *frame)
enum handler_return platform_irq(arm_platform_iframe_t *frame)
{
uint vector;
uint cpu = arch_curr_cpu_num();
Expand Down Expand Up @@ -252,12 +262,12 @@ enum handler_return platform_irq(struct arm_iframe *frame)
return ret;
}

enum handler_return platform_fiq(struct arm_iframe *frame)
enum handler_return platform_fiq(arm_platform_iframe_t *frame)
{
PANIC_UNIMPLEMENTED;
}

void bcm2835_send_ipi(uint irq, uint cpu_mask)
void bcm28xx_send_ipi(uint irq, uint cpu_mask)
{
LTRACEF("irq %u, cpu_mask 0x%x\n", irq, cpu_mask);

Expand Down
Loading

0 comments on commit f2c9072

Please sign in to comment.