36
23

Delete article

Deleted articles cannot be recovered.

Draft of this article would be also deleted.

Are you sure you want to delete this article?

More than 3 years have passed since last update.

Arduino Dueに3相同期・三角波・相補PWMを打たせる

Last updated at Posted at 2021-06-20

はじめに

本記事はMATLAB Expo2021 LTでの発表「MATLAB Homeでのモータ制御MBD開発に向けた“脱獄指南書”」の解説をシリーズ化したものの最初の記事となります。
シリーズ構成案は下記。(完了時期:未定)

①Arduino Dueに3相同期・三角波・相補PWMを打たせる
②Arduino DueでPWM山同期AD変換を行う
番外編 実質無料! Tiの3相GaNインバータの使い方
③Arduino Dueの2ch DACを利用する
④MATLAB/SimulinkでArduinoのレジスタを叩く
⑤MATLAB/SimulinkとArduino DueでPWM同期の制御を実現する

今回使用するArduino Dueですが、FPU=浮動小数点演算ユニットを持たないためMATLAB/Simulnkと連携させない限りモータ制御用に使用する旨味はあまり無いです。というか辛いのでオススメしません。
(逆に言うと連携させた環境は大変具合が良いです。個人的感想ですが)
なのでMATLAB/Simulinkを購入するアテの無い方は、その点留意して読んで頂けると幸いです。

下記、スピード重視で書きつつ躓きを割ける目的で割と懇切丁寧に書いていたりします。
このため、表題の「Arduino Dueに3相同期・三角波・相補PWMを打たせる」だけの情報が欲しい人は ぶっとばして 4. Arduino Dueでの設定方法から読んで頂ければと思います。

1.PWMの仕組みと種類(のこぎり波・三角波)

PWMは搬送波(キャリアとも呼ぶ)と、出力信号の大きさを規定する値(以降Duty指令と呼ぶ)を比較することで出力調整を実現します。
image.png

搬送波の種類としてはのこぎり波と三角波があります。
いずれもマイコンの1クロックごとに1加算もしく減算することで搬送波が作られます。
image.png

モータ制御用途に限って言えば、マイコンの機能として三角波が利用可能である場合は三角波を用いることが好ましいです。理由は2にて説明を実施します。

2.モータ制御にて3相同期・三角波が必要な理由

3相交流モータの制御においては、インバータより出力される3相の電圧を操作する必要があります。このため搬送波、Duty指令についてはそれぞれ3つ必要となりますが、搬送波については3相が同期している(あるいは3相で同じ値を用いる)必要があります。
image.png

なぜ同期が必要かと言うと、理由は様々ですがその1つとして搬送波の頂点(山)で出力が全OFF、底辺(谷)で全ONとなる特性を得るために必要となります。
image.png

この特性がなぜ必要かというとモータの電流検出を(可能な限り)ノイズを回避した状態にて行うためとなります。

ここでいきなり電流が出てきてしまいましたが、本記事はベクトル制御やセンサレスベクトル制御を行う場合を想定しており、これらには電流検出が必要不可欠となります。(強制転流のような電流検出不要な制御もあります)

電流検出した結果がクソノイズまみれの場合、ベクトル制御やセンサレスベクトル制御を行うことはノイズ沼の中で華麗なダンスを踊ることを強いられるという苦行が待っているので、可能な限り電流検出はノイズを回避する必要があります。

ノイズの発生源は色々ありますが、代表的に下記2つがあります。
搬送波を3相同期、三角波にすることでその両方を回避することが出来ます。
①スイッチング素子のON/OFFによって発生するノイズ
②検出タイミングが不均一化することによって発生するノイズ

ところで、のこぎり波の場合はどうなるかと言うと上記①の回避が困難になります
image.png

搬送波を3角波とすることで頂点もしく底辺が、3相のDuty指令によらずON時およびOFF時から最も遠いタイミングとなります。このためモータ制御における搬送波は3相同期、三角波が原則として必要であり、マイコン立ち上げの場合は最初に行うべき設定となります。

3.相補PWMとは

上記の通り、搬送波とDuty指令値の関係によってマイコンからの出力波を操作することが可能ですが、インバータからの出力波を操作するには2つのスイッチング素子のON/OFFを操作する必要があります。
image.png
上記の通り、インバータ出力ONを得るには上側のSW素子をON、下側のSW素子をOFFとする必要があります。インバータ出力OFFの場合はこの逆となります。

このように、上側SW素子と下側SW素子の関係はON/OFFが逆の関係となります。この関係を相補と呼び、上下SWを相補とするPWMを相補PWMと呼びます。
image.png

相補PWMについて、実現方法は下記の2通りがあります。
①インバータ回路に相補PWM機能を持たせる
②マイコンに相補PWM機能を持たせる

例として、STのモータ制御開発キットに使われているL6230は①にて実現されており、Tiの3相GANインバータは②にて実現する必要があります。

見分け方として、インバータ入力ピンに「U相入力H,U相入力L」のようにHigh/Lowのピンがある場合は②となります。逆に「U相入力」のみの場合は①となります。

①はメリットとして、マイコンとインバータの配線数を少なくすることが出来ます。またデッドタイム(下図参照)がインバータ側にて設定されているため、パワエレ初心者でも扱いやすい特徴があります。ただしデッドタイムが任意に設定できない点がデメリットとなります。
image.png

一方で②ですが、メリデメは①の裏返しとなります。デッドタイムをユーザー側が好きなように設定できますが、デッドタイムの設定を間違えるとインバータを破壊しえます。

個人的な考えとしては、初心者は①でモータ制御を初めて、慣れてきたら②に乗り換えるのがよいと考えています。(まあ、慣れてても設定ミスとかで②のインバータ壊したりするのがザラですが…。ケガだけはしないようにしましょう)

4.Arduino Dueでの設定方法

前置きが長くなりましたが、Arduino Dueのコード例としては下記になります。
本シリーズの次回タイトル「②Arduino DueでPWM山同期AD変換を行う」に向けた設定も一部含んでいますがあまり気にしないで下さい。

//3相同期・三角波・相補PWMを打たせるための設定関数
void pwm3_setup(){
    uint16_t CounterPeriod;
    uint16_t DeadTime;
    
    //キャリア周波数10Hz、デッドタイム約1.2usの場合の設定
    CounterPeriod = 4200 - 1;
    DeadTime = 100;

    //PWM Power ON
    REG_PMC_PCER1=PMC_PCER1_PID36;
    
    //キャリア周波数の設定
    //PWM1~3を3相PWMとして使用。PWM0はPWM同期AD変換用(次回説明)
    REG_PWM_CPRD0 = CounterPeriod;
    REG_PWM_CPRD1 = CounterPeriod;
    REG_PWM_CPRD2 = CounterPeriod;
    REG_PWM_CPRD3 = CounterPeriod;
    
    //各相Duty指令の設定
    REG_PWM_CDTY1 = 2100;
    REG_PWM_CDTY2 = 2100;
    REG_PWM_CDTY3 = 2100;
    
    //デッドタイム有効化、プリスケーラ=0、三角波の設定
    REG_PWM_CMR0 = PWM_CMR_CALG | PWM_CMR_CPRE_MCK;
    REG_PWM_CMR1 = PWM_CMR_DTE | PWM_CMR_CALG | PWM_CMR_CPRE_MCK;
    REG_PWM_CMR2 = PWM_CMR_DTE | PWM_CMR_CALG | PWM_CMR_CPRE_MCK;
    REG_PWM_CMR3 = PWM_CMR_DTE | PWM_CMR_CALG | PWM_CMR_CPRE_MCK;
    
    //PWMHおよびPWMLのデッドタイム設定
    REG_PWM_DT1 = PWM_DT_DTH(DeadTime) | PWM_DT_DTL(DeadTime);
    REG_PWM_DT2 = PWM_DT_DTH(DeadTime) | PWM_DT_DTL(DeadTime);
    REG_PWM_DT3 = PWM_DT_DTH(DeadTime) | PWM_DT_DTL(DeadTime);
     
    //PIOのディセーブルレジスタ
    REG_PIOC_PDR = PIO_PDR_P9 | PIO_PDR_P8 | PIO_PDR_P7 | PIO_PDR_P6 | PIO_PDR_P5 | PIO_PDR_P4;
    //ペリフェラルABセレクタ
    REG_PIOC_ABSR |= PIO_ABSR_P9 | PIO_ABSR_P8 | PIO_ABSR_P7 | PIO_ABSR_P6 | PIO_ABSR_P5 | PIO_ABSR_P4;

    //AD変換のためのPWMイベントライン設定                                                             
    PWM->PWM_CMP[0].PWM_CMPM = PWM_CMPM_CEN;                       // PWM0の比較を有効化
    PWM->PWM_ELMR[1] = PWM_ELMR_CSEL0;                             // PWMイベントライン1にPWM0を設定
    PWM->PWM_CMP[0].PWM_CMPV = PWM_CMPV_CV(CounterPeriod - 10);  // PWM0のDUTYを設定
      
    // PWM0~3の開始
    REG_PWM_ENA = PWM_ENA_CHID3 | PWM_ENA_CHID2 | PWM_ENA_CHID1 | PWM_ENA_CHID0;
}

上記の関数pwm3_setupをArduinoのsetup内でコールすることで、Arduino DueのD36~41pinに3相同期・三角波・相補PWMを打たせることが出来ます。

image.png
(上記画像は Arduino DueでNo Device Foundで困った場合の対処方法より拝借)

D36~41pinの割り当てとしては下記になります。
D36:PWM1L
D37:PWM1H
D38:PWM2L
D39:PWM2H
D40:PWM3L
D41:PWM3H

5. 設定の解説

5.1 どこで3相同期を取っているか

答えはシンプルで、PWMの開始(すなわち搬送波のカウント開始)を一斉に実施することで同期を取っています。
コードとしての対応箇所は上記コードの一番下の

// PWM0~3の開始
    REG_PWM_ENA = PWM_ENA_CHID3 | PWM_ENA_CHID2 | PWM_ENA_CHID1 | PWM_ENA_CHID0;

になります。
別の実現方法として、搬送波のリセットを一斉実施することでも同期を取る事が出来ます。

5.2 どこで三角波にしているか

コードの中でコメントとして書いていますが、

    //デッドタイム有効化、プリスケーラ=0、三角波の設定
    REG_PWM_CMR0 = PWM_CMR_CALG | PWM_CMR_CPRE_MCK;
    REG_PWM_CMR1 = PWM_CMR_DTE | PWM_CMR_CALG | PWM_CMR_CPRE_MCK;
    REG_PWM_CMR2 = PWM_CMR_DTE | PWM_CMR_CALG | PWM_CMR_CPRE_MCK;
    REG_PWM_CMR3 = PWM_CMR_DTE | PWM_CMR_CALG | PWM_CMR_CPRE_MCK;

PWM_CMR_CALG で三角波に設定しています。
CALG = Center ALiGned = 中央揃え = 三角波を意味します。

なおPWM_CMR_DTEは単純にデッドタイムの有効化を設定しており、デッドタイムの長さ設定はその下の

    //PWMHおよびPWMLのデッドタイム設定
    REG_PWM_DT1 = PWM_DT_DTH(DeadTime) | PWM_DT_DTL(DeadTime);
    REG_PWM_DT2 = PWM_DT_DTH(DeadTime) | PWM_DT_DTL(DeadTime);
    REG_PWM_DT3 = PWM_DT_DTH(DeadTime) | PWM_DT_DTL(DeadTime);

で行っています。
親切なことに、上側SWと下側SWのデッドタイムを別途設定できるようになっています。
どちらかのデッドタイムの設定を忘れるとインバータが壊れると思われます、親切!

5.3 どこで相補にしているか

これが一番分かりにくいです。下記になります。

    //PIOのディセーブルレジスタ
    REG_PIOC_PDR = PIO_PDR_P9 | PIO_PDR_P8 | PIO_PDR_P7 | PIO_PDR_P6 | PIO_PDR_P5 | PIO_PDR_P4;
    //ペリフェラルABセレクタ
    REG_PIOC_ABSR |= PIO_ABSR_P9 | PIO_ABSR_P8 | PIO_ABSR_P7 | PIO_ABSR_P6 | PIO_ABSR_P5 | PIO_ABSR_P4;

D36~41pinの割り当てを改めて書くと下記です。
D36:PWM1L(Port4)
D37:PWM1H(Port5)
D38:PWM2L(Port6)
D39:PWM2H(Port7)
D40:PWM3L(Port8)
D41:PWM3H(Port9)

すなわち、P4に対してのみPIOディセーブルおよびABセレクタの設定を行った場合はPWM1Lのみが有効化されます。
これに加え、P5に対して同様の設定を行った場合はPWM1Hが有効化されます。
P4とP5はいずれもPWM1であり、相補の関係にあるためP4とP5の両方を有効化することで相補PWMが実現されます。
同様の設定をPWM2およびPWM3に設定することで3相の相補PWMを得ることが出来ます。

なお、ABセレクタに限りビット論理和代入演算子 |=が用いられていますが、これは他のペリフェラルのABセレクタは変えずに該当する部分のみを書き換えるためとなります。

6. 正しく設定できているかどうかの確認

オシロスコープで下記を確認しましょう。

①三角波PWMが正しく設定されているか ⇒ D36のON周期が10kHzとなっているかを確認
 (CounterPeriod = 4200 - 1と設定した場合、三角波だと10kHzだが
  のこぎり波の場合は20kHzとなる。)

②3相同期PWMとなっているか ⇒ D36、D38、D40 の3つのPWMのON/OFFが同期しているかを確認
 (Duty指令を3相で同じ値に設定したので全てのON/OFFが同期するはず)

③デッドタイムが正しく設定されているか ⇒ D36とD37、D38とD39、D40とD41を確認
 (インバータへの接続はデッドタイムをちゃんと確認してからにしましょう)

7. おわりに

モータ制御の解説記事、書きたい事が多すぎてしんどい!
でもこれで沼に嵌る人が増えるのならお安いもんですわ…。

36
23
2

Register as a new user and use Qiita more conveniently

  1. You get articles that match your needs
  2. You can efficiently read back useful information
  3. You can use dark theme
What you can do with signing up
36
23

Delete article

Deleted articles cannot be recovered.

Draft of this article would be also deleted.

Are you sure you want to delete this article?