SimpleFOC源码学习07(v2.3.2) - 增量式编码器Encoder.cpp与Encoder.h,从一对 A、B 信号,到速度、方向、绝对位置的完整解法

news2026/4/15 23:04:28
导言github 源码https://github.com/simplefoc/Arduino-FOC/blob/v2.3.2/src/sensors/Encoder.hhttps://github.com/simplefoc/Arduino-FOC/blob/v2.3.2/src/sensors/Encoder.cpp你有没有在调 FOC 时遇到电机转向和预期相反或者速度读数在低速时抖个不停这两个问题根子都在增量式编码器的信号处理上。刚学完Sensor基类后,可以把它理解为一个抽象契约:“任何传感器都必须告诉我当前的机械角度getSensorAngle(),然后由我(基类)负责累加圈数、计算速度。”Encoder就是这个契约的第一个真实实现者——它用正交编码器(Quadrature Encoder)这种硬件来回答轴现在转到哪了?一、硬件原理——什么是正交编码器?在读代码之前,必须先理解硬件产生的信号长什么样,否则代码里的handleA()、pulse_counter ...会像天书。一个增量式正交编码器最基本有 2 根信号线 A/B有些型号还会额外提供 1 根 Z(Index) 信号线。再算上电源与地,常见接线会是 4 根或 5 根:信号作用A方波脉冲B方波脉冲,相位比 A 超前或滞后 90°Z (Index)可选信号,每转一圈只出现一次的脉冲,用来对零关键点:A 和 B 之所以相差 90°,就是为了判断方向。现在让我用一张图帮你看清 A/B 信号和方向判断的关系:一个电机转一圈,A 和 B 各产生 PPR 个完整方波(PPR Pulses Per Revolution)。但每个方波有4 个可识别的边沿:A↑、B↑、A↓、B↓。如果我们把每个边沿都当作一次计数事件,那么一圈就有4×PPR次计数 —— 这就是CPR 4×PPR(Counts Per Revolution),也就是正交模式(Quadrature::ON)带来的4 倍分辨率提升。这是理解整个Encoder代码的地基。二、头文件Encoder.h的结构解剖classEncoder:publicSensor{...};一句话就说明了一切:Encoder继承Sensor,要履行 Sensor 留下的合同。让我把头文件的成员按角色分类:1. 硬件配置(构造时确定,之后不变)pinA,pinB,index_pin—— 3 根线接到 MCU 的哪几个引脚cpr—— 字段名虽然叫cpr,但刚构造完成时先暂存用户传入的_ppr;等init()执行后,它才真正表示每转多少计数pullup—— 用 MCU 内部上拉还是外部上拉电阻quadrature—— 正交模式开/关2.中断里会被修改的共享变量(注意volatile)volatilelongpulse_counter;// 累计脉冲数(带符号,方向就是符号)volatilelongpulse_timestamp;// 最后一次脉冲到达的时刻(微秒)volatileintA_active,B_active,I_active;// 当前 A/B/Z 电平的缓存volatileboolindex_found;// 是否已经见过 Z 脉冲volatile关键字是C/C 告诉编译器:“这个变量随时可能被中断改写,别把它优化成寄存器缓存,每次都要从内存真实地读。”这是嵌入式主循环 vs 中断共享数据的基本要求。你会在update()里看到配套的noInterrupts()/interrupts()临界区保护。3.速度计算相关的历史变量floatprev_Th,pulse_per_second;volatilelongprev_pulse_counter,prev_timestamp_us;其中prev_Th、pulse_per_second确实只在主循环里使用,不需要volatile。但prev_pulse_counter之所以仍然是volatile,是因为handleIndex()在做 index 对齐时会顺手修正它,避免速度计算出现假跳变;prev_timestamp_us则主要是主循环中的历史时间戳。4.履行 Sensor 契约的函数floatgetSensorAngle()override;// 核心!Sensor 基类强制要求floatgetVelocity()override;// 可选重写(Encoder 选择重写)voidupdate()override;// 可选重写intneedsSearch()override;// 绝对位置支持5.中断服务函数(ISR 回调)voidhandleA();// A 线边沿触发时调用voidhandleB();// B 线边沿触发时调用voidhandleIndex();// Z 线边沿触发时调用这里有一个嵌入式世界的通用模式要强调:Arduino 的attachInterrupt()要求注册一个无参普通函数,不能直接注册类成员函数(因为成员函数隐藏地带着this指针)。所以 SimpleFOC 的使用模式是:用户在自己的.ino里写三个全局薄函数:Encoderenc(2,3,500);voiddoA(){enc.handleA();}voiddoB(){enc.handleB();}enc.enableInterrupts(doA,doB);这就是enableInterrupts()接收 3 个函数指针(*doA)()的原因。三、构造函数与init()—— 对象的出生构造函数基本就是字段初始化,没有惊喜。但init()里有一行值得专门标注:// initial cpr PPR// change it if the mode is quadratureif(quadratureQuadrature::ON)cpr4*cpr;这是一个语义切换:用户传进来的_ppr参数先被存在cpr字段里,然后根据模式决定是否放大 4 倍。从这一刻起,cpr在整个类里都代表真正的每转计数值,后续所有/cpr的归一化都不用再区分模式了——非常干净的设计。init()另一个关键动作是根据pullup配置决定用INPUT_PULLUP还是INPUT。光电编码器通常需要上拉电阻,因为它的输出常常是开集(open-collector)—— 它只能把线拉到地,松开时线是浮空的,必须靠上拉电阻拉回高电平。四、中断回调 —— 本文件的技术核心这是Encoder最精妙、也最容易看懵的部分。我们看handleA():voidEncoder::handleA(){boolAdigitalRead(pinA);// 读当前 A 电平switch(quadrature){caseQuadrature::ON:if(A!A_active){// 确认是真变化(过滤伪触发)pulse_counter(A_activeB_active)?1:-1;pulse_timestamp_micros();A_activeA;}break;...看起来只有 4 行,但每一行都有含义。让我用一张表和一张图彻底展开(A_active B_active) ? 1 : -1这条方向判断的精髓。当handleA()被触发时,说明 A 刚发生了边沿跳变。A_active存的是上一次记录的 A 电平,也就是跳变前的 A。此时观察 A_active 和 B_active(此刻的 B)的关系:这就是正交编码器的全部方向秘密:通过比较A 刚才的电平和B 现在的电平是否相同,一次比较就得出方向。handleB()里条件反过来(!),原因是 B 的边沿相对 A 错开了 90°,奇偶关系正好翻转。另外注意if ( A ! A_active )这道防线——attachInterrupt(..., CHANGE)模式下偶尔会因为毛刺或去抖问题产生重复触发,这个判断相当于一个软件去抖/幂等保护:如果读出来的 A 跟记录的一样,说明是假触发,直接忽略。Index 脉冲handleIndex()的对齐逻辑longtmppulse_counter;pulse_counterround((double)pulse_counter/(double)cpr)*cpr;prev_pulse_counterpulse_counter-tmp;这三行解决一个实际问题:累计过程中可能产生丢脉冲(比如中断没及时响应,或信号抖动),导致pulse_counter漂移几个计数。Z 脉冲是一圈一次的物理基准,每次触发时把pulse_counter“四舍五入到最近的整圈”——这样长期运行下误差不会累积。最后那行prev_pulse_counter pulse_counter - tmp;很精巧:速度计算会用到pulse_counter - prev_pulse_counter这个差,如果只修正了当前值,下一次算速度会出现一个虚假的巨大跳变。所以把校正量同步加到prev_pulse_counter,让速度计算看不到这个阶跃,保证速度曲线的平滑性。这体现了维护不变量(invariant)的思维。五、update()—— 中断世界和主循环世界的桥梁voidEncoder::update(){noInterrupts();angle_prev_tspulse_timestamp;longcopy_pulse_counterpulse_counter;interrupts();full_rotationscopy_pulse_counter/(int)cpr;angle_prev_2PI*((copy_pulse_counter)%((int)cpr))/((float)cpr);}这里就是你在 Sensor 基类里看到的那个update()契约的具体实现。它做三件事:1. 临界区拷贝 volatile 数据noInterrupts()暂时关中断 → 把pulse_counter和pulse_timestamp快速拷贝到本地变量 →interrupts()立刻开中断。为什么?因为long在 8 位 AVR 上是 4 字节,CPU 没办法一次读完——如果正读到一半,中断冲进来把变量改了,主循环就会读到一个半旧半新的鬼畜值(这叫torn read,撕裂读)。关中断是最粗暴但最可靠的方案。关中断时间必须极短,所以这里只做简单拷贝和赋值,不做任何运算——运算都放在临界区之外。是否一定要关中断,取决于update()会不会和修改这些变量的上下文并发执行。本文按 Arduino 常见用法来理解:它和编码器 ISR 并发,所以这里需要临界区保护。2. 计算full_rotations和angle_prev还记得 Sensor 基类里的angle_prev和full_rotations吗?基类的getAngle()就是用full_rotations * 2π angle_prev拼出的绝对角度。Encoder 在这里填上这两个字段的值:full_rotations copy_pulse_counter / cpr—— 整数除法,直接得圈数angle_prev 2π × (counter % cpr) / cpr—— 把当前计数在这一圈内对应成机械角分量注意:C11 规定负数取模结果向零截断,若copy_pulse_counter为负,则angle_prev可能也是负值。这是刻意的——负值表示从零点往反转方向偏移,Sensor 基类的getAngle()用full_rotations × 2π angle_prev能正确处理这个情况,不会产生 bug。3.angle_prev_ts pulse_timestamp记录这个角度是什么时候测到的,基类的getVelocity()默认实现会用到这个时间戳(虽然 Encoder 还重写了自己的版本)。六、getVelocity()—— 混合测频/测周期法速度计算是整个Encoder最有工程味的部分。理论上你有两种经典方法测角速度:M 法(测频):固定时间窗Ts,数窗内来了几个脉冲dN。高速时好用,低速时dN经常是 0 或 1,分辨率很差。T 法(测周期):数相邻两个脉冲的时间差。低速时好用,高速时时间差太短,计时分辨率不够。SimpleFOC 用的是M/T 混合法。关键一行:floatdtTsprev_Th-Th;pulse_per_second(dN!0dtTs/2)?dN/dt:pulse_per_second;dt的含义一开始容易看混,用一条时间轴来拆解它:上次调用 上次脉冲 本次脉冲 本次调用 |←─ prev_Th ─→| |←── Th ──→| |←──────────────────── Ts ───────────────────→| dt Ts prev_Th - Th ≈ 上次脉冲 → 本次脉冲 的真实间距这里的dt不是简单的timestamp - prev_timestamp,而是从上一次真正的脉冲,到这一次真正的脉冲的时间——用Th(本次调用时刻距最后一个脉冲的时间)修正掉了尾部的空闲时间。这样dN/dt得到的速度更准确,尤其在低速情况下避免了脉冲落在采样点附近导致的抖动。其余几个细节:if ( Th 0.1f) pulse_per_second 0;—— 100ms 都没来新脉冲,认为电机停了,直接清零,避免速度挂在旧值上。if(Ts 0 || Ts 0.5f) Ts 1e-3f;—— 处理_micros()溢出异常或者长时间没调用的边界情况。还记得在time_utils篇里分析过的吗?_micros()的unsigned long大约71.6 分钟溢出回绕一次(详见第4篇),这里就是在防御这种时刻。velocity pulse_per_second / cpr * 2π—— 从脉冲/秒换算成弧度/秒,这是整个类的输出。七、needsSearch()—— 对 Sensor 契约的另一个答复intEncoder::needsSearch(){returnhasIndex()!index_found;}Sensor 基类里的needsSearch()是问你是不是需要 FOC 启动阶段做一次开环搜索来找到零点?。这里用了一个三段式的逻辑,清晰地覆盖了三种状态:没有 Z 线→ 不需要搜,反正也找不到绝对零点有 Z 线但还没见过 Z 脉冲→ 需要搜,让电机转一下触发 Z已经见过 Z 脉冲→ 不需要搜,已经对齐了这个函数会被BLDCMotor::initFOC()调用,决定是否触发开环旋转去找 index。八、总结Encoder 是如何填满 Sensor 合同的?几个值得记住的要点cpr 4 × ppr在init()里一次性完成语义转换,之后全类都以 CPR 为单位思考,是很干净的设计模式。volatilenoInterrupts()/interrupts()临界区 本地拷贝是嵌入式ISR 与主循环共享数据的标准三件套,后面看HallSensor时你会看到几乎一样的模式。方向判断的精髓是:某一路发生边沿时,比较边沿前的本相信号和另一相当前信号的关系来判断方向。其中handleA()判断相等,handleB()判断不等,而A_active/B_active保存的正是这个边沿前的历史状态。Index 脉冲的四舍五入对齐 同步修正prev_pulse_counter,体现了修正绝对量时必须同步修正差分量以免产生虚假跳变的思维,跟你在 PID 里看到的 anti-windup 精神是相通的——保护状态变量的一致性。混合 M/T 测速法通过dt Ts prev_Th - Th这个小技巧,用脉冲实际到达的时刻替代采样边界,在低速下显著提高精度。如果把前面几篇串起来看,已经形成了一条完整的底层传感器链路:time_utils第4篇解决的是时间基准foc_utils第5篇解决的是高频数学运算Sensor基类第6、7篇定义了传感器契约Encoder本篇是这个契约的第一个完整实现,集成了中断驱动、临界区保护、M/T 混合测速的全套工程实践下一篇进入HallSensor,看基于霍尔传感器的位置感知是如何实现的——你会发现它和Encoder的代码结构高度相似,但在方向判断和速度计算上有自己的特殊处理。你在使用增量式编码器时有没有遇到过方向读反、低速速度抖动或 Index 对齐失效的问题欢迎在评论区聊聊你的排查过程——这类问题排查起来现象很玄学但原因往往就藏在这几行中断代码里。

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

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

相关文章

SpringBoot-17-MyBatis动态SQL标签之常用标签

文章目录 1 代码1.1 实体User.java1.2 接口UserMapper.java1.3 映射UserMapper.xml1.3.1 标签if1.3.2 标签if和where1.3.3 标签choose和when和otherwise1.4 UserController.java2 常用动态SQL标签2.1 标签set2.1.1 UserMapper.java2.1.2 UserMapper.xml2.1.3 UserController.ja…

wordpress后台更新后 前端没变化的解决方法

使用siteground主机的wordpress网站,会出现更新了网站内容和修改了php模板文件、js文件、css文件、图片文件后,网站没有变化的情况。 不熟悉siteground主机的新手,遇到这个问题,就很抓狂,明明是哪都没操作错误&#x…

网络编程(Modbus进阶)

思维导图 Modbus RTU(先学一点理论) 概念 Modbus RTU 是工业自动化领域 最广泛应用的串行通信协议,由 Modicon 公司(现施耐德电气)于 1979 年推出。它以 高效率、强健性、易实现的特点成为工业控制系统的通信标准。 包…

UE5 学习系列(二)用户操作界面及介绍

这篇博客是 UE5 学习系列博客的第二篇,在第一篇的基础上展开这篇内容。博客参考的 B 站视频资料和第一篇的链接如下: 【Note】:如果你已经完成安装等操作,可以只执行第一篇博客中 2. 新建一个空白游戏项目 章节操作,重…

IDEA运行Tomcat出现乱码问题解决汇总

最近正值期末周,有很多同学在写期末Java web作业时,运行tomcat出现乱码问题,经过多次解决与研究,我做了如下整理: 原因: IDEA本身编码与tomcat的编码与Windows编码不同导致,Windows 系统控制台…

利用最小二乘法找圆心和半径

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

使用docker在3台服务器上搭建基于redis 6.x的一主两从三台均是哨兵模式

一、环境及版本说明 如果服务器已经安装了docker,则忽略此步骤,如果没有安装,则可以按照一下方式安装: 1. 在线安装(有互联网环境): 请看我这篇文章 传送阵>> 点我查看 2. 离线安装(内网环境):请看我这篇文章 传送阵>> 点我查看 说明&#xff1a;假设每台服务器已…

XML Group端口详解

在XML数据映射过程中&#xff0c;经常需要对数据进行分组聚合操作。例如&#xff0c;当处理包含多个物料明细的XML文件时&#xff0c;可能需要将相同物料号的明细归为一组&#xff0c;或对相同物料号的数量进行求和计算。传统实现方式通常需要编写脚本代码&#xff0c;增加了开…

LBE-LEX系列工业语音播放器|预警播报器|喇叭蜂鸣器的上位机配置操作说明

LBE-LEX系列工业语音播放器|预警播报器|喇叭蜂鸣器专为工业环境精心打造&#xff0c;完美适配AGV和无人叉车。同时&#xff0c;集成以太网与语音合成技术&#xff0c;为各类高级系统&#xff08;如MES、调度系统、库位管理、立库等&#xff09;提供高效便捷的语音交互体验。 L…

(LeetCode 每日一题) 3442. 奇偶频次间的最大差值 I (哈希、字符串)

题目&#xff1a;3442. 奇偶频次间的最大差值 I 思路 &#xff1a;哈希&#xff0c;时间复杂度0(n)。 用哈希表来记录每个字符串中字符的分布情况&#xff0c;哈希表这里用数组即可实现。 C版本&#xff1a; class Solution { public:int maxDifference(string s) {int a[26]…

【大模型RAG】拍照搜题技术架构速览:三层管道、两级检索、兜底大模型

摘要 拍照搜题系统采用“三层管道&#xff08;多模态 OCR → 语义检索 → 答案渲染&#xff09;、两级检索&#xff08;倒排 BM25 向量 HNSW&#xff09;并以大语言模型兜底”的整体框架&#xff1a; 多模态 OCR 层 将题目图片经过超分、去噪、倾斜校正后&#xff0c;分别用…

【Axure高保真原型】引导弹窗

今天和大家中分享引导弹窗的原型模板&#xff0c;载入页面后&#xff0c;会显示引导弹窗&#xff0c;适用于引导用户使用页面&#xff0c;点击完成后&#xff0c;会显示下一个引导弹窗&#xff0c;直至最后一个引导弹窗完成后进入首页。具体效果可以点击下方视频观看或打开下方…

接口测试中缓存处理策略

在接口测试中&#xff0c;缓存处理策略是一个关键环节&#xff0c;直接影响测试结果的准确性和可靠性。合理的缓存处理策略能够确保测试环境的一致性&#xff0c;避免因缓存数据导致的测试偏差。以下是接口测试中常见的缓存处理策略及其详细说明&#xff1a; 一、缓存处理的核…

龙虎榜——20250610

上证指数放量收阴线&#xff0c;个股多数下跌&#xff0c;盘中受消息影响大幅波动。 深证指数放量收阴线形成顶分型&#xff0c;指数短线有调整的需求&#xff0c;大概需要一两天。 2025年6月10日龙虎榜行业方向分析 1. 金融科技 代表标的&#xff1a;御银股份、雄帝科技 驱动…

观成科技:隐蔽隧道工具Ligolo-ng加密流量分析

1.工具介绍 Ligolo-ng是一款由go编写的高效隧道工具&#xff0c;该工具基于TUN接口实现其功能&#xff0c;利用反向TCP/TLS连接建立一条隐蔽的通信信道&#xff0c;支持使用Let’s Encrypt自动生成证书。Ligolo-ng的通信隐蔽性体现在其支持多种连接方式&#xff0c;适应复杂网…

铭豹扩展坞 USB转网口 突然无法识别解决方法

当 USB 转网口扩展坞在一台笔记本上无法识别,但在其他电脑上正常工作时,问题通常出在笔记本自身或其与扩展坞的兼容性上。以下是系统化的定位思路和排查步骤,帮助你快速找到故障原因: 背景: 一个M-pard(铭豹)扩展坞的网卡突然无法识别了,扩展出来的三个USB接口正常。…

未来机器人的大脑:如何用神经网络模拟器实现更智能的决策?

编辑&#xff1a;陈萍萍的公主一点人工一点智能 未来机器人的大脑&#xff1a;如何用神经网络模拟器实现更智能的决策&#xff1f;RWM通过双自回归机制有效解决了复合误差、部分可观测性和随机动力学等关键挑战&#xff0c;在不依赖领域特定归纳偏见的条件下实现了卓越的预测准…

Linux应用开发之网络套接字编程(实例篇)

服务端与客户端单连接 服务端代码 #include <sys/socket.h> #include <sys/types.h> #include <netinet/in.h> #include <stdio.h> #include <stdlib.h> #include <string.h> #include <arpa/inet.h> #include <pthread.h> …

华为云AI开发平台ModelArts

华为云ModelArts&#xff1a;重塑AI开发流程的“智能引擎”与“创新加速器”&#xff01; 在人工智能浪潮席卷全球的2025年&#xff0c;企业拥抱AI的意愿空前高涨&#xff0c;但技术门槛高、流程复杂、资源投入巨大的现实&#xff0c;却让许多创新构想止步于实验室。数据科学家…

深度学习在微纳光子学中的应用

深度学习在微纳光子学中的主要应用方向 深度学习与微纳光子学的结合主要集中在以下几个方向&#xff1a; 逆向设计 通过神经网络快速预测微纳结构的光学响应&#xff0c;替代传统耗时的数值模拟方法。例如设计超表面、光子晶体等结构。 特征提取与优化 从复杂的光学数据中自…