LoginSignup
25
19

More than 1 year has passed since last update.

Arduino DueでPWM山同期AD変換を行う

Last updated at Posted at 2021-07-18

はじめに

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

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

いつものことですが、前置きがとっても長いです。
技術記事といより読み物として楽しんで頂ければと思います。

1. モータ制御における電流検出

前記事でも書きましたが、ベクトル制御やセンサレスベクトル制御を行う場合においては電流検出が必要となります。
なお電流検出の対象はどの電流かと言うと、インバータを通じてモータに入力される3相交流電流 となります。
image.png

電流検出の方法は様々ありますが、1例としてパワエレの研究用途ではよく「磁気平衡方式、ホール素子検出タイプ」が用いられます。

下記、HIOKIのサイト電流センサの原理と技術情報より引用。
(これらはどちらかというと制御用というよりオシロスコープに接続して観測用に用いるものですが。イメージ分かり易いので引用として使います)
image.png

本方式の長所は上記の通り、AC/DC問わず広帯域まで低ノイズに電流検出可能なことが挙げられます。
短所はというと、値段がお高いということです。横河やHIOKIが出している、オシロスコープ接続用の製品でだいたい数万円~数十万円といったところです。

もう少し値段の落ち着いたところでは、LEMの基板実装型のものが挙げられます。下記のモータ制御の記事でも使われています。
BLモータのベクトル制御を実装する手順

お値段としては数千円程度であり、電子工作用途としては現実的なラインになってきます。
しかしながらコスト制約の厳しい製品(特に小型モータの類)には殆ど適用されません。

じゃあ貧乏人コスト制約の厳しい場合はどのような方法で電流検出を行うかと言うと、シャント抵抗を使用することになります。

下記はSTのモータ制御評価キットに実装されたシャント抵抗となります。
見ての通り、ただの抵抗素子なのでコスト面では非常に優れます。
image.png

シャント抵抗を用いてどのように電流検出を行うかというと、抵抗両端の電位差を検出することでシャント抵抗に流れる電流を求めることが出来ます。非常にシンプルですね。
image.png
なおここでの電位差は非常に微小なものであることから、実際には抵抗両端とオペアンプを接続して電位差を増幅する必要があります。

2. シャント抵抗電流検出の種類

下記の2分類に大別されます。
①複数のシャント抵抗を用いて相電流を検出する方法
②1つのシャント抵抗を用いて相電流を推定(復元とも言われる)する方法

下記では①に限定して説明を行うものとします。
①はさらに下記に分類されます。
 ①-a ローサイド3シャント電流検出
 ①-b ハイサイド3シャント電流検出
 ①-c インバータ-モータ間 3シャント電流検出

なお、上記3手法は3シャント⇒2シャントに簡素化することも可能ですがそれはまたの機会に。

①-a ローサイド3シャント電流検出

3相インバータ下側のSW素子と直列にシャント抵抗を接続した方式で、シャント抵抗電流検出方法の中では最も一般的なものの1つと言えます。
image.png

本方式が最も一般的に用いられる理由は様々ありますが、例として下記が挙げられます。
・オペアンプに接続される端子のうち一方が電源のGND側となる
・もう一方の端子の電圧についてもせいぜい数mVであり、オペアンプへの入力電圧が総じて低い

なお、STのモータ制御評価キットの電流検出方法も本方式となります。
(厳密には、①-a ローサイド3シャント電流検出 と②1つのシャント抵抗を用いて相電流を推定する方法 をジャンパピンで接続可能になっています。欲張りセット。)
https://www.st.com/resource/en/user_manual/dm00226187-getting-started-with-the-xnucleoihm07m1-motor-driver-expansion-board-based-on-the-l6230-for-stm32-nucleo-stmicroelectronics.pdf
image.png

①-b ハイサイド3シャント電流検出

上図で示したローサイド3シャント電流検出に対し、シャント抵抗がインバータ上側のSW素子と直列に接続された方式となります。

なお、ローサイド検出とハイサイド検出のメリデメについては下記のサイトにまとまっていました。ご参考。
https://www.digikey.jp/ja/articles/fundamentals-of-current-measurement-part-2-current-sense-amplifiers

①-c インバータ-モータ間 3シャント電流検出

文字通り、3相インバータの出力端子とモータとの間に直列にシャント抵抗を接続した方式となります。
image.png

(スペースの都合上アンプ省略します、すいません)

本方式もローサイド3シャント電流検出と比較すると広く用いられることのない方法ですが…なぜかTiのGAN評価ボードにて本方式が採用されています。

image.png

ローサイド3シャント電流検出と比較した場合のメリデメは下記です。
メリット:
 ・電流検出が比較的容易
 ・電圧利用率によらず電流検出が可能

デメリット:
 ・常にシャント抵抗に電流が流れるため、損失(=発熱)が大きくなる。
 ・オペアンプに入力される電圧が高い

個人的見解として、趣味で使う分には余りデメリットが気にならず、なおかつメリットを享受しやすいのでもし本方式を採用している評価ボードがあれば1つ買っておいても損はないと思います。
(なお、TiのGAN評価ボードは2021/7月現在購入できなくなっていました…残念
 →21/7/20 下記より後継を購入可能との情報を @wcrvt さんより頂く。感謝!
  https://www.tij.co.jp/tool/jp/BOOSTXL-3PHGANINV)

3. PWM山同期AD変換とは

前置きが長くなりましたが、やっと本題に辿り着きました。
PWM山同期AD変換とは、PWMが頂点(山)のタイミングにて電流検出を行うことを指します。
image.png

前記事でも書いた通り、モータ制御における電流検出は搬送波の頂点(山)もしく底辺(谷)のタイミングで電流検出を行うことが望ましいです。
電流検出の方法として磁気平衡方式を使用する場合にはそのいずれのタイミングでも電流検出が可能なことから、演算負荷などの制約がない限りは「PWM山谷同期AD変換」が用いられます。

ではなぜ本記事でPWM山同期AD変換を紹介するかと言えば、それはシャント方式で一般的である、ローサイド3シャント電流検出において必要となるから です。

ローサイド3シャント電流検出は①-aで説明した通り、下側SW素子と直列に装着した抵抗素子にて電流検出を行います。
この抵抗素子を流れる電流とモータに流れる電流が等しくなるのは下側SW素子がONの時だけで、OFFのときは電流が流れません。

image.png

ではPWM山のタイミングはどうなっているかというと、3相の上側SW素子が全てOFF、下側SW素子が全てONのタイミング となります。

image.png

上記がローサイド3シャント電流検出にてPWM山同期AD変換が必要となる理由となります。
補足ですが、ハイサイド3シャント電流検出はPWM同期AD変換が必要となります。
インバータ-モータ間 3シャント電流検出は山谷いずれでも対応可能となります。
(メリットに電流検出が比較的容易と書いたのはこのためです)

4. Arduino Dueでの設定方法

下記3つの設定が必要となります。
①山同期のタイミングでONとなる信号を発生、イベントとして登録
②AD変換を①イベントに同期して実施、終了後に割り込みを発生させる
③ ②割り込み関数内で変数への受け渡しを行う

順を追って説明して行きましょう。

①山同期のタイミングでONとなる信号を発生、イベントとして登録

Arduino Dueに3相同期・三角波・相補PWMを打たせるに記載したコードの一部で実現しているため、下記にてコードを再掲します。

//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;
}

上記のうち、PWM山同期AD変換を行う上で最も重要な設定は下記になります。

//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を設定

詳しく説明します。
モータ制御には3相PWMが必要となりますが、Arduino DueのPWMうちPWM1~3を割り当てており
PWM0は他の用途、すなわち山同期AD変換を行うための割り込み発生に用いられます。

山同期させるためのミソはDutyにCounterPeriod - 10を設定することです。
搬送波の上限値からわずかに下げた値を設定することで、搬送波の上限すなわち山から少しだけずれたタイミングでONとなる信号を得ることが出来ます。

image.png

なお、上記では-10としていますが別に-1でもOKとは思います。OFF→ONが短すぎると割り込みが発生しないかも? 的なお気持ちから少し大きい数字にしています。

②AD変換を①イベントに同期して実施、終了後に割り込みを発生させる

①に記載した関数pwm3_setup()の次に下記の関数をコールすることで行います。
(一部理解しきれていない部分があります。すいません)

void adc_setup() {
  PMC->PMC_PCER1 |= PMC_PCER1_PID37;                    // ADC power on

  ADC->ADC_CR = ADC_CR_SWRST;                           // Reset ADC
  ADC->ADC_MR =  ADC_MR_TRGEN_EN                       // Hardware trigger select
                  | ADC_MR_TRGSEL_ADC_TRIG5            // Trigger by PWM Event Line 1 PWMイベントライン1をトリガに設定
                  | ADC_MR_PRESCAL(1);                // ここは0でも1でもどっちでも

  ADC->ADC_IER = ADC_IER_EOC7;                          // End Of Conversion interrupt enable for channel 7
  NVIC_EnableIRQ(ADC_IRQn);                             // Enable ADC interrupt
  ADC->ADC_CHER = ADC_CHER_CH7 | ADC_CHER_CH6 | ADC_CHER_CH5;  // Enable Channel 5~7
}

ここでのミソは、言うまでもなくADC->ADC_MRの設定部分です。ここの設定によって「②AD変換を①イベントに同期して実施」が実現されています。

後述しますが、3つのシャント抵抗のによって検出された3相電流をArduino DueのAD CH5~7に接続することでマイコンへの取り込みを実施します。このためADC->ADC_CHERの設定としては上記のようになります。

③ ②割り込み関数内で変数への受け渡しを行う

ここは特に難しい設定はありません。
Iu_ad等の変数はグローバル宣言しています。

void ADC_Handler() {
  Iu_ad = ADC->ADC_CDR[7];  // Read and clear status register 
  //こいつを消すと動かなくなる。CH7の完了と同期しているから?

  Iv_ad = ADC->ADC_CDR[6];
  Iw_ad = ADC->ADC_CDR[5];

  PIOB->PIO_ODSR ^= PIO_ODSR_P27; //Lチカ用
}

PIOB->PIO_ODSR ^= PIO_ODSR_P27 はAD変換が狙い通りPWM山で実施できているかを確認する目的で入れています。

5. おわりに

あっさり書くつもりが、なぜか完成してみるとこってりになってしまう…なぜだろうか。
今日はあっさりを頼もうと思って天一に行くも、注文時はこってりにしてしまうみたいな感じです。

25
19
0

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
25
19