英飞凌TC264无刷驱动方案simplefoc移植(1)-霍尔编码器移植

  • 英飞凌TC264无刷驱动方案simplefoc移植(1)-霍尔编码器移植
    • 一、硬件电路配置
  • 二 、 问题的提出
  • 三 、霍尔编码器原理
  • 四 、霍尔编码角度速度读取
    • 4-1底层配置
    • 4-2 状态更新
    • 4-3 角度速度更新
    • 4-4 完整代码
    • 4-5 函数调用
    • 主函数调用
  • 总结

从今天开始,我将会写一个系列博客,分享我在有感无刷电机移植simplefoc的全过程,并提出自己的理解和改进方案,希望各位大佬讨论。

十七届直立单车组在十六届的基础之后允许动量轮的存在,维持车模平衡,所以就需要使用英飞凌的无刷驱动方案。
本文基于链接:
一、 基于英飞凌MCU GTM模块的无刷电机驱动方
二、 基于英飞凌AURIX的平衡单车组BLDC项目开源
三、 逐飞科技TC264开源库
四、 Arduino SimpleFOClibrary
五、SimpleFOC移植STM32(一)—简介

一、硬件电路配置

无刷电机驱动板 :使用TC264单片机 详细链接如下
17届平衡单车组英飞凌无刷电机驱动英飞凌TC264方案驱动 逐飞科技
无刷电机为选择有感、三槽两极、2860Kv(Kv表示每增加一伏电压电机增加的转速,最高12V)、尺寸36(mm)*50(mm)、额定功率190W、支持1-3S锂电池供电。

二 、 问题的提出

在逐飞的方案中:

扫描霍尔主要是统计每次换相的时间,如果换相时间过长则认为出现故障此时应该及时关闭输出。

当电机正常运行的时候将每次换相的时间都保存在数组内,当得到最近6次的换相时间之后,我们就能知道电机转动一圈所花费的时间,从而就能够计算出电机的转速了。

然后根据读取到的霍尔值计算出下次期望的霍尔值。 霍尔扫描结束之后,开始检查延时换相时间是否到,时间没有到则延时时间减一,延时时间为0的时候开始进行换相动作,这里延时换相的原因是因为在电机高速运转的时候霍尔有滞后导致的,可能有人问为什么霍尔滞后了,你还要延时换相呢,

因为我们采用的方法是,当霍尔出现滞后之后,我们换相的时候并不是换到下一相,而是换到了下下相,这样就相当于超前换相了,所以我们需要加一定的延时去匹配,从而得到一个最佳的换相点。

但是,这就这些操作使用的是CCU6模块,这就需要CPU频繁的处理无刷驱动的换相控制而且方波的控制缺点是噪声特别大,低速的时候会导致车身震荡。

三 、霍尔编码器原理

霍尔编码器检测转子位置,一共安装三个霍尔分别间隔120度安装,霍尔输出的波形如下图所,每当波形改变的时候就需要进行换相。
但是霍尔采集的角度数据是离散的,比如30, 60, 90等,比较适合方波控制。

四 、霍尔编码角度速度读取

4-1底层配置

宏定义霍尔编码器的io口以及极对数,同时设置方向枚举变量

//定义电机极对数
#define POLEPAIRss          1#define HALL_A_PIN          P15_6
#define HALL_B_PIN          P15_7
#define HALL_C_PIN          P15_8/***  Direction structure*/
enum Direction{CW      = 1,  //clockwiseCCW     = -1, // counter clockwiseUNKNOWN = 0   //not yet known or invalid state
};

初始化io口,这里必须设置输入上拉模式
初始化的时候使用gpio_get先读一次io口,并更新此时的状态。

// HallSensor initialisation of the hardware pins
// and calculation variables
void HallSensor_init(){// initialise the electrical rotations to 0electric_rotations = 0;gpio_init(HALL_A_PIN, GPI, 0, PULLDOWN);gpio_init(HALL_B_PIN, GPI, 0, PULLDOWN);gpio_init(HALL_C_PIN, GPI, 0, PULLDOWN);//读取一下当前的霍尔值A_active = gpio_get(HALL_A_PIN);B_active = gpio_get(HALL_B_PIN);C_active = gpio_get(HALL_C_PIN);HallSensor_updateState();pulse_timestamp = systick_getval_us(STM0)
}

4-2 状态更新

更新霍尔状态,调用的是simple的库,有兴趣的可以直接看一。研究一下原理,主要就是判断当前状态和上次状态的变化。
如果变化,利用霍尔编码表查阅状态,判断方向,累计计数。

// seq 1 > 5 > 4 > 6 > 2 > 3 > 1     000 001 010 011 100 101 110 111
const int8_t ELECTRIC_SECTORS[8] = { -1,  0,  4,  5,  2,  1,  3 , -1 };
/*** Updates the state and sector following an interrupt*/
void HallSensor_updateState() {long new_pulse_timestamp = systick_getval_us(STM0);int8_t new_hall_state = C_active + (B_active << 1) + (A_active << 2);// glitch avoidance #1 - sometimes we get an interrupt but pins haven't changedif (new_hall_state == hall_state) {return;}hall_state = new_hall_state;int8_t new_electric_sector = ELECTRIC_SECTORS[hall_state];static int old_direction;if (new_electric_sector - electric_sector > 3) {//underflowdirection = CCW;electric_rotations += direction;} else if (new_electric_sector - electric_sector < (-3)) {//overflowdirection = CW;electric_rotations += direction;} else {direction = (new_electric_sector > electric_sector)? CW : CCW;}electric_sector = new_electric_sector;// glitch avoidance #2 changes in direction can cause velocity spikes.  Possible improvements needed in this areaif (direction == old_direction) {// not oscilating or just changed directionpulse_diff = new_pulse_timestamp - pulse_timestamp;} else {pulse_diff = 0;}pulse_timestamp = new_pulse_timestamp;total_interrupts++;old_direction = direction;/****************************************************/
//  if (onSectorChange != nullptr) onSectorChange(electric_sector);
}

4-3 角度速度更新

最后还有速度更新函数和角度更新函数(单位弧度)
electric_rotations 更新函数中累计记得数
electric_sector 当前所在的区
cpr (POLEPAIRss * 6) 极对数乘6
pulse_diff 更新的时间差

/*Shaft angle calculation
*/
float HallSensor_getAngle() {return ((float)(electric_rotations * 6 + electric_sector) / (float)cpr) * _2PI ;/*Shaft velocity calculationfunction using mixed time and frequency measurement technique
*/
float HallSensor_getVelocity(){if (pulse_diff == 0 || ((systick_getval_us(STM0) - pulse_timestamp) > (pulse_diff*3)) ) { // last velocity isn't accurate if too oldreturn 0;}else{return direction * (_2PI / cpr) / (pulse_diff / 1000000.0f);}
}

4-4 完整代码

HallSensor.h

#ifndef HALLSENSOR_H
#define HALLSENSOR_H#include "headfile.h"
//定义电机极对数
#define POLEPAIRss          1//定义一分钟内ADC中断次数
#define ADC_NUM_PM          60*FPWM#define COMMUTATION_TIMEOUT 5000//定义电机极对数
#define POLEPAIRss          1#define HALL_A_PIN          P15_6
#define HALL_B_PIN          P15_7
#define HALL_C_PIN          P15_8/***  Direction structure*/
enum Direction{CW      = 1,  //clockwiseCCW     = -1, // counter clockwiseUNKNOWN = 0   //not yet known or invalid state
};typedef struct
{float Velocity;float Angle;long time;uint16 Ta,Tb,Tc;}HALL;
extern HALL Hall;
extern float angle_prev;extern volatile int A_active; //!< current active states of A channel
extern volatile int B_active; //!< current active states of B channel
extern volatile int C_active; //!< current active states of C channelvoid HallSensor_init();
float HallSensor_getVelocity();
float HallSensor_getAngle();
void HallSensor_updateState();
void HallSensor_handleC();
void HallSensor_handleB();
void HallSensor_handleA();
float getVelocity(void);#endif

HallSensor.c

#include <common.h>
#include <foc_utils.h>
#include <HallSensor.h>
#include <stdint.h>
#include <zf_gpio.h>
#include <zf_stm_systick.h>// seq 1 > 5 > 4 > 6 > 2 > 3 > 1     000 001 010 011 100 101 110 111
const int8_t ELECTRIC_SECTORS[8] = { -1,  0,  4,  5,  2,  1,  3 , -1 };#define cpr (POLEPAIRss * 6)//!< HallSensor cpr number// the current 3bit state of the hall sensors
volatile int8_t hall_state;
// the current sector of the sensor. Each sector is 60deg electrical
volatile int8_t electric_sector;
// the number of electric rotations
volatile long electric_rotations;
// this is sometimes useful to identify interrupt issues (e.g. weak or no pullup resulting in 1000s of interrupts)
volatile long total_interrupts; volatile unsigned long pulse_timestamp;//!< last impulse timestamp in us
volatile int A_active; //!< current active states of A channel
volatile int B_active; //!< current active states of B channel
volatile int C_active; //!< current active states of C channel
int direction; //!< current direction of rotation
volatile long pulse_diff;
volatile long new_pulse_timestamp;float angle_prev;
void HallSensor_updateState();//  HallSensor interrupt callback functionsHALL Hall;// A channel
void HallSensor_handleA() {A_active = gpio_get(HALL_A_PIN);HallSensor_updateState();
}
// B channel
void HallSensor_handleB() {B_active = gpio_get(HALL_B_PIN);HallSensor_updateState();
}// C channel
void HallSensor_handleC() {C_active = gpio_get(HALL_C_PIN);HallSensor_updateState();
}/*** Updates the state and sector following an interrupt*/
void HallSensor_updateState() {long new_pulse_timestamp = systick_getval_us(STM0);int8_t new_hall_state = C_active + (B_active << 1) + (A_active << 2);// glitch avoidance #1 - sometimes we get an interrupt but pins haven't changedif (new_hall_state == hall_state) {return;}hall_state = new_hall_state;int8_t new_electric_sector = ELECTRIC_SECTORS[hall_state];static int old_direction;if (new_electric_sector - electric_sector > 3) {//underflowdirection = CCW;electric_rotations += direction;} else if (new_electric_sector - electric_sector < (-3)) {//overflowdirection = CW;electric_rotations += direction;} else {direction = (new_electric_sector > electric_sector)? CW : CCW;}electric_sector = new_electric_sector;// glitch avoidance #2 changes in direction can cause velocity spikes.  Possible improvements needed in this areaif (direction == old_direction) {// not oscilating or just changed directionpulse_diff = new_pulse_timestamp - pulse_timestamp;} else {pulse_diff = 0;}pulse_timestamp = new_pulse_timestamp;total_interrupts++;old_direction = direction;/****************************************************/
//  if (onSectorChange != nullptr) onSectorChange(electric_sector);
}/*** Optionally set a function callback to be fired when sector changes* void onSectorChange(int sector) {*  ... // for debug or call driver directly?* }* sensor.attachSectorCallback(onSectorChange);*/ /*Shaft angle calculation
*/
float HallSensor_getAngle() {return ((float)(electric_rotations * 6 + electric_sector) / (float)cpr) * _2PI ;
}/*Shaft velocity calculationfunction using mixed time and frequency measurement technique
*/
float HallSensor_getVelocity(){if (pulse_diff == 0 || ((systick_getval_us(STM0) - pulse_timestamp) > (pulse_diff*3)) ) { // last velocity isn't accurate if too oldreturn 0;}else{return direction * (_2PI / cpr) / (pulse_diff / 1000000.0f);}
}// HallSensor initialisation of the hardware pins
// and calculation variables
void HallSensor_init(){// initialise the electrical rotations to 0electric_rotations = 0;gpio_init(HALL_A_PIN, GPI, 0, PULLDOWN);gpio_init(HALL_B_PIN, GPI, 0, PULLDOWN);gpio_init(HALL_C_PIN, GPI, 0, PULLDOWN);//读取一下当前的霍尔值A_active = gpio_get(HALL_A_PIN);B_active = gpio_get(HALL_B_PIN);C_active = gpio_get(HALL_C_PIN);HallSensor_updateState();pulse_timestamp = systick_getval_us(STM0);
}
/******************************************************************************/

4-5 函数调用

在原版的simplefoc程序中,使用的是外部中断跳边沿触发调用中断函数()

// 中断例程初始化
void doA(){sensor.handleA();}
void doB(){sensor.handleB();}
void doC(){sensor.handleC();}

但是在tc264中,外部中断的资源比较少,而板载连接的又不是在几个引脚。

typedef enum  // 枚举ERU通道
{//一个通道只能选择其中一个引脚作为 外部中断的输入//例如通道0 可选引脚为P10_7 和 P15_4,//在LQFP144封装中没有P10_7ERU_CH0_REQ4_P10_7   = 0*3,  ERU_CH0_REQ0_P15_4,                      //通道0可选引脚   LQFP没有P10_7引脚//在LQFP144封装中没有P10_8ERU_CH1_REQ5_P10_8   = 1*3,  ERU_CH1_REQ10_P14_3,                     //通道1可选引脚   LQFP没有P10_8引脚ERU_CH2_REQ7_P00_4   = 2*3,  ERU_CH2_REQ14_P02_1, ERU_CH2_REQ2_P10_2, //通道2可选引脚ERU_CH3_REQ6_P02_0   = 3*3,  ERU_CH3_REQ3_P10_3,  ERU_CH3_REQ15_P14_1,    //通道3可选引脚//通道4与通道0 共用中断函数 在中断内通过判断标志位来识别是哪个通道触发的中断ERU_CH4_REQ13_P15_5  = 4*3,  ERU_CH4_REQ8_P33_7,                     //通道4可选引脚//通道5与通道1 共用中断函数ERU_CH5_REQ1_P15_8   = 5*3,                                               //通道5可选引脚//通道6与通道2 共用中断函数ERU_CH6_REQ12_P11_10 = 6*3,  ERU_CH6_REQ9_P20_0,                      //通道6可选引脚//通道7与通道3 共用中断函数ERU_CH7_REQ16_P15_1  = 7*3,  ERU_CH7_REQ11_P20_9,                     //通道7可选引脚
}ERU_PIN_enum;

所以我决定将更新函数放到定时器中断之中也是可行的

pit_interrupt_ms(CCU6_1, PIT_CH1, 1); //周期中断初始化IFX_INTERRUPT(cc61_pit_ch1_isr, 0, CCU6_1_CH1_ISR_PRIORITY)
{enableInterrupts();//开启中断嵌套PIT_CLEAR_FLAG(CCU6_1, PIT_CH1);A_active = gpio_get(HALL_A_PIN);B_active = gpio_get(HALL_B_PIN);C_active = gpio_get(HALL_C_PIN);HallSensor_updateState( );
}

主函数调用

#include <Bsp.h>
#include <common.h>
#include <IfxCpu.h>
#include <mpuiic.h>
#include <Platform_Types.h>
#include <zf_stm_systick.h>
#include <zf_uart.h>#pragma section all "cpu0_dsram"//将本语句与#pragma section all restore语句之间的全局变量都放在CPU0的RAM中int core0_main(void)
{get_clk();//获取系统时钟频率uart_init(UART_0,115200,UART0_TX_P14_0, UART0_RX_P14_1);HallSensor_init();pit_interrupt_ms(CCU6_1, PIT_CH1, 1); //周期中断初始//等待所有核心初始化完毕IfxCpu_emitEvent(&g_cpuSyncEvent);IfxCpu_waitEvent(&g_cpuSyncEvent, 0xFFFF);enableInterrupts();while (TRUE){printf ( "angle %d\n", get_angle());}
}#pragma section all restore

总结

霍尔编码器读到的数据比较离散,读到数据也是。
如果以一个速度稳定旋转转抽,霍尔编码器的输出会在一个稳定值得上下进行波动这个就是霍尔编码器的特性。


simplefoc通常采用的是磁编码器,后续我也会移植相应的代码,比较两者的差别,进行总结。最后感谢大家阅读。

【FOC控制】英飞凌TC264无刷驱动方案simplefoc移植(1)-霍尔编码器移植相关推荐

  1. 【FOC控制】英飞凌TC264无刷驱动方案simplefoc移植(5)-磁编码器移植AS5600 软件IIC

    [FOC控制]英飞凌TC264无刷驱动方案simplefoc移植(5)-磁编码器移植 [FOC控制]英飞凌TC264无刷驱动方案simplefoc移植(5)-磁编码器移植 一.编码器选择 二.通讯方式 ...

  2. 【FOC控制】英飞凌TC264无刷驱动方案simplefoc移植(6)- foc速度闭环控制

    [FOC控制]英飞凌TC264无刷驱动方案simplefoc移植(6)- foc速度闭环控制 [FOC控制]英飞凌TC264无刷驱动方案simplefoc移植(6)- foc速度闭环控制 一.电机选择 ...

  3. 【FOC控制】英飞凌TC264无刷驱动方案simplefoc移植(2)-SVPWM波实现

    [FOC控制]英飞凌TC264无刷驱动方案simplefoc移植(2)-SVPWM波实现 SVPWM波实现就是无数电机foc控制的核心,所以这一节就如何在英飞凌无刷驱动上时间互补pwm波形做讲解 [F ...

  4. 【FOC控制】英飞凌TC264无刷驱动方案simplefoc移植(3)-FOC控制原理矢量控制

    英飞凌TC264无刷驱动方案simplefoc移植(3)-FOC控制原理矢量控制 无刷电机是矢量控制,是交流电机调速的核心,也是Foc控制的核心 以下内容学习自[自制FOC驱动器]深入浅出讲解FOC算 ...

  5. [开源]圆形FOC无刷驱动Baize_foc

    介绍 由于做四足机器狗的需要,所以做了这块圆形无刷电机驱动板,自己取名叫Baize_foc了. 上面集成了as5600磁编码器,电流环等功能.形状为圆形,因此可以非常方便的直接用螺丝固定到电机的后面: ...

  6. 电钻有刷好还是无刷好_高中物理好的来看看,永磁同步直流电机是怎样实现无刷驱动的?...

    相信很多新能源车的车主或者打算购买新能源车的用户都听说过永磁同步直流电机这个名词,因为它在市售的纯电动车中使用率非常高,特别是对于那些20万以下,续航里程400公里以下的纯电动车型,应用非常广泛.吉利 ...

  7. DC12-24V直流无刷驱动器方案,原理图,源代码都有

    DC12-24V直流无刷驱动器方案,原理图,源代码都有

  8. 风筒电吹风无刷驱动设计-电吹风无刷电机PCBA方案设计

    1.电吹风市场现状 近年来伴随居民消费实力和意愿的提升,消费者对产品品质和功能的需求日益增加.随着电吹风产品的升级革新,零售额不断增长.数据显示,2021年,电吹风全年零售额53.8亿元,同比增长10 ...

  9. 深入浅出讲解FOC控制与SVPWM技术

    深入浅出讲解FOC控制与SVPWM技术 0.前言 0.1 什么是FOC 0.2 FOC驱动器和无刷电调的区别 1.从电机原理说起 1.1 一些基础知识 1.2 无刷电机原理 1.3 关于BLDC和PM ...

  10. [硬件基础] 有刷、有感和无刷无感电机对比

    原文地址: [转] 有刷.有感和无刷无感电机的使用心得  作者: -工控老鬼 一.有刷马达的原理 要讲清这一问题,那就应粗略地了解一下有刷马达的工作原理.接下来用一个三电极.二磁极内转子有刷马达作为演 ...

最新文章

  1. AI岗位面试屡战屡败?这份“翻盘秘籍”快收好!
  2. 英伟达收购Mellanox接近尾声,将成英伟达史上最大收购案
  3. 高清电影如何加载字幕【解决】
  4. pcl和opencv多版本共存
  5. wamp php启动不成功,wamp的mysql 启动失败解决
  6. 如何让小程序页面更顺滑_小程序怎样让wx.navigateBack更好用的方法实现
  7. python测验2_测验2: Python基础语法(上) (第4周)
  8. u盘读写测试_aigo U395固态U盘评测,速度可能会吓到你,价格很良心
  9. html查看ie版本,jquery怎么判断浏览器是否是ie
  10. [Java]HashMap的两种排序方式
  11. 中国移动笔试题——转自MOP
  12. 以计算机基础知识做二十张ppt,计算机基础知识教程.ppt
  13. CTF中的RSA套路
  14. linux服务器console口,Linux重定向console口控制台
  15. 高手修车都用示波器: 示波器是什么?如何选购?
  16. php html字符转换为字符串,PHP字符串函数html_entity_decode( 把HTML实体转换为字符)
  17. 奶茶新手加盟奶茶品牌培训哪些技能?
  18. 常用的时间系统有哪些?
  19. (六)Docker三剑客之Swarm
  20. Mac Book pro(M1)使用总结

热门文章

  1. 修改BT种子的tracker服务器list
  2. 配置tracker服务
  3. 教妹学Java(十):Unicode字符集简介
  4. 19.敏捷项目管理流程实例 - 变更管理
  5. 【超详细】私有仓库Gitlab的安装与使用详细教程
  6. 两角和正切的展开式+正切公式+一元微积分
  7. JS中定义对象和集合
  8. javascript 自定义对象的两种方法
  9. 【嵌入式模块】直流电机驱动L298N,TB6612详解
  10. matlab单回路和串级控制回路,串级控制回路PID参数如何整定?