センサレス クローズドループ矩形波制御 その2 ーブラシレスモータ駆動への道3ー
前回 ESP32をコントローラとしてセンサレス クローズドループ矩形波制御を実現しました。
ここでは更に検討進めましたので報告いたします。
目次
オンデューティ指定
前回はモータの回転を駆動するドライバのハイサイドトランジスタのPWMオンデューティを指定して制御しました。
この方法では以下のようにモータの負荷によって回転速度は変わってしまいます。
オンデューティ指定での制御だと
負荷が変わると回転速度も変わる#ブラシレスモータ駆動への道 pic.twitter.com/XvCFaNieqR— HomeMadeGarbage (@H0meMadeGarbage) April 28, 2022
そこでここではモータ回転速度を直接指定してのモータ制御を目指します。
またせっかくESP32を使用しているのでBLEで回転速度や正転・逆転切り替えができるようにしました。
せっかくESP32使っているのでBLEで無線で
正転/逆転、回転速度をおいじり相変わらず回転速度はドライバのハイサイド オンデューティ指定なので
回転速度直接指定できるようになりたい#ブラシレスモータ駆動への道 pic.twitter.com/QnD98Ucsxj— HomeMadeGarbage (@H0meMadeGarbage) April 27, 2022
最新版のBlynkではBLEが使用できないので、以前のバージョンのBlynkレガシーを使用してBLE通信しています。
回転速度指定
回転速度を指定して実際の回転速度と比較してドライバのオンデューティを制御します。
回転速度には以下の誘起電圧から検知される各モータ位置ステートの平均時間を用いました。
回転速度からオンデューティの算出には以下の書籍の5.5.11 回転数制御の節のPI制御の原理を参考にいたしました。
以下でオンデューティ$D_{ON}$を定め、係数$K_P, K_I$を動作させながら調整しました。
$$D_{ON} = K_P × (実測回転速度 – 指定回転速度) + K_I × \sum{(実測回転速度 – 指定回転速度) }$$
動作
BLEで回転速度を指定して、モータを回転させています。
負荷を与えてもドライバのオンデューティを変えることで回転速度を保っています。
回転速度指定実装
PI制御で指定回転速度に追従するべくオンデューティ決定
負荷がかかっても回転速度を保つように動作#ブラシレスモータ駆動への道 pic.twitter.com/tLBoGc2EZk
— HomeMadeGarbage (@H0meMadeGarbage) April 28, 2022
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 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 |
#define BLYNK_PRINT Serial #define BLYNK_USE_DIRECT_CONNECT #include <BlynkSimpleEsp32_BLE.h> #include <BLEDevice.h> #include <BLEServer.h> char auth[] = "トークン"; #define Bottun 39 #define uHin 25 #define uLin 5 #define vHin 26 #define vLin 17 #define wHin 27 #define wLin 16 #define Vu 34 #define Vv 35 #define Vw 32 #define Vn 33 #define StateVar 14 #define StateOn 12 #define vol 13 int uPWMCH = 0; int vPWMCH = 1; int wPWMCH = 2; int State = 0, StateOld = 0, IniOK = 0; int span = 10; int vVu = 0; int vVv = 0; int vVw = 0; int vVn = 0; int U = 0; int V = 0; int W = 0; int BottunState = 0; unsigned long oldTime = 0, nowTime; unsigned long rotTime[6] = {0,}; float rotTimeAve; int volPWM; int Kp = 2.5, Ki = 1.0; float rotSpeed = 1.1; float diffP, diffI = 0.0; //Core0 void rotPosition(void *pvParameters) { while(IniOK == 0){ //初期設定待ち delay(1); } nowTime = micros(); for (;;){ Blynk.run(); disableCore0WDT(); vVu = analogRead(Vu); vVv = analogRead(Vv); vVw = analogRead(Vw); vVn = analogRead(Vn); if(vVu >= vVn){ U = 1; }else{ U = 0; } if(vVv >= vVn){ V = 1; }else{ V = 0; } if(vVw >= vVn){ W = 1; }else{ W = 0; } if(U == 1 && V == 0 && W == 1){ if(BottunState){ State = 1; }else{ State = 6; } }else if(U == 1 && V == 0 && W == 0){ if(BottunState){ State = 2; }else{ State = 1; } }else if(U == 1 && V == 1 && W == 0){ if(BottunState){ State = 3; }else{ State = 2; } }else if(U == 0 && V == 1 && W == 0){ if(BottunState){ State = 4; }else{ State = 3; } }else if(U == 0 && V == 1 && W == 1){ if(BottunState){ State = 5; }else{ State = 4; } }else if(U == 0 && V == 0 && W == 1){ if(BottunState){ State = 6; }else{ State = 5; } }else{ //State = 0; } /* Serial.print(U); Serial.print(", "); Serial.print(V); Serial.print(", "); Serial.print(W); Serial.print(", "); Serial.print(State); */ if(StateOld != State){ nowTime = micros(); rotTime[State - 1] = nowTime - oldTime; oldTime = nowTime; StateOld = State; diffP = rotTimeAve / 1000.0 - rotSpeed; diffI += diffP; volPWM = int(Kp * 1000.0 * diffP + Ki * 100 * diffI); if(volPWM < 200) volPWM = 200; if(volPWM > 1023) volPWM = 1023; digitalWrite(StateVar, HIGH); } rotTimeAve = (rotTime[0] + rotTime[1] + rotTime[2] + rotTime[3] + rotTime[4] + rotTime[5]) / 6.0; //Serial.print(", "); } } //ヴァーチャルピンデータ受信 BLYNK_WRITE(V0) { BottunState = param.asInt(); } BLYNK_WRITE(V1) { volPWM = param.asInt(); } BLYNK_WRITE(V2) { Kp = param.asFloat(); } BLYNK_WRITE(V4) { Ki = param.asFloat(); } BLYNK_WRITE(V3) { rotSpeed = param.asFloat() / 100.0; } BLYNK_WRITE(V5) { int Reset = param.asInt(); if(Reset){ diffI = 0.0; } } void setup() { Serial.begin(115200); Blynk.setDeviceName("motor"); Blynk.begin(auth); pinMode(Bottun, INPUT); pinMode(uLin, OUTPUT); pinMode(vLin, OUTPUT); pinMode(wLin, OUTPUT); digitalWrite(uLin, LOW); digitalWrite(vLin, LOW); digitalWrite(wLin, LOW); pinMode(StateVar, OUTPUT); digitalWrite(StateVar, LOW); attachInterrupt(StateOn, rot, RISING); 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); //analogSetAttenuation(ADC_0db); //回転位置検出 タスク xTaskCreatePinnedToCore( rotPosition , "rotPosition" // A name just for humans , 4096 // This stack size can be checked & adjusted by reading the Stack Highwater , NULL , 1 // Priority, with 3 (configMAX_PRIORITIES - 1) being the highest, and 0 being the lowest. , NULL , 0); //State 5 ledcWrite(uPWMCH, 0); digitalWrite(uLin, HIGH); ledcWrite(vPWMCH, 0); digitalWrite(vLin, LOW); ledcWrite(wPWMCH, 128); digitalWrite(wLin, LOW); delay(100); //State 6 ledcWrite(uPWMCH, 0); digitalWrite(uLin, LOW); ledcWrite(vPWMCH, 0); digitalWrite(vLin, HIGH); ledcWrite(wPWMCH, 128); digitalWrite(wLin, LOW); delay(100); IniOK = 1; } void loop() { } void rot(){ digitalWrite(StateVar, LOW); /* Serial.print(rotSpeed); Serial.print(", "); Serial.print(rotTimeAve / 1000.0); Serial.print(", "); Serial.println(volPWM); Serial.print(", "); Serial.print(diffP); Serial.print(", "); Serial.println(diffI); */ delay(int(rotTimeAve / 2.0)); if(State == 1){ ledcWrite(uPWMCH, volPWM); digitalWrite(uLin, LOW); ledcWrite(vPWMCH, 0); digitalWrite(vLin, HIGH); ledcWrite(wPWMCH, 0); digitalWrite(wLin, LOW); }else if(State == 2){ ledcWrite(uPWMCH, volPWM); digitalWrite(uLin, LOW); ledcWrite(vPWMCH, 0); digitalWrite(vLin, LOW); ledcWrite(wPWMCH, 0); digitalWrite(wLin, HIGH); }else if(State == 3){ ledcWrite(uPWMCH, 0); digitalWrite(uLin, LOW); ledcWrite(vPWMCH, volPWM); digitalWrite(vLin, LOW); ledcWrite(wPWMCH, 0); digitalWrite(wLin, HIGH); }else if(State == 4){ ledcWrite(uPWMCH, 0); digitalWrite(uLin, HIGH); ledcWrite(vPWMCH, volPWM); digitalWrite(vLin, LOW); ledcWrite(wPWMCH, 0); digitalWrite(wLin, LOW); }else if(State == 5){ ledcWrite(uPWMCH, 0); digitalWrite(uLin, HIGH); ledcWrite(vPWMCH, 0); digitalWrite(vLin, LOW); ledcWrite(wPWMCH, volPWM); digitalWrite(wLin, LOW); }else if(State == 6){ ledcWrite(uPWMCH, 0); digitalWrite(uLin, LOW); ledcWrite(vPWMCH, 0); digitalWrite(vLin, HIGH); ledcWrite(wPWMCH, volPWM); digitalWrite(wLin, LOW); } } |
前回のオンデューティ指定版と異なる点はBlynkレガシーによるBLE通信の導入と
回転速度からオンデューティを算出する機能です。
L. 149~155で指定回転速度 rotSpeedと実測回転速度 rotTimeAve を比較してPI制御でオンデューティvolPWM を算出しています。
おわりに
ここでは回転速度指定によるセンサレス クローズドループ矩形波制御が実現できました。
回転速度の正確性や応答性は別途評価用に外部エンコーダを導入して確認したいと考えております。
書籍で原理を学習し、実機を組んで原理に基づいてプログラミングすることでブラシレスモータについての理解がかなり深まりました。
今後は別の制御方法についても検証し理解をさらに深めたいと思います。