4
1

Delete article

Deleted articles cannot be recovered.

Draft of this article would be also deleted.

Are you sure you want to delete this article?

【Simulink】【ArduinoR4】BLDC制御のモデルベースな開発環境

Last updated at Posted at 2025-12-07

はじめに

時は来た、それだけだ。
.
.
.
冗談はさておきとして。
本記事は著者が4年前(そんな前か…)に発表したMATLAB Homeでのモータ制御MBD開発に向けた脱獄指南書 の2025年版みたいなものです。要点としては
・「UNO R4を使うとFPUとポン付けインバーターボードがあるからめっちゃ楽チン。下回りのデバッグを考えるとminimaが便利」
・「MATALB 2025a以降、simulinkで書いたモータ制御モデルをminimaで動かせるよ」

の2点です。

ポエムやら解説やらをぶっとばしてsimulinkの環境だけが欲しい方は下記からどうぞ、MATLAB 2025b前提です。
https://github.com/motorcontrolman/minima_simulink
(モデル名 untitled.slx から雑さを察して下さい)

はじめに2

仕切り直して。
MATLAB 2025a以降、Simulink Support Package for Arduino がついに arduino UNO R4 Minimaをサポートしました。
https://jp.mathworks.com/matlabcentral/fileexchange/40312-simulink-support-package-for-arduino-hardware
image.png
(arduino UNO R4 wifiもなんか猛烈に強化されてるっぽい…こっちは未開拓です)

minimaとwifiは機能面としては当然ながら原則としてwifiのほうが上回る訳ですが(Renesas RA4M1とESP32-S3のマイコン2枚乗せの時点でチート)著者の偏った価値観「モータ(BLDC)制御開発用途に適しているか」に基づくと、下記の2観点からminimaのほうがLikeな感じになります。

低価格
モータ制御開発で乱暴していると壊すことがあるのでまぁまぁ重要な観点
といってもそこまでのコスト差は無いが…(正規品で¥800ぐらいの差)

SWDコネクタが生えている
どっちかというとこっちが大事。

SWDコネクタの有無は、本質的にはこの記事のタイトルと関係ないのですがSimulink環境に持ってくる前にarduino IDE環境でデバッグしまくるという辛い工程が実際にはあるので無視が出来ない観点になります。

(関連記事)
・arduino R4 minimaでRAMモニタする
https://qiita.com/motorcontrolman/items/cebfdfdd48e0fc7e2b55

・【STM32】無償のRAMモニターJ-Scopeを使おう
https://qiita.com/motorcontrolman/items/c1910c5a51fb29a700fd

上記はminimaとwifiの比較についての話になりますが、minima/wifi共通で下記2つの特徴が供えられており、このことがBLDC制御のモデルベースな開発環境を構築する上で他マイコンに対する優位性となっています。

特徴①FPUを備える
浮動小数演算しても処理時間が長くならない

MATLAB Homeでのモータ制御MBD開発に向けた脱獄指南書 を発表した当時、arduino UNO R4は存在すらしていなかったのでArduino Due(クロック84MHz)をマイコンボードとして使用していましたが、FPUが無く非常に辛い開発環境となっていました。(Fixed Pointでだいぶ緩和はされていたが、上下限値を意識する必要があるのでやっぱり辛い)

arduino UNO R4 mimima/wifiは、クロックこそ48MHzと控えめなものの(とはいえ今のご時世、このクロックでモータ制御するのも辛さがないと言えば嘘になる)、FPUの有無を考えた場合の利便性としてはarduino Dueに対して圧倒的に有利性があります。

特徴②ポン付け可能かつ割とクセの少ないインバーターボードが存在
Simple FOC Shield V3.2(V2.0.4はあんまりお勧めしない)
https://ja.aliexpress.com/item/1005009742399559.html

image.png
(ちなみに灰色のケーブルはSWDコネクタからJ-Linkに繋いでいます)

arduino UNO はR3が非常にポピュラーなマイコンボードであったため、ホビー用途でのベクトル制御界隈であるSimple FOCの開発ボードの1つとしても挙げられており(これってR3でもベクトル制御やってたんだよな…だとしたらひどいマゾだな)オープンソースな文化からUNO R3にポン付け出来るマイコンボードが過去から開発されていました&AliExpressで購入可能という、回路設計なんて出来ないしやる気もないというモノグサな私からするとありがたい限りの環境が整備されています。

これらの前提を踏まえると、2025年現在、非常にお手軽な形でBLDC制御のモデルベースな開発環境が整えられますよ、ということで本稿を記載するに至っています。

1.購入品リスト

品名 だいたいの価格 どこで買うか
MATLAB Home 16,500円 Mathworksオフィシャルサイト
Simulink 5,000円 Mathworksオフィシャルサイト
arduino UNO R4 minima 4,000円 Amazonとか(Aliだと互換品が安い)
Simple FOC Shield V3.2 2,000円 AliExpress
磁気エンコーダ付きモータ 2,000~4,000円 AliExpress

上記に加えて、DACを使用したい場合はSimple FOC Shield V3.2の0Ω抵抗移動用にはんだごてが、割り込み出力➡入力用にジャンパワイヤー(オス-オス)が必要になります。

なお、磁気エンコーダ付きモータについて、著者はSimpleFOCシールド用 磁気誘導センサーAS5600装着 BLDCモーター を使用していますが、SPI通信でモータ角度を取得できるモータであれば何でも良いです。(センサレスを目指すのであればモータ角度取得機能自体も不要です)

2.miminaのピン配置

大変申し訳ないのですが、モータ角度取得まで実装できていないので3相PWM出力・2相電流検出までを実現する前提でのピン配置になります。

arduinoでのポート名 RA4M1でのピン名 タイマ or AD機能名 機能
D13
D12
D11
D10 GTIOC 3B V相Duty出力
D9
D8 インバータイネーブル出力
D6 GTIOC 0B U相Duty出力
D5 GTIOC 2B W相Duty出力
D4 処理負荷計測用
D3 GTIOC 1B トリガ信号出力(D2と接続)
D2 割り込みピン(D3から入力)
D1
D0
A2 AN001 V相電流検出(入力)
A1 AN000 U相電流検出(入力)
A0 DA0 DAC出力

D5~D10はそのままSimple FOC Shield V3.2に出力されるため基板改造などの物理的な何かをする必要はありません。D4は処理負荷計測用の信号をGPIO出力させたもので、接続先はオシロスコープになりますが処理負荷計測しなければ使いません。

D2,D3はSimulinkで作成した制御モデルをPWM山もしく谷同期で動作させる上で使っているピンで、D3からPWM山もしく谷同期の信号が出力されるのをD2ピンに入力させることで割り込みを発生させます。

image.png
MATLAB Homeでのモータ制御MBD開発に向けた脱獄指南書 より。使いまわしスマン…。

実際にminima+Simple FOC Shield V3.2の環境でD2,D3を接続している写真
image.png

A0~A2ピンについては次章で説明します。

3.Simple FOC Shield V3.2の取り扱い注意

なぜわざわざこれを単一の章として取り上げているかというと、基板に対して若干の改造を施しているからという理由だけでなくSimple FOC Shield V3.2の回路図として公開されている情報と入手した基板の実態が異なっていたことをお伝えしたいからになります。

回路図

image.png
・Duty出力は、IN3 = INA, IN2 = INB, IN1 = INC の配置(なぜ逆順にしたし)
・電流検出用アナログ出力はOUT3 = A相用、 OUT1 = C相用として配置
 ➡A相、C相電流検出と記載

一方で実際の基板はと言うと…
image.png
A相、B相電流検出と記載

…おわかりいただけただろうか…。

と評論家のような事を言っておりますが、人様がお造りになられたインバータボードをありがたく使わせて頂く卑しい立場のワタクシと致しましては、むしろシルクに分かりやすい印字をしてくれてありがとうという感謝の気持ちを抱いて生きていたいなと思う今日この頃であります。もっとも、今回Aliで購入したインバータボードがたまたまそうなっていただけで、他で購入した場合は回路図通りA相、C相電流検出になっている可能性もあるので各自ご確認下さい。

冗談はさておきとして(2度目)、Simple FOC Shield V3.2購入時のデフォルト設定としてはA相電流検出用アナログ出力がA0に接続されていたため、はんだごてを使ってA1側に変更しています。(A0はDAC出力に使用するため。DAC出力を使わない場合はそのままでOK)

相電流検出用アナログ出力のピン選択については、回路図にも下記のように記載されています。(変更したのはC1_OUT側のみで、C2_OUTはデフォルトのまま使っています)
image.png

4. Simulinkのモデリング

最低限の構成としては2階層のモデルになります。

1階層(最上位):初期化関数IoInit、D2ピンを入力した割り込み発生関数を配置
image.png

2階層:割り込み関数(ほぼ作成途中…)ハードへの出力関数SetDutyを配置
image.png

初期化関数IoInit、ハードへの出力関数SetDutyはいずれもS-function Builderを用いて実装しています。それなに?という方は【MATLAB】便利!S-Function Builderの使い方-Arduino連携ライブラリの自作- を参照のこと。

4.1 初期化関数IoInitの中身

細かい説明は割愛しますが、2章で説明したピン配置に対して機能を有効化させるためのコードを記述しています。初期化しているだけなので入出力信号はありません。DAC周りはどこかのコードからコピペしたものですが出処は失念しました…。

/* Includes_BEGIN */
#include <math.h>
# ifndef MATLAB_MEX_FILE
# include <arduino.h>
#define CARRIORCNT 2400 - 1 // クロック周波数48000000 1200で三角波キャリア10kHz
#define DACBASE 0x40050000                                                      // DAC Base - DAC output on A0 (P014 AN09 DAC)
#define DAC12_DADR0 ((volatile unsigned short *)(DACBASE + 0xE000))             // D/A Data Register 0
#define DAC12_DACR ((volatile unsigned char *)(DACBASE + 0xE004))               // D/A Control Register
#define DAC12_DADPR ((volatile unsigned char *)(DACBASE + 0xE005))              // DADR0 Format Select Register
#define DAC12_DAADSCR ((volatile unsigned char *)(DACBASE + 0xE006))            // D/A A/D Synchronous Start Control Register
#define DAC12_DAVREFCR ((volatile unsigned char *)(DACBASE + 0xE007))           // D/A VREF Control Register
#define MSTP_MSTPCRD ((volatile unsigned int *)(MSTP + 0x7008))                 // Module Stop Control Register D
#define MSTP 0x40040000                                                         // Module Registers
#define MSTP_MSTPCRB ((volatile unsigned int *)(MSTP + 0x7000))                 // Module Stop Control Register B
#define PFS_P014PFS ((volatile unsigned int *)(PORTBASE + P000PFS + (14 * 4)))  // A0 / DAC12
#define PORTBASE 0x40040000                                                     /* Port Base */
#define P000PFS 0x0800     
# endif
/* Includes_END */

/* Externs_BEGIN */
/* extern double func(double a); */
/* Externs_END */

void IoInit_Start_wrapper(real_T *xD)
{
/* Start_BEGIN */
# ifndef MATLAB_MEX_FILE
  pinMode(4, OUTPUT);       // D4ピンを出力に設定(処理負荷計測用)

  // GTP32用 モジュールストップ状態を解除
  R_MSTP->MSTPCRD_b.MSTPD5 = 0; 
  // GTP16用 モジュールストップ状態を解除
  R_MSTP->MSTPCRD_b.MSTPD6 = 0; 

  // PWM出力用端子の設定
  // ピンを出力に設定
  R_PFS->PORT[1].PIN[2].PmnPFS_b.PDR = 1; // D5 GTIOC 2B
  R_PFS->PORT[1].PIN[4].PmnPFS_b.PDR = 1; // D3 GTIOC 1B Trig
  R_PFS->PORT[1].PIN[6].PmnPFS_b.PDR = 1; // D6 GTIOC 0B 
  R_PFS->PORT[1].PIN[12].PmnPFS_b.PDR = 1; // D10 GTIOC 3B

  // SimpleFocShieldV3.2 Enable
  R_PFS->PORT[3].PIN[4].PmnPFS_b.PDR = 1; // D8 Enable for SimpleFocShieldV3.2
  R_PORT3->PODR_b.PODR4 = 1;
  
  //周辺選択ビットでGPTを設定
  R_PFS->PORT[1].PIN[2].PmnPFS_b.PSEL = 0b00011;
  R_PFS->PORT[1].PIN[4].PmnPFS_b.PSEL = 0b00011;  
  R_PFS->PORT[1].PIN[6].PmnPFS_b.PSEL = 0b00011;
  R_PFS->PORT[1].PIN[12].PmnPFS_b.PSEL = 0b00011;

  // ポートモード制御ビットで周辺機能に設定
  R_PFS->PORT[1].PIN[2].PmnPFS_b.PMR = 1; 
  R_PFS->PORT[1].PIN[4].PmnPFS_b.PMR = 1;
  R_PFS->PORT[1].PIN[6].PmnPFS_b.PMR = 1;
  R_PFS->PORT[1].PIN[12].PmnPFS_b.PMR = 1;
  
  // PWMタイマの同期
  // GTSTR、GTSTPによるカウンタスタート/ストップを許可
  R_GPT0->GTSSR_b.CSTRT = 1;
  R_GPT1->GTSSR_b.CSTRT = 1;
  R_GPT2->GTSSR_b.CSTRT = 1;
  R_GPT3->GTSSR_b.CSTRT = 1;
  
  //GTSTPによるカウンタストップ(全てのタイマでレジスタは共通)0は違うかも
  R_GPT0->GTSTP = 0b11001111; 
 
  // 搬送波を三角波に設定(三角波PWMモード1、バッファ転送は谷のみ。山谷の場合はPWMモード2を選択)
  R_GPT0->GTCR_b.MD = 0b100;
  R_GPT1->GTCR_b.MD = 0b100;
  R_GPT2->GTCR_b.MD = 0b100;
  R_GPT3->GTCR_b.MD = 0b100;
  
  // GTIOCA, GTIOCB端子の出力許可
  R_GPT0->GTIOR_b.OBE = 1;
  R_GPT1->GTIOR_b.OBE = 1; 
  R_GPT2->GTIOR_b.OBE = 1; 
  R_GPT3->GTIOR_b.OBE = 1; 

  // Dutyのバッファ設定
  // 01bでシングルバッファ
  R_GPT0->GTBER_b.CCRB = 0b01;
  R_GPT1->GTBER_b.CCRB = 0b01;
  R_GPT2->GTBER_b.CCRB = 0b01;
  R_GPT3->GTBER_b.CCRB = 0b01;

  // PWMのHigh,Row設定 
  // GPT1はBchからGPT0B、2B、3Bの山側でトリガ信号を発生させるための設定が必要
  R_GPT1->GTIOR_b.GTIOB = 0b00011;
  // GPT0B、2B、3B
  R_GPT0->GTIOR_b.GTIOB = 0b10011;
  R_GPT2->GTIOR_b.GTIOB = 0b10011;
  R_GPT3->GTIOR_b.GTIOB = 0b10011;


  // キャリア周波数設定
  R_GPT0->GTPR = CARRIORCNT;
  R_GPT1->GTPR = CARRIORCNT;
  R_GPT2->GTPR = CARRIORCNT;
  R_GPT3->GTPR = CARRIORCNT;
  
  // Duty設定
  R_GPT1->GTCCR[3] = 100;    // GPT2はBchを使用、かつバッファ設定のため[3]にDutyを設定
  R_GPT0->GTCCR[3] = 600;
  R_GPT2->GTCCR[3] = 600;  
  R_GPT3->GTCCR[3] = 600;  
  
  // カウンタリセット
  R_GPT0->GTCNT = 0; 
  R_GPT1->GTCNT = 0;
  R_GPT2->GTCNT = 0;
  R_GPT3->GTCNT = 0; 

  //GTSTRによるカウンタスタート(全てのタイマでレジスタは共通)
  R_GPT0->GTSTR = 0b11001111; 
  
  // A/D変換モジュールのクロック供給
  R_MSTP->MSTPCRD_b.MSTPD17 = 0; // ADC120
  R_PFS->PORT[0].PIN[0].PmnPFS_b.PDR = 0;   //A1ポートを入力に設定
  R_PFS->PORT[0].PIN[1].PmnPFS_b.PDR = 0;   // A2ポートを入力に設定
  R_PFS->PORT[0].PIN[0].PmnPFS_b.ASEL = 1;
  R_PFS->PORT[0].PIN[1].PmnPFS_b.ASEL = 1;
  R_ADC0->ADANSA_b[0].ANSA0 = 1;
  R_ADC0->ADANSA_b[0].ANSA1 = 1;

  // DAC
  R_MSTP->MSTPCRD_b.MSTPD20 = 0; 
  *DAC12_DADPR = 0x00;                  // DADR0 Format Select Register - Set right-justified format
                                        //  *DAC12_DAADSCR  = 0x80;             // D/A A/D Synchronous Start Control Register - Enable
  *DAC12_DAADSCR = 0x00;                // D/A A/D Synchronous Start Control Register - Default
                                        // 36.3.2 Notes on Using the Internal Reference Voltage as the Reference Voltage
  *DAC12_DAVREFCR = 0x00;               // D/A VREF Control Register - Write 0x00 first - see 36.2.5
  *DAC12_DADR0 = 0x0000;                // D/A Data Register 0
  delayMicroseconds(10);                // Needed delay - see data sheet
  *DAC12_DAVREFCR = 0x01;               // D/A VREF Control Register - Select AVCC0/AVSS0 for Vref
  *DAC12_DACR = 0x5F;                   // D/A Control Register -
  delayMicroseconds(5);                 // Needed delay - see data sheet
  *DAC12_DADR0 = 2048;                  // D/A Data Register 0 - value of mid range bias
  *PFS_P014PFS = 0x00000000;            // Port Mode Control - Make sure all bits cleared
  *PFS_P014PFS |= (0x1 << 15);          // ... use as an analog pin

  # endif
/* Start_END */
}

void IoInit_Outputs_wrapper(const real_T *xD)
{
/* Output_BEGIN */
/* このサンプルは、出力を入力と等しく設定します
 y0[0] = u0[0]; 
 複素信号の場合は、次を使用します: y0[0].re = u0[0].re; 
 y0[0].im = u0[0].im;
 y1[0].re = u1[0].re;
 y1[0].im = u1[0].im;
 */
/* Output_END */
}

void IoInit_Update_wrapper(real_T *xD)
{
/* Update_BEGIN */

/* Update_END */
}

void IoInit_Terminate_wrapper(real_T *xD)
{
/* Terminate_BEGIN */
/*
 * カスタム終了コードをここに配置します。
 */
/* Terminate_END */
}

4.2 ハード出力関数SetDutyの中身

入力端子として3相Duty(名前Duty_in、uint型)、角度θ(名前theta_in、single型)を持たせていますが、強制転流用θを関数外から入力させて中でDutyを演算しているためDuty_inは使っていません。出力端子theta_outは追々SPIで角度取得し関数外に持っていく目的で存在しますが、これも今の段階では使っていません。
image.png

コードも強制転流を前提とした内容になっています。
R_PORT1->PODR_b.PODR3は処理負荷計測用。

/* Includes_BEGIN */
#include <math.h>
# ifndef MATLAB_MEX_FILE
# include <arduino.h>
#define CARRIORCNT 2400 - 1 // クロック周波数48000000 1200で三角波キャリア10kHz
#define Ts 200E-6f
#define TWOPI           6.283185307f
#define SQRT_2DIV3			0.816496581f
#define SQRT3_DIV2			0.86602540378f
#define DACBASE 0x40050000                                                      // DAC Base - DAC output on A0 (P014 AN09 DAC)
#define DAC12_DADR0 ((volatile unsigned short *)(DACBASE + 0xE000))             // D/A Data Register 0
float theta = 0.0f;
uint16_t Iu_ad = 0;
uint16_t Iv_ad = 0;
uint16_t theta_dac;
# endif
/* Includes_END */

/* Externs_BEGIN */
/* extern double func(double a); */
/* Externs_END */

void SetDuty_Start_wrapper(real_T *xD)
{
/* Start_BEGIN */
/*
 * カスタム開始コードをここに配置します。
 */
/* Start_END */
}

void SetDuty_Outputs_wrapper(const uint16_T *Duty_in,
                             const real32_T *theta_in,
                             real32_T *theta_out,
                             const real_T *xD)
{
/* Output_BEGIN */
# ifndef MATLAB_MEX_FILE
  float omega_ref = 100.0f;
  float sinTheta;
  float cosTheta;
  float dq[2];
  float ab[2];
  float uvw[3];
  float Duty[3];
  uint16_t CNT[3];
  float twoDivVdc = 0.2f; // Vdc = 10V

  R_PORT1->PODR_b.PODR3 = 1;

  // ad convert
  R_ADC0->ADCSR_b.ADST = 1;     //A/D変換開始
  while(R_ADC0->ADCSR_b.ADST);  //A/D変換終了待ち
  Iu_ad = R_ADC0->ADDR[0];    //A/D変換結果取得
  Iv_ad = R_ADC0->ADDR[1];

  //Calc Theta
  theta = theta_in[0];
  sinTheta = sinf(theta); 
  cosTheta = cosf(theta);
  

  // Calc Voltage
  dq[0] = 0.0f;
  dq[1] = 0.5f;

  ab[0] = dq[0] * cosTheta - dq[1] * sinTheta;
  ab[1] = dq[0] * sinTheta + dq[1] * cosTheta;
  uvw[0] = SQRT_2DIV3 * ab[0];
  uvw[1] = SQRT_2DIV3 * ( -0.5f * ab[0] + SQRT3_DIV2 * ab[1] );
  uvw[2] = - uvw[0] - uvw[1];

  // 50% Center
  Duty[0] = uvw[0] * twoDivVdc + 0.5f;
  Duty[1] = uvw[1] * twoDivVdc + 0.5f;
  Duty[2] = uvw[2] * twoDivVdc + 0.5f;

  CNT[0] = Duty[0] * (float)CARRIORCNT;//uint16_t( Duty[0] * (float)CARRIORCNT );
  CNT[1] = Duty[1] * (float)CARRIORCNT;//uint16_t( Duty[1] * (float)CARRIORCNT );
  CNT[2] = Duty[2] * (float)CARRIORCNT;//uint16_t( Duty[2] * (float)CARRIORCNT );

 // PWM output
  R_GPT0->GTCCR[3] = CNT[0];
  R_GPT3->GTCCR[3] = CNT[1];
  R_GPT2->GTCCR[3] = CNT[2];
  
  // DAC output
  theta_dac = ( Iv_ad - 1500 ) * 2;
  *DAC12_DADR0 = theta_dac;//ad1;//(uint16_t)(theta * 200);
   
  R_PORT1->PODR_b.PODR3 = 0;
# endif
/* Output_END */
}

void SetDuty_Update_wrapper(const uint16_T *Duty_in,
                            const real32_T *theta_in,
                            real32_T *theta_out,
                            real_T *xD)
{
/* Update_BEGIN */

/* Update_END */
}

void SetDuty_Terminate_wrapper(real_T *xD)
{
/* Terminate_BEGIN */
/*
 * カスタム終了コードをここに配置します。
 */
/* Terminate_END */
}

あくまで強制転流用なので、自分で制御開発される方はPWM出力、AD変換、DAC出力周りのコードを参考にして下さい。
強制転流させてDAC観測した際の動画が下記です。

5.おわりに

SPI通信で角度取得できる日はいつになるだろうか…。

4
1
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
4
1

Delete article

Deleted articles cannot be recovered.

Draft of this article would be also deleted.

Are you sure you want to delete this article?