打印
[数字电源]

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

[复制链接]
979|11
手机看帖
扫描二维码
随时随地手机跟帖
跳转到指定楼层
楼主
lvuu|  楼主 | 2024-2-29 12:29 | 只看该作者 |只看大图 回帖奖励 |倒序浏览 |阅读模式
十七届直立单车组在十六届的基础之后允许动量轮的存在,维持车模平衡,所以就需要使用英飞凌的无刷驱动方案。



硬件电路配置
无刷电机驱动板 :使用TC264单片机



无刷电机为选择有感、三槽两极、2860Kv(Kv表示每增加一伏电压电机增加的转速,最高12V)、尺寸36(mm)*50(mm)、额定功率190W、支持1-3S锂电池供电。





二 、 问题的提出
在逐飞的方案中:

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

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

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

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

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


使用特权

评论回复
沙发
lvuu|  楼主 | 2024-2-29 12:29 | 只看该作者
霍尔编码器原理
霍尔编码器检测转子位置,一共安装三个霍尔分别间隔120度安装,霍尔输出的波形如下图所,每当波形改变的时候就需要进行换相。
但是霍尔采集的角度数据是离散的,比如30, 60, 90等,比较适合方波控制。

使用特权

评论回复
板凳
lvuu|  楼主 | 2024-2-29 12:30 | 只看该作者
霍尔编码角度速度读取
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,  //clockwise
    CCW     = -1, // counter clockwise
    UNKNOWN = 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 0
    electric_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)
}

使用特权

评论回复
地板
lvuu|  楼主 | 2024-2-29 12:30 | 只看该作者
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 changed
  if (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) {
    //underflow
    direction = CCW;
    electric_rotations += direction;
  } else if (new_electric_sector - electric_sector < (-3)) {
    //overflow
    direction = 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 area
  if (direction == old_direction) {
    // not oscilating or just changed direction
    pulse_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);
}

使用特权

评论回复
5
lvuu|  楼主 | 2024-2-29 12:30 | 只看该作者
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 calculation
  function 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 old
    return 0;
  }
  else
        {
    return direction * (_2PI / cpr) / (pulse_diff / 1000000.0f);
  }
}

使用特权

评论回复
6
lvuu|  楼主 | 2024-2-29 12:31 | 只看该作者
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,  //clockwise
    CCW     = -1, // counter clockwise
    UNKNOWN = 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 channel

void HallSensor_init();
float HallSensor_getVelocity();
float HallSensor_getAngle();
void HallSensor_updateState();
void HallSensor_handleC();
void HallSensor_handleB();
void HallSensor_handleA();
float getVelocity(void);

#endif

使用特权

评论回复
7
lvuu|  楼主 | 2024-2-29 12:32 | 只看该作者
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 functions
       
HALL 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 changed
  if (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) {
    //underflow
    direction = CCW;
    electric_rotations += direction;
  } else if (new_electric_sector - electric_sector < (-3)) {
    //overflow
    direction = 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 area
  if (direction == old_direction) {
    // not oscilating or just changed direction
    pulse_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 calculation
  function 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 old
    return 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 0
    electric_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);
}
/******************************************************************************/

使用特权

评论回复
8
lvuu|  楼主 | 2024-2-29 12:32 | 只看该作者
4-5 函数调用
在原版的simplefoc程序中,使用的是外部中断跳边沿触发调用中断函数()
// 中断例程初始化
void doA(){sensor.handleA();}
void doB(){sensor.handleB();}
void doC(){sensor.handleC();}

使用特权

评论回复
9
lvuu|  楼主 | 2024-2-29 12:32 | 只看该作者
但是在tc264中,外部中断的资源比较少,而板载连接的又不是在几个引脚。
typedef enum  // 枚举ERU通道
{
        //一个通道只能选择其中一个引脚作为 外部中断的输入
        //例如通道0 可选引脚为P10_7 和 P15_4,
        //在LQFP144封装中没有P10_7
        ERU_CH0_REQ4_P10_7   = 0*3,  ERU_CH0_REQ0_P15_4,                                                //通道0可选引脚   LQFP没有P10_7引脚
        //在LQFP144封装中没有P10_8
        ERU_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;

使用特权

评论回复
10
lvuu|  楼主 | 2024-2-29 12:32 | 只看该作者
所以我决定将更新函数放到定时器中断之中也是可行的
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( );
}

使用特权

评论回复
11
lvuu|  楼主 | 2024-2-29 12:32 | 只看该作者
主函数调用
#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

使用特权

评论回复
12
lvuu|  楼主 | 2024-2-29 12:33 | 只看该作者
总结
霍尔编码器读到的数据比较离散,读到数据也是。
如果以一个速度稳定旋转转抽,霍尔编码器的输出会在一个稳定值得上下进行波动这个就是霍尔编码器的特性。


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

使用特权

评论回复
发新帖 我要提问
您需要登录后才可以回帖 登录 | 注册

本版积分规则

51

主题

466

帖子

0

粉丝