M5StackGray モータ駆動デモプログラム TB67H450
2021.5.24 Coskx Lab
1 はじめに
M5StackGrayとモータドライバIC TB67H450を使用し,モータ駆動デモプログラムを作成します。
TB67H450 特徴
2つのモータを駆動できる。
4.5Vから44Vの電圧電源でのモータ駆動ができる。
入力制御信号は2Vから5.5Vの広い範囲が使える。3.3V系マイコンではありがたい
最大電流は3Aまで
電流制限回路がついている。外付けの電流測定用抵抗の電圧を監視していて,電流を制限してくれる。(ありがたい機能)
割り当て可能であるとわかっているGPIOピン2,5およびPWMモジュール(PWMチャンネル)2,3を使ってモータ駆動デモプログラムを作成します。
プログラムでは,ボタンAとボタンBでモータ指令値を変化させます。
参考 モータドライバIC TB67H450資料(東芝デバイス&ストレージ)
データシート https://toshiba.semicon-storage.com/info/docget.jsp?did=65345&prodName=TB67H450FNG
アプリケーションノート https://toshiba.semicon-storage.com/info/docget.jsp?did=65828&prodName=TB67H450FNG
参考 モータドライバIC TB67H450 入出力ファンクション
IN1 | IN2 | OUT1 | OUT2 | モード |
L | L | OFF(Hi-Z) | OFF(Hi-Z) | ストップ(フリー) |
H | L | H | L | 正転 |
L | H | L | H | 逆転 |
H | H | L | L | ショートブレーキ |
IN1=L,IN2=L のときのモータドライバ内の4つのFETの様子
IN1=H,IN2=L のときのモータドライバ内の4つのFETの様子
IN1=L,IN2=H のときのモータドライバ内の4つのFETの様子
IN1=H,IN2=H のときのモータドライバ内の4つのFETの様子
参考 モータドライバIC TB67H450 動作範囲
項目 | 最小 | 標準 | 最大 |
モータ電源電圧 | 4.5V | 24V | 44V |
モータ出力電流 | ― | 1.5A | 3.0A |
ロジックHレベル | 2.0V | ― | 5.5V |
ロジックLレベル | 0V | ― | 0.8V |
ロジック最大周波数 | ― | ― | 400kHz |
参考 モータドライバIC TB67H450基板実装(秋月電子販売)
https://akizukidenshi.com/catalog/g/gK-14753/
2 使用環境
- Windows 10 64-bit
- Arduino IDE 1.8.13
- M5Stack Gray ESP32-D0WDQ6-V3 (revision 3)
MPU6886 + BMM150 16MB 40MHz
- モータドライバIC TB67H450
3 実験用配置と配線
信号線の割付と配線を次のようにします。
M5Stack | TB67H450 |
GPIO 2 | IN1 |
GPIO 5 | IN2 |
実際の配線は次のようになります。
M5Stackの正回転PWM信号の出力は「GPIO 2」です。
「GPIO 2」はM5Stackの裏側に 2 と書いてあるところです。
G2 と書いてあるところも同じ信号です。
M5Stackの逆回転PWM信号の出力は「GPIO 5」です。
「GPIO 5」はM5Stackの裏側に 5 と書いてあるところです。
G5 と書いてあるところも同じ信号です。
モータドライバの電源電圧最小が4.5Vなので,モータ用電源は5Vを使用しています。
モータ駆動電源電圧はモータ推奨電圧1.5~3Vに比べて高いですが,モータをストールさせないようにしましょう。
(モータの電流制限については,補足4 TB67H450の電流制御を参照してください。)
実際の様子です。
TB67H450のVREFには3.3V,RSにはGNDをつなぎます。
写真では,使用していない配線処理がしていないので,見にくいです。
モータ単体では見にくいので,減速ギヤに組み込んだモータを使っています。
参考 M5Stackの裏側に書いてあるピンの名称
プログラムの
PWM_F_PIN = 2; // PWM出力に使用するGPIO PIN番号 Forward
PWM_R_PIN = 5; // PWM出力に使用するGPIO PIN番号 Reverse
は 2 (または G2 )のピンと
5 (または G5 )
のピンをPWM出力に使用するという意味になります。
注意 ピンのいくつかは,他の用途に割り当てられている場合があるため,自由に変更できません。
4 モータ駆動デモプログラム
モータ駆動では,通電駆動状態とショートブレーキ状態を繰り返す駆動をしています。
○ 正転動作(例 デューティ比25%)のときは →
1周期の75%区間で,モータドライバのIN2,IN1ともにHighを与え,残りの25%区間で,モータドライバのIN2にLowを与えとIN1にHighを与えます。(IN1はずっとHigh)
すなわち次の2つの状態が交互に生じます。(ショートブレーキ区間75%,正転通電駆動区間が25%)
○ 逆転動作(例 デューティ比25%)のときは →
1周期の75%区間で,モータドライバのIN1,IN2ともにHighを与え,残りの25%区間で,モータドライバのIN1にLow,IN2にHighを与えます。(IN2はずっとHigh)
すなわち次の2つの状態が交互に生じます。(ショートブレーキ区間75%,逆転通電駆動区間が25%)
2つのPWMモジュール(PWMチャンネル)をそれぞれ別のGPIOピンに出力します。
モータへの指令値は離散的で,プログラム内での見かけ上は
{-1.0, -0.75, -0.5, -0.25, 0., 0.25, 0.5, 0.75, 1.0}
を使用しています。正の値は正転,負の値は逆転になるようにしています。
ボタンAで指令値を増加,ボタンBで指令値を減少させます。
モータ駆動関数driveMotor(int drivevalue)では,指令値の正負によって,PWM発生の仕方を変えています。
設定値は次の通りです。
PWM生成に使用するビット数: 8bit
PWM周波数:20000Hz
使用するPWMモジュール(PWMチャンネル):2と3
(利用可能性を調べてある2,3,4,5,8,9,10,11,12,13,14,15の中から2つを選んでいます)
PWM出力に使用するGPIO PIN番号:2と5
(利用可能性を調べてある2,5,16,17,23,19の中から2つを選んでいます)
PWMの動作テスト用プログラム本体
モータ駆動メインプログラム MotorOOPTest01.ino
//MotorOOPTest01.ino//
#include <M5Stack.h>
#include "MotorDriver.h"
//DCブラシモータを1つ正転逆転駆動するテスト
//class MotorDriver 利用
//1つのモータを正逆駆動するためには,正転用と逆転用の2つのPWM信号が必要です。
//そのため,2つのPWMモジュール(PWMチャンネル)と2つのピンを割り当てます.
//正転(Forward) PWMチャンネル:2 GPIOピン:2
//逆転(Reverse) PWMチャンネル:3 GPIOピン:5
const uint8_t nBits_forPWM = 8; // PWMに使用するビット数 n=1~16[bit]
const double PWM_Frequency = 20000.0; // PWM周波数 Maxfreq=80000000.0/2^n[Hz]
const uint8_t PWM_F_CH = 2; // PWMチャンネル Forward
const uint8_t PWM_R_CH = 3; // PWMチャンネル Reverse
const uint8_t PWM_F_PIN = 2; // PWM出力に使用するGPIO PIN番号 Forward
const uint8_t PWM_R_PIN = 5; // PWM出力に使用するGPIO PIN番号 Reverse
const double Motor_Drive_dutyRatios[] = {-1.0, -0.75, -0.5, -0.25, 0., 0.25, 0.5, 0.75, 1.0};
const int nRatios = sizeof(Motor_Drive_dutyRatios)/sizeof(double);
//Motor_Drive_dutyRatios[]はモータ指令デューティー比の候補(-1.0 <= dutyRatio <= 1.0)
//モータ指令値:正の時は正転側のデューティ比,負のときは逆転側のデューティ比を表す
int dutyRatioIndex = nRatios>>1; //モータ指令値番号
double dutyRatio_Value = Motor_Drive_dutyRatios[dutyRatioIndex];
int value;
MotorDriver mMotorDriver; //class MotorDriver のインスタンス
void setup() {
M5.begin();
M5.Power.begin();
M5.Lcd.setTextSize(4);
M5.Lcd.print("Single Motor\n Drive Test");
mMotorDriver.setPins(PWM_F_PIN, PWM_R_PIN, PWM_F_CH, PWM_R_CH);
mMotorDriver.setPWM(nBits_forPWM, PWM_Frequency);
M5.Lcd.setCursor(10, 80);
M5.Lcd.printf("duty ratio =\n %.4f ",dutyRatio_Value);
value = mMotorDriver.driveMotor(dutyRatio_Value);
M5.Lcd.setCursor(10, 160);
M5.Lcd.printf("value =\n %5d ",value);
}
void loop() {
M5.update();
if (M5.BtnA.wasPressed()) {
dutyRatioIndex ++;
if (nRatios <= dutyRatioIndex) dutyRatioIndex--;
dutyRatio_Value = Motor_Drive_dutyRatios[dutyRatioIndex];
M5.Speaker.tone(880, 200); //Peett
M5.Lcd.setCursor(10, 80);
M5.Lcd.printf("duty ratio =\n %.4f ",dutyRatio_Value);
value = mMotorDriver.driveMotor(dutyRatio_Value);
M5.Lcd.setCursor(10, 160);
M5.Lcd.printf("value =\n %5d ",value);
}
if (M5.BtnB.wasPressed()) {
dutyRatioIndex --;
if (dutyRatioIndex < 0) dutyRatioIndex++;
dutyRatio_Value = Motor_Drive_dutyRatios[dutyRatioIndex];
M5.Speaker.tone(440, 200); //Peett
M5.Lcd.setCursor(10, 80);
M5.Lcd.printf("duty ratio =\n %.4f ",dutyRatio_Value);
value = mMotorDriver.driveMotor(dutyRatio_Value);
M5.Lcd.setCursor(10, 160);
M5.Lcd.printf("value =\n %5d ",value);
}
}
モータドライブクラスヘッダファイル MotorDriver.h
//MotorDriver.h//
#ifndef MotorDriver_h
#define MotorDriver_h
class MotorDriver {
public:
void setPins(int forwardPin, int reversePin, int forwardChannel, int reverseChannel);
void setPWM(int nBits_forPWM, double PWM_Frequency);
int driveMotor(double dutyRatio); // -1.0 <= dutyRatio <= 1.0
private:
int fwdPin, rvsPin;
int fwdChl, rvsChl;
int pwmMaxValue;
};
#endif
モータドライブクラス本体ファイル MotorDrive.cpp
//MotorDrive.cpp//
#include <Arduino.h>
#include "MotorDriver.h"
void MotorDriver::setPins(int forwardPin, int reversePin, int forwardChannel, int reverseChannel) {
fwdPin = forwardPin;
rvsPin = reversePin;
fwdChl = forwardChannel;
rvsChl = reverseChannel;
pinMode(fwdPin, OUTPUT); //出力したいピンを出力用途に設定
pinMode(rvsPin, OUTPUT); //出力したいピンを出力用途に設定
}
void MotorDriver::setPWM(int nBits_forPWM, double PWM_Frequency) {
pwmMaxValue = 1<<nBits_forPWM;
// 指定PWMチャンネルにPWM周波数と使用ビット数を設定
ledcSetup(fwdChl, PWM_Frequency, nBits_forPWM);
ledcSetup(rvsChl, PWM_Frequency, nBits_forPWM);
// 出力したいピンにPWMチャンネル出力をつなげる設定
ledcAttachPin(fwdPin, fwdChl);
ledcAttachPin(rvsPin, rvsChl);
}
//モータ指令値が正のときはモータは正転,負のときは逆転する
//モータ指令値の範囲は-1.0から1.0の間とする -1.0≦dutyratio≦1.0
//デバッグのためにdrivevalueを返す
int MotorDriver::driveMotor(double dutyratio) {
int drivevalue = (int)(pwmMaxValue * dutyratio);
if (drivevalue == 0) {
ledcWrite(PWM_M1_F_CH, 0);
ledcWrite(PWM_M1_R_CH, 0);
} else if (0<drivevalue) {
ledcWrite(PWM_M1_F_CH, pwmMaxValue);
ledcWrite(PWM_M1_R_CH, pwmMaxValue - drivevalue);
} else { //drivevalue<0
ledcWrite(PWM_M1_F_CH, pwmMaxValue + drivevalue);
ledcWrite(PWM_M1_R_CH, pwmMaxValue);
}
return drivevalue;
}
5 PWM信号観察 (PWM周波数:1000のとき)
PWM周波数を1000Hzにして実行時の GPIO 2 と GPIO 5 の信号をオシロスコープで観察しました。
Ch1(緑)が GPIO 2 ,Ch2(黄)が GPIO 5 です。PWM指令値が正のとき,GPIO 5 にPWM波形が見え, GPIO 2 はHighが保たれています。PWM指令値が負のとき,GPIO 5 はHighが保たれ, GPIO 2 にPWM波形が見えています。
(1)PWM指令値 0.25 のとき,GPIO 2がHighでGPIO 5がLowになる区間が正転駆動区間です。デューティ比:25%が出力されています。
(2)PWM指令値 -0.25 のとき,GPIO 5がHighでGPIO 2がLowになる区間が逆転駆動区間です。デューティ比:25%が出力されています。
6 まとめ
M5StackGrayおよびモータドライバTB67H450によるブラシDCモータ駆動テストを行ないました。
割り当て可能であるとわかっているGPIOピン2,5を使い,PWMチャンネルは2,3をそれぞれ割り当てました。
重要な問題
1)モータ用電源があらかじめ入っていると,M5Stackの電源が入り,起動してプログラムが起動するまでの間に,モータが回ってしまいます。
M5Stackの電源が入り,プログラムが起動するまでの間は,GPIOピンの状態は設定出来ず,GPIO 2はL,GPIO 5はHになっていることが原因です。
M5Stackの電源を先に入れて,起動してからモータ側の電源を入れるのが良いでしょう。他にも工夫があるかもしれません。
2)このモータドライバICではモータ駆動用の電圧が4.5V以上となっています。130モータなどでは,大きなモータ負荷をかけると電流が許容値を超えてしまいます。
モータ寿命を考えると,モータと直列に1Ω程度の抵抗を挿入する(モータの電気的時定数が大きくなってしまうが),PWM値はMAXを使わないなどの工夫が必要です。
補足1 M5Stack Gray 出力ピン割り当てとPWMチャンネル選定テストの結果
1)M5Stack Grayで用途が制限されているGPIOピン
・回路図から読み取った,すでに使用されているGPIOピン
GPIO 1 3 ............. USB UART0 (RXD0,TXD0)で使用
GPIO 4 23 18 19 ...... SD SPIと共有
GPIO 33 27 23 18 14 .. LCDで使用
GPIO 21 22 ........... I2C,電源管理,モーションセンサ,磁気センサで使われている
GPIO 25 .............. Audioで使用
・ESP32仕様
GPIO 34~39は読み取り専用
2)M5Stack Grayで使えることを確認したGPIOピン
GPIO 2, GPIO 5 他とは共用していないので自由に使える
GPIO 16, GPIO 17 UART2 (TXD2・RXD2)を使わなければ OK
GPIO 26 DAを使わなければ OK
GPIO 19 SDを使わなければ OK
GPIO 35, GPIO 36 ADを使わなければ,入力のみOK
3)M5Stack Grayで使ってはいけない PWMチャンネル
0 音源として使われている (動作させるとビープ音がなる)
1 用途は不明だが,干渉され周期もデューティ比も指定とは異なる動作をする
6 LCDの輝度調整に使われている (動作させるとLCDの文字の明るさが変化する)
使用bit数が12以上のとき,この現象が現れる
7 LCDの輝度調整に使われている (動作させるとLCDの文字の明るさが変化する)
4)M5Stack Grayで確認できた使用可能なPWMチャンネル
2,3,4,5,8,9,10,11,12,13,14,15