ardupilot启动:从上电到ArduCopter应用层代码(转)

2019-04-13 16:10发布

class="markdown_views prism-kimbie-light">

ardupilot启动:从上电到ArduCopter应用层代码

原文: http://www.amovauto.com/portal.php?mod=view&aid=132 从上电到执行rcS脚本的过程两块控制板(即fmu和io)上电后分别独立启动并运行各自的code。运行过程为:
(1) 2套stm32_start()分别初始化fmu和io
(链接脚本/ardupilot/modules/PX4Firmware/nuttx-configs/px4fmu-v2/scripts/ld.script,中由ENTRY_POINT(__start)指定;同样,/ardupilot/modules/PX4Firmware/nuttx-configs/px4io-v2/scripts/ld.script,中由ENTRY_POINT(__start)指定;px4使用的是stm32,该入口在stm32_start.c中定义) __start-- #处理器执行的第一条指令 | v stm32_clockconfig()------ #初始化时钟 80003d2: f000 f827 bl 8000424 | v rcc_reset() #复位rcc stm32_stdclockconfig() #初始化标准时钟 rcc_enableperipherals() #使能外设时钟 | -------------------- | v stm32_fpuconfig() #配置fpu, stm32_lowsetup() #基本初始化串口,之后可以使用up_lowputc() stm32_gpioinit() #初始化gpio,只是调用stm32_gpioremap()设置重映射 clear bss # 清bss段 up_earlyserialinit() #初始化串口,之后可以使用up_putc() stm32_boardinitialize()-- #板级初始化 | v stm32_spiinitialize() #初始化spi,只是调用stm32_configgpio()设置gpio stm32_usbinitialize() #初始化usb,只是调用stm32_configgpio()设置gpio board_led_initialize() #初始化led,只是调用stm32_configgpio()设置gpio | -------------------- | v (2) 2套os_start()分别初始化nuttx系统 28. os_start()-------------#初始化操作系统 ardupilotmodulesPX4NuttX uttxschedos_start.c 29. | 30. v 31. dq_init() #初始化各种状态的任务列表(置为null) 32. g_pidhash[i]= #初始化唯一可以确定的元素--进程ID 33. g_pidhash[PIDHASH(0)]= #分配空闲任务的进程ID为0 34. g_idletcb= #初始化空闲任务的任务控制块 35. sem_initialize()-- #初始化信号量 36. | 37. v 38. dq_init() #将信号量队列置为null 39. sem_initholders() #初始化持有者结构以支持优先级继承, 40. | 41. -------- 42. | 43. v 44. up_allocate_heap() #分配用户模式的堆(设置堆的起点和大小) 45. kumm_initialize() #初始化用户模式的堆 46. up_allocate_kheap() #分配内核模式的堆, 47. kmm_initialize() #初始化内核模式的堆, 48. task_initialize() #初始化任务数据结构, 49. irq_initialize() #将所有中断向量都指向同一个异常中断处理程序 50. wd_initialize() #初始化看门狗数据结构 51. clock_initialize() #初始化rtc 52. timer_initialize() #配置POSIX定时器 53. sig_initialize() #初始化信号 54. mq_initialize() #初始化命名消息队列 55. pthread_initialize() #初始化线程特定的数据,空函数 56. fs_initialize()--- #初始化文件系统 57. | 58. v 59. sem_init() #初始化节点信号量为1 60. files_initialize() #初始化文件数组,空函数 61. | 62. -------- 63. | 64. v 65. net_initialize()-- #初始化网络 66. | 67. v 68. uip_initialize() #初始化uIP层 69. net_initroute() #初始化路由表, 70. netdev_seminit() #初始化网络设备信号量 71. arptimer_init() #初始化ARP定时器 72. | 73. -------- 74. | 75. v 76. up_initialize()--- #处理器特定的初始化 77. | 78. v 79. up_calibratedelay()#校准定时器 80. up_addregion() #增加额外的内存段 81. up_irqinitialize() #设置中断优先级,关联硬件异常处理函数 82. up_pminitialize() #初始化电源管理, 83. up_dmainitialize() #初始化DMA, 84. up_timerinit() #初始化定时器中断 85. devnull_register() #注册/dev/null 86. devzero_register() #注册/dev/zero, 87. up_serialinit() #注册串口控制台/dev/console和串口/dev/ttyS0 88. up_rnginitialize() #初始化并注册随机数生成器 89. up_netinitialize() #初始化网络,是arch/arm/src/chip/stm32_eth.c中的 90. up_usbinitialize() #初始化usb驱动, 91. board_led_on() #打开中断使能led, 92. | 93. -------- 94. | 95. v 96. lib_initialize() #初始化c库,空函数 97. group_allocate() #分配空闲组 98. group_setupidlefiles() #在空闲任务上创建stdout、stderr、stdin 99. group_initialize() #完全初始化空闲组 100. os_bringup()------ #创建初始任务 os_bringup.c 101. | 102. v 103. KEKERNEL_THREAD() #启动内核工作者线程 104. board_initialize() #最后一刻的板级初始化,nsh未调用 105. TASK_CREATE() #启动默认应用程序 os_bringup.c 106. | 107. -------- 108. | 109. v 110. for up_idle() #空闲任务循环 111. | 112. -------------------- 113. | 114. v 115. for(;;) (3) 2套os_bringup()函数分别创建进程并传入进程指针CONFIG_USER_ENTRYPOINT #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); (4) fmu中的config.h文件宏定义 #define CONFIG_USER_ENTRYPOINT nsh_main io中的config.h文件宏定义 #define CONFIG_USER_ENTRYPOINT user_start (5) fmu开启nshshell int nsh_main(int argc, char *argv[]) { int exitval = 0; int ret; /* Call all C++ static constructors */ #if defined(CONFIG_HAVE_CXX) && defined(CONFIG_HAVE_CXXINITIALIZE) up_cxxinitialize(); #endif /* Make sure that we are using our symbol take */ #if defined(CONFIG_LIBC_EXECFUNCS) && defined(CONFIG_EXECFUNCS_SYMTAB) exec_setsymtab(CONFIG_EXECFUNCS_SYMTAB, 0); #endif /* Register the BINFS file system */ #if defined(CONFIG_FS_BINFS) && (CONFIG_BUILTIN) ret = builtin_initialize(); if (ret < 0) { fprintf(stderr, "ERROR: builtin_initialize failed: %d ", ret); exitval = 1; } #endif /* Initialize the NSH library */ nsh_initialize(); /* If the Telnet console is selected as a front-end, then start the * Telnet daemon. */ #ifdef CONFIG_NSH_TELNET ret = nsh_telnetstart(); if (ret < 0) { /* The daemon is NOT running. Report the the error then fail... * either with the serial console up or just exiting. */ fprintf(stderr, "ERROR: Failed to start TELNET daemon: %d ", ret); exitval = 1; } #endif /* If the serial console front end is selected, then run it on this thread */ #ifdef CONFIG_NSH_CONSOLE ret = nsh_consolemain(0, NULL); /* nsh_consolemain() should not return. So if we get here, something * is wrong. */ fprintf(stderr, "ERROR: nsh_consolemain() returned: %d ", ret); exitval = 1; #endif return exitval; } io
user_start 负责px4io 基础环境的初始化,包括PWM,串口,ADC 等资源的初始化,最后运行一个死循环,用于处理遥控器输入,与PX4FMU 通信的内容
controls_tick 负责处理遥控器的输入内容,包括SBUS 的处理sbus_input、 SPKT/DSM 的处理dsm_port_input、 PPM 的处理ppm_input int user_start(int argc, char *argv[]) { /* configure the first 8 PWM outputs (i.e. all of them) */ up_pwm_servo_init(0xff); /* 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); #ifdef GPIO_LED4 LED_RING(false); #endif /* 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(); /* 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; for (;;) { /* track the rate at which the loop is running */ perf_count(loop_perf); /* kick the mixer */ perf_begin(mixer_perf); if (!(r_setup_features & PX4IO_P_SETUP_FEATURES_ONESHOT)) { /* when in oneshot we don't trigger output until we get new data from the FMU */ mixer_tick(); } perf_end(mixer_perf); /* kick the control inputs */ perf_begin(controls_perf); controls_tick(); perf_end(controls_perf); 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)) { 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)mallinfo().mxordblk); last_debug_time = hrt_absolute_time(); } if (r_page_setup[PX4IO_P_SETUP_HEATER_DUTY_CYCLE] <= PX4IO_HEATER_MAX) { control_IMU_heater(r_page_setup[PX4IO_P_SETUP_HEATER_DUTY_CYCLE]); } else { control_heartbeat_LED(); } } } 至此io板启动分析完了,fmu继续分析
(6)nsh_main中
nsh_initialize()初始化nshshell,
nsh_consolemain()执行nshshell
进入nsh_consolemain() int nsh_consolemain(int argc, char *argv[]) { FAR struct console_stdio_s *pstate = nsh_newconsole(); int ret; DEBUGASSERT(pstate); /* Execute the start-up script */ #ifdef CONFIG_NSH_ROMFSETC (void)nsh_initscript(&pstate->cn_vtbl); #endif /* Initialize any USB tracing options that were requested */ #ifdef CONFIG_NSH_USBDEV_TRACE usbtrace_enable(TRACE_BITSET); #endif /* Execute the session */ ret = nsh_session(pstate); /* Exit upon return */ nsh_exit(&pstate->cn_vtbl, ret); return ret; } (void)nsh_initscript(&pstate->cn_vtbl);初始化nsh脚本
ret = nsh_session(pstate);执行nsh脚本
至此nsh脚本还没有引入,所以需要去寻找nsh脚本是什么,进入nsh_initscript() #ifdef CONFIG_NSH_ROMFSETC int nsh_initscript(FAR struct nsh_vtbl_s *vtbl) { static bool initialized; bool already; int ret = OK; /* Atomic test and set of the initialized flag */ sched_lock(); already = initialized; initialized = true; sched_unlock(); /* If we have not already executed the init script, then do so now */ if (!already) { ret = nsh_script(vtbl, "init", NSH_INITPATH); } return ret; } ret = nsh_script(vtbl, “init”, NSH_INITPATH); //Execute the NSH script at path. #define NSH_INITPATH CONFIG_NSH_ROMFSMOUNTPT “/” CONFIG_NSH_INITSCRIPT
#define CONFIG_NSH_ROMFSMOUNTPT “/etc”
#define CONFIG_NSH_INITSCRIPT “init.d/rcS”
“/etc”是挂载目录
“init.d/rcS”是rcS路径
因此将”/etc”和”init.d/rcS”路径传入nsh_script() int nsh_script(FAR struct nsh_vtbl_s *vtbl, FAR const char *cmd, FAR const char *path) { FAR char *fullpath; FAR FILE *savestream; FAR char *buffer; FAR char *pret; int ret = ERROR; /* The path to the script may be relative to the current working directory */ fullpath = nsh_getfullpath(vtbl, path); if (!fullpath) { return ERROR; } /* Get a reference to the common input buffer */ buffer = nsh_linebuffer(vtbl); if (buffer) { /* Save the parent stream in case of nested script processing */ savestream = vtbl->np.np_stream; /* Open the file containing the script */ vtbl->np.np_stream = fopen(fullpath, "r"); if (!vtbl->np.np_stream) { nsh_output(vtbl, g_fmtcmdfailed, cmd, "fopen", NSH_ERRNO); /* Free the allocated path */ nsh_freefullpath(fullpath); /* Restore the parent script stream */ vtbl->np.np_stream = savestream; return ERROR; } /* Loop, processing each command line in the script file (or * until an error occurs) */ do { /* Flush any output generated by the previous line */ fflush(stdout); #ifndef CONFIG_NSH_DISABLE_LOOPS /* Get the current file position. This is used to control * looping. If a loop begins in the next line, then this file * offset will be needed to locate the top of the loop in the * script file. Note that ftell will return -1 on failure. */ vtbl->np.np_foffs = ftell(vtbl->np.np_stream); vtbl->np.np_loffs = 0; if (vtbl->np.np_foffs < 0) { nsh_output(vtbl, g_fmtcmdfailed, "loop", "ftell", NSH_ERRNO); } #endif /* Now read the next line from the script file */ pret = fgets(buffer, CONFIG_NSH_LINELEN, vtbl->np.np_stream); if (pret) { /* Parse process the command. NOTE: this is recursive... * we got to cmd_sh via a call to nsh_parse. So some * considerable amount of stack may be used. */ if ((vtbl->np.np_flags & NSH_PFLAG_SILENT) == 0) { nsh_output(vtbl,"%s", buffer); } ret = nsh_parse(vtbl, buffer); } } while (pret && (ret == OK || (vtbl->np.np_flags & NSH_PFLAG_IGNORE))); /* Close the script file */ fclose(vtbl->np.np_stream); /* Restore the parent script stream */ vtbl->np.np_stream = savestream; } /* Free the allocated path */ nsh_freefullpath(fullpath); return ret; } 其中nsh_output(vtbl, g_fmtcmdfailed, cmd, “fopen”, NSH_ERRNO);是将脚本打开
ret = nsh_parse(vtbl, buffer);解析脚本
至此分析完了fmu从上电到执行rcS脚本的过程。 从rcS启动到ArduCopter执行setup()、loop()
rcS的命令是nshshell的命令,比如 if rgbled start 先执行rgbled start,再作判断。
rgbled 可以对应到modules/PX4Firmware/Build/px4fmu-v2_APM.build/builtin_commands.c中
该文件在固件编译过程中自动生成,记录着一个名为g_builtin[]的数组,数组所有成员即为飞控上电之后,后台运行的所有应用程序,每个成员均有4个参数,分别为程序名、程序调度优先级、堆栈大小以及程序入口函数。 /* builtin command list - automatically generated, do not edit */ #include #include extern int sercon_main(int argc, char *argv[]); extern int serdis_main(int argc, char *argv[]); extern int px4io_main(int argc, char *argv[]); extern int mtd_main(int argc, char *argv[]); extern int adc_main(int argc, char *argv[]); extern int perf_main(int argc, char *argv[]); extern int fmu_main(int argc, char *argv[]); extern int tone_alarm_main(int argc, char *argv[]); extern int ArduPilot_main(int argc, char *argv[]); ///< -------------------- extern int pwm_input_main(int argc, char *argv[]); extern int nshterm_main(int argc, char *argv[]); extern int mixer_main(int argc, char *argv[]); extern int uorb_main(int argc, char *argv[]); extern int ver_main(int argc, char *argv[]); extern int usb_connected_main(int argc, char *argv[]); extern int bl_update_main(int argc, char *argv[]); extern int top_main(int argc, char *argv[]); extern int reboot_main(int argc, char *argv[]); const struct builtin_s g_builtins[] = { {"sercon", SCHED_PRIORITY_DEFAULT, 2048, sercon_main}, {"serdis", SCHED_PRIORITY_DEFAULT, 2048, serdis_main}, {"px4io", SCHED_PRIORITY_DEFAULT, 1200, px4io_main}, {"mtd", SCHED_PRIORITY_DEFAULT, CONFIG_PTHREAD_STACK_DEFAULT, mtd_main}, {"adc", SCHED_PRIORITY_DEFAULT, CONFIG_PTHREAD_STACK_DEFAULT, adc_main}, {"perf", SCHED_PRIORITY_DEFAULT, 1800