ExpressLRS开源之基本调试数据含义
ExpressLRS开源之基本调试数据含义
- 1. 源由
- 2. 代码
- 2.1 debugRcvrLinkstats
- 2.2 debugRcvrSignalStats
- 3. 含义解释
- 3.1 ID(packetCounter),Antenna,RSSI(dBm),LQ,SNR,PWR,FHSS,TimingOffset
- 3.2 IRQ_CNT,RSSI_AVE,SNR_AVE,SNV_MAX,TELEM_CNT,FAIL_CNT
- 4. 总结
- 5. 参考资料
1. 源由
基于ExpressLRS开源代码对基本调试验证数据进行详细的研读理解,以期望更深入的理解相关数据的实际含义。
ID(packetCounter),Antenna,RSSI(dBm),LQ,SNR,PWR,FHSS,TimingOffset
IRQ_CNT,RSSI_AVE,SNR_AVE,SNV_MAX,TELEM_CNT,FAIL_CNT
2. 代码
2.1 debugRcvrLinkstats
static void debugRcvrLinkstats()
{
#if defined(DEBUG_RCVR_LINKSTATS)if (debugRcvrLinkstatsPending){debugRcvrLinkstatsPending = false;// Copy the data out of the ISR-updating bits ASAP// While YOLOing (const void *) away the volatilecrsfLinkStatistics_t ls = *(crsfLinkStatistics_t *)((const void *)&CRSF::LinkStatistics);uint32_t packetCounter = debugRcvrLinkstatsPacketId;uint8_t fhss = debugRcvrLinkstatsFhssIdx;// actually the previous packet's offset since the update happens in tick, and this will// fire right after packet reception (a little before tock)int32_t pfd = PfdPrevRawOffset;// Use serial instead of DBG() because do not necessarily want all the debug in our logschar buf[50];snprintf(buf, sizeof(buf), "%u,%u,-%u,%u,%d,%u,%u,%d\r\n",packetCounter, ls.active_antenna,ls.active_antenna ? ls.uplink_RSSI_2 : ls.uplink_RSSI_1,ls.uplink_Link_quality, ls.uplink_SNR,ls.uplink_TX_Power, fhss, pfd);Serial.write(buf);}
#endif
}
2.2 debugRcvrSignalStats
static void debugRcvrSignalStats(uint32_t now)
{
#if defined(DEBUG_RCVR_SIGNAL_STATS)static uint32_t lastReport = 0;// log column header: cnt1, rssi1, snr1, snr1_max, telem1, fail1, cnt2, rssi2, snr2, snr2_max, telem2, fail2, or, bothif(now - lastReport >= 1000 && connectionState == connected){for (int i = 0 ; i < (isDualRadio()?2:1) ; i++){DBG("%d\t%f\t%f\t%f\t%d\t%d\t",Radio.rxSignalStats[i].irq_count,(Radio.rxSignalStats[i].irq_count==0) ? 0 : double(Radio.rxSignalStats[i].rssi_sum)/Radio.rxSignalStats[i].irq_count,(Radio.rxSignalStats[i].irq_count==0) ? 0 : double(Radio.rxSignalStats[i].snr_sum)/Radio.rxSignalStats[i].irq_count/RADIO_SNR_SCALE,float(Radio.rxSignalStats[i].snr_max)/RADIO_SNR_SCALE,Radio.rxSignalStats[i].telem_count,Radio.rxSignalStats[i].fail_count);Radio.rxSignalStats[i].irq_count = 0;Radio.rxSignalStats[i].snr_sum = 0;Radio.rxSignalStats[i].rssi_sum = 0;Radio.rxSignalStats[i].snr_max = INT8_MIN;Radio.rxSignalStats[i].telem_count = 0;Radio.rxSignalStats[i].fail_count = 0;}if (isDualRadio()){DBGLN("%d\t%d", Radio.irq_count_or, Radio.irq_count_both);}else{DBGLN("");}Radio.irq_count_or = 0;Radio.irq_count_both = 0;lastReport = now;}
#endif
}
3. 含义解释
对于debug给出参数含义解释,有助于理解性能测试结果。
ID(packetCounter),Antenna,RSSI(dBm),LQ,SNR,PWR,FHSS,TimingOffset
IRQ_CNT,RSSI_AVE,SNR_AVE,SNV_MAX,TELEM_CNT,FAIL_CNT
3.1 ID(packetCounter),Antenna,RSSI(dBm),LQ,SNR,PWR,FHSS,TimingOffset
- ID(packetCounter):报文ID(递增,需打开Tx发射端DEBUG_RCVR_LINKSTATS)
报文ID是在发射机发射信号是递增,接收机解析报文是获取ID信息的。
//接收机
OtaUpdateSerializers├──> UnpackChannelDataHybridSwitch8/UnpackChannelDataHybridWide│ └──> UnpackChannelDataHybridCommon - ota4->dbg_linkstats.packetNum│ └──> debugRcvrLinkstatsPacketId│ └──> packetCounter└──> UnpackChannelData8ch - ota8->dbg_linkstats.packetNum└──> debugRcvrLinkstatsPacketId└──> packetCounter//发射机
OtaUpdateSerializers└──> GenerateChannelData8ch/GenerateChannelData12ch└──> GenerateChannelData8ch12ch└──> <DEBUG_RCVR_LINKSTATS> ota8->dbg_linkstats.packetNum = packetCnt++
- Antenna:天线编号(0或1)
目前,天线配置方面有以下几种工作模式:
- Basic:一根天线
- Antenna Diversity:两根天线,其中一根天线接收信号
- True Diversity:两根天线,同时接收信号
- Gemini:两根天线,同时接收信号,并且工作在两个不同的频点。
- RSSI(dBm):信号强度,单位dBm
分贝毫瓦简写为dBm或dBmW,是一个表示绝对功率的量。
uplink_RSSI_1/uplink_RSSI_2└──> rssiDBM└──> LastPacketRSSI└──> GetLastPacketRSSI/GetLastPacketStats└──> readRegister(SX127X_REG_PKT_RSSI_VALUE)/ReadCommand(SX1280_RADIO_GET_PACKETSTATUS)
- LQ(Link Quality):链路质量
链路接收到数据包与预期数据包的百分比,表示信号中丢包的概率。
uplink_Link_quality└──> uplinkLQ└──> LQCalc.getLQ()/LQCalcDVDA.getLQ()
- SNR(Signal-to-noise ratio):信噪比
信号与干扰加噪声比 (Signal to Interference plus Noise Ratio)是指接收到的有用信号的强度与接收到的干扰信号(噪声和干扰)的强度的比值。
uplink_SNR└──> LastPacketSNRRaw└──> GetLastPacketSNRRaw/GetLastPacketStats└──> readRegister(SX127X_REG_PKT_SNR_VALUE)/ReadCommand(SX1280_RADIO_GET_PACKETSTATUS)
- PWR(Power):功率
发射机工作时的发射功率。
RX::uplink_TX_Power└──> RX::UnpackChannelData8ch/UnpackChannelDataHybridWide└──> TX::GenerateChannelDataHybridWide/GenerateChannelData8ch12ch└──> TX::CurrentPower└──> TX::decPower/incPower└──> TX::DynamicPower_Update└──> TX::loop
其对应输出数值与功率之间的对应关系。
uint8_t powerToCrsfPower(PowerLevels_e Power)
{// Crossfire's power levels as defined in opentx:radio/src/telemetry/crossfire.cpp//static const int32_t power_values[] = { 0, 10, 25, 100, 500, 1000, 2000, 250, 50 };switch (Power){case PWR_10mW: return 1;case PWR_25mW: return 2;case PWR_50mW: return 8;case PWR_100mW: return 3;case PWR_250mW: return 7;case PWR_500mW: return 4;case PWR_1000mW: return 5;case PWR_2000mW: return 6;default:return 0;}
}
- FHSS(Frequency-hopping spread spectrum):跳频频率
FHSS,跳频技术 (Frequency-Hopping Spread Spectrum)在同步、且同时的情况下,接受两端以特定型式的窄频载波来传送讯号,对于一个非特定的接受器,FHSS所产生的跳动讯号对它而言,也只算是脉冲噪声。FHSS所展开的讯号可依特别设计来规避噪声或One-to-Many的非重复的频道,并且这些跳频讯号必须遵守要求。
debugRcvrLinkstatsFhssIdx└──> getRFlinkInfo└──> ProcessRFPacket└──> RXdoneISR└──> setupRadio└──> setup
注:关于跳频方面的设置,详见FHSSrandomiseFHSSsequence
和FHSSgetNextFreq
。
- TimingOffset
这里的时间差是指HWtimerCallbackTock
调用到ProcessRFPacket
报文开始处理的时间差。
PfdPrevRawOffset└──> PFDloop.calcResult() = PFDloop.intEvent(HWtimerCallbackTock) - PFDloop.extEvent(ProcessRFPacket)└──> updatePhaseLock└──> HWtimerCallbackTick└──> setup
3.2 IRQ_CNT,RSSI_AVE,SNR_AVE,SNV_MAX,TELEM_CNT,FAIL_CNT
- IRQ_CNT
接收机收到RF芯片中断的数量。
setup└──> setupRadio└──> RXdoneISR└──> ProcessRFPacket└──> GetLastPacketStats└──> instance->rxSignalStats[i].irq_count++
- RSSI_AVE
接收机平均RSSI信号强度。
double(Radio.rxSignalStats[i].rssi_sum)/Radio.rxSignalStats[i].irq_count
- SNR_AVE
接收机平均SNR信号强度。
double(Radio.rxSignalStats[i].snr_sum)/Radio.rxSignalStats[i].irq_count/RADIO_SNR_SCALE
- SNV_MAX
接收机最大SNR信号强度。
float(Radio.rxSignalStats[i].snr_max)/RADIO_SNR_SCALE
- TELEM_CNT
接收机发送报文数量。
setup└──> HWtimerCallbackTock└──> HandleSendTelemetryResponse└──> TXnb└──> telem_count++
- FAIL_CNT
判断双天线是否第二根天线受到同样的报文,如果没有收到则fail++。
setup└──> setupRadio└──> RXdoneISR└──> ProcessRFPacket└──> GetLastPacketStats└──> fail_count++
4. 总结
通过对上面调试参数含义的分析,在对单/双天线模块配置下:
可以根据以下表格内容进行可选择性的分析比对,详细比对方法请见:
【1】ExpressLRS开源之RC链路性能测试
【2】ExpressLRS开源之接收机固件编译烧录步骤
ID(packetCounter) | Antenna | RSSI(dBm) | LQ | SNR | PWR | FHSS | TimingOffset |
---|---|---|---|---|---|---|---|
报文ID | 天线编号 | 信号强度 | 信号质量 | 信噪比 | 发射功率 | 跳频频率 | 中断时延 |
单、双 | 双 | 单、双 | 单、双 | 单、双 | 单、双 | 单、双 | 单、双 |
IRQ_CNT | RSSI_AVE | SNR_AVE | SNV_MAX | TELEM_CNT | FAIL_CNT |
---|---|---|---|---|---|
中断数量 | 平均信号强度 | 平均信噪比 | 最大信噪比 | 发送报文数量 | 报文缺失次数 |
单、双 | 单、双 | 单、双 | 单、双 | 单、双 | 双 |
,
5. 参考资料
【1】ExpressLRS开源之RC链路性能测试
【2】ExpressLRS开源之接收机固件编译烧录步骤
【3】High-performance Open Source Radio Control Link
相关文章:

ExpressLRS开源之基本调试数据含义
ExpressLRS开源之基本调试数据含义 1. 源由2. 代码2.1 debugRcvrLinkstats2.2 debugRcvrSignalStats 3. 含义解释3.1 ID(packetCounter),Antenna,RSSI(dBm),LQ,SNR,PWR,FHSS,TimingOffset3.2 IRQ_CNT,RSSI_AVE,SNR_AVE,SNV_MAX,TELEM_CNT,FAIL_CNT 4. 总结5. 参考资料 1. 源由 …...

DOM 简介 | 深入了解DOM
目录 一、DOM是什么 二、DOM的访问 三、DOM节点类型 四、DOM的分级 今天我们将了解WEB编程中一个重要的概念DOM(Document Object Model)文档对象模型,它帮助我们使用JavaScript(或其他编程语言)操纵文档。 一、DO…...
机器学习丨2. 线性回归(Linear Regression)
Author:AXYZdong 硕士在读 工科男 有一点思考,有一点想法,有一点理性! 定个小小目标,努力成为习惯!在最美的年华遇见更好的自己! CSDNAXYZdong,CSDN首发,AXYZdong原创 唯…...

python+django企业员工考勤打卡信息管理系统66lgr
本员工信息管理系统以Django作为框架,Python语言,B/S模式以及MySql作为后台运行的数据库。本系统主要包括以下功能模块:员工、部门、员工合同、考勤信息、打卡信息、员工工资等模块。 本文着重阐述了员工信息管理系统的分析、设计与实现&…...
【Java Web】论坛帖子添加评论
数据层 增加评论数据;修改帖子评论数量; 业务层 处理添加评论的业务;先增加评论、在更新帖子的评论数量; 表现层 处理添加评论数据的请求;设置添加评论的表单。 一、数据层 1.1 CommentMapper.java package com.no…...

如何建设一个安全运营中心(SOC)?
然信息安全管理问题主要是个从上而下的问题,不能指望通过某一种工具来解决,但良好的安全技术基础架构能有效的推动和保障信息安全管理。随着国内行业IT应用度和信息安全管理水平的不断提高,企业对于安全管理的配套设施如安全运营中心…...
如何以Base64形式存储、返回图片数据
在Java中,可以使用Base64类来将图片转换为Base64编码。下面是一个示例代码: Java代码直接处理: import java.io.File; import java.io.FileInputStream; import java.io.IOException; import java.util.Base64; public class ImageToBase64…...
【大模型】自动化问答生成:使用GPT-3.5将文档转化为问答对
自动化问答生成:使用GPT-3.5将文档转化为问答对 正文步骤1:准备工作步骤2:编写Python脚本 总结 当我们需要将大段文档转化为问答对时,OpenAI的GPT-3.5模型提供了一个强大的工具。这个教程将向您展示如何编写一个Python脚本&#x…...

普通平衡树 Splay
Splay 简介 Splay(伸展树),又叫做分裂树,是一种自调整形式的二叉查找树,满足二叉查找树的性质:一个节点左子树的所有节点的权值,均小于这个节点的权值。且其右子树所有节点的权值,均…...

复旦-华盛顿EMBA:走近亿咖通科技,探寻汽车智能化的科创“密码”
6月20日,应复旦大学-华盛顿大学EMBA项目18班校友周靖的邀请,项目校友参访了科创企业ECARX亿咖通科技。作为该公司资深副总裁、中国首席财务官,周靖带领大家通过产品演示、实车驾驶和交流对话探寻汽车智能化的科创“密码”,近距离感…...

学习心得07:C#
之前也没有看过C#的书,C#的程序倒是搞了一些。好在项目不大,我又会套路。 C#很象是JAVA。好像就是JAVA出来之后,微软抄的。好东西就要学习,这不丢脸。 我倒是想,有没有办法把JAVA和C#进行映射,然后直接编译…...

importlib的使用、9个视图子类、视图集、drf之路由、drf之请求响应回顾、GenericViewSet相关流程图
一 drf之请求响应回顾 # 1 drf请求-请求对象:data,query_params,其他跟之前一样,FILES-默认:支持三种编码-局部配置:视图类中-from rest_framework.parsers import JSONParser, FormParser, MultiPartPars…...
国际站阿里云服务器远程桌面密码错误怎么办?苹果手机如何远程登录?
阿里云服务器是云计算领域的一种重要服务,它可以帮助用户在云端部署和管理自己的应用程序和网站。但是,有时候用户可能会遇到远程桌面密码错误的问题,导致无法登录到服务器。本文将介绍一些解决办法,以及如何使用苹果手机远程登录…...

CRMEB多端多语言系统文件上传0Day代审历程
Git仓库: https://github.com/crmeb/CRMEB简介: 两天攻防中,某政局子公司官网后台采用的CRMEB开源商城CMS,挺奇葩,别问怎么总让我碰到这种东西,我也不知道,主打的就是一个魔幻、抽象。最后通过…...

孙哥Spring源码第18集
第18集 refresh()-invokeBeanFactoryPostProcessor-二-ConfigurationClassPostProcessor的处理逻辑 【视频来源于:B站up主孙帅suns Spring源码视频】【微信号:suns45】 1、为什么PropertySource先处理? 因为Conponent A在处理的过程中 要把…...

【STM32】文件系统FATFS与Flash的初步使用
文件系统简介 简介可以不看,直接看移植步骤 文件系统是介于应用层和底层间的模糊层。底层提供API,比如说使用SDIO或者SPI等读写一个字节。文件系统把这些API组合包装起来,并且提供一些列函数,我们可以使用这些函数进行更进一步的…...
Android Glide in RecyclerView,only load visible item when page return,Kotlin
Android Glide in RecyclerView,only load visible item when page return,Kotlin base on this article: Android Glide preload RecyclerView切入后台不可见再切换可见只加载当前视野可见区域item图片,Kotlin_zhangphil的博客…...
【SCI征稿】3个月左右录用!计算机信息技术等领域均可,如机器学习、遥感技术、人工智能、物联网、人工神经网络、数据挖掘、图像处理
计算机技术类SCIE&EI 【期刊简介】IF:1.0-2.0,JCR4区,中科院4区 【检索情况】SCIE&EI 双检,正刊 【参考周期】期刊部系统内提交,录用周期3个月左右,走完期刊部流程上线 【征稿领域】计算机信息…...
Golang 中的 crypto/ecdh 包详解
什么是 ECDH 算法? ECDH(Elliptic Curve Diffie-Hellman)算法是一种基于椭圆曲线的密钥交换协议,用于安全地协商共享密钥(Secret Key),步骤如下: 1. 选择椭圆曲线:ECDH…...
系统学习live555
文章目录 系统学习live555系统学习LIVE555的步骤:1.了解基本概念:2.**查看官方文档:**3.**下载和编译库:**4.**阅读示例代码:**5.**了解库结构:**6.**创建简单项目:**7.**阅读更多文档ÿ…...

利用最小二乘法找圆心和半径
#include <iostream> #include <vector> #include <cmath> #include <Eigen/Dense> // 需安装Eigen库用于矩阵运算 // 定义点结构 struct Point { double x, y; Point(double x_, double y_) : x(x_), y(y_) {} }; // 最小二乘法求圆心和半径 …...

【SQL学习笔记1】增删改查+多表连接全解析(内附SQL免费在线练习工具)
可以使用Sqliteviz这个网站免费编写sql语句,它能够让用户直接在浏览器内练习SQL的语法,不需要安装任何软件。 链接如下: sqliteviz 注意: 在转写SQL语法时,关键字之间有一个特定的顺序,这个顺序会影响到…...
【HTML-16】深入理解HTML中的块元素与行内元素
HTML元素根据其显示特性可以分为两大类:块元素(Block-level Elements)和行内元素(Inline Elements)。理解这两者的区别对于构建良好的网页布局至关重要。本文将全面解析这两种元素的特性、区别以及实际应用场景。 1. 块元素(Block-level Elements) 1.1 基本特性 …...
汇编常见指令
汇编常见指令 一、数据传送指令 指令功能示例说明MOV数据传送MOV EAX, 10将立即数 10 送入 EAXMOV [EBX], EAX将 EAX 值存入 EBX 指向的内存LEA加载有效地址LEA EAX, [EBX4]将 EBX4 的地址存入 EAX(不访问内存)XCHG交换数据XCHG EAX, EBX交换 EAX 和 EB…...

C++ Visual Studio 2017厂商给的源码没有.sln文件 易兆微芯片下载工具加开机动画下载。
1.先用Visual Studio 2017打开Yichip YC31xx loader.vcxproj,再用Visual Studio 2022打开。再保侟就有.sln文件了。 易兆微芯片下载工具加开机动画下载 ExtraDownloadFile1Info.\logo.bin|0|0|10D2000|0 MFC应用兼容CMD 在BOOL CYichipYC31xxloaderDlg::OnIni…...

RSS 2025|从说明书学习复杂机器人操作任务:NUS邵林团队提出全新机器人装配技能学习框架Manual2Skill
视觉语言模型(Vision-Language Models, VLMs),为真实环境中的机器人操作任务提供了极具潜力的解决方案。 尽管 VLMs 取得了显著进展,机器人仍难以胜任复杂的长时程任务(如家具装配),主要受限于人…...

C# 表达式和运算符(求值顺序)
求值顺序 表达式可以由许多嵌套的子表达式构成。子表达式的求值顺序可以使表达式的最终值发生 变化。 例如,已知表达式3*52,依照子表达式的求值顺序,有两种可能的结果,如图9-3所示。 如果乘法先执行,结果是17。如果5…...
为什么要创建 Vue 实例
核心原因:Vue 需要一个「控制中心」来驱动整个应用 你可以把 Vue 实例想象成你应用的**「大脑」或「引擎」。它负责协调模板、数据、逻辑和行为,将它们变成一个活的、可交互的应用**。没有这个实例,你的代码只是一堆静态的 HTML、JavaScript 变量和函数,无法「活」起来。 …...

抽象类和接口(全)
一、抽象类 1.概念:如果⼀个类中没有包含⾜够的信息来描绘⼀个具体的对象,这样的类就是抽象类。 像是没有实际⼯作的⽅法,我们可以把它设计成⼀个抽象⽅法,包含抽象⽅法的类我们称为抽象类。 2.语法 在Java中,⼀个类如果被 abs…...

Kubernetes 节点自动伸缩(Cluster Autoscaler)原理与实践
在 Kubernetes 集群中,如何在保障应用高可用的同时有效地管理资源,一直是运维人员和开发者关注的重点。随着微服务架构的普及,集群内各个服务的负载波动日趋明显,传统的手动扩缩容方式已无法满足实时性和弹性需求。 Cluster Auto…...