2020年7月2日 星期四

用 ESP8266 驅動 BLDC

之前硬碟故障後一直保存在庫房裏, 裏面有一棵 3 相 BLDC 包在鋁合金裏面, 無法拆, 索性上網買兩顆橋式電路板練習用 PWM(pulse width modulation)來驅動看看, 3 相 BLDC 端點電壓 A, B,  C 在相對應的 U, V, W 相位差需彼此相差 120 度才能驅動, 同一時間點 BLDC 的其中兩端點根據電流流向產生磁極去吸引馬達轉子(永久磁鐵)達到正轉或逆轉的目的, 第 3 端點必須保持高阻抗讓它自由滑行, BLDC 雖中文翻譯為無刷直流馬達, 實際上卻是一個名不符實的交流馬達, 只是他不用負電壓去驅動, 而是靠端點相對電壓產生負電流去驅動, 透過 PWM 信號控制橋式電路板就能產生交流(正負)電流, 網上買的橋式 IC 是 MX1508, 他有兩個全橋式通道, 每個通道是 2 個輸入, 去控制 2 個橋式輸出,真值表如下:
         In+    In-     Out+    Out-
           0       0       HiZ       HiZ
           0       1       GND     VCC
           1       0       VCC      GND
           1       1       煞車      煞車

驅動 3 個相位的 BLDC 需要用 2 棵 MX1508 IC 將直流 PWM 信號轉換成交流的橋式電流去推動馬達的電感性負載, 2 棵 MX1508 就有 4 個全橋式通道可以使用, 只要取其中 3 個通道, 另外一個通道的兩個輸入端直接接地避免誤動作,  順轉時,電流推導順序如下:
    step 1.   A -> B (C HiZ) : A+ = 1, (A- = 0) , B+ = 0, (B- = 1), C+ = 0, (C- = 0)
    step 2.   A -> C (B HiZ) : A+ = 1, (A- = 0) , B+ = 0, (B- = 0), C+ = 0, (C- = 1)
    step 3.   B -> C (A HiZ):  A+ = 0, (A- = 0) , B+ = 1, (B- = 0), C+ = 0, (C- = 1)
    step 4.   B -> A (C HiZ):  A+ = 0 , (A- = 1), B+ = 1, (B- = 0), C+ = 0, (C- = 0)
    step 5.   C -> A (B HiZ):  A+ = 0 , (A- = 1), B+ = 0, (B- = 0), C+ = 1, (C- = 0)
    step 6.   C -> B (A HiZ):  A+ = 0 , (A- = 0), B+ = 0, (B- = 1), C+ = 1, (C- = 0)

如果要逆轉, 只要將順序反過來就可:
    step 1.   C -> B (A HiZ):  A+ = 0 , (A- = 0), B+ = 0, (B- = 1), C+ = 1, (C- = 0)
    step 2.   C -> A (B HiZ):  A+ = 0 , (A- = 1), B+ = 0, (B- = 0), C+ = 1, (C- = 0)
    step 3.   B -> A (C HiZ):  A+ = 0 , (A- = 1), B+ = 1, (B- = 0), C+ = 0, (C- = 0)
    step 4.   B -> C (A HiZ):  A+ = 0, (A- = 0) , B+ = 1, (B- = 0), C+ = 0, (C- = 1)
    step 5.   A -> C (B HiZ) : A+ = 1, (A- = 0) , B+ = 0, (B- = 0), C+ = 0, (C- = 1)
    step 6.   A -> B (C HiZ) : A+ = 1, (A- = 0) , B+ = 0, (B- = 1), C+ = 0, (C- = 0)

之後循環重複  1 ~ 6 步驟就能產生 120 度相位差, 持續推動 BLDC, 底下只看順轉的情形, 搭配上述真值表, 把電流的流向控制邏輯數位化成一個 6x6 矩陣表來表示, 橫軸是時間軸, 縱軸是每個數位化控制邏輯:

  const int motorPhases[6][6] = {
     {1, 1, 0, 0, 0, 0}, // A+: 1, 1, z, 0, 0, z
     {0, 0, 0, 1, 1, 0}, // A- : 0, 0, z, 1, 1, z
     {0, 0, 1, 1, 0, 0}, // B+: 0, z, 1, 1, z, 0
     {1, 0, 0, 0, 0, 1}, // B- : 1, z, 0, 0, z, 1
     {0, 0, 0, 0, 1, 1}, // C+: z, 0, 0, z, 1, 1
     {0, 1, 1, 0, 0, 0}  // C- : z, 1, 1, z, 0, 0
  };
  mx1508 真值表:
  輸入(+-)    輸出(+-)
     00       -> GND, GND : 高阻抗 HiZ
     10       ->  VCC, GND : 電流順向 Forward
     01       ->  GND, VCC : 電流反向 Reverse
     11       ->  VCC, VCC  : 煞車 Brake

另外要特別注意的是 MX1508 耐電壓只到 9V, 驅動力有限, 可能無法產生太大扭力, 尤其使用 PWM 訊號去驅動時, 有效扭力與 duty cycle 成正比, 因此可能還要打個折. 想要讓 BLDC 保持高速運動, 就算沒有 sensor 也可以推動, 就要像盪鞦韆一樣慢慢的定時加速. 下面要利用 ESP8266 的 timer1 中斷服務程式(interrupt service routine) 從 GPIO 輸出正相位 phase0A, phase0B, phase0C 去控制橋式電路的 U, V, W 相, 也就是說將相對應橋式輸出端分別連接馬達的 U, V, W 相, 至於負相位 phase_A, phase_B, phase_C 主要是控制MX1508 的輸出邏輯, 因此負相位要與橋式輸入相對應的相位連接, 但橋式輸出端就空著不用接,換句話說連接 BLDC 的其實只用通道的半橋式輸出電路, 而控制時運用全橋式輸入邏輯. 相位順序必須連接正確否則是無法推動 BLDC 的,完整 arduino 程式碼如下:
// app.ino
#include "ESP8266WiFi.h"
#define phase0A   14 // A+ use GPIO14: D5
#define phase_A   12 // A- use GPIO12 : D6
#define phase0B   13 // B+ use GPIO13 : D7
#define phase_B   15 // B-  use GPIO15 : D8
#define phase0C   4  //  C+ use GPIO4 : D2
#define phase_C   5  //  C- use GPIO5 : D1
#define RED_LED  2  // GPIO2  is D4
const int motorPhases[6][6] = {
  {1,1,0,0,0,0},// A+: 1, 1, z, 0, 0, z
  {0,0,0,1,1,0},// A- : 0, 0, z, 1, 1, z
  {0,0,1,1,0,0},// B+: 0, z, 1, 1, z, 0
  {1,0,0,0,0,1},// B- : 1, z, 0, 0, z, 1
  {0,0,0,0,1,1},// C+: z, 0, 0, z, 1, 1
  {0,1,1,0,0,0} // C- : z, 1, 1, z, 0, 0
};
int currentPhase = 0;
uint32_t prescaler = 5e6;
int downCounter = 5e6/prescaler;// counter upto 1 second

void ICACHE_RAM_ATTR  onTimeCounter( ) {
  timer1_write(prescaler);
  if(prescaler < 2e6) {     
    digitalWrite(RED_LED, 1);// Turn off LED, begin to speed up ...
    digitalWrite(phase0A , motorPhases[0][currentPhase]);
    digitalWrite(phase_A , motorPhases[1][currentPhase]);
    digitalWrite(phase0B , motorPhases[2][currentPhase]);
    digitalWrite(phase_B , motorPhases[3][currentPhase]);
    digitalWrite(phase0C , motorPhases[4][currentPhase]);
    digitalWrite(phase_C , motorPhases[5][currentPhase]);
    if (++  currentPhase > 5) currentPhase = 0;  
  } else { // to brake BLDC
    digitalWrite(phase0A, 1);
    digitalWrite(phase_A, 1);
    digitalWrite(phase0B, 1);
    digitalWrite(phase_B, 1);
    digitalWrite(phase0C, 1);
    digitalWrite(phase_C, 1);
  }
  if (downCounter > 0) downCounter --;
  else { // time to speed up
    if(prescaler >= 2e5) {
      prescaler = prescaler * 90 / 100; // to speed up 1/0.9    ~= 1.1
    } else if(prescaler >= 2e4) {
      prescaler = prescaler * 95 / 100; // to speed up 1/0.95 ~= 1.05
    } else if (prescaler >= 10e3) {
      prescaler = prescaler * 98 / 100; // to speed up 1/0.98 ~= 1.02
    } else if (prescaler >= 5e3 ) {
      prescaler = prescaler * 99 / 100; // to speed up 1/0.99 ~= 1.01
    } // else keep speed constant, if prescaler smaller than 4500, kernel panic!
    downCounter  = (625e3/prescaler); // counter upto 1/8 second
  } 
}

void setup( ) {
  Serial.begin(115200);
  pinMode(RED_LED, OUTPUT); 
  digitalWrite(RED_LED, 0);// Turn on LED
  pinMode(phase0A, OUTPUT);// A+
  pinMode(phase_A, OUTPUT);// A-
  pinMode(phase0B, OUTPUT);// B+
  pinMode(phase_B, OUTPUT);// B-
  pinMode(phase0C, OUTPUT);// C+
  pinMode(phase_C, OUTPUT);// C-
  timer1_attachInterrupt(onTimeCounter);
  timer1_enable(TIM_DIV16, TIM_EDGE, TIM_SINGLE);
  timer1_write(prescaler);
}

void loop( ) {
}

仔細觀查 6x6 矩陣表會發現一個有趣的現象  A+  與 A- , B+ 與 B- , C+ 與 C- 都相差(超前或是延後) 3 個時間單位(全相是 6 個時間單位, 一圈是 360 度), 稍微運算後會發現正好就是 + 與 - 相位差 180 度, 而 A+ 與 B+  與 C+ 之間也都相互差了 2 個時間單位, 也是因為相位差 120 度的必然結果:
    360 * 3 / 6 = 180
    360 * 2 / 6 = 120
因此只要保存 baseVector= {1, 1, 0, 0, 0, 0} 這一基礎向量, 其它時間的相位用"取模 6 運算"(% 6) 來得到, 因此推動 BLDC 可以簡單用下面的虛擬運算碼來呈現:
const bool  baseVector[6] = {true, true, false, false, false, false};//向量, 共 6 個時間相 0 ~ 5
int n = 0 ;  // 初始相 0, in phase
while (true) {
    digitalWrite(A+,  baseVector[n % 6]);// in  phase  0
    digitalWrite(A- , baseVector[(n - 3) % 6]);// phase lag 3
    digitalWrite(B+, baseVector[(n - 2) % 6]);// phase lag 2
    digitalWrite(B- , baseVector[(n - 5) % 6]);// phase lag 5
    digitalWrite(C+, baseVector[(n - 4) % 6]);// phase lag 4
    digitalWrite(C- , baseVector[(n - 1) % 6]);// phase lag 1
    n = (n + 1) % 6;
    delay(.);
}

另一種演算法是先分別取出每個相, 結束後再準備下個時間單位的向量, 只要把基礎向量旋轉一個時間單位, 同樣可以達到相同目的:
bool  baseVector[6] = {true, true, false, false, false, false};//初始向量, 共 6 個時間相 0 ~ 5
while (true) {
    digitalWrite(A+, baseVector[0]);// phase 0
    digitalWrite(A- , baseVector[3]);// phase -3 % 6 = phase 3
    digitalWrite(B+, baseVector[4]);// phase -2 % 6 = phase 4
    digitalWrite(B- , baseVector[1]);// phase -5 % 6 = phase 1
    digitalWrite(C+, baseVector[2]);// phase -4 % 6 = phase 2
    digitalWrite(C- , baseVector[5]);// phase -1 % 6 = phase 5
    bool temp =  baseVector[0];
    for (int  i = 0; i < 5 ; i ++) baseVector[i] = baseVector[i + 1];// 順時移動
    baseVector[5] = temp;
    delay(.);
}

因為沒使用 sensor 去感應磁鐵的位置, 因此很有可能一開始的慣性力矩造成旋轉方向錯誤,或是有阻力導致後續驅動 BLDC 的相位無法與旋轉運動產生有效共振而停止運動, 或許 BLDC 必須用 hall sensor 的助力才能穩定運行!

簡單 c 程式碼, 根據五行八卦相生相剋推斷吉凶

#include "stdio.h" // 五行: //               木2 //      水1           火3 //         金0     土4 // // 先天八卦 vs 五行 //                    ...