ESP32パルスカウント機能の利用

2025.7.2 Coskx Lab  

1 はじめに

ESP32S3でロータリエンコーダのパルスをカウントします。
ロータリエンコーダは,回転軸の回転角を測定する機構でアブソリュート型とインクリメンタル型があります。
インクリメンタル型ロータリエンコーダでは,出力パルスを数えて,回転角度を取得します。
正逆回転が混ざった動作でも正しく回転角を得られるように,2系統のパルスが出力されます。
構造的には光学式と磁気式がありますが,2系統のパルスが出力されることに変わりありません。
2系統のパルスはA相,B相と呼ばれ,次のような形状です。A相とB相では位相が1/4ずれていて,正転・逆転を比較するとA相に対するB相の位相が進んだり遅れたりしています。



回転軸が1回転する間に,数パルス発生するものから,10000パルスを超えるものまで製品化されています。ギヤドモータのモータ軸に直接取り付けるなら数パルスのものが使われますが,ギヤドモータの出力軸に取り付けるなら数千パルス以上のものが使われるでしょう。

次の写真はギアドモータのモータ軸(モータの後端部)に付けられた磁気センサを使用したロータリエンコーダの例です。



光学式ロータリエンコーダでは,次の図のようにスリットが入った円板(4スリットの例)と2つのセンサがあります。円板が回転すると2つのセンサからは先の図のような位相がずれた信号が得られます。



(1)パルス発生機構と正逆転を正しくカウントする方法

パルス発生機構は回転検出のため,リング状のものですが,検討のため次のような直線移動の機構を想定します。

図では現在A相,B相センサともにLを検出しています。
図の状態から帯状板が右方向に少し動くとA相センサはHになり,B相センサはLを保ちます。
また図の状態から帯状板が左方向に少し動くとA相センサはLを保ち,B相センサはHになります。



帯状板が左方向に移動したらカウントアップし,逆だったらカウントダウンすることにし,
「B相センサがLのとき,A相センサがLからHに変化したらカウントダウン,A相センサがHからLに変化したら,カウントアップする」
というルールを採用します。
(下図で状態1から状態2に変化したらカウントダウン,状態2から状態1に変化したらカウントアップ)



LからHに変化することを正エッジ,HからLに変化することを負エッジとも表現されるので
「B相センサがLのとき,A相センサが正エッジを検出したらカウントダウン,A相センサが負エッジを検出したら,カウントアップする」
とも表現できます。
このルールでは,Aセンサ信号の一周期に一回カウントされる基本カウントです。Pの位置がカウントされます。
(B相センサがHのとき,Aセンサがエッジを検出しても何もしません。Qの位置は無視です。)

(2)正逆転をカウントするルール

正逆転をカウントするルールは3つ考えられます。

  1. 基本カウント
    B相センサがLのとき,A相センサがLからHに変化したらカウントアップ,A相センサがHからLに変化したら,カウントダウンする
    B相センサがHのときはなにもしない
    (Pのみで数える)
    A相信号の一周期に1回数えます
  2. 2倍カウント
    B相センサがLのとき,A相センサがLからHに変化したらカウントアップ,A相センサがHからLに変化したら,カウントダウンする
    B相センサがHのとき,A相センサがHからLに変化したらカウントアップ,A相センサがLからHに変化したら,カウントダウンする
    (P,Qで数える)
    A相信号の一周期に2回数えます
  3. 4倍カウント
    B相センサがLのとき,A相センサがLからHに変化したらカウントアップ,A相センサがHからLに変化したら,カウントダウンする
    B相センサがHのとき,A相センサがHからLに変化したらカウントアップ,A相センサがLからHに変化したら,カウントダウンする
    A相センサがLのとき,B相センサがHからLに変化したらカウントアップ,B相センサがLからHに変化したら,カウントダウンする
    A相センサがHのとき,B相センサがLからHに変化したらカウントアップ,B相センサがHからLに変化したら,カウントダウンする
    (P,Qで数える)
    A相信号の一周期に4回数えます

(3)ESP32のうれしい機能

正逆転をカウントするルールをプログラムで記述することもできます。エッジ割り込みやポーリングを使うことになります。その場合,ソフトウエアの動作では,カウントに多くの時間を割くことになってしまします
ESP32にはロータリエンコーダの二相信号を想定したハードウエアのカウンタが搭載されています。これを使うと,プログラム側は読みだしたいときにこのカウンタを読みだすだけになります。
このハードウエアカウンタを使用するには,パルスカウントライブラリを使うのですが,新旧2つのライブラリがあります。旧ライブラリはpcntで,新しいライブラリはpulse_cntです。
pcntはすでにDeprecatedとなっていますが,pulse_cntはArduinoIDEに移植中と思われ,サンプルプログラムを試した多ころ,コンパイルは通るのですが,実行時にエラーが続出となってしまいます。
そのため,ここでは旧ライブラリpcntを使用します。

ESP32は何を使っても良いはずですが,ここではXiao ESP32S3を使用します。


パルスカウントライブラリに関しましては以下の解説を参考にいたしました。 感謝申し上げます。
https://qiita.com/wanko_in_lunch/items/a508d8da78961c855d7f
https://esp-idf-zh.readthedocs.io/zh-cn/latest/api-reference/peripherals/pcnt.html

2 使用環境

3 ロータリエンコーダの配線

ロータリエンコーダからは4本の配線が出ており,そのうち2つは電源VDD(3.3V)とGNDです。残りの2つはA相信号とB相信号です。
A相信号とB相信号はXiao ESP32S3の端子に次のように接続することにします。
 D7 ー A相信号
 D8 ー B相信号
(A相信号とB相信号は逆でも差し支えありません。正転とみなす回転方向が逆になるだけです。)


4 ロータリエンコーダ用ライブラリpcnt

ライブラリpcntの起動停止,カウンタクリア,カウンタ読み出しは関数を呼ぶだけなので簡単です。
設定用構造体 pcnt_config の構成が面倒です。
カウントするルールが3つあるため,それぞれに合わせた設定が必要です。
カウントルール設定用の構造体メンバは4つあります。
ここの説明では,A相信号をpulse信号,B相信号をcontrol信号と表しています。

 pos_mode
 neg_mode
 lctrl_mode
 hctrl_mode

pos_modeとneg_modeはそれぞれ「pulse信号の正エッジを検出した際にどうするか」,「pulse信号の負エッジを検出した際にどうするか」を決めます。ただし,次のlctrl_modeとhctrl_modeの設定によってはこの設定が無効にされたり,反転されたりします。

lctrl_modeとhctrl_modeは,それぞれ「control信号がLの時」と「control信号がHの時」に,pulse信号の正負エッジが来た時にpos_modeとneg_modeの設定をどう修正するかを決めます。

pos_modeとneg_modeのそれぞれに設定できる定数は次の3つです。
 PCNT_COUNT_DIS → カウントしない
 PCNT_COUNT_INC → インクリメント(カウントアップ)
 PCNT_COUNT_DEC → デクリメント(カウントダウン)

lctrl_modeとhctrl_modeのそれぞれに設定できる定数は次の3つです。
 PCNT_MODE_KEEP → pos_modeとneg_modeでの設定どおり動作
 PCNT_MODE_REVERSE → pos_modeとneg_modeでのINC,DECを逆にして動作
 PCNT_MODE_DISABLE → カウントしない

そのため,基本カウント(Pでカウント)では次のように設定します。
 lctrl_mode = PCNT_MODE_KEEP;
 hctrl_mode = PCNT_MODE_DISABLE;
 pos_mode = PCNT_COUNT_INC;
 neg_mode = PCNT_COUNT_DEC;

また,2倍カウント(P,Qでカウント)では次のように設定します。
 lctrl_mode = PCNT_MODE_KEEP;
 hctrl_mode = PCNT_MODE_REVERSE;
 pos_mode = PCNT_COUNT_INC;
 neg_mode = PCNT_COUNT_DEC;

さらに4倍カウントでは2倍カウントの設定を,pulse信号とcontrol信号を逆に読み替え,lctrl_modeとhctrl_modeを逆にし,チャンネルを異にした設定をもう一つ作ります。

このほかには次のようなものがあります。
pulse信号とcontrol信号を与えているピン番号を指定する構造体メンバ
 pulse_gpio_num
 ctrl_gpio_num
チャンネルを指定する構造体メンバ
 channel  → PCNT_CHANNEL_0,PCNT_CHANNEL_1
パルスカウントユニットを指定する構造体メンバ
 unit  → PCNT_UNIT_0 から PCNT_UNIT_7
カウンタ値の上限下限(クリアされる値)を定める構造体メンバ
 counter_h_lim
 counter_l_lim
(これは必要で,これがないとおかしな値でクリアされる)
(両方0に設定すると16bitカウンタがフルに使える)

5 動作テスト用プログラム

このプログラムではロータリエンコーダ値を基本カウント方式で読み込みます。
ロータリエンコーダのA相信号,B相信号は,それぞれ D7,D8 に接続されています。

基本カウントの設定
・pos_mode = PCNT_COUNT_INC;
 pulse信号の正エッジではカウントアップする
・neg_mode = PCNT_COUNT_DEC;
 pulse信号の負エッジではカウントダウンする
・lctrl_mode = PCNT_MODE_KEEP;
 control信号がLのとき,pulse信号のエッジ検出時には
 pos_mode,neg_mode通りに動作する
・hctrl_mode = PCNT_MODE_DISABLE;
 control信号がHのとき,pulse信号のエッジ検出時には
 pos_mode,neg_modeの設定を無視してなにもしない

  動作テスト用プログラム本体

//pulse_counter_test0.ino

# include "driver/pcnt.h"

# define PULSE_INPUT_PIN D7 //パルスの入力ピン 今回はエンコーダのA相を接続
# define PULSE_CTRL_PIN D8 //制御ピン 今回はエンコーダのB相を接続
# define PCNT_H_LIM_VAL 0 //カウンタの上限 これで設定なしになる
# define PCNT_L_LIM_VAL 0 //カウンタの下限 これで設定なしになる

void setup() {
  pcnt_config_t pcnt_config;      //設定用のpcnt_config構造体の宣言
    pcnt_config.pulse_gpio_num = PULSE_INPUT_PIN;
    pcnt_config.ctrl_gpio_num = PULSE_CTRL_PIN;
    pcnt_config.lctrl_mode = PCNT_MODE_KEEP;
    pcnt_config.hctrl_mode = PCNT_MODE_DISABLE;
    pcnt_config.channel = PCNT_CHANNEL_0;
    pcnt_config.unit = PCNT_UNIT_0;
    pcnt_config.pos_mode = PCNT_COUNT_INC;
    pcnt_config.neg_mode = PCNT_COUNT_DEC;
    pcnt_config.counter_h_lim = PCNT_H_LIM_VAL;  //これは必要 これがないとおかしな値でクリアされる
    pcnt_config.counter_l_lim = PCNT_L_LIM_VAL;  //これは必要 これがないとおかしな値でクリアされる
  pcnt_unit_config(&pcnt_config);//ユニット初期化
  pcnt_set_filter_value(PCNT_UNIT_0, 100); // 1023まで 100 は1.25microsec以下の短いパルスを無視する設定
  pcnt_filter_enable(PCNT_UNIT_0);
  pcnt_counter_pause(PCNT_UNIT_0);//カウンタ一時停止
  pcnt_counter_clear(PCNT_UNIT_0);//カウンタ初期化
  Serial.begin(115200);
  delay(1000);
  pcnt_counter_resume(PCNT_UNIT_0);//カウント開始
}

void loop() {
  int16_t count = 0; //カウント数
  pcnt_get_counter_value(PCNT_UNIT_0, &count);
  Serial.print("Counter value: ");
  Serial.println(count);
  delay(1000);
}

実行結果
次のように16ビットの符号付き変数の境界値(-32768..32767)で循環して見えます。

Counter value: 31702
Counter value: 32133
Counter value: 32505
Counter value: -32658
Counter value: -32360
Counter value: -32114
Counter value: -31779

6 基本カウントカウンタのクラス化

基本カウントするカウンタをクラス化しました。ロータリエンコーダ付のギヤドモータを2つ使う際には便利です。
このプログラムでは2つのロータリエンコーダ値を基本カウント方式で読み込みます。
ロータリエンコーダ1のA相信号,B相信号は,それぞれ D7,D8 に接続されています。
ロータリエンコーダ2のA相信号,B相信号は,それぞれ D9,D10 に接続されています。

2つのロータリエンコーダのカウントを読むメインプログラム

//pulse_counter_classtest.ino

#include <IncRotaryEncoder.h>

IncRotaryEncoder re_right;
IncRotaryEncoder re_left;


void setup() {
  re_right.initialize(D7, D8, 0);
  re_left.initialize(D9, D10, 1);
  Serial.begin(115200);
  delay(1000);
  re_right.startCount();
  re_left.startCount();
}

void loop() {
  long int rightwheel = re_right.getCount();
  long int leftwheel = re_left.getCount();
  Serial.print("Counter value: ");
  Serial.print(rightwheel);
  Serial.print(", ");
  Serial.println(leftwheel);
  delay(500);
}

このクラスでは,カウンタ値が循環するのをソフトウエアで防いでいます。(カウンタオーバフローへの対処)

クラスソース

//IncRotaryEncoder.h

//インクリメンタルロータリエンコーダのパルスカウントをESP32の2相パルスカウント機能を使って行います
//2つのピンへの入力信号はロータリエンコーダのA相信号とB相信号です
//A相信号はパルス信号,B相信号はコントロール信号として扱います
//1倍カウントとし,コントロール信号がLのとき,
//   パルス信号の正エッジによりカウントアップ
//  パルス信号の負エッジによりカウントダウン
//とします。
//コントロール信号がHのときパルス信号にエッジが現れても何もしません。

#include <driver/pcnt.h>

#ifndef INC_ROTARY_ENCODER_h
#define INC_ROTARY_ENCODER_h

class IncRotaryEncoder {
public:
  IncRotaryEncoder(void){};
  void initialize(uint8_t inputpin1, uint8_t inputpin2, uint8_t resourcenumber);
   //inputpin1, inputpin2: rotaryencoder pin assigns, resourcenumber: 0 or 1
   //resourcenumber: 0, 1
  void startCount(void);
  void clearCount(void);
  void addCount(int step);
  long int getCount(void);

private:
  uint8_t pin1, pin2;
  pcnt_unit_t unit; 
  const pcnt_channel_t channels[2] ={PCNT_CHANNEL_0, PCNT_CHANNEL_1};
  const pcnt_unit_t units[2] ={PCNT_UNIT_0, PCNT_UNIT_1};
  int stepstobeadded = 0;
  long int lcount = 0L;
  long int lcountprev = 0L;
};
#endif

//IncRotaryEncoder.cpp

#include <IncRotaryEncoder.h>

void IncRotaryEncoder::initialize(uint8_t inputpin1, uint8_t inputpin2, uint8_t resourcenumber) {
  //inputpin1, inputpin2: rotaryencoder pin assigns
  //resourcenumber: 0, 1
  unit = units[resourcenumber];
  pcnt_config_t pcnt_config;//設定用の構造体の宣言   基本カウント
        pcnt_config.pulse_gpio_num = inputpin1;
        pcnt_config.ctrl_gpio_num = inputpin2;
        pcnt_config.lctrl_mode = PCNT_MODE_KEEP;
        pcnt_config.hctrl_mode = PCNT_MODE_DISABLE;
        pcnt_config.channel = channels[resourcenumber];
        pcnt_config.unit = unit;
        pcnt_config.pos_mode = PCNT_COUNT_INC;
        pcnt_config.neg_mode = PCNT_COUNT_DEC;
        pcnt_config.counter_h_lim = 0;
        pcnt_config.counter_l_lim = 0;
  pcnt_unit_config(&pcnt_config);//ユニット初期化
  pcnt_set_filter_value(unit, 100); // 1023まで 100 は1.25microsec以下の短いパルスを無視する設定
  pcnt_filter_enable(unit);
  pcnt_counter_pause(unit);//カウンタ一時停止
  pcnt_counter_clear(unit);//カウンタ初期化
}
void IncRotaryEncoder::startCount(void) {
  pcnt_counter_resume(unit);
}
void IncRotaryEncoder::clearCount(void){
  pcnt_counter_clear(unit);
  lcount = 0L;
  lcountprev = 0L;
  stepstobeadded = 0;
}
void IncRotaryEncoder::addCount(int step){
  stepstobeadded += step;
}
long int IncRotaryEncoder::getCount(void){
  int16_t count;
  pcnt_get_counter_value(unit, &count);
  lcount = count;
  while (lcount < lcountprev - 60000) lcount += 65536;
  while (lcountprev + 60000 < lcount) lcount -= 65536;
  lcountprev = lcount;
  long int ret = lcount + stepstobeadded;
  return ret;
}

実行結果

Counter value: 0, 0
Counter value: 0, 0
Counter value: 0, 0
Counter value: 0, 1
Counter value: 3, 5
Counter value: 82, 78
Counter value: 82, 78
Counter value: 82, 77
Counter value: 8, 10
Counter value: -47, -18
Counter value: -47, -17
Counter value: -60, -45
Counter value: -125, -105
Counter value: -124, -104
Counter value: -148, -106

7 まとめ

ESP32が持っている二相パルス信号カウント機能を使ったロータリエンコーダカウント取得プログラムを制作しました。基本カウント方式でカウントします。