Pixhawk_nuttx启动过程和启动文件
转自:http://blog.csdn.net/wangcfan/article/details/51273923
通过系统在编译生成的 elf 文件 我们可以查看到nuttx 的文件头中可以找到这个程序入口点的地址0x80003d1;
根据 cortex-m3 的定义,系统从 flash 启动时,0x08000004中的值就是 PC(程序计数器)的初始值,这才是真正起作用的,它决定了处理器执行的第一条指令。
- nuttx.S文件中关于启动地址的说明:
- 8000004: 080003d1 .word 0x080003d1 <---PC 初始值
- 080003d0 <__start>:
- 80003d0: b510 push {r4, lr} <---处理器执行的第一条指令
- 1. __start-- #处理器执行的第一条指令 (px4使用的是stm32,入口在stm32_start.c中)
- 2. |
- 3. v
- 4. stm32_clockconfig()------ #初始化时钟 80003d2: f000 f827 bl 8000424
- 5. |
- 6. v
- 7. rcc_reset() #复位rcc
- 8. stm32_stdclockconfig() #初始化标准时钟
- 9. rcc_enableperipherals() #使能外设时钟
- 10. |
- 11. --------------------
- 12. |
- 13. v
- 14. stm32_fpuconfig() #配置fpu,
- 15. stm32_lowsetup() #基本初始化串口,之后可以使用up_lowputc()
- 16. stm32_gpioinit() #初始化gpio,只是调用stm32_gpioremap()设置重映射
- 17. up_earlyserialinit() #初始化串口,之后可以使用up_putc()
- 18. stm32_boardinitialize()-- #板级初始化
- 19. |
- 20. v
- 21. stm32_spiinitialize() #初始化spi,只是调用stm32_configgpio()设置gpio
- 22. stm32_usbinitialize() #初始化usb,只是调用stm32_configgpio()设置gpio
- 23. board_led_initialize() #初始化led,只是调用stm32_configgpio()设置gpio
- 24. |
- 25. --------------------
- 26. |
- 27. v
- 28. os_start()-------------#初始化操作系统 ardupilot\modules\PX4NuttX\nuttx\sched\os_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(;;)
ASK_CREATE()这里是启动默认的应用程序,入口点由CONFIG_USER_ENTRYPOINT给出
TASK_CREATE()启动Nsh终端程序, nsh_script.c文件中的 nsh_initscript
NSH.h中NSH_INITPATH文件为RCS文件路径, 开始执行rcS脚本文件.
进入控制台程序,也就是nsh_consolemain()函数。在这里实际上nsh_initscript和nsh_session都会去执行命令,但是前者是执行启动脚本也就是rcS,后者是执行用户程序。
当系统启动NSH之后,系统就算是正常启动起来了,之后NSH通过脚本启动PX4代码或Ardupilot代码;
Ardupilot的启动脚本:
rcS: Nuttx系统默认的启动脚本,
Ardupilot代码中用来加载LED灯,SD卡,USB连接,最后加载Ardupilot的启动文件rc.APM;
rc.APM:
创建SD卡中的APM目录,
加载binfs,
检测硬件版本V1,V2,V4,
启动Uorb,
检测PX4IO板,并BIN的更新,
加载各种传感器,hmc5883,mpu6000,空速,声纳,光流,PWM输入,指示灯,smbus电池检测,IR;
最后启用Ardupilot启动飞控代码, Ardupilot内嵌程序,Builtin_Commandes.c中有定义.
- echo Starting ArduPilot $deviceA $deviceC $deviceD
- if ArduPilot -d $deviceA -d2 $deviceC -d3 $deviceD start
- then
- echo ArduPilot started OK;启动Ardupilot飞控代码,
- else
- sh /etc/init.d/rc.error
- fi
- echo "rc.APM finished"
浙公网安备 33010602011771号