linker script, kernel

Asked by Jeremy Li

i'm trying to write a little kernel on stm32.
here is my linker script:/*
 * Memory Spaces Definitions.
 *
 * Need modifying for a specific board.
 * FLASH.ORIGIN: starting address of flash
 * FLASH.LENGTH: length of flash
 * RAM.ORIGIN: starting address of RAM bank 0
 * RAM.LENGTH: length of RAM bank 0
 *
 * The values below can be addressed in further linker scripts
 * using functions like 'ORIGIN(RAM)' or 'LENGTH(RAM)'.
 */

MEMORY
{
  RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
  CCMRAM (xrw) : ORIGIN = 0x10000000, LENGTH = 64K
  FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 1024K
  FLASHB1 (rx) : ORIGIN = 0x00000000, LENGTH = 0
  EXTMEMB0 (rx) : ORIGIN = 0x00000000, LENGTH = 0
  EXTMEMB1 (rx) : ORIGIN = 0x00000000, LENGTH = 0
  EXTMEMB2 (rx) : ORIGIN = 0x00000000, LENGTH = 0
  EXTMEMB3 (rx) : ORIGIN = 0x00000000, LENGTH = 0
  MEMORY_ARRAY (xrw) : ORIGIN = 0x20002000, LENGTH = 32
}

/*
 * For external ram use something like:

   RAM (xrw) : ORIGIN = 0x64000000, LENGTH = 2048K

 */

/*
 * Default linker script for Cortex-M (it includes specifics for STM32F[34]xx).
 *
 * To make use of the multi-region initialisations, define
 * OS_INCLUDE_STARTUP_INIT_MULTIPLE_RAM_SECTIONS for the _startup.c file.
 */
OUTPUT_ARCH(arm)
ENTRY(__kernel_init)

/*
 * The '__stack' definition is required by crt0, do not remove it.
 */
__stack = ORIGIN(RAM) + LENGTH(RAM);

_estack = __stack - 0x010000; /* STM specific definition */

/*
 * Default stack sizes.
 * These are used by the startup in order to allocate stacks
 * for the different modes.
 */

/* __Main_Stack_Size = 1024 ;

//PROVIDE ( _Main_Stack_Size = __Main_Stack_Size ) ;

//__Main_Stack_Limit = __stack - __Main_Stack_Size ;

*/

/* "PROVIDE" allows to easily override these values from an
 * object file or the command line. */
 /*
//PROVIDE ( _Main_Stack_Limit = __Main_Stack_Limit ) ;
*/
/*
 * There will be a link error if there is not this amount of
 * RAM free at the end.
 */

 /* */
_Minimum_Stack_Size = 256 ;

/*
 * Default heap definitions.
 * The heap start immediately after the last statically allocated
 * .sbss/.noinit section, and extends up to the main stack limit.
 */

 /*
//PROVIDE ( _Heap_Begin = _end_noinit ) ;
//PROVIDE ( _Heap_Limit = __stack - __Main_Stack_Size ) ;
*/
/*
 * The entry point is informative, for debuggers and simulators,
 * since the Cortex-M vector points to it anyway.
 */

 /*
//ENTRY(_start)
*/

/* Sections Definitions */

SECTIONS
{

 .init 0x08004000 : AT(0x08004000)
 {
  LONG(LOADADDR(.isr_vector));
        LONG(ADDR(.isr_vector));
        LONG(SIZEOF(.isr_vector));

        LONG(LOADADDR(.text));
        LONG(ADDR(.text));
        LONG(SIZEOF(.text));

        LONG(LOADADDR(.data));
        LONG(ADDR(.data));
        LONG(SIZEOF(.data));

        LONG(ADDR(.bss));
        LONG(SIZEOF(.bss));

 } >FLASH

 . = 0x20000000;

 . = ALIGN(512); /*TODO: fix align*/
    /*
     * For Cortex-M devices, the beginning of the startup code is stored in
     * the .isr_vector section, which goes to FLASH.
     */
    .isr_vector 0x20000000 : AT(LOADADDR(.init)+SIZEOF(.init))
    {
        __vectors_start = .;

        FILL(0xFF)
        /*
        //__isr_start = .;
        //__vectors_start = ABSOLUTE(.) ;
        //__vectors_start__ = ABSOLUTE(.) ; /* STM specific definition */
        *(.isr_vector) /* Interrupt vectors */
  /*KEEP(*(.cfmconfig)) /* Freescale configuration words */

        /*
         * This section is here for convenience, to store the
         * startup code at the beginning of the flash area, hoping that
         * this will increase the readability of the listing.
         */
        /*(.after_vectors .after_vectors.*) /* Startup code and ISR */
  /* //__vectors_end = ABSOLUTE(.) ;
        /*__vectors_end__ = ABSOLUTE(.) ; /* STM specific definition */
        __vectors_end = .;
    } >RAM

 . = ALIGN(4);
    /*
     * The program code is stored in the .text section,
     * which goes to FLASH.
     */
    .text ADDR(.isr_vector)+SIZEOF(.isr_vector): AT(LOADADDR(.isr_vector)+SIZEOF(.isr_vector))
    {
     __text_start = .;
     *(init.o)
        *(.text .text.*) /* all remaining code */

   /* read-only data (constants) */
        *(.rodata .rodata.* .constdata .constdata.*)

        /* *(vtable) /* C++ virtual tables */

  KEEP(*(.eh_frame*))

  /*
   * Stub sections generated by the linker, to glue together
   * ARM and Thumb code. .glue_7 is used for ARM code calling
   * Thumb code, and .glue_7t is used for Thumb code calling
   * ARM code. Apparently always generated by the linker, for some
   * architectures, so better leave them here.
   */
        *(.glue_7)
        *(.glue_7t)
        __text_end = .;
    } >RAM

    /*
     * The initialised data section.
     *
     * The program executes knowing that the data is in the RAM
     * but the loader puts the initial values in the FLASH (inidata).
     * It is one task of the startup to copy the initial values from
     * FLASH to RAM.
     */
     . = ALIGN(4);
    .data : AT(LOADADDR(.text)+SIZEOF(.text))
    {
     FILL(0xFF)
        /* This is used by the startup code to initialise the .data section */
        _sdata = . ; /* STM specific definition */
        __data_start = . ;
  *(.data_begin .data_begin.*)

  *(.data .data.*)

  *(.data_end .data_end.*)
     . = ALIGN(4);

     /* This is used by the startup code to initialise the .data section */
        _edata = . ; /* STM specific definition */
        __data_end = . ;
    } >RAM

    . = ALIGN(4);
    __bss_start = .;
    /* The primary uninitialised data section. */
    .bss (NOLOAD) : AT(LOADADDR(.data)+SIZEOF(.data))
    {
        __bss_start = .; /* standard newlib definition */
        _sbss = .; /* STM specific definition */
        *(.bss_begin .bss_begin.*)

        *(.bss .bss.*)
        *(COMMON)

        *(.bss_end .bss_end.*)
     . = ALIGN(4);
        __bss_end = .; /* standard newlib definition */
        _ebss = . ; /* STM specific definition */
    } >RAM

/*
 .rel.dyn : {
  __rel_dyn_start = .;
  *(.rel*)
  __rel_dyn_end = .;
 }
*/
 /* ARM magic sections */
 . = ALIGN(4);
 .ARM.extab : AT(LOADADDR(.bss)+SIZEOF(.bss))
    {
       *(.ARM.extab* .gnu.linkonce.armextab.*)
    } >RAM

    . = ALIGN(4);
    __exidx_start = .;
    .ARM.exidx : AT(LOADADDR(.ARM.extab)+SIZEOF(.ARM.extab))
    {
       *(.ARM.exidx* .gnu.linkonce.armexidx.*)
    } >RAM
    __exidx_end = .;

    _etext = .;
    __etext = .;

 /*
  * The secondary initialised data section.
  */
  /*
    .data_CCMRAM : ALIGN(4)
    {
       FILL(0xFF)
       *(.data.CCMRAM .data.CCMRAM.*)
       . = ALIGN(4) ;
    } > CCMRAM
 */
 /*
     * This address is used by the startup code to
     * initialise the .data section.
     */
    _sidata = LOADADDR(.data);

 /*
     * The uninitialised data sections. NOLOAD is used to avoid
     * the "section `.bss' type changed to PROGBITS" warning
     */

    /* The secondary uninitialised data section. */
    /*
 .bss_CCMRAM (NOLOAD) : ALIGN(4)
 {
  *(.bss.CCMRAM .bss.CCMRAM.*)
 } > CCMRAM

  */

    /* Mandatory to be word aligned, _sbrk assumes this */
    /*
    PROVIDE ( end = _end_noinit );
    PROVIDE ( _end = _end_noinit );
    PROVIDE ( __end = _end_noinit );
    PROVIDE ( __end__ = _end_noinit );

    */

    /*
     * Used for validation only, do not allocate anything here!
     *
     * This is just to check that there is enough RAM left for the Main
     * stack. It should generate an error if it's full.
     */
    ._check_stack :
    {
        . = . + _Minimum_Stack_Size ;
    } >RAM

    /* After that there are only debugging sections. */

    /* This can remove the debugging information from the standard libraries */
    /*
    DISCARD :
    {
     libc.a ( * )
     libm.a ( * )
     libgcc.a ( * )
     }
     */

    /* Stabs debugging sections. */
    .stab 0 : { *(.stab) }
    .stabstr 0 : { *(.stabstr) }
    .stab.excl 0 : { *(.stab.excl) }
    .stab.exclstr 0 : { *(.stab.exclstr) }
    .stab.index 0 : { *(.stab.index) }
    .stab.indexstr 0 : { *(.stab.indexstr) }
    .comment 0 : { *(.comment) }
    /*
     * DWARF debug sections.
     * Symbols in the DWARF debugging sections are relative to the beginning
     * of the section so we begin them at 0.
     */
    /* DWARF 1 */
    .debug 0 : { *(.debug) }
    .line 0 : { *(.line) }
    /* GNU DWARF 1 extensions */
    .debug_srcinfo 0 : { *(.debug_srcinfo) }
    .debug_sfnames 0 : { *(.debug_sfnames) }
    /* DWARF 1.1 and DWARF 2 */
    .debug_aranges 0 : { *(.debug_aranges) }
    .debug_pubnames 0 : { *(.debug_pubnames) }
    /* DWARF 2 */
    .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
    .debug_abbrev 0 : { *(.debug_abbrev) }
    .debug_line 0 : { *(.debug_line) }
    .debug_frame 0 : { *(.debug_frame) }
    .debug_str 0 : { *(.debug_str) }
    .debug_loc 0 : { *(.debug_loc) }
    .debug_macinfo 0 : { *(.debug_macinfo) }
    /* SGI/MIPS DWARF 2 extensions */
    .debug_weaknames 0 : { *(.debug_weaknames) }
    .debug_funcnames 0 : { *(.debug_funcnames) }
    .debug_typenames 0 : { *(.debug_typenames) }
    .debug_varnames 0 : { *(.debug_varnames) }
}

and here is the interrupt vectors:
//file interrupt_asm.S
#define NVIC_INT_CTRL 0xE000ED04 ; Interrupt control state register.
#define NVIC_SYSPRI14 0xE000ED22 ; System priority register (priority 14).
#define NVIC_PENDSV_PRI 0xFFFF ; PendSV priority value (lowest).
#define NVIC_PENDSVSET 0x10000000 ; Value to trigger PendSV exception.

#define REGISTER_SIZE 4
#define STACK_FRAME_REGISTER_NUM 8
#define STACK_FRAME_SIZE (REGISTER_SIZE * STACK_FRAME_REGISTER_NUM)
/*
.equ REGISTER_SIZE, 4
.equ STACK_FRAME_REGISTER_NUM, 8
.equ STACK_FRAME_SIZE, (REGISTER_SIZE * STACK_FRAME_REGISTER_NUM)

.equ NVIC_INT_CTRL, 0xE000ED04
.equ NVIC_SYSPRI14, 0xE000ED22
.equ NVIC_PENDSV_PRI, 0xFFFF
.equ NVIC_PENDSVSET, 0x10000000
*/
.syntax unified
.thumb

.text
.align 4

.thumb_func
.type Reset_Handler, %function
Reset_Handler:
                .global Reset_Handler
                //## disable watchdog ???
    # ldr r0, =336
    # ldr r1, =8
    # ldr r2, =2
    # ldr r3, =7
    # ldr r4, =Stm32_Clock_Init
                # blx r4
    # ldr r0, =84
    # ldr r1, =115200
    # ldr r2, =__uart_init
    # blx r2
    # mov r0, #0x04
    ldr r0, =__kernel_init
    # orr r0, r0, #0x01
    bx r0

.thumb_func
.type NMI_Handler, %function
NMI_Handler:
                .weak NMI_Handler
                b .

.thumb_func
.type HardFault_Handler, %function
HardFault_Handler:
                .weak HardFault_Handler
                b .

.thumb_func
.type MemManage_Handler, %function
MemManage_Handler:
                .weak MemManage_Handler
                b .

.thumb_func
.type BusFault_Handler, %function
BusFault_Handler:
                .weak BusFault_Handler
                b .

.thumb_func
.type UsageFault_Handler, %function
UsageFault_Handler:
                .weak UsageFault_Handler
                b .

.thumb_func
.type SVC_Handler, %function
SVC_Handler:
                .weak SVC_Handler
    push {lr} //#needed???,需要,因为下面需要调用c函数,会覆盖lr,所以需要先保存它
//# tst lr, #0x04
//# ite eq
//# mrseq r0, msp //#//##maybe come from another interrupt
//# mrsne r0, psp
//# subs r0, r0, #STACK_FRAME_SIZE //#//#其他的寄存器不需要都入栈,显式占用的才需要入栈,调用子函数时,子函数会自己把占用的寄存器入栈出栈
//# stm r0, {r4-r11}
 //# push {r0} //##不需要保存r0,因为入栈的寄存器个数是一定的,长度一定,只需要恢复的时候再加上相应的offset就好了,可移植性后期再考虑
    mov r0, r7
 //# mov r2, r6
    ldr r3, =SVC_Handler_C
    //#//#r3 = SVC_Handler_C (real exception handler)
    //#//# r0 = svc_num, r1 = args, r2 = rets
    blx r3
 //# pop {r1}
//# mrs r1, psp
//# subs r1, r1, #STACK_FRAME_SIZE
//# ldm r1, {r4-r11}
    pop {pc}
//# tst lr, #0x04
//# ite ne
//# mrsne r1, psp
//# beq _return //#//#interrupt(not syscall) no need to return a value...no! only syscall will trigger this exception
//# subs r1, #0x04
//# str r0, [r1] //#//#return value
//# msr psp, r1
//# _return:
// # bx lr

.thumb_func
.type DebugMon_Handler, %function
DebugMon_Handler:
                .weak DebugMon_Handler
                b .
.thumb_func
.type TIM2_IRQHandler, %function
TIM2_IRQHandler:
   .weak TIM2_IRQHandler
   mov r1, lr
   ldr r0, =__TimerScheduler_del_first
   blx r0
   bx r1

.thumb_func
.type PendSV_Handler, %function
PendSV_Handler:
                .global PendSV_Handler
                cpsid i //##needed???
                ///TODO: check order of disable MPU
    //MPU->CTRL : 0xE000E000 + 0x0D90 + 0x04 = 0xE000ED94
    ldr r0, =0xE000ED94
    ldr r1, [r0]
    and r1, r1, 0xfffffffe
    str r1, [r0]

                ldr r0, =__kernel_thread_initialised__
                ldr r0, [r0]
                cmp r0, #0x0
                bne _schedule_check
                //#//#初始化__kernel_tcb__的stack
                ldr r0, =__switch_to_stack
                ldr r0, [r0]
                ldr r1, [r0] // 构造的lr的值
    adds r0, r0, #0x04
    ldm r0, {r4-r11}
    adds r0, #0x20
    msr msp, r0 ///kernel thread也使用psp,只有中断才使用msp???会不会浪费ram???
    cpsie i //##needed???
    bx r1

_schedule_check:
    mov r2, lr//push {lr} ////##tail-chaining也会生成新的lr???
                ldr r0, =__Scheduler
                ldr r1, = __Scheduler_schedule
    blx r1
    //pop {lr}
    mov lr, r2
    cmp r0, #0x0
    bne _no_switch
_switch:
    //#//#save
_save:
    tst lr, #0x04
    ite eq
    mrseq r0, msp //#//##maybe come from another interrupt
    mrsne r0, psp

    subs r0, r0, #0x20
                stm r0, {r4-r11}
    ldr r1, =__switch_from_stack
                str r0, [r1]

    //#//#restore
_restore:
    ldr r0, =__switch_to_stack
    ldr r1, [r0]
    ldm r1, {r4-r11}
    adds r1, r1, #0x20 //#//#needed???
    # str r1, [r0]
    ldr r2, =__kernel_tcb__ ///暂时设置为中断和kernel thread都使用msp
    ldr r3, =__next_tcb__
    tst r2, r3
    ite eq
    msreq msp, r1
    msrne psp, r1
_no_switch:
// orr lr, lr, #0x04
    cpsie i //# needed ???
    ///TODO: check order of enable MPU
    //MPU->CTRL : 0xE000E000 + 0x0D90 + 0x04 = 0xE000ED94
    ldr r0, =0xE000ED94
    ldr r1, [r0]
    orr r1, r1, 0x05
    str r1, [r0]
    bx lr

.thumb_func
.type SysTick_Handler, %function
SysTick_Handler:
                .global SysTick_Handler
                // push {lr}
                mov r1, lr
    ldr r0, =SysTick_Handler_C
    blx r0
    //pop {pc}
    bx r1
    # bx lr

.thumb_func
.type Default_Handler, %function
Default_Handler:
           .weak WWDG_IRQHandler //# Window WatchDog
           .weak PVD_IRQHandler //# PVD through EXTI Line detection
        .weak TAMP_STAMP_IRQHandler //# Tamper and TimeStamps through the EXTI line
        .weak RTC_WKUP_IRQHandler //# RTC Wakeup through the EXTI line
        .weak FLASH_IRQHandler //# FLASH
        .weak RCC_IRQHandler //# RCC
        .weak EXTI0_IRQHandler //# EXTI Line0
        .weak EXTI1_IRQHandler //# EXTI Line1
        .weak EXTI2_IRQHandler //# EXTI Line2
        .weak EXTI3_IRQHandler //# EXTI Line3
        .weak EXTI4_IRQHandler //# EXTI Line4
        .weak DMA1_Stream0_IRQHandler //# DMA1 Stream 0
        .weak DMA1_Stream1_IRQHandler //# DMA1 Stream 1
        .weak DMA1_Stream2_IRQHandler //# DMA1 Stream 2
        .weak DMA1_Stream3_IRQHandler //# DMA1 Stream 3
        .weak DMA1_Stream4_IRQHandler //# DMA1 Stream 4
        .weak DMA1_Stream5_IRQHandler //# DMA1 Stream 5
        .weak DMA1_Stream6_IRQHandler //# DMA1 Stream 6
        .weak ADC_IRQHandler //# ADC1, ADC2 and ADC3s
        .weak CAN1_TX_IRQHandler //# CAN1 TX
        .weak CAN1_RX0_IRQHandler //# CAN1 RX0
        .weak CAN1_RX1_IRQHandler //# CAN1 RX1
        .weak CAN1_SCE_IRQHandler //# CAN1 SCE
        .weak EXTI9_5_IRQHandler //# External Line[9:5]s
        .weak TIM1_BRK_TIM9_IRQHandler //# TIM1 Break and TIM9
        .weak TIM1_UP_TIM10_IRQHandler //# TIM1 Update and TIM10
        .weak TIM1_TRG_COM_TIM11_IRQHandler //# TIM1 Trigger and Commutation and TIM11
        .weak TIM1_CC_IRQHandler //# TIM1 Capture Compare
        .weak TIM2_IRQHandler //# TIM2
        .weak TIM3_IRQHandler //# TIM3
        .weak TIM4_IRQHandler //# TIM4
        .weak I2C1_EV_IRQHandler //# I2C1 Event
        .weak I2C1_ER_IRQHandler //# I2C1 Error
        .weak I2C2_EV_IRQHandler //# I2C2 Event
        .weak I2C2_ER_IRQHandler //# I2C2 Error
        .weak SPI1_IRQHandler //# SPI1
        .weak SPI2_IRQHandler //# SPI2
        .weak USART1_IRQHandler //# USART1
        .weak USART2_IRQHandler //# USART2
        .weak USART3_IRQHandler //# USART3
        .weak EXTI15_10_IRQHandler //# External Line[15:10]s
        .weak RTC_Alarm_IRQHandler //# RTC Alarm (A and B) through EXTI Line
        .weak OTG_FS_WKUP_IRQHandler //# USbOTG FS Wakeup through EXTI line
        .weak TIM8_BRK_TIM12_IRQHandler //# TIM8 Break and TIM12
        .weak TIM8_UP_TIM13_IRQHandler //# TIM8 Update and TIM13
        .weak TIM8_TRG_COM_TIM14_IRQHandler //# TIM8 Trigger and Commutation and TIM14
        .weak TIM8_CC_IRQHandler //# TIM8 Capture Compare
        .weak DMA1_Stream7_IRQHandler //# DMA1 Stream7
        .weak FMC_IRQHandler //# FMC
        .weak SDIO_IRQHandler //# SDIO
        .weak TIM5_IRQHandler //# TIM5
        .weak SPI3_IRQHandler //# SPI3
        .weak UART4_IRQHandler //# UART4
        .weak UART5_IRQHandler //# UART5
        .weak TIM6_DAC_IRQHandler //# TIM6 and DAC1&2 underrun errors
        .weak TIM7_IRQHandler //# TIM7
        .weak DMA2_Stream0_IRQHandler //# DMA2 Stream 0
        .weak DMA2_Stream1_IRQHandler //# DMA2 Stream 1
        .weak DMA2_Stream2_IRQHandler //# DMA2 Stream 2
        .weak DMA2_Stream3_IRQHandler //# DMA2 Stream 3
        .weak DMA2_Stream4_IRQHandler //# DMA2 Stream 4
        .weak ETH_IRQHandler //# Ethernet
        .weak ETH_WKUP_IRQHandler //# Ethernet Wakeup through EXTI line
        .weak CAN2_TX_IRQHandler //# CAN2 TX
        .weak CAN2_RX0_IRQHandler //# CAN2 RX0
        .weak CAN2_RX1_IRQHandler //# CAN2 RX1
        .weak CAN2_SCE_IRQHandler //# CAN2 SCE
        .weak OTG_FS_IRQHandler //# USbOTG FS
        .weak DMA2_Stream5_IRQHandler //# DMA2 Stream 5
        .weak DMA2_Stream6_IRQHandler //# DMA2 Stream 6
        .weak DMA2_Stream7_IRQHandler //# DMA2 Stream 7
        .weak USART6_IRQHandler //# USART6
        .weak I2C3_EV_IRQHandler //# I2C3 event
        .weak I2C3_ER_IRQHandler //# I2C3 error
        .weak OTG_HS_EP1_OUT_IRQHandler //# USbOTG HS End Point 1 Out
        .weak OTG_HS_EP1_IN_IRQHandler //# USbOTG HS End Point 1 In
        .weak OTG_HS_WKUP_IRQHandler //# USbOTG HS Wakeup through EXTI
        .weak OTG_HS_IRQHandler //# USbOTG HS
        .weak DCMI_IRQHandler //# DCMI
        .weak HASH_RNG_IRQHandler //# Hash and Rng
        .weak FPU_IRQHandler //# FPU

WWDG_IRQHandler: //# Window WatchDog
PVD_IRQHandler: //# PVD through EXTI Line detection
TAMP_STAMP_IRQHandler: //# Tamper and TimeStamps through the EXTI line
RTC_WKUP_IRQHandler: //# RTC Wakeup through the EXTI line
FLASH_IRQHandler: //# FLASH
RCC_IRQHandler: //# RCC
EXTI0_IRQHandler: //# EXTI Line0
EXTI1_IRQHandler: //# EXTI Line1
EXTI2_IRQHandler: //# EXTI Line2
EXTI3_IRQHandler: //# EXTI Line3
EXTI4_IRQHandler: //# EXTI Line4
DMA1_Stream0_IRQHandler: //# DMA1 Stream 0
DMA1_Stream1_IRQHandler: //# DMA1 Stream 1
DMA1_Stream2_IRQHandler: //# DMA1 Stream 2
DMA1_Stream3_IRQHandler: //# DMA1 Stream 3
DMA1_Stream4_IRQHandler: //# DMA1 Stream 4
DMA1_Stream5_IRQHandler: //# DMA1 Stream 5
DMA1_Stream6_IRQHandler: //# DMA1 Stream 6
ADC_IRQHandler: //# ADC1, ADC2 and ADC3s
CAN1_TX_IRQHandler: //# CAN1 TX
CAN1_RX0_IRQHandler: //# CAN1 RX0
CAN1_RX1_IRQHandler: //# CAN1 RX1
CAN1_SCE_IRQHandler: //# CAN1 SCE
EXTI9_5_IRQHandler: //# External Line[9:5]s
TIM1_BRK_TIM9_IRQHandler: //# TIM1 Break and TIM9
TIM1_UP_TIM10_IRQHandler: //# TIM1 Update and TIM10
TIM1_TRG_COM_TIM11_IRQHandler: //# TIM1 Trigger and Commutation and TIM11
TIM1_CC_IRQHandler: //# TIM1 Capture Compare
//TIM2_IRQHandler: //# TIM2
TIM3_IRQHandler: //# TIM3
TIM4_IRQHandler: //# TIM4
I2C1_EV_IRQHandler: //# I2C1 Event
I2C1_ER_IRQHandler: //# I2C1 Error
I2C2_EV_IRQHandler: //# I2C2 Event
I2C2_ER_IRQHandler: //# I2C2 Error
SPI1_IRQHandler: //# SPI1
SPI2_IRQHandler: //# SPI2
USART1_IRQHandler: //# USART1
USART2_IRQHandler: //# USART2
USART3_IRQHandler: //# USART3
EXTI15_10_IRQHandler: //# External Line[15:10]s
RTC_Alarm_IRQHandler: //# RTC Alarm (A and B) through EXTI Line
OTG_FS_WKUP_IRQHandler: //# USbOTG FS Wakeup through EXTI line
TIM8_BRK_TIM12_IRQHandler: //# TIM8 Break and TIM12
TIM8_UP_TIM13_IRQHandler: //# TIM8 Update and TIM13
TIM8_TRG_COM_TIM14_IRQHandler: //# TIM8 Trigger and Commutation and TIM14
TIM8_CC_IRQHandler: //# TIM8 Capture Compare
DMA1_Stream7_IRQHandler: //# DMA1 Stream7
FMC_IRQHandler: //# FMC
SDIO_IRQHandler: //# SDIO
TIM5_IRQHandler: //# TIM5
SPI3_IRQHandler: //# SPI3
UART4_IRQHandler: //# UART4
UART5_IRQHandler: //# UART5
TIM6_DAC_IRQHandler: //# TIM6 and DAC1&2 underrun errors
TIM7_IRQHandler: //# TIM7
DMA2_Stream0_IRQHandler: //# DMA2 Stream 0
DMA2_Stream1_IRQHandler: //# DMA2 Stream 1
DMA2_Stream2_IRQHandler: //# DMA2 Stream 2
DMA2_Stream3_IRQHandler: //# DMA2 Stream 3
DMA2_Stream4_IRQHandler: //# DMA2 Stream 4
ETH_IRQHandler: //# Ethernet
ETH_WKUP_IRQHandler: //# Ethernet Wakeup through EXTI line
CAN2_TX_IRQHandler: //# CAN2 TX
CAN2_RX0_IRQHandler: //# CAN2 RX0
CAN2_RX1_IRQHandler: //# CAN2 RX1
CAN2_SCE_IRQHandler: //# CAN2 SCE
OTG_FS_IRQHandler: //# USbOTG FS
DMA2_Stream5_IRQHandler: //# DMA2 Stream 5
DMA2_Stream6_IRQHandler: //# DMA2 Stream 6
DMA2_Stream7_IRQHandler: //# DMA2 Stream 7
USART6_IRQHandler: //# USART6
I2C3_EV_IRQHandler: //# I2C3 event
I2C3_ER_IRQHandler: //# I2C3 error
OTG_HS_EP1_OUT_IRQHandler: //# USbOTG HS End Point 1 Out
OTG_HS_EP1_IN_IRQHandler: //# USbOTG HS End Point 1 In
OTG_HS_WKUP_IRQHandler: //# USbOTG HS Wakeup through EXTI
OTG_HS_IRQHandler: //# USbOTG HS
DCMI_IRQHandler: //# DCMI
HASH_RNG_IRQHandler: //# Hash and Rng
FPU_IRQHandler: //# FPU
                b .

.global __isr_vectors
.global __isr_vectors_end

//.org 0x00000000
//.org 0x20000000
.section .isr_vector
//.align 512
__isr_vectors:
     .word _estack //# The initial stack pointer
        .word Reset_Handler //# The reset handler
        .word NMI_Handler //# The NMI handler
        .word HardFault_Handler //# The hard fault handler
#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__)
        .word MemManage_Handler //# The MPU fault handler
        .word BusFault_Handler //# The bus fault handler
        .word UsageFault_Handler //# The usage fault handler
#else
        .word 0 //# Reserved
        .word 0 //# Reserved
        .word 0 //# Reserved
#endif
        .word 0 //# Reserved
        .word 0 //# Reserved
        .word 0 //# Reserved
        .word 0 //# Reserved
           .word SVC_Handler //# SVCall handler
#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__)
           .word DebugMon_Handler //# Debug monitor handler
#else
           .word 0 //# Reserved
#endif
           .word 0 //# Reserved
           .word PendSV_Handler //# The PendSV handler
           .word SysTick_Handler //# The SysTick handler
    //# ----------------------------------------------------------------------
    //# External Interrupts
           .word WWDG_IRQHandler //# Window WatchDog
           .word PVD_IRQHandler //# PVD through EXTI Line detection
        .word TAMP_STAMP_IRQHandler //# Tamper and TimeStamps through the EXTI line
        .word RTC_WKUP_IRQHandler //# RTC Wakeup through the EXTI line
        .word FLASH_IRQHandler //# FLASH
        .word RCC_IRQHandler //# RCC
        .word EXTI0_IRQHandler //# EXTI Line0
        .word EXTI1_IRQHandler //# EXTI Line1
        .word EXTI2_IRQHandler //# EXTI Line2
        .word EXTI3_IRQHandler //# EXTI Line3
        .word EXTI4_IRQHandler //# EXTI Line4
        .word DMA1_Stream0_IRQHandler //# DMA1 Stream 0
        .word DMA1_Stream1_IRQHandler //# DMA1 Stream 1
        .word DMA1_Stream2_IRQHandler //# DMA1 Stream 2
        .word DMA1_Stream3_IRQHandler //# DMA1 Stream 3
        .word DMA1_Stream4_IRQHandler //# DMA1 Stream 4
        .word DMA1_Stream5_IRQHandler //# DMA1 Stream 5
        .word DMA1_Stream6_IRQHandler //# DMA1 Stream 6
        .word ADC_IRQHandler //# ADC1, ADC2 and ADC3s
        .word CAN1_TX_IRQHandler //# CAN1 TX
        .word CAN1_RX0_IRQHandler //# CAN1 RX0
        .word CAN1_RX1_IRQHandler //# CAN1 RX1
        .word CAN1_SCE_IRQHandler //# CAN1 SCE
        .word EXTI9_5_IRQHandler //# External Line[9:5]s
        .word TIM1_BRK_TIM9_IRQHandler //# TIM1 Break and TIM9
        .word TIM1_UP_TIM10_IRQHandler //# TIM1 Update and TIM10
        .word TIM1_TRG_COM_TIM11_IRQHandler //# TIM1 Trigger and Commutation and TIM11
        .word TIM1_CC_IRQHandler //# TIM1 Capture Compare
        .word TIM2_IRQHandler //# TIM2
        .word TIM3_IRQHandler //# TIM3
        .word TIM4_IRQHandler //# TIM4
        .word I2C1_EV_IRQHandler //# I2C1 Event
        .word I2C1_ER_IRQHandler //# I2C1 Error
        .word I2C2_EV_IRQHandler //# I2C2 Event
        .word I2C2_ER_IRQHandler //# I2C2 Error
        .word SPI1_IRQHandler //# SPI1
        .word SPI2_IRQHandler //# SPI2
        .word USART1_IRQHandler //# USART1
        .word USART2_IRQHandler //# USART2
        .word USART3_IRQHandler //# USART3
        .word EXTI15_10_IRQHandler //# External Line[15:10]s
        .word RTC_Alarm_IRQHandler //# RTC Alarm (A and B) through EXTI Line
        .word OTG_FS_WKUP_IRQHandler //# USbOTG FS Wakeup through EXTI line
        .word TIM8_BRK_TIM12_IRQHandler //# TIM8 Break and TIM12
        .word TIM8_UP_TIM13_IRQHandler //# TIM8 Update and TIM13
        .word TIM8_TRG_COM_TIM14_IRQHandler //# TIM8 Trigger and Commutation and TIM14
        .word TIM8_CC_IRQHandler //# TIM8 Capture Compare
        .word DMA1_Stream7_IRQHandler //# DMA1 Stream7
        .word FMC_IRQHandler //# FMC
        .word SDIO_IRQHandler //# SDIO
        .word TIM5_IRQHandler //# TIM5
        .word SPI3_IRQHandler //# SPI3
        .word UART4_IRQHandler //# UART4
        .word UART5_IRQHandler //# UART5
        .word TIM6_DAC_IRQHandler //# TIM6 and DAC1&2 underrun errors
        .word TIM7_IRQHandler //# TIM7
        .word DMA2_Stream0_IRQHandler //# DMA2 Stream 0
        .word DMA2_Stream1_IRQHandler //# DMA2 Stream 1
        .word DMA2_Stream2_IRQHandler //# DMA2 Stream 2
        .word DMA2_Stream3_IRQHandler //# DMA2 Stream 3
        .word DMA2_Stream4_IRQHandler //# DMA2 Stream 4
        .word ETH_IRQHandler //# Ethernet
        .word ETH_WKUP_IRQHandler //# Ethernet Wakeup through EXTI line
        .word CAN2_TX_IRQHandler //# CAN2 TX
        .word CAN2_RX0_IRQHandler //# CAN2 RX0
        .word CAN2_RX1_IRQHandler //# CAN2 RX1
        .word CAN2_SCE_IRQHandler //# CAN2 SCE
        .word OTG_FS_IRQHandler //# USbOTG FS
        .word DMA2_Stream5_IRQHandler //# DMA2 Stream 5
        .word DMA2_Stream6_IRQHandler //# DMA2 Stream 6
        .word DMA2_Stream7_IRQHandler //# DMA2 Stream 7
        .word USART6_IRQHandler //# USART6
        .word I2C3_EV_IRQHandler //# I2C3 event
        .word I2C3_ER_IRQHandler //# I2C3 error
        .word OTG_HS_EP1_OUT_IRQHandler //# USbOTG HS End Point 1 Out
        .word OTG_HS_EP1_IN_IRQHandler //# USbOTG HS End Point 1 In
        .word OTG_HS_WKUP_IRQHandler //# USbOTG HS Wakeup through EXTI
        .word OTG_HS_IRQHandler //# USbOTG HS
        .word DCMI_IRQHandler //# DCMI
        .word 0 //# Reserved
        .word HASH_RNG_IRQHandler //# Hash and Rng
        .word FPU_IRQHandler //# FPU
__isr_vectors_end:

it's expected that at offset 0x002c of kernel bin file, the value is 00 00 01 20, whichi is the initial stack pointer.
but i got all zeros...
 $ hexdump debug/bin/kernel.bin
0000000 2c 40 00 08 00 00 00 20 88 01 00 00 b4 41 00 08
0000010 88 01 00 20 49 19 00 00 fd 5a 00 08 d4 1a 00 20
0000020 08 00 00 00 e0 1a 00 20 34 00 00 00 00 00 00 00
0000030 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
*
00001b0 00 00 00 00 08 b5 72 b6 0a 48 01 f0 61 fa 00 f0
00001c0 a9 fb 00 f0 b5 f8 00 f0 bf fe 01 f0 3d f9 00 f0
00001d0 0d f8 62 b6 04 4b 00 e0 13 46 5a 1e 00 2b fb d1
00001e0 08 bd 00 bf a8 19 00 20 00 ca 9a 3b 02 48 4f f0

is this a mistake of usage of arm-none-eabi-ld, or a bug in it?

Question information

Language:
English Edit question
Status:
Answered
For:
GNU Arm Embedded Toolchain Edit question
Assignee:
No assignee Edit question
Last query:
Last reply:
Revision history for this message
Jeremy Li (ijeremyli) said :
#1

##this is the makefile
AS=/Users/apple/bin/gcc-arm-none-eabi-5_4-2016q3/bin/arm-none-eabi-as
CC=/Users/apple/bin/gcc-arm-none-eabi-5_4-2016q3/bin/arm-none-eabi-gcc
OBJCOPY=/Users/apple/bin/gcc-arm-none-eabi-5_4-2016q3/bin/arm-none-eabi-objcopy
LD=/Users/apple/bin/gcc-arm-none-eabi-5_4-2016q3/bin/arm-none-eabi-ld

CFLAGS=-mcpu=cortex-m4 -mfpu=fpv4-sp-d16 -mthumb -mfloat-abi=soft --specs=nosys.specs -nostartfiles -Og -fmessage-length=0 -fsigned-char -ffunction-sections -fdata-sections -ffreestanding -fno-move-loop-invariants -Wall -Wextra -g3 -DDEBUG -DUSE_FULL_ASSERT -DTRACE -DOS_USE_TRACE_SEMIHOSTING_DEBUG -DSTM32F407xx -DUSE_HAL_DRIVER -std=gnu11 -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@)" #-c -o "$@" "$<"
# CFLAGS += -fpic -pie
CFLAGS+=-I$(INCLUDE_DIR) -I$(INCLUDE_DIR)/cmsis -I$(INCLUDE_DIR)/stm32f4-hal
LDFLAGS=

SUBDIRS=$(shell ls -l | grep ^d | awk '{if($$9 != "debug" && $$9 != "include") print $$9}')

ROOT_DIR=$(shell pwd)
INCLUDE_DIR=$(ROOT_DIR)/include
LOADER_DIR=$(shell cd ../bootloader/debug/bin && pwd)

ELF=kernel.elf
BIN=kernel.bin
LOADER_BIN=bootloader.bin
OBJS_DIR=$(ROOT_DIR)/debug/obj
MAKE_FLASH=$(ROOT_DIR)/make_flash.sh

##################TODO: fix this offset
KERNEL_ENTRY_OFFSET=392 ###1024

BIN_DIR=$(ROOT_DIR)/debug/bin

CUR_SOURCE=$(wildcard *.c)
CUR_ASM_SRC=$(wildcard *.S)

CUR_OBJS=$(patsubst %.c, %.o, $(CUR_SOURCE))
CUR_ASM_OBJS=$(patsubst %.S, %.o, $(CUR_ASM_SRC))
# OBJS=$(shell ls -l $(OBJS_DIR) | grep ^- | awk '{print $9}' | sed "s:^:$(OBJS_DIR)/:")
# OBJS=${patsubst %.c, %.o, $(CUR_SOURCE)}
OBJS=$(wildcard $(OBJS_DIR)/*.o)

export CC BIN OBJS_DIR BIN_DIR ROOT_DIR CFLAGS OBJS

all: objs kernel flash

objs:$(SUBDIRS) $(CUR_OBJS) $(CUR_ASM_OBJS)

target: $(OBJS)
 $(CC) $(CFLAGS) -T $(ROOT_DIR)/kernel.ld $^ -o $(BIN_DIR)/$(ELF)
# $(LD) -T $(ROOT_DIR)/kernel.ld -L /Users/apple/bin/gcc-arm-none-eabi-5_4-2016q3/lib/gcc/arm-none-eabi/5.4.1/ -lgcc $^ -o $(BIN_DIR)/$(ELF)

kernel: target
 $(OBJCOPY) -O binary $(BIN_DIR)/$(ELF) $(BIN_DIR)/$(BIN)

flash:
 $(MAKE_FLASH) $(LOADER_DIR)/$(LOADER_BIN) $(BIN_DIR)/$(BIN)

$(SUBDIRS):echo
 make -C $@
debug:echo
 make -C debug
echo:
 @echo $(SUBDIRS)

$(CUR_OBJS):%.o:%.c
 $(CC) $(CFLAGS) -c $^ -o $(ROOT_DIR)/$(OBJS_DIR)/$@

$(CUR_ASM_OBJS):%.o:%.S
 $(CC) $(CFLAGS) -c $^ -o $(ROOT_DIR)/$(OBJS_DIR)/$@

clean:
 @rm -f $(OBJS_DIR)/*.o
 @rm -rf $(BIN_DIR)/*

Revision history for this message
Tejas Belagod (belagod-tejas) said :
#2

Hi Jeremy, any chance you could reduce the size of the sources that can reproduce the issue that you're seeing? If not, it might take us a long time to get back to you with an answer.

Can you help with this problem?

Provide an answer of your own, or ask Jeremy Li for more information if necessary.

To post a message you must log in.