1.背景
昨今の某SNS上ではモータ制御沼に引きずり込む沢山の手が存在しており、無事に引きずり込まれました。結果としてBLモータのベクトル制御まで一通りできたので、堅実にベクトル制御を実装する手順を残すことにしました。
なお、モータの制御理論そのものは各種専門書がありますので、ここでは実際に実装する際に必要な理論式だけを掲載しています。
※導出の過程で躓いた部分については、別途記事に起こしてまとめるかもしれません。
これまでにもBLモータの回し方を解説した記事やサイトはたくさんありました。最近の記事では、@motorcontrolmanさんの記事などが有力です。
一方で、上記の記事を含めた多くの記事では、センサレス方式(120度駆動や正弦波駆動)が対象であり、センサード方式についてはホール素子を用いた記事が多少見受けられる程度でした。ホールセンサ式は角度検出の分解能が粗く、そのため、ベクトル制御の本流ではない部分で躓くといった課題がありました。
そこで、本記事では絶対位置検出器(アブソリュートエンコーダ)を利用することで、簡単にベクトル制御を実装し、ベクトル制御は難しくないことを布教周知することを目的としました。
本記事象は、電気回路やマイコンについての一通りの予備知識をお持ちの方を対象として、ベクトル制御を実装する上で特有の事項について実際の手順に基づき詳解します。
2.BLDCモータについて
本記事でBLモータ(ブラシレスモータ)と記述するモータは、PMモータ(Permanent Magnetic Motor)です。PMモータは永久磁石の配置構造によって、さらに表面磁石同期型モータ(SPMSM:Surface Permanent Magnetic Syncronous Motor)や埋込磁石同期型モータ(IPMSM:Interior Permanent Magnetic Synchronous Motor)などに分類されます。本書で対象とするモータはSPMSMとなります。モータの詳細は例えば参考文献[1]が非常にわかりやすいと思います。
3.環境
3.1.全体構成
全体構成は下図のようになります。具体的には、BLモータ、インバータボード、制御ボード、電流検出器、位置検出器によって構成されます。
3.2.BLモータ
本記事では、たまたまヤフオクで入手したモータ(SGMMJ-A3C2A21-E,安川電機)を使用します。BLモータとしては、ドローン等で使用するモータでもよいですが、極対数が多いモータですと電気角の検出分解能が低下するため、極対数の少ないモータを選ぶとよいと思います。また、使用するインバータボードが最大48V,1.4A出力であるため、おおよそ30~50Wくらいのモータを購入されるといいと思います。
ここで、BLモータを下図のようにモデル化して表記します。本モデルでは、ステータ(固定子)に電流が流入する方向を、電流の正方向として定義します。また、U相ステータ方向を電気角$\theta_e=0$として定義します。図ではコイルのみを記載しますが、実際には内部抵抗も存在します。
なお、BLモータの各相コイルは片側がすべてショートしている(図中では円になっている部分)ので、三相電流の和は0になります。
i_u+i_v+i_w=0
多くのBLモータは多極機(N極とS極の組が何個もある)ですので、実際には上図のような電気回路モデルが複数あって構成されます(参考文献[1]参照)。ベクトル制御を実装する上では、まずは、機械角(モータの軸が実際に回転した角度)を極対数で割ると電気角$\theta_e$を算出できることだけ把握しておけばよいです。
機械角\theta_m = \frac{電気角\theta_e }{極対数}
3.3.インバータ(IHM07M1)
インバータには、STマイクロエレクトロニクス社製IC L6230の評価ボードであるIHM07M1(同社製)を利用します。この評価ボードにはシャント抵抗を利用した電流検出機能が付属していますが、残念ながら電流検出タイミングに気を付ける必要があり使い勝手が悪いので、別途、電流検出器を用います。よって、本記事ではIHM07M1のジャンパーピンを図のように設定しす。また、インバータボードへ3.3Vを供給することを忘れると全く動作しなくなるのでご注意ください。
なお、詳細な回路図は、ST社が公開している本ボードのマニュアル(UM1943 User manual)で確認できます。
実際に使用するピンは下記の8本です。
端子名称 | ピン番号 |
---|---|
+3V3 | CN7 Pin16 |
GND | Gndならどこでもいい |
Enable CH1-6230(U相に対応) | CN7 Pin1 |
Enable CH2-6230(V相に対応) | CN7 Pin2 |
Enable CH3-6230(W相に対応) | CN7 Pin3 |
UH_PWM | CN10 Pin23 |
VH_PWM | CN10 Pin21 |
WH_PWM | CN10 Pin33 |
IHM07M1(L6230)は下図のように3つのハーフブリッジから構成されます。各相毎にPWM端子とEnable端子を持ちますが、特にEnable端子の取り扱いに注意が必要です。Enable端子の入力をHiとすると、PWM端子の入力に応じて上下どちらかのFETがOnします。つまり、Enable端子入力がHiの時は、常にモータ端子は電気的に電源またはGndに繋がっていることになります。これに対して、Enable端子の入力をLowにすると、モータ端子がどこにも繋がっていない状態、つまりハイインピーダンス状態にすることができます。
特に後述する120度矩形波駆動では、ハイインピーダンス状態が必要ですので、Enalbe端子への入力を制御することが重要となります。なお、Enalbe端子の入力がLowの時はPWM端子は動作に関係がないため、好きなように設定しておけばよいです。
なお、ベクトル制御では、三相への印加電圧を常に制御する必要がありますので、Enable端子入力は常にHiとして、PWM端子への入力によって印加電圧を制御してください(ベクトル制御ではハイイピーダンス状態は不要です)。
3.4.制御用ボード
今回は、制御用のマイコンとしてRenesas Electronics社製マイコン RX63Tを用いました。主なスペックは下記のとおりです。今回はインバータボードとIHM07M1を直接繋ぎ、またその他の部分とのインターフェースもコネクタ化するために下図の制御用ボードを作成しました。基板作成は必須ではないですが、デバッグを容易にするためにも作成を推奨します。
項目 | スペック |
---|---|
動作周波数 | 100[MHz] |
AD変換分解能 | 12[bit] |
SPI機能 | 2[ch] |
3.5.位置検出器
位置検出器として、AMS社製の磁気式エンコーダIC AS5048Aを用いました。本ICは14[bit/回転]と高分解能で絶対位置を検出でき、また、SPI接続によって高速に通信できる使いやすいICです。今回はSWITCHSCIENCEで販売されているモジュール基板を使いましたが、ICの周辺回路自体はパスコン(0.1[uF])だけですので、安く抑えたいorモータへの取り付けの都合で自作基板としたい方は制御ボードと一緒に基板を作成するとよいと思います。なお、今回は下図のようにモータの一方にエンコーダを取りつけましたが、片軸使用のモータの場合は、その軸に直接磁石を付けてあげればよいです。
このエンコーダは絶対位置検出式なので、電源On/Off等しても1回転以内の絶対位置を検出できるので、ベクトル制御で必須となるステータU相とロータ磁束との間の角度を直接敵に検出可能です。本ICに限りませんが、ベクトル制御にこれから挑まれる方はぜひ絶対位置検出タイプのエンコーダをご使用ください。色々と楽になります。
3.6.電流検出器
電流検出器として、LEM社製のクローズドループ式の電流センサLTS 6-npを用いました。具体的な回路図は下記に掲載します。本回路は、主にLTS6-NPの周辺回路と、ボルテージフォロワ、ローパスフィルタで構成されます。
このセンサは駆動電圧が5[V]であることに注意が必要です。一方で検出結果の出力範囲は2.5[V]±0.625[V]とぎりぎり3.3[V]系マイコンのAD変換で読み取れる範囲ですので、分圧等無しでマイコンに突っ込むことができます(非常に素晴らしいです)。
実際に作成した基板は下図のとおりです。2相分の電流を検出できれば、3相電流の和が0になることを利用して残りの1相の電流も検出できるので、2相分のみ実装しました。
4.センサレス120度駆動(強制転流)
BLモータの最も初歩的な駆動方式が強制転流によるセンサレス120度駆動です。センサレス120度駆動は、制御ボードとインバータボード、BLモータのみで実現できます。単純にセンサレス120度駆動と記載すると誘起電圧を用いてセンサレスで速度を検出し制御する方式と区別がつかなくなる可能性もありますが、本文では、強制転流により回転させることをセンサレス120度駆動と記載しました。
本駆動方式はフィードフォワードで動作します。そのため、本方式を実装することで以下2点に問題がないか確認できます。
- インバーターボードから意図した電圧を3相に印加することができるか
- モータの3相配線はあっているかを確認できます。
4.1.回転原理
我々がBLモータに対してできることは、たかだか、ステータ側コイル電流を流して(≒電圧を印加して)任意の磁界を作り出すことだけです。それだけでロータ(≒磁石)の回転を実現しなければなりません。
まず、各相について、U相にプラスの電流を、V相にマイナスの電流を、W相は電流が流れていない状況を考えてみます。これは、U相にプラス電圧をV相にマイナス電圧を与え、W相は開放(ハイインピーダンス状態)となるようにインバータボードへの入力を与えればよいです。ロータが停止した状態では各相の電流は内部抵抗のみに起因して決まり、また、発生する磁束は各コイルの電流に比例します。よって、U,V,W相のそれぞれが発生する磁界(W相は0なので記載なし)とそれを合成した次回は図の上段(左)となります。
このような合成磁界中にロータ(永久磁石)を置くと、図の上段(右)の位置で釣り合って静止します(厳密には、ロータの初期位置が図に対して180度回転した位置でも静止する可能性はありますが、そうそう起こりづらいことなので、割愛します)。
次に、U相にプラス電流を、W相にマイナス電流を、V相は開放となるように通電した場合を考えると、図の下段(左)のような合成磁界が発生します。よって、図の上段の状態に対してロータ(永久磁石)は、新たな磁界の位置に移動し、停止します。つまり、ロータ(永久磁石)は60度回転することになります。以上から、通電相を変えることで合成磁束ベクトルの向きを変更でき、それに伴ってロータ(永久磁石)が回転することがわかっていただけると思います。
改めてセンサレス120度駆動での全動作を図に示します。図のように通電状態を一定時間ごとに切り替えることで合成磁界を60度刻みで回転させ、それに伴ってロータを回転させることができます。なお、ここで各相の電圧が正の期間が120度で入れ替わるこから、本制御方式は120度駆動と呼ばれます。
図からもわかるように、センサレス120度駆動における回転速度は、各相を切り替えるタイミングによって決定され、各相電圧(電流)に依存しません。そのため、各状態毎の切り替えが早すぎると、ロータが追従できなくなり、一定以上の回転数を安定して実現するのは難しいです。
4.2.インバータボード出力電圧の制御
センサレス120度駆動では前述したように各相に電圧を与えますが、常にインバータボードの電源電圧をモータに印加すると、低速時に大きな電流が流れ、非常に発熱してしまいます。そこで、各相に印加する電圧を制御する必要があります。ここでは各相への印加電圧をインバータボードを経由して制御できるようにします。
電圧制御にはPWM制御を使用しますが、ここで各相電圧は正負の値をとる必要があります。そこで、電源電圧(24[V])に対して、12[V]を基準として±12[V]を取れるように、つまり、各相への印加電圧が0[V]のときにPWMのDutyが50[%]となるようにします。この際のPWMの様子を下図に示します。
電圧を出力する場合は、インバータボードの対応する相のEnable信号をHi(Enable)とします。Low(Disable)ではハイインピーダンスとなり、何も出力されません。ここでは、実際にインバータボード(IHM07M1)のJ2コネクタ-Gnd間の電圧をオシロスコープやテスタなどで測定した際に、制御側で指令した電圧に応じて、各相のPWM Dutyが変化することを確認します。この時点ではモータは繋がなくても大丈夫です。
ここまででの確認項目は以下の2点となります。
- 三相から任意の電圧を出力できるか?(=任意のDutyのPWMを出力できるか?)
- Enable端子をLowにすることでハイイピーダンスになるか?(任意の相とGND間に適当な抵抗を挟んでそこを電流が流れるかテスターで計ればよいとです。ハイインピーダンス状態なら、電流は流れません)
なお、本記事では三相電流を直接検出するようにシステムを構成するので大丈夫ですが、インバータ部のローサイド側から電流を検出する方式(IHM07M1に付属の電流検出方式等)では、PWMのタイミングに合わせてAD変換を行う必要があることにご注意ください。
PWMのタイミングについてはこちらの記事で詳細に解説されていたりします。
4.3.実装
4.1.回転原理で説明したことを実装します。再記しますが、インバータボード(IHM07M1)は、Enable信号に従い各相の出力/ハイインピーダンスを決定します。そこで、4.2.で前述した図のように6状態を切り替える際は、各状態毎に通電したい二相のEnable端子をHi(Enable)とし、ハイインピーダンスとしたい一相はLow(Disable)としてください。
具体的には、図のフローチャートのように状態を切り替えます。センサレス120度駆動では、実装方法はポーリング方式でも、割り込み方式でも大丈夫です。各相の切り替え時間は数[msec]~数百[msec]程度で良いです(遅いとステッピングモータのようにカクカクと回るだけで、回らないということはありません。回らないとしたら別要因です)。
この時点でモータが回らない場合の原因はとして考えられうことは以下の3点です。
- 回転しないが振動したり音が鳴る場合は、Enable/Disalbeの切り替えができていない(ハイイピーダンスにできていない)
- うんともすんとも言わない場合は、インバータボードに3.3[V]を供給していない
- 音が鳴るが回転はしない場合はモータ印加電圧不足(Duty比を大きくするor電源電圧を上げる)
5.センサード120度駆動
センサード120度駆動はセンサレス方式に比べて脱調しづらいなどのメリットがあります。また、センサード120度駆動を実装することで、ベクトル制御の実装に必須である位置検出器を正しく実装できたかや、位置検出器の位置合わせ(電気角0度をステータのU相方向と一致させる)をできたかを確認できます。
5.1.回転原理
回転原理はセンサレス120度駆動と同様です。ただし、センサード120度駆動では、ロータ位置がわかるため、ある程度トルク発生効率の良い範囲、具体的にはロータ側磁束とステータ側磁束が直行する範囲で6ステップの状態を遷移することができます。
フレミングの左手の法則から、ロータに起因する磁界と固定子に起因する磁界が直行する際に、最も回転トルクを発生します。よって、センサード120度駆動では、ロータ(永久磁石)の磁束と直行する方向にステータ側で合成磁束を生成することが望ましいです。ただし、120度駆動では、ステータは60度刻みでしか合成磁束を作れないため、ロータ角度に直交するうちの±30度の範囲毎に磁束を与えることで制御します。下記の図は、各ロータ状態毎にどの磁束状態(①~⑥)を与えるかを示したものです。図のように電気角の60度毎に領域を分割し、それにおおよそ直行する方向に合成磁束を作り出すことでモータを回転させます。
センサード駆動ですので、ロータの位置に併せて合成磁束は切り替わります。印加する電圧を高くすると、流れる電流が増加し結果的に磁束も強まるので、ロータが各状態を遷移(例えば状態①→②)する時間も短くなります(=回転数が高くなります)。よって、センサード120度駆動では、印加電圧を高くすることで回転速度を上げることができます。そのため、外部にボリュームなどを付けたり、内部で一定時間ごとに指令電圧を変えるなどしたりすると速度を可変することもできます。この状態で速度制御器や位置制御器を組めば、速度や位置の制御もできます。
なお、センサレス120度駆動(強制転流)では、磁束の状態遷移が早くなっても、磁束の状態を切り替える(例えば状態①→②)までの時間は一定にするので回転速度は変化しません。
5.2.位置検出器の位置合わせ(原点設定)
位置検出結果に基づいて状態を切り替えるといっても、ロータ側の電気角(=機械角÷極対数)を検出することが必要です。今回使用した位置検出器は1回転以内の絶対位置を検出できますが、残念ながら電気角=0度がどこに対応するかはわかりません。そこで、センサレス120度駆動で回転させた際の角度と磁束の状態を基に、電気角=0度の位置を測定します。
具体的には、センサレス120度駆動では、各状態ごとにロータ位置が停止することを利用し、極低速時(磁束の状態を数[sec]程度で切り替えるようなカクカクとした回転)の位置検出値と対応する磁束の状態(①~⑥)をロギングします。ログは例えばシリアル通信で磁束の状態(①~⑥)と位置検出値を送る方法等々がありますが割愛します。
実際のログは以下のようになりました。
状態①~⑥の遷移(電気角1回転)が3回で位置検出値(=角度=機械角)が1周していることがわかります。よってこのモータは極対数3のモータと考えられます。
位置検出値の補正は2段階で行います。初めに回転方向を合わせ、次にオフセット量を補正します。
初めに回転方向を合わせこみます。120度センサレス駆動の動作原理で示したように状態遷移(①~⑥)をした場合、位置検出値は増加する方向となるはずです(なると楽です)。そこで、**回転方向があっていない場合(位置検出値が減少方向に移動した場合)は、モータの三相配線のうち2相を入れ替えて回転方向を逆にします(どの二相を入れ替えてもいいです)。**ここで、回転方向を修正した場合は、再度ログを取り直してください。
次に、ステータ側U相との位置関係を、位置検出値のオフセット量として補正します。極低速時には磁束が状態④と⑤の中間でロータ磁束とU相方向とが一致しますので、状態④と⑤の真ん中の角度がU相方向と考えられます。そこで、状態④と状態⑤の時の角度の真ん中の値を位置検出値のオフセット量とし補正します。具的には下記の計算式で位置検出値(補正後)を計算します。
位置検出値(補正後)=mod(位置検出値(生値)-オフセット量,位置検出器の分解能)
上記のログでは、位置検出値のオフセット量は、3439となります。補正後に再度ログをとった結果が図のようになります。また、電気角も併記しました。
電気角は、機械角を極対数で割った余りになるので、電気角の範囲は0~5460(=位置検出器分解能÷極対数)です。図からは少しわかりづらいですが、状態④と⑤の中間で電気角がゼロクロスしていることが推察できます。ここまで出来ればセンサード120度駆動の実装まであと一歩です。他方、ここをおろそかにするとベクトル制御の際に詰まりますのでご注意ください。
ここまでの確認項目は以下になります。
- 回転方向は回転角度が増加する方向か?
- 状態④と⑤の間で電気角がゼロクロスしているか?
5.3.実装
回転原理のところで記述したように、電気角を6等分し、その範囲毎に対応したステータ磁束(状態①~⑥)を出力すればよいです。センサード120度駆動もポーリングで実装はできますが、ベクトル制御を見据えて割り込みで実装することを推奨します。なお、割り込み周期は計算時間の都合から10[kHz]としました。位置検出器からの読み込みは、割り込みの先頭で行いましたが、それでもベクトル制御まではできました。なお、具体的なロータ角度とそれに対応する磁束の状態は以下の表のようになります。
ロータ角度[度] | 電気角(補正後位置検出値) | 設定する磁束の状態 |
---|---|---|
210~270 | 3185~4095 | ①UH->VL |
270~330 | 4096~5005 | ②UH->WL |
330~30 | 5005~5460,0~455 | ③VH->WL |
30~90 | 455~1365 | ④VH->UL |
90~150 | 1366~2275 | ⑤WH->UL |
150~210 | 2276~3185 | ⑥WH-VL |
また、駆動部のコードのイメージは下記の通りで、電気角に応じて磁束の状態を決定しています。ここで、各関数(Out_WH2VL();など)は、2相を選択し電圧を印加する関数です。例えば、Out_WH2VL();は、W相に正電圧をV相に負電圧を印加し、U相はハイインピーダンスとする関数です**(ハイインピーダンスとすることを忘れないように)**。
//6ステップ駆動 with 位置検出器
if( (2275) <= current_angle_elec && current_angle_elec < (3185) ){
//WH-VL
Out_WH2VL();
}else if( (3185) <= current_angle_elec && current_angle_elec < (4095) ){
//UH-VL
Out_UH2VL();
}else if( (4095) <= current_angle_elec && current_angle_elec < (5006) ){
//UH-WL
Out_UH2WL();
//下のif文1つだけ判定条件が異なることに注意
}else if( (5006) <= current_angle_elec || current_angle_elec < (455) ){
//VH-WL
Out_VH2WL();
}else if( (455) <= current_angle_elec && current_angle_elec < (1365) ){
//VH-UL
Out_VH2UL();
}else{
//WH-UL
Out_WH2UL();
}
なお、システム構成図には記していないですが、割込み開始時に適当な端子からLEDを点灯し、割込み終了時にLEDを消灯する等で割込み内部の処理時間を計測することを推奨します(オシロスコープ必須)。当初は制御周期20[kHz]としていたのですが、処理に60[μsec]程度かかりおかしな動作を起こしました。
6.ベクトル制御
6.1.回転原理
詳細な理論説明は参考文献[2]を参照ください。ここでは、dq軸座標系に変換することで以下のメリットがあることを把握していただければ良いと思います。
- トルク発生効率がよい(センサード120度駆動の時は±30度の範囲でロータ磁束とステータ磁束が交差していたのに対して、ベクトル制御では常に直交させることができます)。
- q軸電流$i_q$のみがトルクを発生し、d軸電流$i_d$は発生トルクに寄与しないこと
- $V_d,V_q$を直流として$i_d,i_q$を制御できます。
特に3つ目について追記します。3相印加電圧でBLモータを回すためには、三相交流が必要です。しかし、定常偏差なく$V_u,V_v,V_w$を三相交流状に制御しようとすると、内部モデル原理から、制御器の分母に$s^2+\omega^2$の項が必要になり煩雑です。それに対して、$V_d,V_q$は直流として制御すればよいので、制御器には積分項$\frac{1}{s}$があればよくPI制御器で定常偏差なく制御できます
実装上必要になるのは、BLモータのdq軸座標での回路方程式と、三相電流検出値$i_u,i_v,i_w$からdq軸の電流値$i_d,i_q$への変換式、dq軸電圧指令値$V_d,V_q$から三相電圧指令値$V_u,V_v,V_w$への変換式だけです。これら3つだけ記載しておきます。なお、途中で、$\alpha\beta$座標系を挟んでいますが、詳細は各種参考文献をどうぞ。
dq座標での回路方程式\\
\begin{bmatrix} V_d \\ V_q \end{bmatrix}
=
\begin{bmatrix} R & -L\omega_r \\ L \omega_r & R \end{bmatrix}
\begin{bmatrix} i_d \\ i_q \end{bmatrix}
+L\frac{d}{dt}
\begin{bmatrix} i_d \\ i_q \end{bmatrix}
+
\begin{bmatrix} 0 \\ \sqrt\frac{3}{2}K_e \omega_r \end{bmatrix}\\
R:相抵抗[\Omega],L:相インダクタンス[H],\omega_r:ロータ角速度[rad/s],K_e:逆起電力定数[V/(rad/s)]
電流検出値i_u,i_v,i_wからi_d,i_qの変換式(電力等価変換=絶対変換)\\
\begin{bmatrix} i_\alpha \\ i_\beta \end{bmatrix}
=\sqrt\frac{3}{2}
\begin{bmatrix} 1 & -\frac{1}{2} & -\frac{1}{2} \\ 0 & \frac{\sqrt3}{2} & -\frac{\sqrt3}{2}\end{bmatrix}
\begin{bmatrix} i_u \\ i_v \\ i_w \end{bmatrix}
\\
\begin{bmatrix} i_d \\ i_q \end{bmatrix}
=
\begin{bmatrix} cos\theta_e & sin\theta_e \\ -sin\theta_e & cos\theta_e \end{bmatrix}
\begin{bmatrix} i_\alpha \\ i_\beta \end{bmatrix}
dq軸電圧V_d,V_qから三相電圧V_u,V_v,V_wへの変換式(電力等価変換=絶対変換)\\
\begin{bmatrix} V_\alpha \\ V_\beta \end{bmatrix}
=
\begin{bmatrix} cos\theta_e & -sin\theta_e \\ sin\theta_e & cos\theta_e \end{bmatrix}
\begin{bmatrix} V_d \\ V_q \end{bmatrix}
\\
\begin{bmatrix} V_u \\ V_v \\ V_w \end{bmatrix}
=\sqrt\frac{2}{3}
\begin{bmatrix} 1 & 0\\ -\frac{1}{2} & \frac{\sqrt3}{2} \\ -\frac{1}{2} &-\frac{\sqrt3}{2}\end{bmatrix}
\begin{bmatrix} V_\alpha \\ V_\beta \end{bmatrix}
6.2.dq軸電圧一定制御
dq座標系でのBLモータの回路方程式を眺めてみると、dq軸電圧一定($V_d=0,V_q=非零$)にするとモータが回ることがわかります。
最終的には、電流検出結果を利用してdq軸電流を個別に制御しますが、うまく回らなかった際に、位置検出器が悪いのか、電流検出器が悪いのか区別がつきません。そこで、まずはdq軸電圧一定にしてモータを回します。その後、改めてdq軸電流制御を取り入れます。
実際にまわす際の処理コードは以下の通りです(フローチャート化が面倒でした、許してください)。120度駆動と異なり、3相すべてに常に電圧を印加しますので、Enable端子は常時Hi(Enable)としてくださいこの際のdq軸電流をロギングした結果も図に示しますが、d軸電流に比べてq軸電流がたくさん流れていることがわかります(d軸電圧0、q軸電圧を一定時間ごとにステップ状に可変しました)。
volatile uint16_t ad_result[16];
extern "C" void Mtu4IntFunc_V(){
/*----ベクトル制御用変数----*/
float curr_u,curr_v,curr_w; //uvw相電流[A]
float curr_alpha,curr_beta; //Iα,Iβ電流[A]
float curr_d,curr_q; //Id,Iq電流[A]
volatile float vol_u,vol_v,vol_w; //uvw相電圧[V]
volatile float vol_alpha, vol_beta; //Vα,Vβ[v]
volatile float vol_d,vol_q; //Vd,Vq[V]
float THdc; //電気角[rad]
float SIN0 ; //sin(電気角)
float COS0; //cos(電気角)
//処理時間計測用LED
R_PG_IO_PORT_Write_P70(1);
/*-----------------位置検出器関連処理-----------------*/
//エンコーダ読み込み
//SPI通信
R_PG_RSPI_TransferAllData_C0(tx_data,rx_data,1);
//エンコーダ パリティチェック
uint32_t data=rx_data[0];
count_one = 0;
for(int i=0;i<16;++i){
if((data & 0x01) == 1){
count_one++;
}
data = data >> 1;
}
count_one = count_one % 2;
if(count_one == 0){
uint16_t temp_angle;
if( (rx_data[0] & 0x4000) != 0){
temp_angle= rx_data[0] & 0x3fff;
//受信?エラー EF
err_cnt_EF++;
}else{
temp_angle = rx_data[0] & 0x3fff;
}
//機械角オフセット補正
if(temp_angle >= kOffsetMech ){
current_angle_mech = temp_angle - kOffsetMech;
}else{
current_angle_mech = 16383- (kOffsetMech - temp_angle);
}
//電気角の算出
current_angle_elec = current_angle_mech % 5461;
}else{
//エンコーダ通信のパリティエラー時
err_cnt_parity++;
}
/*-----------------制御-----------------*/
//電気角を位置検出値から物理量[rad]に変換し、対応するsin,cosを計算する
//THdc = 2*3.1415926353 *((float)current_angle_elec / 5461); 処理速度のため下記に数値変換
THdc = 0.001150555 * (float)current_angle_elec;
SIN0 = sinf(THdc);
COS0 = cosf(THdc);
//dq軸電圧の計算(d軸電圧0,q軸電圧=3[V]なので、以下のように設定)
//dq軸電流制御をする場合は等はここに順次コードを追加します。
vol_d=0;
vol_q=3;
//dq軸電圧から三相電圧への逆変換
//dq -> αβ
vol_alpha = vol_d * COS0 - vol_q *SIN0;
vol_beta = vol_d * SIN0 + vol_q * COS0;
//αβ -> UVW
vol_u = 0.81649658 * vol_alpha; //ルート(2/3)×Vα
vol_v = -0.40824829 * vol_alpha + 0.707106781 * vol_beta;//-1/ルート(6) × Vα + 1/ルート(2) ×Vβ
vol_w = -0.40824829 * vol_alpha - 0.707106781 * vol_beta;//-1/ルート(6) × Vα - 1/ルート(2) ×Vβ
/*-----------------ここまで制御-----------------*/
//モータ出力レジスタ値計算
//出力電圧のクランプ
//PWMレジスタへのセットしてみる(バッファレジスタに入れてる&タイミングとか特に考えていない)
vol_u = 4999 - (vol_u + 12.0) * 2498/24;
if(vol_u < 1){vol_u = 1;
}else if(vol_u > 4999){
4999;
}
vol_v = 4999 - (vol_v + 12.0) * 2498/24;
if(vol_v < 1){vol_v = 1;
}else if(vol_v > 4999){
4999;
}
vol_w = 4999 - (vol_w + 12.0) * 2498/24;
if(vol_w < 1){vol_w = 1;
}else if(vol_w > 4999){
4999;
}
//PWM用レジスタへの設定
R_PG_Timer_SetTGR_D_MTU_U0_C3((uint16_t)vol_u); //U
R_PG_Timer_SetTGR_C_MTU_U0_C4((uint16_t)vol_v); //V
R_PG_Timer_SetTGR_D_MTU_U0_C4((uint16_t)vol_w); //W
//処理時間計測用LED
R_PG_IO_PORT_Write_P70(0);
}
なお、q軸電圧一定、d軸電圧0でも回転することもありますが、私は理由がわかってない(理論上は回らないはず)ので、気になった方は調べて記事を起こしてくれると嬉しいです。
ここでの確認項目は以下の通りです。
- q軸電圧一定で回るか
6.3.電流検出値の確認
電流検出器が正しく実装できているかを確認します。U相にプラス電圧をV相にマイナス電圧を印加し、W相をハイインピーダンスとして、その際のU相電流をテスタで計測します(W相ハイイピーダンスにすることで、U相に正の電流がV相に負の電流が、同じ絶対値で流れるはずです)。計測結果を、制御ボードのマイコン側の結果と比較します。
まず、電流検出の符号(向き)が反対だった場合は、電流検出器のモータとインバータの配線を入れ替えて電流検出の向きを逆にします。次に、U,V相で電流値が等しくなかった場合は(最初は、まず間違いなく等しくないですが)、電流を何も流さない状態(0[A])のAD変換結果をロギングして、各電流センサごとにオフセット補正します。
ここまでできたら、電流検出器の設定もOKです。なお筆者は電流検出器自体の電源を入れ忘れ(マイコンと別系統にしていたため)、電流が検出されないとうなっていたことが何度かあります。
ここでの確認項目は以下となります。
- モータ静止時にマイコンの電流検出結果とテスタの計測結果が一致するか?(10~20[mA]くらいの誤差は問題ないと思います)
6.4.ベクトル制御(dq軸電流制御)
やってきましたベクトル制御。ここでは、dq軸電圧を一定値として与えていました。それに対して、ベクトル制御では、dq軸電圧を操作量として、dq軸電流を制御します。そのためには、6.2.に対して、電流検出結果のdq座標系への変換と、dq座標上でのdq軸それぞれでの電流フィードバック制御を実装します。
三相電流から二相電流への変換は理論式に従って計算するだけです。dq座標への変換の結果、dq軸電流をそれぞれdq軸電圧でPI制御するだけですので簡単に実装できます。PIパラメタは、本来ならモータ定数(内部の抵抗値などなど)から決定すべきですが、とりあえずは試行錯誤でやります。なお、私はIゲイン多めの方が良く制御できました。
6.2.で使用したソースコードに対して、制御部分の変更後を下記に記載します。
/*-----------------ベクトル制御-----------------*/
//dq軸電流制御用変数
float err_d;
static float err_d_int = 0;
float err_q;
static float err_q_int = 0;
//AD変換結果の読み込み(エンコーダ読み込み後なら変換完了していると思う
R_PG_ADC_12_GetResult_S12AD0((uint16_t*)ad_result);
//ADC結果→3相電流[A]変換 (高速化のため定数部は事前に計算しておく
curr_u = ((float)ad_result[0] - 3165 )* (0.002578125);//(3.3/4096) * (2.0 /0.625);
curr_v = ((float)ad_result[1] - 3179 )* (0.002578125);
curr_w = -curr_u -curr_v;
//UVW -> αβ
curr_alpha = 0.8169496580928 * (curr_u - 0.5 * (curr_v + curr_w) );
curr_beta = 0.7071067811866 * (curr_v - curr_w);
//THdc = 2*3.1415926353 *((float)current_angle_elec / 5461); 処理速度のため下記に数値変換
THdc = 0.001150555 * (float)current_angle_elec;
SIN0 = sinf(THdc);
COS0 = cosf(THdc);
//αβγ -> dq
curr_d = curr_alpha * COS0 + curr_beta *SIN0;
curr_q = -curr_alpha * SIN0 + curr_beta * COS0;
//dq軸電流制御
err_d = 0.0 -curr_d;
err_d_int += err_d;
vol_d = 5 * err_d + 3e-2 * err_d_int;
err_q = ref_curr_q - curr_q;
err_q_int += err_q;
vol_q = 5 * err_q + 3e-2 * err_q_int;
ここでの注意点は、制御器を調整する際は、dq軸電流のステップ応答を確認しながら調整することです。調整に際してはq軸電流は一定時間ごとにステップ状(0.4→0.6→0.4など)にしてください。ステップ応答がないと制御器の性能がなかなか把握できません。また、調整の際はモータ軸に適当な負荷をかける必要があります(トルク一定制御になるので、負荷なしだと延々加速して脱調します)。~~適当に手で軸を抑えてあげましょう(やけど注意)。~~何か負荷を用意してください。
ここまでできていれば、もうベクトル制御の一番基礎はできました。あとは速度制御器なり位置制御器なり作ってあげて、煮るなり焼くなりご自由にどうぞ。
ここでの確認事項は以下になります。
- モータは回転したか?
- d軸電流を0近傍に、q軸電流を指令値に追従して制御できたか?
6.5.非干渉化の導入(回路パラメタの測定)
ベクトル制御の基本の最後として、非干渉化項を導入します(詳細は参考文献[2]辺りをどうぞ)。この際に厄介なことは、非干渉化をするためにモータパラメタ、具体的には内部抵抗R、内部インダクタンスL、逆起電力$K_e$が必要になることです。そこで各パラメタを測定します。
まず、内部抵抗Rは任意の相間の抵抗値をテスタで測定します。一応出力軸の位置を変えて測定し、その平均値を採用します。実際の測定結果は以下のとおりで、平均値は1.59[Ω]です。よって、1相当たりの抵抗値はその半分の0.79[Ω]となります。
| 機械角[deg] | 相間抵抗[Ω] |
|---|---|---|
| 0 | 1.8 |
| 45| 1.6 |
| 90| 1.5 |
| 135| 1.6 |
| 180| 1.6 |
| 225| 1.5 |
| 270| 1.5 |
| 315| 1.6 |
内部インダクタンスLは、出力軸を固定した状態でq軸電流のステップ応答をとります。応答はdq軸座標系の回路方程式から、L,Rに起因する1次遅れになります(停止時は$\omega_r=0$のため)。内部抵抗Rが測定できていることから、Lを推定できます。
これも出力軸の位置を適当に変えて何個か取ることが理想的ですが、今回はとりあえず、1箇所で行いました。なお、下記のようにモータ出力軸をクランプして固定できるようなテストベンチを作成し、測定しました。
よって、時定数(定常値の約0.632倍までに要した時間)が0.7[msec]であり、相抵抗R=0.79[Ω]なので、$L=0.7×10^{-3} ×0.79\cong0.55[mH]$と測定できました。
最後に、逆起電力定数$K_e$を測定します。図のように別のモータを用意し、強制的に回転させます。すると、制御対象のBLモータの相間には逆起電力のみに起因して誘起電圧が正弦波状に発生します。そこで、この正弦波電圧の実行値(ピーク値のルート2分の1倍)を測定します(実際はピーク値を測定してルート2で割る)。これは回転数を可変して測定します。
実際に、外部から対象のBLモータを回転した際のU-V相の間の電圧波形は図のとおりです。オシロスコープのプローブのうち、GNDをV相に接続し、U相にプローブを当てました。多くのオシロスコープでは、Gndは内部で共通ですので、使うプローブは1本だけにしておきましょう。
回転数を可変して測定した結果を次の図に示します。また、図のように直線近似式の傾きから、逆起電力定数$K_e=0.022[V/(rad/s)]$と測定できました。
以上の結果をまとめると、今回のBLモータのパラメタは以下に示します。
|名称| 値|
|-==|==-|
|内部抵抗| 0.79[Ω]|
|内部インダクタンス | 0.55[mH] |
|逆起電力定数| 0.022[V/(rad/s)] |
よって、求めたパラメタを基に、非干渉化項を導入した制御器を実装します。実装結果のコードのうち非干渉化項の部分だけ以下に掲載します。。
//dq軸電流制御
err_d = 0.0 -curr_d;
err_d_int += err_d;
vol_d = 5 * err_d + 3e-2 * err_d_int;
err_q = ref_curr_q - curr_q;
err_q_int += err_q;
vol_q = 5 * err_q + 3e-2 * err_q_int;
//ここまで同一
const float mtr_R = 0.79,mtr_L = 0.55e-3,mtr_Ke=0.022; //相間抵抗(制御上は使用しない)、相間インダクタンス、逆起電力定数
float v_od,v_oq; //V_od,V_oq 非干渉化項[V]
//非干渉化項の計算
v_od = -EncMtr.GetVel() * mtr_L * curr_q;
v_oq = EncMtr.GetVel() * (mtr_L * curr_d + mtr_Ke);
vol_d += v_od;
vol_q += v_oq;
ここでの確認事項は以下の通りです。
- ベクトル制御を完全に理解したか
また、ここまで合わせてモータを回した結果の動画は以下の通りです。
7.おわりに
モータを回すために最も重要なことは、どれだけお金を注ぎ込むかです。最初からセンサレスで安価に実現しようと考えても、どんどん時間だけが浪費されていきます。とにかくいいモータやオシロスコープ、エンコーダ等々お金で押し切りましょう。センサレスとかそのあとで十分です。
本記事によって、一人でも多くの方が モータ沼に沈んで モータ制御の魅力に気づいていただけたら幸いです。
※質問・指摘事項等々ありましたらお気軽にコメントください。
参考文献
[1]史上最強カラー図解 最新版 モータ技術のすべてがわかる本
色々な種類のモータの構造や動作原理について解説があります。全頁カラーで大変見やすいです。
[2]ACドライブシステムのセンサレスベクトル制御
タイトルにセンサレスとありますが、センサありの理論を詳細に説明したうえで、センサレスに拡張しています。センサあり/なしを問わずベクトル制御理論の入門として、私には最もわかりやすかったです
[3]省エネモータードライブシステムの基礎と設計法
モータパラメータを測定する方法について解説があります
[4]高トルク&高速応答! センサレス・モータ制御技術
実装上の多くの説明は本誌に基づいている気がします。