前言
电机的定位控速都离不开对于转子位置的检测。采用霍尔传感器的是电机控制的常用方法。
本文就笔者学习霍尔传感器的使用尝试自己写这部分算法的一些心得与各位大神交流。
1 电机霍尔状态
我们知道,一个周期有6个霍尔状态,而霍尔状态的数值顺序与霍尔安装角度和霍尔传感器的型号、安装方式都有关系。但无论哪一种情况,我们都可以通过一定的数学变换对应到同一种顺序定义,便于程序简化。
我们计划按照严格120°相位差来作为归一化的处理代码,则霍尔状态依次为5(101)、4(100)、6(110)、2(010)、3(011)、1(001)。
关于霍尔传感器的顺序表现可以参见以下两篇文章:
链接: 【电机控制】霍尔传感器和反电动势的关系分析
链接: 【电机控制】无刷电机基础算法
以下通过伪代码简要说明实现方式。
/* 确定霍尔安装方式以及HU HV HW与GPIO的对应关系;
可以通过电机测试或霍尔自学习获得;
自学习算法之后填坑 */
/* 锁定HU HV HW与GPIO的对应关系 */
hall_u_status = Get_PinLevel(real_hall_u_port&pin);
hall_v_status = Get_PinLevel(real_hall_v_port&pin);
hall_w_status = Get_PinLevel(real_hall_w_port&pin);
if (hall_sensor_placement == INTERVAL_120_DEGREES)
{
//do nothing
}
else //hall_sensor_placement == INTERVAL_060_DEGREES)
{
// transform to 120 degrees interval.
hall_v_status ~= hall_v_status;
}
/* 根据对应关系获取霍尔状态 */
hall_status = hall_u_status<<2 | hall_v_status<<1 | hall_w_status<<0;
2 霍尔检测的基本目标
2.1 位置(电角度)初始化
对于一个确定的电极,霍尔状态分为6种,即每次霍尔状态更新我们可以校正一次电角度,显然,根据霍尔状态测量得到的电角度精度为60°。
由于启动时速度为0,也没有反电动势等可供参考的信息,因此初始电角度只能依据霍尔状态进行粗略估算。
以下代买摘自ST的开源算法库中的估算方式,依据霍尔状态对应的电角度中值进行设定。该方法的优点是不管正转反转,其误差都是±30°。需要注意的是,初始电角度只是给整个运行提供一个初始状态,并不需要一个特别精确的值。后面的电角度会根据前面的运行信息得到更精确的估算。
/**
* @brief Read the logic level of the three Hall sensor and individuates in this
* way the position of the rotor (+/- 30°). Electrical angle is then
* initialized.
* @param pHandle: handler of the current instance of the hall_speed_pos_fdbk component
* @retval none
*/
static void HALL_Init_Electrical_Angle(HALL_Handle_t *pHandle)
{
if (pHandle->SensorPlacement == DEGREES_120)
{
pHandle->HallState = LL_GPIO_IsInputPinSet(pHandle->H3Port, pHandle->H3Pin)<<2
| LL_GPIO_IsInputPinSet(pHandle->H2Port, pHandle->H2Pin)<<1
| LL_GPIO_IsInputPinSet(pHandle->H1Port, pHandle->H1Pin);
}
else {
pHandle->HallState = (LL_GPIO_IsInputPinSet(pHandle->H2Port, pHandle->H2Pin)^1)<<2
| LL_GPIO_IsInputPinSet(pHandle->H3Port, pHandle->H3Pin)<<1
| LL_GPIO_IsInputPinSet(pHandle->H1Port, pHandle->H1Pin);
}
switch(pHandle->HallState)
{
case STATE_5:
pHandle->_Super.hElAngle = (int16_t)(pHandle->PhaseShift+S16_60_PHASE_SHIFT/2);
break;
case STATE_1:
pHandle->_Super.hElAngle =(int16_t)(pHandle->PhaseShift+S16_60_PHASE_SHIFT+
S16_60_PHASE_SHIFT/2);
break;
case STATE_3:
pHandle->_Super.hElAngle =(int16_t)(pHandle->PhaseShift+S16_120_PHASE_SHIFT+
S16_60_PHASE_SHIFT/2);
break;
case STATE_2:
pHandle->_Super.hElAngle =(int16_t)(pHandle->PhaseShift-S16_120_PHASE_SHIFT-
S16_60_PHASE_SHIFT/2);
break;
case STATE_6:
pHandle->_Super.hElAngle =(int16_t)(pHandle->PhaseShift-S16_60_PHASE_SHIFT-
S16_60_PHASE_SHIFT/2);
break;
case STATE_4:
pHandle->_Super.hElAngle =(int16_t)(pHandle->PhaseShift-S16_60_PHASE_SHIFT/2);
break;
default:
/* Bad hall sensor configutarion so update the speed reliability */
pHandle->SensorIsReliable = false;
break;
}
/* Initialize the measured angle */
pHandle->MeasuredElAngle = pHandle->_Super.hElAngle;
}
2.2 估算当前转速
基本思路:通过FIFO数组来记录通过六区的时间。
(1)启动时,电机速度尚未稳定,FIFO数组尚未被填满,当前转速用最近一次更新的数组数据来进行估算;
(2)FIFO数组填满后,电机处于变动过程中,可以使用最近一次的分区的时间进行估算;当电机转速相对稳定时,FIFO数组的值会在目标转速附件,其极差取决于转速稳定区间。
(3)每当霍尔状态更新时,校正当前霍尔角度。注意,不同转向的校正计算是不一样的。
2.3 霍尔相序的自学习
注:以下是笔者的思路,未参考成熟库的代码,不确保逻辑中没有漏洞。
- 方案(1)
- 定向,给VW通一个较小的正电流使得U相绕组正对N极,取得0电角度的霍尔状态。
- 按照定义的相线驱动电机正转,方法有VF或IF,记录连续6p个霍尔状态(p为极对数)。
- 构造霍尔状态数组,穷举所有可能的霍尔状态排列。前面提到霍尔状态(120°安装)正转时是5、4、6、2、3、1;反转是5、1、3、2、6、4。构造一个2倍长度的循环数组,则霍尔状态一定是上面两个循环数组中的一部分。60°霍尔安装原理类似。
- 方案(2)
- 按照六扇区定向方法依次给线圈通上电流,找到对应的霍尔状态,据此确定电机霍尔的对应关系。
- 盗个图用以说明思路:通过U+V-W悬空、U悬空V+W-和U-V悬空W+来确定霍尔传感器的对应关系。
- 需要提醒的是,用以定向选取的电流既要能保持转子位置,又不能电流过大,时间过长,以致烧坏电机。
- 由于绕线方向或霍尔安装方向角度等各种因素,实际测试出来的结果可能需要按位取反。
关于代码容后补充。