Odrive源码分析(七) 逆park变换

Odrive源码分析(七) Park逆变换

Odrive中FOC部分代码分散在各个对象中,并不是集中在某一块,所以试图在某一段代码就能得到FOC全貌是不现实的。

先看下FOC的整个流程:
FOC控制流程图

控制变量到三相电流输出的关键部分分为Park逆变换和SVPWM。本文主要讨论逆park变换在odrive中的代码实现。、

代码主要在FieldOrientedController::get_alpha_beta_output函数中。

ODriveIntf::MotorIntf::Error FieldOrientedController::get_alpha_beta_output(uint32_t output_timestamp, std::optional<float2D>* mod_alpha_beta,std::optional<float>* ibus) {if (!vbus_voltage_measured_.has_value() || !Ialpha_beta_measured_.has_value()) {// FOC didn't receive a current measurement yet.return Motor::ERROR_CONTROLLER_INITIALIZING;} else if (abs((int32_t)(i_timestamp_ - ctrl_timestamp_)) > MAX_CONTROL_LOOP_UPDATE_TO_CURRENT_UPDATE_DELTA) {// Data from control loop and current measurement are too far apart.return Motor::ERROR_BAD_TIMING;}// TODO: improve efficiency in case PWM updates are requested at a higher// rate than current sensor updates. In this case we can reuse mod_d and// mod_q from a previous iteration.if (!Vdq_setpoint_.has_value()) {return Motor::ERROR_UNKNOWN_VOLTAGE_COMMAND;} else if (!phase_.has_value() || !phase_vel_.has_value()) {return Motor::ERROR_UNKNOWN_PHASE_ESTIMATE;} else if (!vbus_voltage_measured_.has_value()) {return Motor::ERROR_UNKNOWN_VBUS_VOLTAGE;}auto [Vd, Vq] = *Vdq_setpoint_;float phase = *phase_;float phase_vel = *phase_vel_;float vbus_voltage = *vbus_voltage_measured_;std::optional<float2D> Idq;// Park transformif (Ialpha_beta_measured_.has_value()) {auto [Ialpha, Ibeta] = *Ialpha_beta_measured_;float I_phase = phase + phase_vel * ((float)(int32_t)(i_timestamp_ - ctrl_timestamp_) / (float)TIM_1_8_CLOCK_HZ);float c_I = our_arm_cos_f32(I_phase);float s_I = our_arm_sin_f32(I_phase);Idq = {c_I * Ialpha + s_I * Ibeta,c_I * Ibeta - s_I * Ialpha};Id_measured_ += I_measured_report_filter_k_ * (Idq->first - Id_measured_);Iq_measured_ += I_measured_report_filter_k_ * (Idq->second - Iq_measured_);} else {Id_measured_ = 0.0f;Iq_measured_ = 0.0f;}float mod_to_V = (2.0f / 3.0f) * vbus_voltage;float V_to_mod = 1.0f / mod_to_V;float mod_d;float mod_q;if (enable_current_control_) {// Current control modeif (!pi_gains_.has_value()) {return Motor::ERROR_UNKNOWN_GAINS;} else if (!Idq.has_value()) {return Motor::ERROR_UNKNOWN_CURRENT_MEASUREMENT;} else if (!Idq_setpoint_.has_value()) {return Motor::ERROR_UNKNOWN_CURRENT_COMMAND;}auto [p_gain, i_gain] = *pi_gains_;auto [Id, Iq] = *Idq;auto [Id_setpoint, Iq_setpoint] = *Idq_setpoint_;float Ierr_d = Id_setpoint - Id;float Ierr_q = Iq_setpoint - Iq;// Apply PI control (V{d,q}_setpoint act as feed-forward terms in this mode)mod_d = V_to_mod * (Vd + v_current_control_integral_d_ + Ierr_d * p_gain);mod_q = V_to_mod * (Vq + v_current_control_integral_q_ + Ierr_q * p_gain);// Vector modulation saturation, lock integrator if saturated// TODO make maximum modulation configurablefloat mod_scalefactor = 0.80f * sqrt3_by_2 * 1.0f / std::sqrt(mod_d * mod_d + mod_q * mod_q);if (mod_scalefactor < 1.0f) {mod_d *= mod_scalefactor;mod_q *= mod_scalefactor;// TODO make decayfactor configurablev_current_control_integral_d_ *= 0.99f;v_current_control_integral_q_ *= 0.99f;} else {v_current_control_integral_d_ += Ierr_d * (i_gain * current_meas_period);v_current_control_integral_q_ += Ierr_q * (i_gain * current_meas_period);}} else {// Voltage control modemod_d = V_to_mod * Vd;mod_q = V_to_mod * Vq;}// Inverse park transformfloat pwm_phase = phase + phase_vel * ((float)(int32_t)(output_timestamp - ctrl_timestamp_) / (float)TIM_1_8_CLOCK_HZ);float c_p = our_arm_cos_f32(pwm_phase);float s_p = our_arm_sin_f32(pwm_phase);float mod_alpha = c_p * mod_d - s_p * mod_q;float mod_beta = c_p * mod_q + s_p * mod_d;// Report final applied voltage in stationary frame (for sensorless estimator)final_v_alpha_ = mod_to_V * mod_alpha;final_v_beta_ = mod_to_V * mod_beta;*mod_alpha_beta = {mod_alpha, mod_beta};if (Idq.has_value()) {auto [Id, Iq] = *Idq;*ibus = mod_d * Id + mod_q * Iq;power_ = vbus_voltage * (*ibus).value();}return Motor::ERROR_NONE;
}

下面主要分析上述函数的具体实现:

step1 在进入本函数计算之前,必须已经完成线电压的测量和相电流的测量,同时要保证时效性,如下所示:

//本函数调用前,在ControlLoop_IRQHandler函数中已经完成了测量。所以本条件必然满足。
if (!vbus_voltage_measured_.has_value() || !Ialpha_beta_measured_.has_value()) {// FOC didn't receive a current measurement yet.return Motor::ERROR_CONTROLLER_INITIALIZING;
} 
//i_timestamp_和ctrl_timestamp_实际上是同一个值,因为都是外部传进来的
else if (abs((int32_t)(i_timestamp_ - ctrl_timestamp_)) > MAX_CONTROL_LOOP_UPDATE_TO_CURRENT_UPDATE_DELTA) {// Data from control loop and current measurement are too far apart.return Motor::ERROR_BAD_TIMING;
}

step2 相关控制数据检查,如下所示:

//判断是否已经计算出Vdq_setpoint(motor.cpp已通过PID计算得出)
if (!Vdq_setpoint_.has_value()) {return Motor::ERROR_UNKNOWN_VOLTAGE_COMMAND;
} 
//判断是否已经得到电角度和电角速度(已经通过encode.cpp计算得出)
else if (!phase_.has_value() || !phase_vel_.has_value()) {return Motor::ERROR_UNKNOWN_PHASE_ESTIMATE;
} 
//这里其实重复判断了...
else if (!vbus_voltage_measured_.has_value()) {return Motor::ERROR_UNKNOWN_VBUS_VOLTAGE;
}//变量提取
auto [Vd, Vq] = *Vdq_setpoint_;
float phase = *phase_;
float phase_vel = *phase_vel_;
float vbus_voltage = *vbus_voltage_measured_;

step3 通过测量到的电流进行Park变换转换到观察到的DQ,如下所示:

// 检查AB空间数据有效性,Ialpha_beta_measured_是通过FieldOrientedController父类 AlphaBetaFrameController::on_measurement计算得出。
if (Ialpha_beta_measured_.has_value()) {auto [Ialpha, Ibeta] = *Ialpha_beta_measured_;//这里得到电流测量时刻的电角度,这里很严谨,虽然i_timestamp_和 ctrl_timestamp_其实是相等的值,但是软件保留了拓展能力。float I_phase = phase + phase_vel * ((float)(int32_t)(i_timestamp_ - ctrl_timestamp_) / (float)TIM_1_8_CLOCK_HZ);//计算Park变换得到测量的DQ值用于后面的电流环闭环float c_I = our_arm_cos_f32(I_phase);float s_I = our_arm_sin_f32(I_phase);Idq = {c_I * Ialpha + s_I * Ibeta,c_I * Ibeta - s_I * Ialpha};Id_measured_ += I_measured_report_filter_k_ * (Idq->first - Id_measured_);Iq_measured_ += I_measured_report_filter_k_ * (Idq->second - Iq_measured_);
} else {Id_measured_ = 0.0f;Iq_measured_ = 0.0f;
}//相关中间变量计算
//这里mod_to_V是线电压的2/3.实际上这是相电压能达到的最大值,这里可以理解为SVPWM扇区的内接圆半径。
float mod_to_V = (2.0f / 3.0f) * vbus_voltage;
float V_to_mod = 1.0f / mod_to_V;
float mod_d;
float mod_q;

step4 电流环控制,如下所示:

//只有在开启了电流闭环控制时以下代码才会生效
//当motor_.config_.motor_type 为 Motor::MOTOR_TYPE_GIMBA 云台电机时,不使用电流控制模式而采用电压控制模式。
if (enable_current_control_) {//检查是否配置了PI参数if (!pi_gains_.has_value()) {return Motor::ERROR_UNKNOWN_GAINS;} //电流环控制必须已经得到了Idq(上面计算已经得出)else if (!Idq.has_value()) {return Motor::ERROR_UNKNOWN_CURRENT_MEASUREMENT;} //是否存在控制量Idq_setpoint_(该变量已经由motor.cpp中计算得出)else if (!Idq_setpoint_.has_value()) {return Motor::ERROR_UNKNOWN_CURRENT_COMMAND;}//语法糖auto [p_gain, i_gain] = *pi_gains_;auto [Id, Iq] = *Idq;auto [Id_setpoint, Iq_setpoint] = *Idq_setpoint_;//使用PI控制计算得出mod_q,mod_d,这里mod_q和mod_d可以理解为mod_to_V的倍数。float Ierr_d = Id_setpoint - Id;float Ierr_q = Iq_setpoint - Iq;//Vd/Vq作为前馈量加入到电流环PI控制中mod_d = V_to_mod * (Vd + v_current_control_integral_d_ + Ierr_d * p_gain);mod_q = V_to_mod * (Vq + v_current_control_integral_q_ + Ierr_q * p_gain);// Vector modulation saturation, lock integrator if saturated// TODO make maximum modulation configurablefloat mod_scalefactor = 0.80f * sqrt3_by_2 * 1.0f / std::sqrt(mod_d * mod_d + mod_q * mod_q);if (mod_scalefactor < 1.0f) {mod_d *= mod_scalefactor;mod_q *= mod_scalefactor;// TODO make decayfactor configurablev_current_control_integral_d_ *= 0.99f;v_current_control_integral_q_ *= 0.99f;} else {v_current_control_integral_d_ += Ierr_d * (i_gain * current_meas_period);v_current_control_integral_q_ += Ierr_q * (i_gain * current_meas_period);}} else {//直接使用Vd/Vq 电压控制,得到控制量为mod_to_V的倍数。mod_d = V_to_mod * Vd;mod_q = V_to_mod * Vq;
}

step5 正式完成park逆变换,如下所示:

//这里得到电角度,这里output_timestamp的时间会大于ctrl_timestamp_(理论上真好会大于一个控制周期),此时的电角度比测量电流时的电角度是不同的。
float pwm_phase = phase + phase_vel * ((float)(int32_t)(output_timestamp - ctrl_timestamp_) / (float)TIM_1_8_CLOCK_HZ);
float c_p = our_arm_cos_f32(pwm_phase);
float s_p = our_arm_sin_f32(pwm_phase);
float mod_alpha = c_p * mod_d - s_p * mod_q;
float mod_beta = c_p * mod_q + s_p * mod_d;// Report final applied voltage in stationary frame (for sensorless estimator)
final_v_alpha_ = mod_to_V * mod_alpha;
final_v_beta_ = mod_to_V * mod_beta;//得到最终计算出的AB控制量(后面会输入到SVPWM模块逆变出三相电流)
*mod_alpha_beta = {mod_alpha, mod_beta};//计算出相关数据
if (Idq.has_value()) {auto [Id, Iq] = *Idq;//计算出线电流*ibus = mod_d * Id + mod_q * Iq;//计算功率(电压和电流乘积)power_ = vbus_voltage * (*ibus).value();
}

完成Park逆变换后,下一步就直接送入了SVPWM模块了。

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

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

相关文章

Flink Hive Catalog最佳实践

Flink Hive Catalog 最佳实践 一、配置与初始化 依赖管理 Hive Connector 版本对齐&#xff1a;需确保 flink-sql-connector-hive 版本与 Hive 版本严格匹配&#xff08;如 Hive 3.1.3 对应 flink-sql-connector-hive-3.1.3_2.12&#xff09;&#xff0c;同时添加 Hadoop 遮蔽…

通过人类和机器人演示进行联合逆向和正向动力学的机器人训练

25年3月来自哥伦比亚大学的论文“Train Robots in a JIF: Joint Inverse and Forward Dynamics with Human and Robot Demonstrations”。 在大型机器人演示数据集上进行预训练是学习各种操作技能的强大技术&#xff0c;但通常受到收集以机器人为中心数据的高成本和复杂性限制…

金融简单介绍及金融诈骗防范

在当今社会&#xff0c;金融学如同一股无形却强大的力量&#xff0c;深刻影响着我们生活的方方面面。无论是个人的日常收支、投资理财&#xff0c;还是国家的宏观经济调控&#xff0c;都与金融学紧密相连。​ 一、金融学的概念​ 金融学&#xff0c;简单来说&#xff0c;是研…

JavaScript `new Date()` 方法移动端 `兼容 ios`,ios环境new Date()返回NaN

在 iOS 环境下&#xff0c;new Date() 方法会返回 NaN&#xff0c;这通常是由于时间字符串的格式问题。iOS 的 Date 构造函数对时间字符串的格式要求比其他平台更严格。 原因&#xff1a;ios端不兼容“-”为连接符的时间。 解决办法&#xff1a; 替换时间格式 IOS 不支持某…

【网络编程】网络编程基础和Socket套接字

目录 一. 网络编程的概念 二. 网络编程基础知识 1&#xff09;网卡 2&#xff09;接收端和发送端 3&#xff09;客户端和服务器 4&#xff09;请求和响应 5&#xff09;客户端和服务器的交互模式 三. Socket 套接字模型 一. 网络编程的概念 网络编程 是通过编程实现不同…

盛水最多的容器问题详解:双指针法与暴力法的对比与实现

文章目录 问题描述方法探讨方法一&#xff1a;暴力法&#xff08;Brute Force&#xff09;思路代码实现复杂度分析 方法二&#xff1a;双指针法&#xff08;Two Pointers&#xff09;思路正确性证明代码实现复杂度分析 方法对比总结 摘要 盛水最多的容器&#xff08;Container …

图论-BFS搜索图/树-最短路径问题的解决

续上篇~图论--DFS搜索图/树-CSDN博客 先看第一次学习的博客&#xff01;&#xff01;&#x1f447;&#x1f447;&#x1f447;&#x1f447; &#x1f449; 有一些问题是广搜 和 深搜都可以解决的&#xff0c;例如岛屿问题&#xff0c;这里我们记dfs的写法就好啦&#xff0c;…

C++进阶——C++11_智能指针

目录 1、问题引入 2、RAII和智能指针 3、C标准库的智能指针 3.1 auto_ptr (不好) 3.2 unique_ptr 3.3 shared_ptr (重点) 3.4 weak_ptr (重点) 4、shared_ptr的循环引用问题(重点) 5、shared_ptr的线程安全问题 6、C11智能指针和boost的关系 7、内存泄漏 7.1 什么是…

数据库的基本原则

数据库的核心原则 原子性与持久性&#xff1a;原子性&#xff08;Atomicity&#xff09;确保一个事务中的所有操作要么全部完成&#xff0c;要么完全不执行&#xff0c;不会出现部分完成的情况。持久性&#xff08;Durability&#xff09;则保证一旦事务提交成功&#xff0c;即…

Java设计模式实战:装饰模式在星巴克咖啡系统中的应用

一、装饰模式简介 装饰模式&#xff08;Decorator Pattern&#xff09;是一种结构型设计模式&#xff0c;它允许向一个现有的对象添加新的功能&#xff0c;同时又不改变其结构。这种模式创建了一个装饰类&#xff0c;用来包装原有的类&#xff0c;并在保持类方法签名完整性的前…

使用MPI-IO并行读写HDF5文件

使用MPI-IO并行读写HDF5文件 HDF5支持通过MPI-IO进行并行读写&#xff0c;这对于大规模科学计算应用非常重要。下面我将提供C和Fortran的示例程序&#xff0c;展示如何使用MPI-IO并行读写HDF5文件。 准备工作 在使用MPI-IO的HDF5之前&#xff0c;需要确保: HDF5库编译时启用…

七、自动化概念篇

自动化测试概念 自动化测试是把以人为驱动的测试行为转化为机器执行的一种过程。通常&#xff0c;在设计了测试用例并通过评审之后&#xff0c;由测试人员根据测试用例中描述的过程一步步执行测试&#xff0c;得到实际结果与期望结果的比较。在此过程中&#xff0c;为了节省人…

redis cluster 的通信机制

Redis Cluster 的通信机制是其分布式架构的核心&#xff0c;基于 Gossip 协议 和 Cluster Bus 实现节点间状态同步与数据协调。以下是其通信机制的核心要点&#xff1a; 二进制协议&#xff1a;数据以字节流形式编码&#xff08;如Protobuf、Thrift、MQTT、Gossip&#xff09;。…

CTF web入门之文件上传

知识点 产生文件上传漏洞的原因 原因: 对于上传文件的后缀名(扩展名)没有做较为严格的限制 对于上传文件的MIMETYPE(用于描述文件的类型的一种表述方法) 没有做检查 权限上没有对于上传的文件目录设置不可执行权限,(尤其是对于shebang类型的文件) 对于web server对于上传…

PhotoShop学习09

1.弯曲钢笔工具 PhotoShop提供了弯曲钢笔工具可以直观地创建路径&#xff0c;只需要对分段推拉就能够进行修改。弯曲港币工具位于工具面板中的钢笔工具里&#xff0c;它的快捷键为P。 在使用前&#xff0c;可以把填充和描边选为空颜色&#xff0c;并打开路径选项&#xff0c;勾…

tsconfig.json配置不生效

说明一下我遇到的问题&#xff0c;这是我的配置文件代码的 {"compilerOptions": {"module": "none","target": "ES5","outFile": "./dist/bundle.js"} } 和我想象不同的是&#xff0c;我编译成 js 没…

源代码加密之零日攻击

# SDC沙盒&#xff1a;有效防御零日攻击的多层防护体系 在当今复杂多变的网络安全环境中&#xff0c;零日攻击已成为企业面临的重大威胁之一。零日攻击利用尚未被公众发现或尚未被软件供应商修复的漏洞进行攻击&#xff0c;具有极高的隐蔽性和破坏性。SDC沙盒作为一种先进的数…

记录一次TDSQL网关夯住故障

环境信息&#xff1a; TDSQL-MySQL同城双中心集群&#xff0c;集中式实例&#xff0c;一主三副本&#xff0c;每个中心两个db副本&#xff0c;每个中心一个VIP&#xff0c;V每个IP通过硬件做负载均衡指向该中心两个proxy&#xff0c;操作系统为麒麟v10 arm。 故障描述&#xf…

代码随想录八股训练营完结总结

&#xff01; 40天的训练营&#xff0c;我总结了自己完整的八股文&#xff0c;后续在面试过程中可以补充 很感谢这次训练营&#xff0c;真的高频&#xff0c;在面试中能击中60%以上&#xff0c;剩下的就靠平时的积累了。 感谢训练营的小伙伴&#xff0c;很多次想偷懒&#x…

VS Code 的 .S 汇编文件里面的注释不显示绿色

1. 确认文件语言模式 打开 .S 文件后&#xff0c;查看 VS Code 右下角的状态栏&#xff0c;确认当前文件的识别模式&#xff08;如 Assembly、Plain Text 等&#xff09;。如果显示为 Plain Text 或其他非汇编模式&#xff1a; 点击状态栏中的语言模式&#xff08;如 Plain Te…