クローズドループ正弦波駆動 リベンジ ーブラシレスモータ駆動への道10ー
HomeMadeGarbage Advent Calendar 2022 |14日目
前回は “50日後にセンサレスベクトル制御してみたい俺” の時に実施したESP32を用いたブラシレスモータのセンサありベクトル制御について報告しました。
ここではクローズドループ正弦波駆動に再挑戦しましたので報告します。
目次
ドライバ修理
“50日後にセンサレスベクトル制御してみたい俺” の際にドライバを破壊してしまいましたので まずは修理しました。
50日後にセンサレスベクトル制御してみたい俺
50日目 #ブラシレスモータ駆動への道 #50daysBLDC pic.twitter.com/hiyPNSRY4r— HomeMadeGarbage (@H0meMadeGarbage) December 5, 2022
やはりプリドライバが壊れており、部品交換で無事に治りました。
治った
ビール飲んでも1608ならまだ余裕
でも最近目に入ってくる光の量が少なくなった気がする。。 pic.twitter.com/hv35nZBSse— HomeMadeGarbage (@H0meMadeGarbage) December 7, 2022
クローズドループ正弦波駆動
磁気エンコーダによってモータの回転位置を検知するクローズドループ正弦波駆動には以前挑戦しておりました。
しかしエンコーダによる回転位置を直接フィードバックしての回転がどうしてもうまくいかず若干変則的な方法で回転を実現させました。
エンコーダ検知遅延
“50日後にセンサレスベクトル制御してみたい俺” の際に磁気エンコーダの値検知動作に50msecのディレイがあることに気づきました。
以前うまくいかなかったのはこのディレイのせいである可能性が高いので、今回はこの遅延をなくして実験を進めます。
構成
構成は以前と同様です。
ここでは可変抵抗は使用せず、BlynkレガシーアプリでBLEを介してスマホで変数調整しました。
- ESP32 評価基板
- プリドライバIC IR2302
- NMOS 2SK4017
- ブートストラップ用ダイオード 1N4148W
- ブラシレスモータ
- 磁気エンコーダ AS5048
システム概要
磁気エンコーダでロータの回転位置と回転速度を検知して、指定の回転速度との差分で正弦波電圧値をPI制御で算出します。
また正弦波の位相は検知したロータ位置を電気角にして使用します。
Arduinoコード
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 |
#define BLYNK_PRINT Serial #define BLYNK_USE_DIRECT_CONNECT #include <BlynkSimpleEsp32_BLE.h> #include <BLEDevice.h> #include <BLEServer.h> #include <AS5048A.h> char auth[] = "トークン"; AS5048A angleSensor(SS, false); #define ampPin 39 #define uHin 25 #define vHin 26 #define wHin 27 int uPWMCH = 0; int vPWMCH = 1; int wPWMCH = 2; float twoPI = 2.0 * PI; float onePI = PI; float Vu, Vv, Vw, Vmin, Vmax, Vzero; int amp = 100; float Vdd = 7.4; //電源電圧[V] unsigned long oldTime = 0, nowTime, loopTime; unsigned long measTime = 0; float rotSpeed; int State = 0; uint16_t rotData, rotDataIni; int rotDataCal, rotDataCalOld, rotDiff; int BottunState = 0; float u, v, w; float uOffset = 0, vOffset = 0; int IniOK = 0; float Kpr = 5.0, Kir = 0.5; float diffPr, diffIr = 0.0; float rotSpeedTarget = 80; //指定回転速度[rad/s] float Div = 1024.0; float theta = 0.0; //Core0 void rotPosition(void *pvParameters) { for (;;){ Blynk.run(); rotData = angleSensor.getRawRotation() >> 4; if(IniOK == 1){ delay(200); rotDataIni = rotData; IniOK = 2; } if(IniOK == 2){ nowTime = micros(); rotDataCal = int(rotData - rotDataIni); if(rotDataCal < 0) rotDataCal += Div; if(BottunState){ rotDiff = rotDataCalOld - rotDataCal; }else{ rotDiff = rotDataCal - rotDataCalOld; } if(rotDiff < 0){ rotDiff += Div; } if(rotDiff > 10){ rotDataCalOld = rotDataCal; loopTime = nowTime - oldTime; oldTime = nowTime; rotSpeed = rotDiff / Div * twoPI / (loopTime / 1000000.0); //[rad/s] rotSpeed = constrain(rotSpeed, 0, 200); } diffPr = rotSpeedTarget - rotSpeed; diffIr += diffPr; amp = Kpr / 185.0 * diffPr + Kir / 185.0 * diffIr; amp = constrain(amp, 0, 511); if(nowTime - measTime > 50000){ Serial.print(rotSpeedTarget); Serial.print(", "); Serial.print(rotSpeed); Serial.println(""); measTime = nowTime; } } disableCore0WDT(); } } //ヴァーチャルピンデータ受信 BLYNK_WRITE(V0) { BottunState = param.asInt(); } BLYNK_WRITE(V7) { amp = param.asInt(); } BLYNK_WRITE(V9) { Kpr = param.asFloat(); } BLYNK_WRITE(V10) { Kir = param.asFloat(); } BLYNK_WRITE(V3) { rotSpeedTarget = param.asFloat(); } BLYNK_WRITE(V5) { diffIr = 0; IniOK = 0; } void setup() { Serial.begin(2000000); angleSensor.begin(); Blynk.setDeviceName("motor"); Blynk.begin(auth); ledcSetup(uPWMCH, 20000, 10); ledcAttachPin(uHin, uPWMCH); ledcWrite(uPWMCH, 0); ledcSetup(vPWMCH, 20000, 10); ledcAttachPin(vHin, vPWMCH); ledcWrite(vPWMCH, 0); ledcSetup(wPWMCH, 20000, 10); ledcAttachPin(wHin, wPWMCH); ledcWrite(wPWMCH, 0); //回転位置検出 タスク xTaskCreatePinnedToCore( rotPosition , "rotPosition" // A name just for humans , 4096 // This stack size can be checked & adjusted by reading the Stack Highwater , NULL , 3 // Priority, with 3 (configMAX_PRIORITIES - 1) being the highest, and 0 being the lowest. , NULL , 0); } void loop() { //初期回転 if(IniOK == 0){ for(int i = 0; i < 512; i++){ u = i; if(BottunState){ v = i + 512.0 * 2.0 / 3.0; w = i + 512.0 / 3.0; }else{ w = i + 512.0 * 2.0 / 3.0; v = i + 512.0 / 3.0; } if(u >= 512) u -= 512; if(v >= 512) v -= 512; if(w >= 512) w -= 512; Vu = 250 *(1.0 + sin(twoPI / (512.0 / 7.0) * u)) / 2.0; Vv = 250 *(1.0 + sin(twoPI / (512.0 / 7.0) * v)) / 2.0; Vw = 250 *(1.0 + sin(twoPI / (512.0 / 7.0) * w)) / 2.0; ledcWrite(uPWMCH, int(Vu)); ledcWrite(vPWMCH, int(Vv)); ledcWrite(wPWMCH, int(Vw)); delayMicroseconds(2000); } IniOK = 1; } if(IniOK == 2){ //ロータ位置 (電気角) [rad] theta = rotDataCal / Div * 7.0 * twoPI; if(BottunState){ Vu = amp *(1.0 - cos(theta)); Vv = amp *(1.0 - cos(theta + twoPI / 3.0)); Vw = amp *(1.0 - cos(theta + 2.0 * twoPI / 3.0)); }else{ Vu = amp *(1.0 + cos(theta)); Vv = amp *(1.0 + cos(theta + twoPI / 3.0)); Vw = amp *(1.0 + cos(theta + 2.0 * twoPI / 3.0)); } //PWM出力 ledcWrite(uPWMCH, int(Vu)); ledcWrite(vPWMCH, int(Vv)); ledcWrite(wPWMCH, int(Vw)); } } |
最新版のBlynkではBLEが使用できないので、以前のバージョンのBlynkレガシーを使用してBLE通信しています。
疑似正弦波を生成するためにドライバ駆動ピン(IO25~27)はledcWriteを用いて20kHz PWM出力します。分解能は10ビット(0~1023) (L. 148-156)。
起動時に1周期分オープンループで回転させてロータ位置のオフセットを導出します (L. 172-199)。
ロータ位置のオフセット導出後はクローズドループで回転し続けます 。
オフセットを加味したモータのロータ位置rotData をデュアルコアのcore0で検出しています。
1周の分解能を14bitから10bit (1024)にしています (L. 60)。
モータ回転速度 rotSpeed を検知して、指定の回転速度 rotSpeedTarget との差分をPI制御して正弦波波高値 amp を算出します (L. 69-95)。
core1でロータ位置からモータの電気角 theta [rad] を算出。使用しているブラシレスモータのロータの極数は14 [7ペア] (L. 203)。
BottunStateによって正転/逆転を判断してcore0で算出された波高値 ampで正弦波を生成します (L. 205-213)。
導出された正弦波をPWM変換してドライバを駆動します (L. 215-218)。
Blynkアプリで、モータ回転方向BottunStateと回転速度rotSpeedTarget 、PI制御の係数をBLEで受信します (L. 114-138) 。
動作
無事に正転反転動作もでき、PI制御の係数を調整して指定の回転速度への制動のとれた追従動作も確認できました。
おわりに
ここでは “50日後にセンサレスベクトル制御してみたい俺” によって気づいた磁気エンコーダの遅延を改善してクローズドループ正弦波駆動に再挑戦しました。
無事に回転動作を確認でき、リベンジすることができました。
今回の実験で正弦波駆動でブラシレスモータをかなり自由に動かせることがわかりました。
しばらくはクローズドループ正弦波駆動で色々楽しみたいと考えております。
次の記事