はじめに
どうも、倉澤ズズくんです。前回は足周りを設計しました。これを駆動するためにモータを回して、回転数が得られることを確認します。マイクロマウスに搭載するユニット毎(足周り部、距離測定センサ部、ジャイロセンサ部)にブレッドボード上で回路を組んで動作確認することで、実際の回路を安心して組める状態にします。
モータの運転と回転数の取得
今回はモータ出力とエンコーダ読み取りについて扱います。
- ソフトウェア
- モータ(+エンコーダ)
FAULHABER 1717sr
- モータドライバ(
DRV8835
) - エンコーダ(
IEH2-4096
) - 実験
ソフトウェア
今回の実験では自作した制御ライブラリMSLH
を使います。MSLH
はGitHubの
リポジトリ(https://github.com/KuraZuzu/MSLH)にて公開しています。プログラムの一部を抜粋して説明しますが、全体を見たい方はご参照ください。HAL
API(説明は後述)を用いて制作しています。
マウスに用いるマイコンSTM32F446
では、ツールSTM32CubeMX
を使って機能の設定と初期化を行い、HAL
かLL
のどちらかのAPIを選択します。HAL
はマイコンの各機能がメソッドとしてまとめられているので動かす上では非常に楽で、GPIOやPWMを駆動する際にも1行で済みます(初期化を除く)。ただし、複数の工程を踏むので実行速度が遅くライブラリのコード容量もかさみます。
LL
は低レイヤ寄りになるので、GPIOの出力だけでも数行の記述が必要となってしまいますが、実行速度が早くコードの容量も少ないです。
今回は制作期間を短縮できるHAL
APIでプログラムします。
モータ(+エンコーダ)FAULHABER 1717sr
DCモータを回すのは簡単です。モータの両端側に電圧を印加(バッテリー等で電圧を与える)すれば回ります。小学生の理科でソーラーカー等を組み立てたりした方も多いと思います。
今回使用するモータFAULHABER 1717sr
でも、データシートから抜粋した以下の画像に示すようにモータに繋がる端子は2つです。
FAULHABER 1717srの端子(データシートより引用)
(今回使用するものは、このモータに追加でエンコーダが取り付けられたものですので、実際の端子の見た目は異なります)
モータドライバ(DRV8835)
モータをただ回転させるにはバッテリーに繋げば完了します。ただし、問題としてはバッテリーに直につなぐと印加する電圧がバッテリー残量に依存し、回転の加減ができません。加えて、回転方向を変えることも難しいです。そこで登場するのがモータドライバです。これによってモータに印加する電圧を制御できます。以下の図はモータドライバの一例です。

モータドライバ “DRV6636”

モータドライバ “EIC4311”
今回使用するモータドライバはDRV8835
で、マイクロマウスではよく使われる型番です。DRV8835
は2×3[mm]の小さなICチップ(先程のDRV8836と同様のパッケージ)で省スペースですが、はんだ付けの手間がかかります。秋月電子で売っているDRV8835モジュールでは周辺回路に必要なコンデンサがはんだ付けされており、ピンヘッダも付いてきます。ブレットボードに挿して実験が可能となり、マウスの機体にそのまま実装もできます。

秋月電子の”DRV8835″が搭載されたモジュール
DRV8835
ではIN/INモードとPHASE/ENABLEの2つのモードが使えます。今回はPHASE/ENABLEモードを利用します。マイコン側から印加電圧の大きさを変更するPWMと回転方向を指定するデジタル出力を受け取り、これに応じてモータを回転させる信号を出力する方式です(下記画像はデータシートより引用)。
DRV8835のPHASE/ENABLEモード (データシートより引用)
実験には機体に搭載する型番と同様のSTM32マイコンを搭載した評価ボードNucleoF446
を使います。STM32シリーズではSTM32CubeMX
を用いてGUIでピンアサインを設定することが出来ます。以下の図は機体で使う機能全てのピンアサインを設定したものです。モータ用にはPWMとGPIOを設定しています。

STM32CubeMXのピンアサイン(赤丸がモータ部分)
エンコーダ(IEH2-4096)
モータに印加する電圧の制御だけでは回転数が得られないため回転速度の制御が出来ません。そこで必要となるのがエンコーダで、連続的な現象である回転数をデジタル信号として変換します。今回使うモータは磁気式エンコーダが搭載されたモデルのため、新たな部品は不要です。IEH2-4096
はインクリメンタル型で、2つの相(A相とB相と呼ぶ)が互い違いにパルスを発生させます。
回転時にどちらの相が先にパルスを発生させるかで回転方向を検出できます。また、一定の時間にどれだけパルスが発生するかで回転速度を図れます。IEH2-4096では1回転につき4096パルスを発生させます。

STM32CubeMXのピンアサイン(赤丸がエンコーダ部分)
STM32F446
ではタイマの機能としてエンコーダモードがあります。インクリメンタル方式のA・B相をそれぞれ特定のピンに接続すれば良いです。加えて、エンコーダには駆動電源として5[v]とGNDのピンも接続します(マイコンは3.3[v]での駆動に対し、5[v]を用意しなければいけないので注意)。
実験
実験として、モータを回転させてエンコーダで回転数を取得するプログラムで動作確認をします。ソースコードは見やすくするために一部抜粋して掲載しています。

モータとエンコーダの実験風景
モータ制御ライブラリ
motorクラスのプログラムについて簡単に説明すると、Duty比を指定することでモータの回転を制御します。mslh::Motor::update(float32_t duty_ratio)
で引数に与えられた通りのDuty比でモータが回転します。-1.0 ~ 1.0
の範囲で指定します。0 ~ 1.0
でDuty比の大きさを指定し、符号によって回転方向が決まります。例えば、update(0.2)
でDuty比0.2で正転、update(-0.5)
だとDuty比0.5で逆転します。
motor.h
#include "tim.h"
#include "digital_out.h"
#include "arm_math.h"
namespace mslh {
class Motor {
public:
// MotorのPWMと方向ピン、正転方向を定義
Motor(TIM_HandleTypeDef &htim_x, uint32_t channel, GPIO_TypeDef *phase_x, uint16_t phase_pin, bool cw);
// PWMのDuty比を設定
void update(float32_t duty_ratio);
private:
GPIO_TypeDef *_phase_x;
const uint16_t _phase_pin;
TIM_HandleTypeDef &_htim_x;
const uint64_t _channel;
const GPIO_PinState _forward_wise;
};
} // namespace mslh
motor.cpp
#include "motor.h"
mslh::Motor::Motor(TIM_HandleTypeDef &htim_x, uint32_t channel, GPIO_TypeDef *phase_x, uint16_t phase_pin, bool cw)
: _htim_x(htim_x)
, _channel(channel)
, _phase_x(phase_x)
, _phase_pin(phase_pin)
, _forward_wise(static_cast<GPIO_PinState>(cw)) {}
void mslh::Motor::update(float32_t duty_ratio) {
if (duty_ratio < -1.0f) duty_ratio = -1.0f; // Duty比が-1.0(-100%)を超えたときに100%にする
else if (duty_ratio > 1.0f) duty_ratio = 1.0f; // Duty比が1.0(100%)を超えたときに100%にする
HAL_GPIO_WritePin(_phase_x, _phase_pin, _forward_wise); // 正転方向を定義
// Toggle rotation wise, If duty_ratio less than 0.0.
if (duty_ratio < 0) {
HAL_GPIO_TogglePin(_phase_x, _phase_pin); //< 回転方向を設定
duty_ratio *= -1; //< Duty比がマイナスの際に正の値に戻す
}
__HAL_TIM_SET_COMPARE(&_htim_x, _channel, (duty_ratio * _htim_x.Init.Period));
}
エンコーダ制御ライブラリ
エンコーダもモータと同様にupdate()
を呼ぶ度に情報が更新され、getDeltaPulse()
は前回と最新で呼んだupdate()
の間に計測したエンコーダの差分パルスを得ます)。つまり、一定間隔でupdate()
を呼び、getDeltaPulse()
で値を読むことで秒間の発生パルス数が分かり、回転速度も得られます。
今回は動作の確認なので、パルスをカウントできていることだけが分かればいいです。計測開始時からの合計パルス数や回転数を得る機能を用い、while(1)
の無限ループ内でひたすらupdate()
を呼んでひたすら計測内容をコンソールに表示します。
encoder.h
#include "arm_math.h"
#include "tim.h"
namespace mslh {
class Encoder {
public:
// Encoderモードで使用するタイマの情報と正転方向を定義
Encoder(TIM_HandleTypeDef &htim_x, int32_t one_rotation_pulse, bool cw);
void update();
// 最新で呼んだ update() と前回呼んだ update() 時点でのパルス差分を取得(今回の実験では使わない)
[[gnu::warn_unused_result]] inline int32_t getDeltaPulse() const { return _delta_pulse; }
// 最新で呼んだ update() 時点での合計パルス数を取得
[[gnu::warn_unused_result]] inline int32_t getTotalPulse() const { return _total_pulse; }
//< 最新で呼んだ update() 時点での合計回転数を取得
[[gnu::warn_unused_result]] inline int32_t getRotationCount() const { return _total_pulse / _one_rotation_pulse; }
private:
int32_t _delta_pulse;
int32_t _total_pulse;
TIM_HandleTypeDef& _htim_x;
const bool _forward_wise;
const int32_t _one_rotation_pulse;
const uint32_t _offset_pulse ; //< (0x0FFF) 回転差分を得るためのオフセットパルス数
};
} // namespace mslh
encoder.cpp
#include "encoder.h"
mslh::Encoder::Encoder(TIM_HandleTypeDef &htim_x, int32_t one_rotation_pulse, bool cw)
: _delta_pulse(0)
, _total_pulse(0)
, _htim_x(htim_x)
, _offset_pulse(__HAL_TIM_GET_AUTORELOAD(&_htim_x) / 2 - 1)
, _one_rotation_pulse(one_rotation_pulse) //< 計算高速化のため.
, _forward_wise(cw)
{}
void mslh::Encoder::update() {
uint32_t pulse_count = __HAL_TIM_GET_COUNTER(&_htim_x);
__HAL_TIM_SET_COUNTER(&_htim_x, _offset_pulse);
/// _delta_pulse を更新
_delta_pulse = static_cast<int32_t>(pulse_count - _offset_pulse);
/// _forward_wise が true の時にカウントアップとする
if (!_forward_wise) _delta_pulse *= -1;
/// _total_pulse を更新
_total_pulse += _delta_pulse;
}
実験プログラム(モータ回転&エンコーダ計測)
ライブラリ自体は過去のマウスでも使用しており、動作が確認されているため、回路が正しく接続されて信号が出力・受信されているか確認します。
void test_motor_encoder_drive() {
mslh::Motor motor(htim1, TIM_CHANNEL_1, GPIOB, GPIO_PIN_10, 0);
motor.start();
motor.update(0.08); // Duty:0.08 正転
HAL_Delay(2000); // 2秒待機
motor.update(0.08); // Duty:0.08 正転
HAL_Delay(1000); // 1秒待機
motor.update(-0.1); // Duty:0.1 逆転
mslh::Encoder encoder(htim3, 4096*4, 0);
encoder.start();
encoder.reset();
while (1) {
encoder.update(); // エンコーダの情報をアップデート
const int32_t rotation_count = encoder.getRotationCount();
const int32_t total_pulse = encoder.getTotalPulse();
printf("回転数:%d パルス数%d\r\n", rotation_count, total_pulse);
}
}
実際に動かした動画が以下になります。モータが回転してパルス・回転数が取得できています。
まとめ
モータとエンコーダを駆動させて動作確認をしました。実際にこの接続方法で回路を組んでも大丈夫そうです。
次回は距離センサについて実験します。そして、今回が大会前最後のブログ更新となります(大会後もブログは継続します)。
東北地区大会まで、残り2日!