PX4FMU和PX4IO最底层启动过程分析(下)

PX4FMU和PX4IO最底层启动过程分析(下)

PX4FMU的系统启动函数为nash_main(int argc,char *argv[])
PX4IO的系统启动函数为nash_start(int argc,char *argv[])

PX4FMU启动函数nash_main(int argc,char *argv[])

首先分析一下nash_main(int argc,char *argv[])
PX4FMU中有#define CONFIG_USER_ENTRYPOINT nsh_main

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\n", 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_TELNETret = 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\n", ret);exitval = 1;}
#endif/* If the serial console front end is selected, then run it on this thread */#ifdef CONFIG_NSH_CONSOLEret = nsh_consolemain(0, NULL);/* nsh_consolemain() should not return.  So if we get here, something* is wrong.*/fprintf(stderr, "ERROR: nsh_consolemain() returned: %d\n", ret);exitval = 1;
#endifreturn exitval;
}

其中包含

#ifdef CONFIG_NSH_CONSOLEret = nsh_consolemain(0, NULL);

进入nsh_consolemain(int argc, char *argv[])函数

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_TRACEusbtrace_enable(TRACE_BITSET);
#endif/* Execute the session */ret = nsh_session(pstate);/* Exit upon return */nsh_exit(&pstate->cn_vtbl, ret);return ret;
}

其中包含

/* Execute the start-up script */#ifdef CONFIG_NSH_ROMFSETC(void)nsh_initscript(&pstate->cn_vtbl);
#endif

执行启动脚本也就是rcS,接下来根据本身版本分别看ardupilot和PX4原生码

/* Execute the session */ret = nsh_session(pstate);

执行用户程序
跟踪pstate

FAR struct console_stdio_s *pstate = nsh_newconsole();

进入console_stdio_s *nsh_newconsole(void)

FAR struct console_stdio_s *nsh_newconsole(void)
{struct console_stdio_s *pstate = (struct console_stdio_s *)zalloc(sizeof(struct console_stdio_s));if (pstate){/* Initialize the call table */#ifndef CONFIG_NSH_DISABLEBGpstate->cn_vtbl.clone      = nsh_consoleclone;pstate->cn_vtbl.release    = nsh_consolerelease;
#endifpstate->cn_vtbl.write      = nsh_consolewrite;pstate->cn_vtbl.output     = nsh_consoleoutput;pstate->cn_vtbl.linebuffer = nsh_consolelinebuffer;pstate->cn_vtbl.redirect   = nsh_consoleredirect;pstate->cn_vtbl.undirect   = nsh_consoleundirect;pstate->cn_vtbl.exit       = nsh_consoleexit;/* (Re-) open the console input device */#ifdef CONFIG_NSH_CONDEVpstate->cn_confd           = open(CONFIG_NSH_CONDEV, O_RDWR);if (pstate->cn_confd < 0){free(pstate);return NULL;}/* Create a standard C stream on the console device */pstate->cn_constream = fdopen(pstate->cn_confd, "r+");if (!pstate->cn_constream){close(pstate->cn_confd);free(pstate);return NULL;}
#endif/* Initialize the output stream */pstate->cn_outfd           = OUTFD(pstate);pstate->cn_outstream       = OUTSTREAM(pstate);}return pstate;
}

应该是用户在console输入新的nsh命令吧


PX4IO启动函数nash_start(int argc,char *argv[])

接着分析一下nash_start(int argc,char *argv[])
PX4IO中有#define CONFIG_USER_ENTRYPOINT user_start

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_DMAhrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL);
#endif/* print some startup info */lowsyslog("\nPX4IO: starting\n");/* default all the LEDs to off while we start */LED_AMBER(false);LED_BLUE(false);LED_SAFETY(false);
#ifdef GPIO_LED4LED_RING(false);
#endif/* turn on servo power (if supported) */
#ifdef POWER_SERVOPOWER_SERVO(true);
#endif/* turn off S.Bus out (if supported) */
#ifdef ENABLE_SBUS_OUTENABLE_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\n", 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();}ring_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)) {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();}}
}

user_start 负责px4io 基础环境的初始化,包括PWM,串口,ADC 等资源的初始化,最后运行一个死循环,用于处理遥控器输入,与PX4FMU 通讯的内容
controls_tick 负责处理遥控器的输入内容,包括SBUS 的处理sbus_input、 SPKT/DSM 的处理dsm_port_input、 PPM 的处理ppm_input

PX4IO 底层中断处理的内容以下图

(1)紫色为PX4IO 的底层串口IO 操做,流程为当PX4IO 收到PX4FMU 的串口数据后会运行serial_interrupt, serial_interrupt 负责收发DMA 的操做,若是收到一个完整的包,则调用rx_dma_callback 进行处理, rx_dma_callback 首先调用rx_handle_packet 解析包中的内容,判断为写寄存器仍是读寄存器,处理完成后由rx_dma_callback 发送回包给PX4FMU

static int
serial_interrupt(int irq, void *context)
{static bool abort_on_idle = false;uint32_t sr = rSR;	/* get UART status register */(void)rDR;		/* required to clear any of the interrupt status that brought us here */if (sr & (USART_SR_ORE |	/* overrun error - packet was too big for DMA or DMA was too slow */USART_SR_NE |		/* noise error - we have lost a byte due to noise */USART_SR_FE)) {		/* framing error - start/stop bit lost or line break */perf_count(pc_errors);if (sr & USART_SR_ORE) {perf_count(pc_ore);}if (sr & USART_SR_NE) {perf_count(pc_ne);}if (sr & USART_SR_FE) {perf_count(pc_fe);}/* send a line break - this will abort transmission/reception on the other end */rCR1 |= USART_CR1_SBK;/* when the line goes idle, abort rather than look at the packet */abort_on_idle = true;}if (sr & USART_SR_IDLE) {/** If we saw an error, don't bother looking at the packet - it should have* been aborted by the sender and will definitely be bad. Get the DMA reconfigured* ready for their retry.*/if (abort_on_idle) {abort_on_idle = false;dma_reset();return 0;}/** The sender has stopped sending - this is probably the end of a packet.* Check the received length against the length in the header to see if* we have something that looks like a packet.*/unsigned length = sizeof(dma_packet) - stm32_dmaresidual(rx_dma);if ((length < 1) || (length < PKT_SIZE(dma_packet))) {/* it was too short - possibly truncated */perf_count(pc_badidle);dma_reset();return 0;}/** Looks like we received a packet. Stop the DMA and go process the* packet.*/perf_count(pc_idle);stm32_dmastop(rx_dma);rx_dma_callback(rx_dma, DMA_STATUS_TCIF, NULL);}return 0;
}
static void
rx_dma_callback(DMA_HANDLE handle, uint8_t status, void *arg)
{/** We are here because DMA completed, or UART reception stopped and* we think we have a packet in the buffer.*/perf_begin(pc_txns);/* disable UART DMA */rCR3 &= ~(USART_CR3_DMAT | USART_CR3_DMAR);/* handle the received packet */rx_handle_packet();/* re-set DMA for reception first, so we are ready to receive before we start sending */dma_reset();/* send the reply to the just-processed request */dma_packet.crc = 0;dma_packet.crc = crc_packet(&dma_packet);stm32_dmasetup(tx_dma,(uint32_t)&rDR,(uint32_t)&dma_packet,PKT_SIZE(dma_packet),DMA_CCR_DIR		|DMA_CCR_MINC		|DMA_CCR_PSIZE_8BITS	|DMA_CCR_MSIZE_8BITS);stm32_dmastart(tx_dma, NULL, NULL, false);rCR3 |= USART_CR3_DMAT;perf_end(pc_txns);
}
static void
rx_handle_packet(void)
{/* check packet CRC */uint8_t crc = dma_packet.crc;dma_packet.crc = 0;if (crc != crc_packet(&dma_packet)) {perf_count(pc_crcerr);/* send a CRC error reply */dma_packet.count_code = PKT_CODE_CORRUPT;dma_packet.page = 0xff;dma_packet.offset = 0xff;return;}if (PKT_CODE(dma_packet) == PKT_CODE_WRITE) {/* it's a blind write - pass it on */if (registers_set(dma_packet.page, dma_packet.offset, &dma_packet.regs[0], PKT_COUNT(dma_packet))) {perf_count(pc_regerr);dma_packet.count_code = PKT_CODE_ERROR;} else {dma_packet.count_code = PKT_CODE_SUCCESS;}return;}if (PKT_CODE(dma_packet) == PKT_CODE_READ) {/* it's a read - get register pointer for reply */unsigned count;uint16_t *registers;if (registers_get(dma_packet.page, dma_packet.offset, &registers, &count) < 0) {perf_count(pc_regerr);dma_packet.count_code = PKT_CODE_ERROR;} else {/* constrain reply to requested size */if (count > PKT_MAX_REGS) {count = PKT_MAX_REGS;}if (count > PKT_COUNT(dma_packet)) {count = PKT_COUNT(dma_packet);}/* copy reply registers into DMA buffer */memcpy((void *)&dma_packet.regs[0], registers, count * 2);dma_packet.count_code = count | PKT_CODE_SUCCESS;}return;}/* send a bad-packet error reply */dma_packet.count_code = PKT_CODE_CORRUPT;dma_packet.page = 0xff;dma_packet.offset = 0xfe;
}

(2) 蓝色为包操做,只提供registers_set 写操做和registers_get 读操做
(3)IOPacket 为协议包,包括如下几部分

定义描述
count_code标记包的读写,错误,长度等信息
crc为包的效验码
page为数据页
offset为数据偏移量
regs为数据内容

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.mzph.cn/bicheng/10499.shtml

如若内容造成侵权/违法违规/事实不符,请联系多彩编程网进行投诉反馈email:809451989@qq.com,一经查实,立即删除!

相关文章

高效视频剪辑:视频批量调色,如何利用色调调整提升效率

在视频剪辑的后期处理中&#xff0c;调色是一个至关重要的环节。它不仅能够改变视频的整体氛围和风格&#xff0c;还能够突出视频的重点&#xff0c;增强观众的视觉体验。然而&#xff0c;对于大量的视频素材进行逐个调色处理&#xff0c;无疑会耗费大量的时间和精力。我们可以…

软件安装及YOLOv8环境配置及验证

先附上本章中所用到的软件及环境安装包&#xff0c;还有YOLOv8各任务权重&#xff1a; 软件及环境配置链接&#xff1a;https://pan.baidu.com/s/1-n2HJybicA6vW1YXfGRtcA 提取码&#xff1a;6vh8 YOLOv8各权重&#xff1a;链接&#xff1a;https://pan.baidu.com/s/1ApYUrJ_s…

C++相关概念和易错语法(12)(迭代器、string容量调整)

1.迭代器&#xff08;以string为例&#xff09; &#xff08;1&#xff09;基本理解&#xff1a;在我们刚接触迭代器的时候&#xff0c;我们可以将迭代器理解为改造过的“指针”&#xff0c;这是一个新的类型&#xff0c;指向对应容器中的各个元素。我们可以像指针那样对迭代器…

Lombok介绍、使用方法和安装

目录 1 Lombok背景介绍 2 Lombok使用方法 2.1 Data 2.2 Getter/Setter 2.3 NonNull 2.4 Cleanup 2.5 EqualsAndHashCode 2.6 ToString 2.7 NoArgsConstructor, RequiredArgsConstructor and AllArgsConstructor 3 Lombok工作原理分析 4. Lombok的优缺点 5. 总结 1 …

Idea入门:一分钟创建一个Java工程

一&#xff0c;新建一个Java工程 1&#xff0c;启动Idea后&#xff0c;选择 [New Project] 2&#xff0c;完善工程信息 填写工程名称&#xff0c;根据实际用途取有意义的英文名称选择Java语言&#xff0c;可以看到还支持Kotlin、Javascript等语言选择包管理和项目构建工具Mav…

LVS的三种工作模式---(DR/TUN/NAT)

目录 一、NAT模式&#xff08;LVS-NAT&#xff09; 二、IP隧道模式&#xff08;LVS-TUN&#xff09; 三、DR模型--直接路由模式&#xff08;LVS-DR&#xff09; LVS/DR模式ARP抑制 原因&#xff1a; LVS的DR工作模式及配置&#xff1a; LVS的NAT工作模式及配置&#xff1…

PyQt6--Python桌面开发(7.QTextEdit多行富文本框控件)

QTextEdit多行富文本框控件 保存文件到本地QLine多行文本框.ui import sys import time from PyQt6.QtGui import QValidator,QIntValidator from PyQt6.QtWidgets import QApplication,QLabel,QLineEdit,QTextEdit from PyQt6 import uic,QtGuiif __name__ __main__:appQApp…

二叉树进阶 --- 上

目录 1. 二叉搜索树的概念及结构 1.1. 二叉搜索树的概念 1.2. 二叉搜索树的结构样例 2. 二叉搜索树的实现 2.1. insert 的非递归实现 2.2. find 的非递归实现 2.3. erase 的非递归实现 2.3.1. 第一种情况&#xff1a;所删除的节点的左孩子为空 2.3.1.1. 错误的代码 2…

基本QinQ

拓扑图 配置 开启LLDP功能&#xff0c;查看是否能通过QinQ隧道透传 sysname AR1 # lldp enable # interface GigabitEthernet0/0/0.10dot1q termination vid 10ip address 12.1.1.1 255.255.255.0 arp broadcast enable # sysname AR2 # lldp enable # interface GigabitE…

地磁暴红色预警来袭,普通人该如何应对?绝绝子的防护指南来了

近日&#xff0c;国家空间天气监测预警中心发布了一则令人瞩目的消息——地磁暴红色预警。这一预警不仅提醒我们地磁暴即将影响我国的电离层和低轨卫星&#xff0c;更让我们深刻认识到地球空间环境的脆弱性和复杂性。对于普通公众而言&#xff0c;地磁暴的概念可能相对陌生&…

【每日刷题】Day37

【每日刷题】Day37 &#x1f955;个人主页&#xff1a;开敲&#x1f349; &#x1f525;所属专栏&#xff1a;每日刷题&#x1f34d; &#x1f33c;文章目录&#x1f33c; 1. 2391. 收集垃圾的最少总时间 - 力扣&#xff08;LeetCode&#xff09; 2. 1614. 括号的最大嵌套深度…

你可能喜欢但也许还不知道的好用网站-搜嗖工具箱

在线工具 https://www.zxgj.cn/ 作为一个工作生活好帮手&#xff0c;在线咨询网站提供了丰富的实用功能&#xff0c;从工作中的图表制作、图片修改到生活中的各种测试、健康、娱乐、学习、理财等等涵盖面很广。 在线工具网站从界面和操作上来看对用户也很友好&#xff0c;页面…

论文研读 An Image Is Worth 16x16 Words: Transformers For Image Recognition At Scale

完整翻译 《An Image is Worth 16x16 Words》完整版翻译_an image is worth 16*16words-CSDN博客 大神讲解 Vision Transformer详解-CSDN博客 视频讲解 11.1 Vision Transformer(vit)网络详解_哔哩哔哩_bilibili 学习整理 简要概述&#xff1a;Vision Transformer&#xff…

在 Kubernetes 上运行 Apache Spark 进行大规模数据处理的实践

在刚刚结束的 Kubernetes Community Day 上海站&#xff0c;亚马逊云科技在云原生分论坛分享的“在 Kunernets 上运行 Apache Spark 进行大规模数据处理实践”引起了现场参与者的关注。开发者告诉我们&#xff0c;为了充分利用 Kubernetes 的高可用设计、弹性&#xff0c;在越来…

AIGC (AI-Generated Content) 技术深度探索:现状、挑战与未来愿景

&#x1f525; 个人主页&#xff1a;空白诗 文章目录 &#x1f916; AIGC技术&#xff1a;塑造未来的创意与内容革命 &#x1f31f;引言 &#x1f680;AIGC技术发展现状 &#x1f4c8;核心技术驱动 &#x1f4a1;应用领域拓展 &#x1f310; 面临的挑战 ❌真实性与伦理考量 &am…

SAP-CentralFinance - 会计核算中的组织要素 - 学习心得1

1. 定义SAP组织架构和理解各组织架构含义 组织结构遍布SAP 系统的所有重要功能范围。FI 中最重要的组织要素是公司代码。它是“财务会计”中的最小组织单位,可以为其编制自主式完整科目集供外部报告使用。其他重要的组织要素是利润中心业务范围和段。您可以为各个利润中…

大模型微调之 在亚马逊AWS上实战LlaMA案例(十)

大模型微调之 在亚马逊AWS上实战LlaMA案例&#xff08;十&#xff09; 训练数据集格式 SageMaker JumpStart 目前支持域适应格式和指令调整格式的数据集。在本节中&#xff0c;我们指定两种格式的示例数据集。有关更多详细信息&#xff0c;请参阅附录中的数据集格式化部分。 …

iview(viewUI) span-method 表格实现将指定列的值相同的行合并单元格

效果图是上面这样的&#xff0c;将第一列的名字一样的合并在一起&#xff1b; <template><div class"table-wrap"><Table stripe :columns"columns" :data"data" :span-method"handleSpan"></Table></div&…

HDFS- DataNode磁盘扩缩容

HDFS- DataNode磁盘扩缩容 背景: 缩减/增加节点磁盘 方案介绍: 采用hdfs dfsadmin -reconfig 动态刷新配置实现,不停服扩缩容。 注意事项: 请在进行缩容之前,务必了解实际的数据量,并确保磁盘有足够的空间来容纳这些数据。还需要考虑未来的使用需求,要预留一定数量的空间…

java+vue3+iclientol实现警务地理信息系统实践

警务地理信息系统&#xff08;Police Geographic Information System, PGIS&#xff09;是一种专为警务工作设计的地理信息系统&#xff0c;它结合了地理信息技术、数据库技术、网络技术和现代警务理念&#xff0c;旨在提升公安机关的空间数据分析、决策支持、指挥调度、案件管…