• PX4 IO板启动流程


    PX4 IO板启动流程

    PX4 IO板启动流程

                                                                                 -------- 转载请注明出处

    -------- 2014-11-27.冷月追风

                                                                                 -------- email:merafour@163.com 
        我们这里选择先分析 IO板主要还是 IO板的源码相对少,相对简单。

    1. IO板启动

        在前面分析脚本的时候我们知道 IO板的源码会在 “config_px4io-v2_default.mk”中指定。

    #
    # Makefile for the px4iov2_default configuration
    #
    #
    # Board support modules
    #
    MODULES  += drivers/stm32
    MODULES  += drivers/boards/px4io-v2
    MODULES  += modules/px4iofirmware

    那我们就不妨到这些目录下去看看都有些什么文件。

    bitcraze@bitcraze-vm:~/apm/PX4Firmware/src$ ls drivers/stm32/
    adc  drv_hrt.c  drv_pwm_servo.c  drv_pwm_servo.h  module.mk  tone_alarm
    bitcraze@bitcraze-vm:~/apm/PX4Firmware/src$ ls drivers/boards/px4io-v2/
    board_config.h  module.mk  px4iov2_init.c  px4iov2_pwm_servo.c
    bitcraze@bitcraze-vm:~/apm/PX4Firmware/src$ ls modules/px4iofirmware/
    adc.c       dsm.c  mixer.cpp  protocol.h  px4io.h      safety.c  serial.c
    controls.c  i2c.c  module.mk  px4io.c     registers.c  sbus.c
    bitcraze@bitcraze-vm:~/apm/PX4Firmware/src$

    所以源码不是很多,除非是所使用的 lib里边有大动作,否则很难想像这里边有很复杂的算法。只是从PCB上看, SBUS和主电机都由 IO板进行控制。
        在 “drivers/boards/px4io-v2”目录下, “module.mk”文件的内容为:

    #
    # Board-specific startup code for the PX4IOv2
    #
    SRCS  = px4iov2_init.c
        px4iov2_pwm_servo.c

    在该木兰下其实也就只有这两个源文件。而头文件 “board_config.h”我们如果去阅读其内容就会发现里面基本上是 IO板的硬件资源。而源文件 “px4iov2_init.c”从名称上看就是一段初始化代码,其中也确实只有一个函数:

    __EXPORT void stm32_boardinitialize(void)
    {
     /* configure GPIOs */
     /* LEDS - default to off */
     stm32_configgpio(GPIO_LED1);
     stm32_configgpio(GPIO_LED2);
     stm32_configgpio(GPIO_LED3);
     stm32_configgpio(GPIO_BTN_SAFETY);
     /* spektrum power enable is active high - enable it by default */
     stm32_configgpio(GPIO_SPEKTRUM_PWR_EN);
     stm32_configgpio(GPIO_SERVO_FAULT_DETECT);
     /* RSSI inputs */
     stm32_configgpio(GPIO_TIM_RSSI); /* xxx alternate function */
     stm32_configgpio(GPIO_ADC_RSSI);
     /* servo rail voltage */
     stm32_configgpio(GPIO_ADC_VSERVO);
     stm32_configgpio(GPIO_SBUS_INPUT); /* xxx alternate function */
     stm32_configgpio(GPIO_SBUS_OUTPUT);
     
     /* sbus output enable is active low - disable it by default */
     stm32_gpiowrite(GPIO_SBUS_OENABLE, true);
     stm32_configgpio(GPIO_SBUS_OENABLE);
     stm32_configgpio(GPIO_PPM); /* xxx alternate function */
     stm32_gpiowrite(GPIO_PWM1, false);
     stm32_configgpio(GPIO_PWM1);
     stm32_gpiowrite(GPIO_PWM2, false);
     stm32_configgpio(GPIO_PWM2);
     stm32_gpiowrite(GPIO_PWM3, false);
     stm32_configgpio(GPIO_PWM3);
     stm32_gpiowrite(GPIO_PWM4, false);
     stm32_configgpio(GPIO_PWM4);
     stm32_gpiowrite(GPIO_PWM5, false);
     stm32_configgpio(GPIO_PWM5);
     stm32_gpiowrite(GPIO_PWM6, false);
     stm32_configgpio(GPIO_PWM6);
     stm32_gpiowrite(GPIO_PWM7, false);
     stm32_configgpio(GPIO_PWM7);
     stm32_gpiowrite(GPIO_PWM8, false);
     stm32_configgpio(GPIO_PWM8);
    }

    确切地说,这其实是一个入口函数,如果进行匹配,我们会找到这样一段信息:

    ../../PX4NuttX/nuttx/arch/arm/src/stm32/stm32_start.c:254:  stm32_boardinitialize();

    该源文件的内容如下:

    /****************************************************************************
     * Name: _start
     *
     * Description:
     *   This is the reset entry point.
     *
     ****************************************************************************/
    void __start(void)
    {
      const uint32_t *src;
      uint32_t *dest;
    #ifdef CONFIG_ARMV7M_STACKCHECK
      /* Set the stack limit before we attempt to call any functions */
      __asm__ volatile ("sub r10, sp, %0" : : "r" (CONFIG_IDLETHREAD_STACKSIZE - 64) : );
    #endif
      /* Configure the uart so that we can get debug output as soon as possible */
      stm32_clockconfig();
      stm32_fpuconfig();
      stm32_lowsetup();
      stm32_gpioinit();
      showprogress('A');
      /* Clear .bss.  We'll do this inline (vs. calling memset) just to be
       * certain that there are no issues with the state of global variables.
       */
      for (dest = &_sbss; dest < &_ebss; )
        {
          *dest++ = 0;
        }
      showprogress('B');
      /* Move the intialized data section from his temporary holding spot in
       * FLASH into the correct place in SRAM.  The correct place in SRAM is
       * give by _sdata and _edata.  The temporary location is in FLASH at the
       * end of all of the other read-only data (.text, .rodata) at _eronly.
       */
      for (src = &_eronly, dest = &_sdata; dest < &_edata; )
        {
          *dest++ = *src++;
        }
      showprogress('C');
      /* Perform early serial initialization */
    #ifdef USE_EARLYSERIALINIT
      up_earlyserialinit();
    #endif
      showprogress('D');
      /* For the case of the separate user-/kernel-space build, perform whatever
       * platform specific initialization of the user memory is required.
       * Normally this just means initializing the user space .data and .bss
       * segments.
       */
    #ifdef CONFIG_NUTTX_KERNEL
      stm32_userspace();
      showprogress('E');
    #endif
      /* Initialize onboard resources */
      stm32_boardinitialize();
      showprogress('F');
      /* Then start NuttX */
      showprogress(' ');
      showprogress(' ');
      os_start();
      /* Shoulnd't get here */
      for(;;);
    }

    __start函数是 Nuttx系统的入口函数。
        可能有些人就会有疑问了,C语言的入口函数不应该是 main函数的吗?确实,我们都说 C语言的入口是 main函数,而且我们也都是这么做的。但是请记住, main函数本质上也是一个函数,没有区别,只是在我们不手动指定的情况下编译器默认入口函数为 main函数,但其实入口是可以手动进行指定的。这里用的是链接脚本。编译过的源码在 “PX4Firmware/Build”目录下会有一个 “px4io-v2_default.build”目录。你可以在 “PX4Firmware/Build/px4io-v2_default.build/nuttx-export/build”目录下找到 “ld.script”文件,内容如下:

    /* The STM32F100C8 has 64Kb of FLASH beginning at address 0x0800:0000 and
     * 8Kb of SRAM beginning at address 0x2000:0000.  When booting from FLASH,
     * FLASH memory is aliased to address 0x0000:0000 where the code expects to
     * begin execution by jumping to the entry point in the 0x0800:0000 address
     * range.
     */
    MEMORY
    {
        flash (rx) : ORIGIN = 0x08001000, LENGTH = 60K
        sram (rwx) : ORIGIN = 0x20000000, LENGTH = 8K
    }
    OUTPUT_ARCH(arm)
    ENTRY(__start)  /* treat __start as the anchor for dead code stripping */
    EXTERN(_vectors) /* force the vectors to be included in the output */
    /* 
     * Ensure that abort() is present in the final object.  The exception handling
     * code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
     */
    EXTERN(abort)
    SECTIONS
    {
     .text : {
      _stext = ABSOLUTE(.);
      *(.vectors)
      *(.text .text.*)        
      *(.fixup)
      *(.gnu.warning)
      *(.rodata .rodata.*)        
      *(.gnu.linkonce.t.*)
      *(.glue_7)
      *(.glue_7t)
      *(.got)
      *(.gcc_except_table)
      *(.gnu.linkonce.r.*)
      _etext = ABSOLUTE(.);
     } > flash
     /*
      * Init functions (static constructors and the like)
      */
            .init_section : {
                    _sinit = ABSOLUTE(.);
                    KEEP(*(.init_array .init_array.*))
                    _einit = ABSOLUTE(.);
            } > flash
     .ARM.extab : {
      *(.ARM.extab*)
     } > flash
     __exidx_start = ABSOLUTE(.);
     .ARM.exidx : {
      *(.ARM.exidx*)
     } > flash
     __exidx_end = ABSOLUTE(.);
     _eronly = ABSOLUTE(.);
     /* The STM32F100CB has 8Kb of SRAM beginning at the following address */
     .data : {
      _sdata = ABSOLUTE(.);
      *(.data .data.*)
      *(.gnu.linkonce.d.*)
      CONSTRUCTORS
      _edata = ABSOLUTE(.);
     } > sram AT > flash
     .bss : {
      _sbss = ABSOLUTE(.);
      *(.bss .bss.*)
      *(.gnu.linkonce.b.*)
      *(COMMON)
      _ebss = ABSOLUTE(.);
     } > sram
     /* 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) }
     .debug_abbrev 0 : { *(.debug_abbrev) }
     .debug_info 0 : { *(.debug_info) }
     .debug_line 0 : { *(.debug_line) }
     .debug_pubnames 0 : { *(.debug_pubnames) }
     .debug_aranges 0 : { *(.debug_aranges) }
    }

    我们知道 STM32的 Flash起始地址是 0x08000000,而且大小从来都没有听说做有 60K的。实际上这里用的是 64K芯片, 0x1000也正是 4K。稍微了解下 PX4都知道, PX4的两个芯片都是有 bootloader的,也就是说这 4K用来存放 bootloader。
        同时我们也看到,链接脚本中有:“ENTRY(__start)”这样一段内容,也就是这个地方指定了程序的入口。
        我们可以找到这样一个文件 “PX4NuttX/nuttx/arch/arm/src/stm32/stm32_vectors.S”,一看就知道里边定义了中断向量表。在链接脚本中我们看到,在程序开始的地方放的是中断向量表,那么这个中断向量表又有哪些内容呢?

    #define IDLE_STACK  (_ebss+CONFIG_IDLETHREAD_STACKSIZE-4)
    #define HEAP_BASE  (_ebss+CONFIG_IDLETHREAD_STACKSIZE)
    /************************************************************************************
     * Global Symbols
     ************************************************************************************/
     .syntax  unified
     .thumb
     .file  "stm32_vectors.S"
    /* Check if common ARMv7 interrupt vectoring is used (see arch/arm/src/armv7-m/up_vectors.S) */
    #ifndef CONFIG_ARMV7M_CMNVECTOR
     .globl  __start
    /************************************************************************************
     * Macros
     ************************************************************************************/
    /* On entry into an IRQ, the hardware automatically saves the xPSR, PC, LR, R12, R0-R3
     * registers on the stack, then branches to an instantantiation of the following
     * macro.  This macro simply loads the IRQ number into R0, then jumps to the common
     * IRQ handling logic.
     */
     .macro HANDLER, label, irqno
     .thumb_func
    label:
     mov  r0, #irqno
     b  stm32_common
     .endm
    /************************************************************************************
     * Vectors
     ************************************************************************************/
     .section .vectors, "ax"
     .code  16
     .align  2
     .globl  stm32_vectors
     .type  stm32_vectors, function
    stm32_vectors:
    /* Processor Exceptions */
     .word IDLE_STACK   /* Vector  0: Reset stack pointer */
     .word __start    /* Vector  1: Reset vector */
     .word stm32_nmi   /* Vector  2: Non-Maskable Interrupt (NMI) */
     .word stm32_hardfault  /* Vector  3: Hard fault */
     .word stm32_mpu   /* Vector  4: Memory management (MPU) */
     .word stm32_busfault  /* Vector  5: Bus fault */
     .word stm32_usagefault /* Vector  6: Usage fault */
     .word stm32_reserved  /* Vector  7: Reserved */
     .word stm32_reserved  /* Vector  8: Reserved */
     .word stm32_reserved  /* Vector  9: Reserved */
     .word stm32_reserved  /* Vector 10: Reserved */
     .word stm32_svcall  /* Vector 11: SVC call */
     .word stm32_dbgmonitor /* Vector 12: Debug monitor */
     .word stm32_reserved  /* Vector 13: Reserved */
     .word stm32_pendsv  /* Vector 14: Pendable system service request */
     .word stm32_systick  /* Vector 15: System tick */
    /* External Interrupts */

    阅读过 keil中 STM32启动代码的应该大体上都能看懂这段代码。在 keil中最后是调用了一个 “__main”的符号进入 main函数的,其实就是 C语言函数汇编之后的符号。这里其实都一样,只是入口函数不再是 main函数而已。
        这里定义了堆栈大小还有 “.vectors”段,即中断向量表。 bootloader引导的时候会进入该中断向量表的复位向量即 “__start”。之后就是初始化,知道调用我们的 stm32_boardinitialize函数并启动系统。而在我们的初始化中基本上都是对 IO进行配置。
        那么现在的疑问是,当系统启动之后是如何调用我们的其他函数的?进程调用吗?这是操作系统的通用做法。而且这样做通常需要把我们自己的程序设计成操作系统中的一个进程。
        如果我们去阅读 IO板的相关源码,我们会在 px4io.c文件中看到这样一个函数:

    int user_start(int argc, char *argv[])
    {
        /* run C++ ctors before we go any further */
        up_cxxinitialize();

        /* reset all to zero */
        memset(&system_state, 0, sizeof(system_state));

        /* configure the high-resolution time/callout interface */
        hrt_init();

        /* calculate our fw CRC so FMU can decide if we need to update */
        calculate_fw_crc();

        
    /*
         * Poll at 1ms intervals for received bytes that have not triggered
         * a DMA event.
         */
    #ifdef CONFIG_ARCH_DMA
        hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL);
    #endif

        /* print some startup info */
        lowsyslog(" PX4IO: starting ");

        /* default all the LEDs to off while we start */
        LED_AMBER(false);
        LED_BLUE(false);
        LED_SAFETY(false);

        /* turn on servo power (if supported) */
    #ifdef POWER_SERVO
        POWER_SERVO(true);
    #endif

        /* turn off S.Bus out (if supported) */
    #ifdef ENABLE_SBUS_OUT
        ENABLE_SBUS_OUT(false);
    #endif

        /* start the safety switch handler */
        safety_init();

        /* configure the first 8 PWM outputs (i.e. all of them) */
        up_pwm_servo_init(0xff);

        /* initialise the control inputs */
        controls_init();

        /* set up the ADC */
        adc_init();

        /* start the FMU interface */
        interface_init();

        /* add a performance counter for mixing */
        perf_counter_t mixer_perf = perf_alloc(PC_ELAPSED, "mix");

        /* add a performance counter for controls */
        perf_counter_t controls_perf = perf_alloc(PC_ELAPSED, "controls");

        /* and one for measuring the loop rate */
        perf_counter_t loop_perf = perf_alloc(PC_INTERVAL, "loop");

        struct mallinfo minfo = mallinfo();
        lowsyslog("MEM: free %u, largest %u ", minfo.mxordblk, minfo.fordblks);

        /* initialize PWM limit lib */
        pwm_limit_init(&pwm_limit);

        
    /*
         *    P O L I C E    L I G H T S
         *
         * Not enough memory, lock down.
         *
         * We might need to allocate mixers later, and this will
         * ensure that a developer doing a change will notice
         * that he just burned the remaining RAM with static
         * allocations. We don't want him to be able to
         * get past that point. This needs to be clearly
         * documented in the dev guide.
             *
         */
        if (minfo.mxordblk < 600) {

            lowsyslog("ERR: not enough MEM");
            bool phase = false;

            while (true) {

                if (phase) {
                    LED_AMBER(true);
                    LED_BLUE(false);
                } else {
                    LED_AMBER(false);
                    LED_BLUE(true);
                }
                up_udelay(250000);

                phase = !phase;
            }
        }

        /* Start the failsafe led init */
        failsafe_led_init();

        
    /*
         * Run everything in a tight loop.
         */

        uint64_t last_debug_time = 0;
            uint64_t last_heartbeat_time = 0;
        for (;;) {

            /* track the rate at which the loop is running */
            perf_count(loop_perf);

            /* kick the mixer */
            perf_begin(mixer_perf);
            mixer_tick();
            perf_end(mixer_perf);

            /* kick the control inputs */
            perf_begin(controls_perf);
            controls_tick();
            perf_end(controls_perf);

                    if ((hrt_absolute_time() - last_heartbeat_time) > 250*1000) {
                        last_heartbeat_time = hrt_absolute_time();
                        heartbeat_blink();
                    }

                    check_reboot();

            /* check for debug activity (default: none) */
            show_debug_messages();

            
    /* post debug state at ~1Hz - this is via an auxiliary serial port
             * DEFAULTS TO OFF!
             */
            if (hrt_absolute_time() - last_debug_time > (1000 * 1000)) {

                struct mallinfo minfo = mallinfo();

                isr_debug(1, "d:%u s=0x%x a=0x%x f=0x%x m=%u", 
                      (unsigned)r_page_setup[PX4IO_P_SETUP_SET_DEBUG],
                      (unsigned)r_status_flags,
                      (unsigned)r_setup_arming,
                      (unsigned)r_setup_features,
                      (unsigned)minfo.mxordblk);
                last_debug_time = hrt_absolute_time();
            }
        }
    }

        user_start函数之所以能够吸引我主要基于下面三点:
    一、函数的定义。 “int user_start(int argc, char *argv[])”是一个标准的 main函数形式。而 main函数通常作为程序的入口,这也就意味着这是一个入口函数。而且可以推测这是应用程序入口,因为至少目前在 Linux中不会这样去写一个驱动的入口, Nuttx是类 Linux系统,我自然确信不会这么做。那么既然是入口,那肯定有人去调用。
    二、这里调用了一些初始化函数,也就是说 IO板在这里进行初始化。那我们就容易想到这实际上就相当于我们跑裸机时的 main函数。
    三、主循环。我们跑裸机的时候一定会有一个主循环。不管这个循环是在 mian函数还是子函数中,但肯定会有。
    这三点可以说确定了 user_start函数在 IO的地位。而且我们可以找到以下内容:

    ../PX4NuttX/nuttx/.config:320:CONFIG_USER_ENTRYPOINT="user_start"

    “.config”是 Nuttx系统的配置文件,而 “CONFIG_USER_ENTRYPOINT”的命名已经明明白白地告诉我们这是一个入口,用户入口。最后我们可以匹配到下面的内容:

    ../PX4NuttX/nuttx/include/nuttx/init.h:71:EXTERN int    CONFIG_USER_ENTRYPOINT(int argc, char *argv[]);
    ../PX4NuttX/nuttx/include/nuttx/config.h:89:#define CONFIG_USER_ENTRYPOINT user_start
    ../PX4NuttX/nuttx/include/nuttx/config.h:389: * with existing code, for builds which donot define CONFIG_USER_ENTRYPOINT.
    ../PX4NuttX/nuttx/include/nuttx/config.h:392:#ifndef CONFIG_USER_ENTRYPOINT
    ../PX4NuttX/nuttx/include/nuttx/config.h:393:# defineCONFIG_USER_ENTRYPOINT user_start
    ../PX4NuttX/nuttx/tools/cfgdefine.c:66:  "CONFIG_USER_ENTRYPOINT",            /* Name of entry point function */
    ../PX4NuttX/nuttx/tools/mkconfig.c:266:  printf(" * with existing code, for builds which do not define CONFIG_USER_ENTRYPOINT. ");
    ../PX4NuttX/nuttx/tools/mkconfig.c:268:  printf("#ifndef CONFIG_USER_ENTRYPOINT ");
    ../PX4NuttX/nuttx/tools/mkconfig.c:269:  printf("# define CONFIG_USER_ENTRYPOINT user_start ");
    ../PX4NuttX/nuttx/sched/os_bringup.c:219:   * is given by the definitions, CONFIG_USER_ENTRYPOINT.  In the kernel
    ../PX4NuttX/nuttx/sched/os_bringup.c:232:                       (main_t)CONFIG_USER_ENTRYPOINT,

    最后一条信息实际上就告诉了我们 “CONFIG_USER_ENTRYPOINT”是如何调用的。

    /****************************************************************************
     * Name: os_bringup
     *
     * Description:
     *   Start all initial system tasks.  This does the "system bring-up" after
     *   the conclusion of basic OS initialization.  These initial system tasks
     *   may include:
     *
     *   - pg_worker:   The page-fault worker thread (only if CONFIG_PAGING is
     *                  defined.
     *   - work_thread: The work thread.  This general thread can be used to
     *                  perform most any kind of queued work.  Its primary
     *                  function is to serve as the "bottom half" of device
     *                  drivers.
     *
     *   And the main application entry point:
     *   symbols:
     *
     *   - USER_ENTRYPOINT: This is the default user application entry point.
     *                 
     ****************************************************************************/

    int os_bringup(void)
    {
      int taskid;

      /* Setup up the initial environment for the idle task.  At present, this
       * may consist of only the initial PATH variable.  The PATH variable is
       * (probably) not used by the IDLE task.  However, the environment
       * containing the PATH variable will be inherited by all of the threads
       * created by the IDLE task.
       */

    #if !defined(CONFIG_DISABLE_ENVIRON) && defined(CONFIG_PATH_INITIAL)
      (void)setenv("PATH", CONFIG_PATH_INITIAL, 1);
    #endif

      /* Start the page fill worker kernel thread that will resolve page faults.
       * This should always be the first thread started because it may have to
       * resolve page faults in other threads
       */

    #ifdef CONFIG_PAGING
      svdbg("Starting paging thread ");

      g_pgworker = KERNEL_THREAD("pgfill", CONFIG_PAGING_DEFPRIO,
                                 CONFIG_PAGING_STACKSIZE,
                                 (main_t)pg_worker, (FAR char * const *)NULL);
      DEBUGASSERT(g_pgworker > 0);
    #endif

      /* Start the worker thread that will serve as the device driver "bottom-
       * half" and will perform misc garbage clean-up.
       */

    #ifdef CONFIG_SCHED_WORKQUEUE
    #ifdef CONFIG_SCHED_HPWORK

    #ifdef CONFIG_SCHED_LPWORK
      svdbg("Starting high-priority kernel worker thread ");
    #else
      svdbg("Starting kernel worker thread ");
    #endif

      g_work[HPWORK].pid = KERNEL_THREAD(HPWORKNAME, CONFIG_SCHED_WORKPRIORITY,
                                         CONFIG_SCHED_WORKSTACKSIZE,
                                         (main_t)work_hpthread, (FAR char * const *)NULL);
      DEBUGASSERT(g_work[HPWORK].pid > 0);

      /* Start a lower priority worker thread for other, non-critical continuation
       * tasks
       */

    #ifdef CONFIG_SCHED_LPWORK

      svdbg("Starting low-priority kernel worker thread ");

      g_work[LPWORK].pid = KERNEL_THREAD(LPWORKNAME, CONFIG_SCHED_LPWORKPRIORITY,
                                         CONFIG_SCHED_LPWORKSTACKSIZE,
                                         (main_t)work_lpthread, (FAR char * const *)NULL);
      DEBUGASSERT(g_work[LPWORK].pid > 0);

    #endif /* CONFIG_SCHED_LPWORK */
    #endif /* CONFIG_SCHED_HPWORK */

    #if defined(CONFIG_NUTTX_KERNEL) && defined(CONFIG_SCHED_USRWORK)
      /* Start the user-space work queue */

      DEBUGASSERT(USERSPACE->work_usrstart != NULL);
      taskid = USERSPACE->work_usrstart();
      DEBUGASSERT(taskid > 0);
    #endif

    #endif /* CONFIG_SCHED_WORKQUEUE */

      /* Once the operating system has been initialized, the system must be
       * started by spawning the user init thread of execution.  This is the
       * first user-mode thead.
       */

      svdbg("Starting init thread ");

      /* Perform any last-minute, board-specific initialization, if so
       * configured.
       */

    #ifdef CONFIG_BOARD_INITIALIZE
      board_initialize();
    #endif

      /* Start the default application.  In a flat build, this is entrypoint
       * is given by the definitions, CONFIG_USER_ENTRYPOINT.  In the kernel
       * build, however, we must get the address of the entrypoint from the
       * header at the beginning of the user-space blob.
       */

    #ifdef CONFIG_NUTTX_KERNEL
      DEBUGASSERT(USERSPACE->us_entrypoint != NULL);
      taskid = TASK_CREATE("init", SCHED_PRIORITY_DEFAULT,
                           CONFIG_USERMAIN_STACKSIZE, USERSPACE->us_entrypoint,
                           (FAR char * const *)NULL);
    #else
      taskid = TASK_CREATE("init", SCHED_PRIORITY_DEFAULT,
                           CONFIG_USERMAIN_STACKSIZE,
                           (main_t)CONFIG_USER_ENTRYPOINT,
                           (FAR char * const *)NULL);
    #endif
      ASSERT(taskid > 0);

      /* We an save a few bytes by discarding the IDLE thread's environment. */

    #if !defined(CONFIG_DISABLE_ENVIRON) && defined(CONFIG_PATH_INITIAL)
      (void)clearenv();
    #endif

      return OK;
    }

    在这里我们看到我们的入口函数是作为操作系统的 init进程在运行的。熟悉 Linux系统的人想必都知道 init进程在 Linux系统中的特殊地位,这里我就不介绍了。
        在分析脚本的时候,我看到 IO板没有 g_builtins数组于是就认为 IO板是跑裸机的,其实这只是其中一个原因,还有一个原因是 IO板没有使用根文件系统。因为通常跑操作系统都离不开根文件系统,这应该是我的定势思维在作祟了,于是就认为 IO板如果运行 Nuttx系统也必须有一个根文件系统。而我在观察编译输出信息的时候也确实只有核心板才会去制作根文件系统,并且进行链接。后面我看到 IO板的编译使用了 Nuttx库,于是我不得不承认 IO板确实是跑操作系统的。直到此时我心中的疑团才算是解开了,因为我们的 init进程根本就没有使用根文件系统,也没有使用 g_builtins数组,既然不使用,那自然也就不需要。
        若是我们想知道 “os_bringup”函数是如何被使用的,这倒也简单。在 “__start”函数的最后调用了一个 “os_start”函数,其源码如下:

    /****************************************************************************
     * Name: os_start
     *
     * Description:
     *   This function is called to initialize the operating system and to spawn
     *   the user initization thread of execution
     *
     ****************************************************************************/

    void os_start(void)
    {
      int i;

      slldbg("Entry ");

      /* Initialize RTOS Data ***************************************************/
      /* Initialize all task lists */

      dq_init(&g_readytorun);
      dq_init(&g_pendingtasks);
      dq_init(&g_waitingforsemaphore);
    #ifndef CONFIG_DISABLE_SIGNALS
      dq_init(&g_waitingforsignal);
    #endif
    #ifndef CONFIG_DISABLE_MQUEUE
      dq_init(&g_waitingformqnotfull);
      dq_init(&g_waitingformqnotempty);
    #endif
    #ifdef CONFIG_PAGING
      dq_init(&g_waitingforfill);
    #endif
      dq_init(&g_inactivetasks);
      sq_init(&g_delayed_kufree);
    #if defined(CONFIG_NUTTX_KERNEL) && defined(CONFIG_MM_KERNEL_HEAP)
      sq_init(&g_delayed_kfree);
    #endif

      /* Initialize the logic that determine unique process IDs. */

      g_lastpid = 0;
      for (i = 0; i < CONFIG_MAX_TASKS; i++)
        {
          g_pidhash[i].tcb = NULL;
          g_pidhash[i].pid = INVALID_PROCESS_ID;
        }

      /* Assign the process ID of ZERO to the idle task */

      g_pidhash[ PIDHASH(0)].tcb = &g_idletcb.cmn;
      g_pidhash[ PIDHASH(0)].pid = 0;

      /* Initialize the IDLE task TCB *******************************************/
      /* Initialize a TCB for this thread of execution.  NOTE:  The default
       * value for most components of the g_idletcb are zero.  The entire
       * structure is set to zero.  Then only the (potentially) non-zero
       * elements are initialized. NOTE:  The idle task is the only task in
       * that has pid == 0 and sched_priority == 0.
       */

      bzero((void*)&g_idletcb, sizeof(struct task_tcb_s));
      g_idletcb.cmn.task_state = TSTATE_TASK_RUNNING;
      g_idletcb.cmn.entry.main = (main_t)os_start;

      /* Set the IDLE task name */

    #if CONFIG_TASK_NAME_SIZE > 0
      strncpy(g_idletcb.cmn.name, g_idlename, CONFIG_TASK_NAME_SIZE-1);
    #endif /* CONFIG_TASK_NAME_SIZE */

      /* Configure the task name in the argument list.  The IDLE task does
       * not really have an argument list, but this name is still useful
       * for things like the NSH PS command.
       *
       * In the kernel mode build, the arguments are saved on the task's stack
       * and there is no support that yet.
       */

    #if defined(CONFIG_CUSTOM_STACK) || !defined(CONFIG_NUTTX_KERNEL)
    #if CONFIG_TASK_NAME_SIZE > 0
      g_idletcb.argv[0] = g_idletcb.cmn.name;
    #else
      g_idletcb.argv[0] = (char*)g_idlename;
    #endif /* CONFIG_TASK_NAME_SIZE */
    #endif /* CONFIG_CUSTOM_STACK || !CONFIG_NUTTX_KERNEL */

      /* Then add the idle task's TCB to the head of the ready to run list */

      dq_addfirst((FAR dq_entry_t*)&g_idletcb, (FAR dq_queue_t*)&g_readytorun);

      /* Initialize the processor-specific portion of the TCB */

      up_initial_state(&g_idletcb.cmn);

      /* Initialize RTOS facilities *********************************************/
      /* Initialize the semaphore facility(if in link).  This has to be done
       * very early because many subsystems depend upon fully functional
       * semaphores.
       */

    #ifdef CONFIG_HAVE_WEAKFUNCTIONS
      if (sem_initialize != NULL)
    #endif
        {
          sem_initialize();
        }

      /* Initialize the memory manager */

      {
        FAR void *heap_start;
        size_t heap_size;

        /* Get the user-mode heap from the platform specific code and configure
         * the user-mode memory allocator.
         */

        up_allocate_heap(&heap_start, &heap_size);
        kumm_initialize(heap_start, heap_size);

    #if defined(CONFIG_NUTTX_KERNEL) && defined(CONFIG_MM_KERNEL_HEAP)
        /* Get the kernel-mode heap from the platform specific code and configure
         * the kernel-mode memory allocator.
         */

        up_allocate_kheap(&heap_start, &heap_size);
        kmm_initialize(heap_start, heap_size);
    #endif
      }

      /* Initialize tasking data structures */

    #if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS)
    #ifdef CONFIG_HAVE_WEAKFUNCTIONS
      if (task_initialize != NULL)
    #endif
        {
          task_initialize();
        }
    #endif

      /* Initialize the interrupt handling subsystem (if included) */

    #ifdef CONFIG_HAVE_WEAKFUNCTIONS
      if (irq_initialize != NULL)
    #endif
        {
          irq_initialize();
        }

      /* Initialize the watchdog facility (if included in the link) */

    #ifdef CONFIG_HAVE_WEAKFUNCTIONS
      if (wd_initialize != NULL)
    #endif
        {
          wd_initialize();
        }

      /* Initialize the POSIX timer facility (if included in the link) */

    #ifndef CONFIG_DISABLE_CLOCK
    #ifdef CONFIG_HAVE_WEAKFUNCTIONS
      if (clock_initialize != NULL)
    #endif
        {
          clock_initialize();
        }
    #endif

    #ifndef CONFIG_DISABLE_POSIX_TIMERS
    #ifdef CONFIG_HAVE_WEAKFUNCTIONS
      if (timer_initialize != NULL)
    #endif
        {
          timer_initialize();
        }
    #endif

      /* Initialize the signal facility (if in link) */

    #ifndef CONFIG_DISABLE_SIGNALS
    #ifdef CONFIG_HAVE_WEAKFUNCTIONS
      if (sig_initialize != NULL)
    #endif
        {
          sig_initialize();
        }
    #endif

      /* Initialize the named message queue facility (if in link) */

    #ifndef CONFIG_DISABLE_MQUEUE
    #ifdef CONFIG_HAVE_WEAKFUNCTIONS
      if (mq_initialize != NULL)
    #endif
        {
          mq_initialize();
        }
    #endif

      /* Initialize the thread-specific data facility (if in link) */

    #ifndef CONFIG_DISABLE_PTHREAD
    #ifdef CONFIG_HAVE_WEAKFUNCTIONS
      if (pthread_initialize != NULL)
    #endif
        {
          pthread_initialize();
        }
    #endif

      /* Initialize the file system (needed to support device drivers) */

    #if CONFIG_NFILE_DESCRIPTORS > 0
    #ifdef CONFIG_HAVE_WEAKFUNCTIONS
      if (fs_initialize != NULL)
    #endif
        {
          fs_initialize();
        }
    #endif

      /* Initialize the network system */

    #ifdef CONFIG_NET
    #if 0
      if (net_initialize != NULL)
    #endif
        {
          net_initialize();
        }
    #endif

      /* The processor specific details of running the operating system
       * will be handled here.  Such things as setting up interrupt
       * service routines and starting the clock are some of the things
       * that are different for each  processor and hardware platform.
       */

      up_initialize();

      /* Initialize the C libraries (if included in the link).  This
       * is done last because the libraries may depend on the above.
       */

    #ifdef CONFIG_HAVE_WEAKFUNCTIONS
      if (lib_initialize != NULL)
    #endif
        {
          lib_initialize();
        }

      /* IDLE Group Initialization **********************************************/
      /* Allocate the IDLE group and suppress child status. */

    #ifdef HAVE_TASK_GROUP
      DEBUGVERIFY(group_allocate(&g_idletcb));
    #endif

      /* Create stdout, stderr, stdin on the IDLE task.  These will be
       * inherited by all of the threads created by the IDLE task.
       */

      DEBUGVERIFY(group_setupidlefiles(&g_idletcb));

      /* Complete initialization of the IDLE group.  Suppress retention
       * of child status in the IDLE group.
       */

    #ifdef HAVE_TASK_GROUP
      DEBUGVERIFY(group_initialize(&g_idletcb));
      g_idletcb.cmn.group->tg_flags = GROUP_FLAG_NOCLDWAIT;
    #endif

      /* Bring Up the System ****************************************************/
      /* Create initial tasks and bring-up the system */

      DEBUGVERIFY(os_bringup());

      /* The IDLE Loop **********************************************************/
      /* When control is return to this point, the system is idle. */

      sdbg("Beginning Idle Loop ");
      for (;;)
        {
          /* Perform garbage collection (if it is not being done by the worker
           * thread).  This cleans-up memory de-allocations that were queued
           * because they could not be freed in that execution context (for
           * example, if the memory was freed from an interrupt handler).
           */

    #ifndef CONFIG_SCHED_WORKQUEUE
          /* We must have exclusive access to the memory manager to do this
           * BUT the idle task cannot wait on a semaphore.  So we only do
           * the cleanup now if we can get the semaphore -- this should be
           * possible because if the IDLE thread is running, no other task is!
           */

          if (kmm_trysemaphore() == 0)
            {
              sched_garbagecollection();
              kmm_givesemaphore();
            }
    #endif

          /* Perform any processor-specific idle state operations */

          up_idle();
        }
    }

    我们其实只关心最后一段代码就可以了。在 for循环前面通过语句 “DEBUGVERIFY(os_bringup());”调用了 “os_bringup”函数。
        以上就是 IO板启动的大致流程。而我们写程序的时候其实只需简单认为 “user_start”就是我们的入口函数,即当作裸机运行时的 main函数即可。于是我们后面的代码都将以 “user_start”函数作为起点,如果我们忽略操作系统细节的话。
    2. firmware
        现在从入口函数开始分析我们的 IO板。
        在入口函数中,调用的第一个函数是 “up_cxxinitialize”:

        /* run C++ ctors before we go any further */
        up_cxxinitialize();

    注释说这里调用了 C++,

    /************************************************************************************
     * Private Types
     ************************************************************************************/
    /* This type defines one entry in initialization array */

    typedef void (*initializer_t)(void);

    /************************************************************************************
     * External references
     ************************************************************************************/
    /* _sinit and _einit are symbols exported by the linker script that mark the
     * beginning and the end of the C++ initialization section.
     */

    extern initializer_t _sinit;
    extern initializer_t _einit;

    /* _stext and _etext are symbols exported by the linker script that mark the
     * beginning and the end of text.
     */

    extern uint32_t _stext;
    extern uint32_t _etext;

    /************************************************************************************
     * Private Functions
     ************************************************************************************/

    /************************************************************************************
     * Public Functions
     ************************************************************************************/

    /****************************************************************************
     * Name: up_cxxinitialize
     *
     * Description:
     *   If C++ and C++ static constructors are supported, then this function
     *   must be provided by board-specific logic in order to perform
     *   initialization of the static C++ class instances.
     *
     *   This function should then be called in the application-specific
     *   user_start logic in order to perform the C++ initialization.  NOTE
     *   that no component of the core NuttX RTOS logic is involved; This
     *   function defintion only provides the 'contract' between application
     *   specific C++ code and platform-specific toolchain support
     *
     ***************************************************************************/

    __EXPORT void up_cxxinitialize(void)
    {
      initializer_t *initp;

      cxxdbg("_sinit: %p _einit: %p _stext: %p _etext: %p ",
             &_sinit, &_einit, &_stext, &_etext);

      /* Visit each entry in the initialzation table */

      for (initp = &_sinit; initp != &_einit; initp++)
        {
          initializer_t initializer = *initp;
          cxxdbg("initp: %p initializer: %p ", initp, initializer);

          /* Make sure that the address is non-NULL and lies in the text region
           * defined by the linker script.  Some toolchains may put NULL values
           * or counts in the initialization table
           */

          if ((void*)initializer > (void*)&_stext && (void*)initializer < (void*)&_etext)
            {
              cxxdbg("Calling %p ", initializer);
              initializer();
            }
        }
    }

    通过源码我们看到初始化是通过段进行调用的。通过段去调用一个函数这在 Linux中国可是家常便饭,像驱动跟板子初始化可都是这么调用的。
        最直接的方式自然是去分析这个段,看下到底哪些数据被放进这个段了。不过这可不简单,费时而且费力。
        但其实我们可以在这里耍点小聪明。
        首先我知道 “_sinit”是该段的起始地址, “_einit”是该段的结束地址。而这两个地址通常都是在链接脚本中定义的,即 ld.script文件。其中就有这样一段内容:

    /*
      * Init functions (static constructors and the like)
      */
            .init_section : {
                    _sinit = ABSOLUTE(.);
                    KEEP(*(.init_array .init_array.*))
                    _einit = ABSOLUTE(.);
            } > flash

    代码注释说调用的是 C++,这里注释说该段放的是构造函数。所以我们不可能到 C源文件中国去寻找这些函数。而我们在 map文件中又可以找到下面的内容:

    .init_section   0x0800979c        0x4
                    0x0800979c                _sinit = ABSOLUTE (.)
     *(.init_array .init_array.*)
     .init_array    0x0800979c        0x4 /home/bitcraze/apm/PX4Firmware/Build/px4io-v2_default.build//home/bitcraze/apm/PX4Firmware/src/modules/px4iofirmware/module.pre.o
                    0x080097a0                _einit = ABSOLUTE (.)

    我们可以从这段内容了解以下信息:
    一、段地址。起始地址跟结束地址。
    二、段大小。已经给出为 0x4,也可以自己计算,这刚好够放一个函数的地址。
    三、该段的内容来自那个目标文件。通过这个内容我们其实可以知道具体的目录 “PX4Firmware/src/modules/px4iofirmware”。
    既然知道了目录,那么我们就可以到相应的目录下去查看 “module.mk”文件。

    SRCS  = adc.c
        controls.c
        dsm.c
        px4io.c
        registers.c
        safety.c
        sbus.c
        ../systemlib/up_cxxinitialize.c
        ../systemlib/perf_counter.c
        mixer.cpp
        ../systemlib/mixer/mixer.cpp
        ../systemlib/mixer/mixer_group.cpp
        ../systemlib/mixer/mixer_multirotor.cpp

  • 相关阅读:
    MySQL 视图的作用
    基类一定要设置虚析构函数,否则会内存泄露
    Delphi ISO,包括D2010DXE6比较全面的测评(绝美PDF)
    一些最重要的PHP数组函数
    没有虚函数情况下的函数覆盖(以原始指针的类型为准)
    使用Mono.Cecil辅助ASP.NET MVC使用dynamic类型Model
    持续集成(CI) TeamCity实战概览
    对.Net状态保持机制和并发问题的思考
    Windows Communication Foundation 概述
    Welcome to HDU Online Judge System
  • 原文地址:https://www.cnblogs.com/eastgeneral/p/10879706.html
Copyright © 2020-2023  润新知