ESP32マウス(shota)マウス自作研修

ESP32マウスPart.36 SPIで磁気式エンコーダMA702を使う

ESP32マウス(shota)

こんにちは、shotaです。

前回の記事ではMCPWMの周波数とデューティの関係を調査し、モータを回しました。

モータが回ったので、エンコーダで回転数を読み取りたいですよね。
今回はSPI機能を使ってエンコーダICのデータを読み取ります。

ブロクで書いたサンプルコードはGitHubに公開しています。
https://github.com/ShotaAk/especial/tree/master/examples

初めてのオリジナルマウス Especial

プログラムを書く前の下準備

さて今回もプログラムを書く前に、Especialの回路図やESP32モジュールのデータシートを読み、情報を集めます。

エンコーダ回路の回路図を確認

まずはじめに、Especialの回路図を確認します。

↓Especialの回路図はこちらです。今回必要なところは、エンコーダ回路です。
especial回路図.pdf

↓エンコーダ回路の設計ブログ記事はこちらです
shotaのマイクロマウス研修16[回路設計④ モータドライバ・エンコーダ回路]

Especial – エンコーダ回路

Especial – エンコーダコネクタ

Especial – ESP32の接続先

エンコーダ回路は、ENC_CS_{L,R}ENC_SCLKENC_MOSIENC_MISOでエンコーダICのMA702とやり取りします。
エンコーダICはL,Rで2個あるのに対し、通信線はCSが2本で、SCLKMOSIMISOが共通であるところが、SPI通信の良いところですね。

ピンの接続先は次のとおりです。

  • ENC_CS_LはIO15
  • ENC_CS_RはIO27
  • ENC_SCLKはIO14
  • ENC_MOSIはIO13
  • ENC_MISOはIO12
  • 回路の情報は揃いました。
    つづいて、ESP32-SPI機能について情報を集めます。

    ESP32のSPI機能について調査

    参考にした資料は、ESP-IDF Programming GuideのSPI Master driverのページと、ESP32 Technical Reference Manualです。

    ESP32で扱えるSPIデバイス

    まず、テクニカルリファレンスマニュアルの7章SPIにある、SPI Architectureを見てみましょう。

    ESP32 SPI Architecture
    https://www.espressif.com/sites/default/files/documentation/esp32_technical_reference_manual_en.pdf

    この図はESP32チップ(SoC)が搭載するSPIモジュールの内部設計図です。
    図の右端にあるPADは、ESP32チップの外側から見える金属端子です。
    この金属端子には、ESP32モジュールとESP32開発ボードのGPIOピンがつながります。

    図の真ん中にあるSPI0〜SPI3が、ESP32で扱えるSPIデバイスです。合計4つあります。

    SPI0はCacheというブロックに接続されています。
    CacheはESP32に接続される外部フラッシュメモリ(ESP32モジュール内の4MBフラッシュメモリ)用の記憶領域で、使用頻度の高いデータが格納されます。
    SPI0は外部フラッシュメモリとの通信のバッファとして使用されます。
    つまり、SPI0はフラッシュメモリとの通信専用デバイスです。
    3つあるPADの1番上にフラッシュメモリが接続されていると考えてください。

    SPI1にはSPI0と同じ通信経路が接続されています。
    SPI1はフラッシュメモリとやり取りしないので、ユーザが使えそうに見えます。
    しかし、SPI0がフラッシュメモリとやり取りしているので、通信経路が使えません。
    つまり、ESP32モジュールの内部フラッシュメモリを使う限り、SPI0もSPI1も使えません。残念。

    残りのSPI2とSPI3が、ユーザが自由に使えるSPIデバイスです。それぞれの通信経路には、HSPIVSPIという名前が付けられています。
    (SPI0とSPI1の通信経路にはSPIという名前が付けられています。)

    さて、右側にはI/O MUX(マルチプレクサ)と、GPIO Matrixという謎のブロックがあります。
    実はこのブロックのおかげで、ほとんどのGPIOピンでSPI機能が使えるのです。

    テクニカルリファレンスマニュアルの4章 IO_MUX and GPIO Matrixを見てみましょう。

    https://www.espressif.com/sites/default/files/documentation/esp32_technical_reference_manual_en.pdf

    ESP32のペリフェラル(SPIやUARTやPWMなど)はGPIO Matrixブロックに接続されます。
    このブロックには、ほぼすべての(全てではない)GPIOピンが接続されているので、
    すきなGPIOピンにペリフェラルを割り当てることができます。

    ただ、GPIO Matrixを経由すると高速通信ができません。それを切り替えるのがI/O MUXです。
    I/O MUXは、ペリフェラルをGPIOピンに直接接続するか、GPIO Matrixを経由して接続するかを切り替えられます。
    その変わり、ペリフェラルが直接接続されたGPIOピンは限られているので、ご注意ください。

    SPIのIOMUXピンはどのGPIOピン?

    テクニカルリファレンスマニュアルの4.10 IO_MUX Pad Listに一覧が書かれていますが、
    すべてのペリフェラルが書かれているので情報量が多いです。

    プログラミングガイドにSPIの情報がまとめられているので見てみましょう。

    次の表が、SPIのIOMUXピンの一覧です。

    ESP32 SPIのIOMUXピン

    この表と私のマウスを比べて見ると分かるように、
    私のESP32マウスはHSPIを使うように設計されています。

    ではIOMUXピンを使うとどれだけ早い通信ができるのでしょうか?
    ページにはこう書かれています。

    When the GPIO matrix is used, signals faster than 40MHz cannot propagate and the setup time of MISO is more easily violated, since the input delay of MISO signal is increased. The maximum clock frequency with GPIO Matrix is 40MHz or less, whereas using all IOMUX pins allows 80MHz.

    GPIO Matrixを使うと40MHzまでの通信速度で、IOMUXピンを使うと80MHzまでの速度が使える、とのこと。
    (40MHzでも十分速い気がしますが)80MHzまで使えて嬉しいですね。

    プログラムの作成

    それではプログラムを作成して、実際に動かしながらSPIへの理解を深めましょう。

    参考にしたサンプルコードはexamples/peripherals/spi_masterです。

    esp-idf/examples/peripherals/spi_master at v3.3.1 · espressif/esp-idf
    Espressif IoT Development Framework. Official development framework for Espressif SoCs. - espressif/esp-idf

    そして、作成したコードのがこちらです。
    行数が多いのでGitHubにアップロードしたコードも参照してください。
    アップロードしたコードにはコメントをたくさん書いています。

    especial/examples/5_encoder/main/main.c at master · ShotaAk/especial
    ESP32を搭載したマイクロマウスのプログラム. Contribute to ShotaAk/especial development by creating an account on GitHub.
    #include <stdio.h>
    #include <math.h>
    #include <string.h>
    #include "freertos/FreeRTOS.h"
    #include "freertos/task.h"
    #include "driver/spi_master.h"
    
    enum SIDE{
        LEFT = 0,
        RIGHT,
        SIDE_SIZE
    };
    
    const size_t DATA_LENGTH = 16;
    
    uint16_t readData(const spi_device_handle_t spidev){
        // MA702から16ビットデータを受け取る
        uint16_t recv_data;
        spi_transaction_t trans;
        memset(&trans, 0, sizeof(trans)); // 構造体をゼロで初期化
        trans.length = DATA_LENGTH; // データ長 bit
        trans.rx_buffer = &recv_data; // 受信バッファのポインタ
    
        esp_err_t ret;
        ret=spi_device_polling_transmit(spidev, &trans);
        assert(ret==ESP_OK);
        return SPI_SWAP_DATA_RX(recv_data, DATA_LENGTH);
    }
    
    uint16_t sendCmdAddrData(const spi_device_handle_t spidev,
            const uint8_t command, const uint8_t address, const uint8_t data){
        // MA702にコマンドとアドレスとデータを送信する
        uint16_t recv_data;
        uint16_t tx_data = command;
        tx_data = (tx_data << 5) | address;
        tx_data = (tx_data << 8) | data;
        tx_data = SPI_SWAP_DATA_TX(tx_data, DATA_LENGTH);
    
        spi_transaction_t trans;
        memset(&trans, 0, sizeof(trans));
        trans.length = DATA_LENGTH;
        trans.tx_buffer = &tx_data;
        trans.rx_buffer = &recv_data;
    
        esp_err_t ret;
        ret=spi_device_polling_transmit(spidev, &trans);
        assert(ret==ESP_OK);
    
        return SPI_SWAP_DATA_RX(recv_data, DATA_LENGTH);
    }
    
    float getAngle(const spi_device_handle_t spidev){
        // MA702から角度データを取得し、ラジアンに変換する
        const uint16_t RESOLUTION = 4096;
    
        uint16_t rawData = readData(spidev);
        rawData >>=4;
        return 2.0*M_PI * (float)rawData / RESOLUTION;
    }
    
    uint8_t readRegister(const spi_device_handle_t spidev, const uint8_t address){
        // MA702のレジスタデータを読み取る
        const uint16_t READ_COMMAND = 0b010;
    
        sendCmdAddrData(spidev, READ_COMMAND, address, 0x00);
        uint16_t rawData = readData(spidev);
        return rawData >>=8;
    }
    
    uint8_t writeRegister(const spi_device_handle_t spidev, const uint8_t address, const uint8_t data){
        // MA702のレジスタにデータを書き込む
        const uint16_t WRITE_COMMAND = 0b100;
    
        sendCmdAddrData(spidev, WRITE_COMMAND, address, data);
        vTaskDelay(20 / portTICK_PERIOD_MS);
        uint16_t rawData = readData(spidev);
        return rawData >>=8;
    }
    
    void app_main(){
        static const gpio_num_t GPIO_HSPI_CS[SIDE_SIZE] 
            = {GPIO_NUM_15, GPIO_NUM_27};
        static const gpio_num_t GPIO_HSPI_SCLK = GPIO_NUM_14;
        static const gpio_num_t GPIO_HSPI_MOSI = GPIO_NUM_13;
        static const gpio_num_t GPIO_HSPI_MISO = GPIO_NUM_12;
    
        esp_err_t ret;
        spi_bus_config_t buscfg = {
            .mosi_io_num = GPIO_HSPI_MOSI, // Master Out Slave Inのピン
            .miso_io_num = GPIO_HSPI_MISO, // Master In Slave Outのピン
            .sclk_io_num = GPIO_HSPI_SCLK, // SPI Clockのピン
            .quadwp_io_num = -1, // Quad SPIのWPピン。使わないので-1をセット。
            .quadhd_io_num = -1, // Quad SPIのHDピン。使わないので-1をセット。
            .max_transfer_sz = 2, // 最大送信バイト数。
            .flags = SPICOMMON_BUSFLAG_MASTER | SPICOMMON_BUSFLAG_NATIVE_PINS,
        };
        ret = spi_bus_initialize(HSPI_HOST, &buscfg, 1);
        ESP_ERROR_CHECK(ret);
    
        spi_device_interface_config_t devcfg = {
            .mode = 3, // SPIのモード
            .clock_speed_hz = SPI_MASTER_FREQ_20M, // クロックスピード。80MHz の分周
            .input_delay_ns = 15, 
            .queue_size = 1, // transactionのキュー数。1以上の値を入れておく。
        };
    
        spi_device_handle_t spidev[SIDE_SIZE];
    
        devcfg.spics_io_num = GPIO_HSPI_CS[LEFT];
        ret = spi_bus_add_device(HSPI_HOST, &devcfg, &spidev[LEFT]);
        ESP_ERROR_CHECK(ret);
    
        devcfg.spics_io_num = GPIO_HSPI_CS[RIGHT];
        ret = spi_bus_add_device(HSPI_HOST, &devcfg, &spidev[RIGHT]);
        ESP_ERROR_CHECK(ret);
    
        uint8_t address = 0b01001; // Rotation Direction
        uint8_t data = 0x80; // 回転方向を逆にする
        uint8_t reg_value;
        reg_value = writeRegister(spidev[LEFT], address, data);
        printf("write: side:%d, address:%x, value:%x\n", LEFT, address, reg_value);
    
        reg_value = readRegister(spidev[LEFT], address);
        printf("read: side:%d, address:%x, value:%x\n", LEFT, address, reg_value);
        vTaskDelay(2000 / portTICK_PERIOD_MS);
    
    
        float wheelAngle[SIDE_SIZE];
        while(1){
            wheelAngle[LEFT] = getAngle(spidev[LEFT]);
            wheelAngle[RIGHT] = getAngle(spidev[RIGHT]);
            
            wheelAngle[LEFT] *= 180.0/M_PI; // radian to degree
            wheelAngle[RIGHT] *= 180.0/M_PI;
            printf("wheelAngle: %f, %f\n",wheelAngle[LEFT], wheelAngle[RIGHT]);
            vTaskDelay(10 / portTICK_PERIOD_MS);
        }
    }
    

    それでは実行してみましょう。

    $ cd ~/esp/especial/examples/5_encoder 
    $ make flash monitor
    --- 省略 ---
    wheelAngle: 90.263672, 285.556641
    wheelAngle: 87.011719, 282.919922
    wheelAngle: 82.968750, 279.667969
    wheelAngle: 78.574219, 275.712891
    wheelAngle: 73.125000, 271.230469
    wheelAngle: 66.884766, 265.869141
    wheelAngle: 60.468750, 259.804688
    wheelAngle: 53.349609, 253.125000
    wheelAngle: 46.142578, 246.181625
    wheelAngle: 38.496094, 238.886719
    wheelAngle: 30.058594, 231.064453
    wheelAngle: 20.917969, 222.714844
    wheelAngle: 11.074219, 213.662109
    wheelAngle: 0.703125, 204.082031
    

    実行すると、10ミリ秒毎に左右のホイール角度が表示されます。

    プログラムの解説

    それでは作成したプログラムを解説します。
    ちょっと長いですが、理解しやすいように丁寧に説明します!

    SPI機能設定

    まず、SPI機能やprintf関数、vTaskDelay関数等を使うためにライブラリをインクルードします。

    #include <stdio.h>
    #include <math.h>
    #include <string.h>
    #include "freertos/FreeRTOS.h"
    #include "freertos/task.h"
    #include "driver/spi_master.h"
    

    次に、app_main関数内でSPI機能を設定します。
    SPIの設定はspi_bus_config_t構造体を使ったSPIバスの設定と、
    spi_device_interface_config_t構造体を使ったSPIデバイスの設定の2つがあります。

    SPIバスでは、GPIOピンの割り当て(MOSI、MISO、SCLK)と、
    送信データバイト数、フラグを設定します。
    エンコーダICのMA702とは16ビット(2バイト)データでやり取りするため、
    最大送信バイト数は2にしています。

    フラグにはSPIOCOMMON_BUSFLAG_MASTERと、SPICOMMON_BUSFLAG_NATIVE_PINSを設定していますが、
    今回の例では設定してもしなくても結果は変わりません。
    SPIマスターであることと、IOMUXピンを使うことを明示するために設定しています。

    void app_main(){
        static const gpio_num_t GPIO_HSPI_CS[SIDE_SIZE] 
            = {GPIO_NUM_15, GPIO_NUM_27};
        static const gpio_num_t GPIO_HSPI_SCLK = GPIO_NUM_14;
        static const gpio_num_t GPIO_HSPI_MOSI = GPIO_NUM_13;
        static const gpio_num_t GPIO_HSPI_MISO = GPIO_NUM_12;
    
        esp_err_t ret;
        // SPIバスの設定
        spi_bus_config_t buscfg = {
            .mosi_io_num = GPIO_HSPI_MOSI, // Master Out Slave Inのピン
            .miso_io_num = GPIO_HSPI_MISO, // Master In Slave Outのピン
            .sclk_io_num = GPIO_HSPI_SCLK, // SPI Clockのピン
            .quadwp_io_num = -1, // Quad SPIのWPピン。使わないので-1をセット。
            .quadhd_io_num = -1, // Quad SPIのHDピン。使わないので-1をセット。
            .max_transfer_sz = 2, // 最大送信バイト数。
            // flags: SPICOMMON_BUSFLAG_で始まるフラグをセットできる
            .flags = SPICOMMON_BUSFLAG_MASTER | SPICOMMON_BUSFLAG_NATIVE_PINS,
            // .intr_flags = NULL, // 割り込みの優先順位フラグ
        };
        ret = spi_bus_initialize(HSPI_HOST, &buscfg, 1);
        ESP_ERROR_CHECK(ret);
    

    SPIデバイスでは、SPIモードや、クロックスピード、CSピン等を設定します。
    また、本来であればコマンドビット数とアドレスビット数を設定しますが、
    MA702はコマンドとアドレスを指定しなくても角度情報を受信できるので、設定不要です。 

    モードとクロックスピードはMA702のデータシートを参考にしました。
    MA702とは最大25MHzでSPI通信できます。
    そのため、IOMUXピンの最大性能80MHzを試すことができません。残念。

        // SPIデバイスの設定
        spi_device_interface_config_t devcfg = {
            // MA702では角度取得時にコマンドアドレスを使用しないので、
            //   command_bitsとaddress_bitsはセットしない
            // .command_bits = 3, // コマンドフェーズのビット長
            // .address_bits = 5, // アドレスフェーズのビット長
            // .dummy_bits = 8, // アドレスフェーズとデータフェーズ間のビット長
            .mode = 3, // SPIのモード
            // .duty_cycle_pos 128, // クロックのデューティ比。デフォルト50%
            // .cs_ena_posttrans = 0, // 半二重通信で送信処理後CSをアクティブにし続けるサイクル数
            .clock_speed_hz = SPI_MASTER_FREQ_20M, // クロックスピード。80MHz の分周
            // input_delay_ns: SCLKとMISOの間にある、
            //   スレーブのデータが有効になるまでの最大遅延時間。
            //   CSをアクティブにして、MISOが送信されるまでに、追加で遅延を設ける。
            //   8MHz以上のクロックスピードを使うときに必要だけど、
            //   正確な値が分からなければ0を設定してね。
            .input_delay_ns = 15, 
            // .spics_io_num // CSピン。後ほど設定する
            // .flags = NULL, // SPI_DEVICE_で始まるフラグを設定できる
            .queue_size = 1, // transactionのキュー数。1以上の値を入れておく。
            // .pre_cb // transactionが始まる前に呼ばれる関数をセットできる
            // .post_cn // transactionが完了した後に呼ばれる関数をセットできる
        };
    

    SPI通信を担うのはデバイスハンドラーです。
    エンコーダは右左で2個あるので、ハンドラーも2つ用意します。
    spi_bus_add_device関数で、ホスト(HSPIかVSPI)とデバイス設定をハンドラーに紐付けます。

        // SPIデバイスハンドラーを使って通信する
        spi_device_handle_t spidev[SIDE_SIZE];
    
        // デバイス設定のCSピンだけ書き換える
        devcfg.spics_io_num = GPIO_HSPI_CS[LEFT];
        ret = spi_bus_add_device(HSPI_HOST, &devcfg, &spidev[LEFT]);
        ESP_ERROR_CHECK(ret);
    
        devcfg.spics_io_num = GPIO_HSPI_CS[RIGHT];
        ret = spi_bus_add_device(HSPI_HOST, &devcfg, &spidev[RIGHT]);
        ESP_ERROR_CHECK(ret);
    

    これで設定は完了です。

    データの送受信関数

    次に、データ送受信の関数を見ます。

    今回はMA702から16ビットデータを受信するreadData関数を作成しました。
    引数にSPIデバイスハンドラーを与えるので、左右どちらのエンコーダとも通信できます。

    SPI機能で通信をするためには、spi_transaction_t構造体を使用します。
    この構造体の変数に、送信データや、受信データのバッファ、コマンド、アドレス等を設定し、
    その後spi_device_polling_transmit関数で通信を開始します。

    MA702は、CSピンがアクティブになると角度データを出力します。
    そのため、マスターはデータを送信しなくてOKです。
    よって、spi_transaction_tには送信データを設定していません。

    SPI Read Angleのプロトロコル。マスターの送信データは0。
    https://www.monolithicpower.com/en/documentview/productdocument/index/version/2/document_type/Datasheet/lang/en/sku/MA702/

    受信データは、recv_dataに格納されます。
    ただ、ESP32はリトルエンディアンで設計されているため、
    受信データをそのまま使うと上位8ビットと下位8ビットが入れ替わってしまいます。
    そのため、SPI_SWAP_DATA_RX関数でデータ順序を入れ替えて受信データを扱いやすくしています。

    const size_t DATA_LENGTH = 16;
    
    uint16_t readData(const spi_device_handle_t spidev){
        // MA702から16ビットデータを受け取る
        
        // MA702からはCSピンをLOWにするたびにデータを取得できる
        // そのためSPI MASTERはデータを送信しなくてよい
        uint16_t recv_data;
        spi_transaction_t trans;
        memset(&trans, 0, sizeof(trans)); // 構造体をゼロで初期化
        // flags: SPI_TRANS_ではじまるフラグを設定できる
        // trans.flags = SPI_TRANS_USE_RXDATA;
        // trans.cmd = NULL;
        // trans.addr = NULL;
        trans.length = DATA_LENGTH; // データ長 bit
        // trans.rxlength = 16; // デフォルトでlengthと同じになるので設定不要 
        // trans.user = NULL; // ユーザ定義の変数、コールバックを使うときに役立つ
        // trans.tx_buffer = &tx_data; // 送信バッファのポインタ
        // trans.tx_data; // SPI_TRANS_USE_TXDATAフラグを立てれば使用可能
        trans.rx_buffer = &recv_data; // 受信バッファのポインタ
        // trans.rx_data; // SPI_TRANS_USE_RXDATAのフラグを立てれば使用可能
    
        // 通信開始
        esp_err_t ret;
        ret=spi_device_polling_transmit(spidev, &trans);
        assert(ret==ESP_OK);
    
        // ESP32はリトルエンディアンで設計されているので
        // ABCD という16bitデータは、CDABという順番でバッファに保存される
        // SPI_SWAP_DATA_RXを使えば、データ順序を入れ変えられる
        return SPI_SWAP_DATA_RX(recv_data, DATA_LENGTH);
    }
    

    MA702は角度情報の出力だけではなく、内部レジスタの読み込みと書き込みも可能です。
    レジスタの読み込み、書き込み時はコマンドとアドレスを送信しなければなりません。
    16ビットの送信データのうち、最上位から3ビットがコマンド、5ビットがアドレス、8ビットがデータです。

    SPI Read Registerのプロトコル。
    https://www.monolithicpower.com/en/documentview/productdocument/index/version/2/document_type/Datasheet/lang/en/sku/MA702/

    それを実現するためにsendCmdAddrData関数を作成しました。
    sendCmdAddrDataの実行後、readDataを実行することでレジスタのデータを取得できます。

    uint16_t sendCmdAddrData(const spi_device_handle_t spidev,
            const uint8_t command, const uint8_t address, const uint8_t data){
        // MA702にコマンドとアドレスとデータを送信する
    
        // コマンド送信時に受け取るデータは角度データなので、
        // この関数実行後にreadData関数を実行して、コマンドの結果を受け取ること
        uint16_t recv_data;
        uint16_t tx_data = command;
        tx_data = (tx_data << 5) | address;
        tx_data = (tx_data << 8) | data;
        // ESP32はリトルエンディアンで設計されているので
        // SPI_SWAP_DATA_TX関数で、データ順序を入れ替える
        tx_data = SPI_SWAP_DATA_TX(tx_data, DATA_LENGTH);
    
        spi_transaction_t trans;
        memset(&trans, 0, sizeof(trans));
        trans.length = DATA_LENGTH;
        trans.tx_buffer = &tx_data;
        trans.rx_buffer = &recv_data;
    
        esp_err_t ret;
        ret=spi_device_polling_transmit(spidev, &trans);
        assert(ret==ESP_OK);
    
        return SPI_SWAP_DATA_RX(recv_data, DATA_LENGTH);
    }
    

    readData関数とsendCmdAddrData関数はそのままだと扱いづらいので、
    ラッパーとしてgetAnglereadRegisterwriteRegister関数を作成しました。

    float getAngle(const spi_device_handle_t spidev){
        // MA702から角度データを取得し、ラジアンに変換する
        const uint16_t RESOLUTION = 4096;
    
        uint16_t rawData = readData(spidev);
        // MA702の角度データは、LSBから4bitが常に0なので右に詰める
        rawData >>=4;
        return 2.0*M_PI * (float)rawData / RESOLUTION;
    }
    
    uint8_t readRegister(const spi_device_handle_t spidev, const uint8_t address){
        // MA702のレジスタデータを読み取る
        const uint16_t READ_COMMAND = 0b010;
    
        sendCmdAddrData(spidev, READ_COMMAND, address, 0x00);
        uint16_t rawData = readData(spidev);
    
        // 上位8ビットにデータが格納されるので、右に詰める
        return rawData >>=8;
    }
    
    uint8_t writeRegister(const spi_device_handle_t spidev, const uint8_t address, const uint8_t data){
        // MA702のレジスタにデータを書き込む
        const uint16_t WRITE_COMMAND = 0b100;
    
        sendCmdAddrData(spidev, WRITE_COMMAND, address, data);
        // 20 msec待機(MA702データシートにかかれている)
        vTaskDelay(20 / portTICK_PERIOD_MS);
        uint16_t rawData = readData(spidev);
    
        // 上位8ビットにデータが格納されるので、右に詰める
        return rawData >>=8;
    }
    

    レジスタ値の書き換えと角度データ取得

    それでは、app_main関数に戻りましょう。
    まずはじめに、MA702のレジスタの値を変更します。

    デフォルト状態でマウスを前進させホイールを回転させると、
    右のエンコーダは角度が増えていきますが、左のエンコーダは角度が減っていきます。
    これは、MA702のRotation Directionレジスタ値を変更することで解決します。

    Rotation Direction
    https://www.monolithicpower.com/en/documentview/productdocument/index/version/2/document_type/Datasheet/lang/en/sku/MA702/

    まず、MA702のレジスタマップを確認します。
    Rotation Direction(RD)は、アドレス0x09の7ビット目に格納されています。
    デフォルトでRDは0なので、これを1に書き換えることで回転方向を逆転できます。

    Register Map
    https://www.monolithicpower.com/en/documentview/productdocument/index/version/2/document_type/Datasheet/lang/en/sku/MA702/

    レジスタには一度書き込むと、電源OFF後も保存されます。
    また、レジスタへの書き込みは1000回までしか保証されていないため、一度writeRegisterで書き込んだら、2回目以降は書き込まないように関数をコメントアウトしましょう。

        // マウスが前進したら左右のエンコーダがカウントアップするように
        // 左エンコーダの回転方向を反転させる
        uint8_t address = 0b01001; // Rotation Direction
        uint8_t data = 0x80; // 回転方向を逆にする
        uint8_t reg_value;
        // MA702レジスタへの書き込みは1000回までなので、
        // 1回書き込んだらwriteRegister関数をコメントアウトすること
        reg_value = writeRegister(spidev[LEFT], address, data);
        printf("write: side:%d, address:%x, value:%x\n", LEFT, address, reg_value);
        // 書き込まれているか確認
        reg_value = readRegister(spidev[LEFT], address);
        printf("read: side:%d, address:%x, value:%x\n", LEFT, address, reg_value);
        vTaskDelay(2000 / portTICK_PERIOD_MS);
    

    最後のwhile文で、getAngle関数を使いエンコーダ角度(ラジアン)を取得し、
    Degreeに変換してprintしています。

        float wheelAngle[SIDE_SIZE];
        while(1){
            wheelAngle[LEFT] = getAngle(spidev[LEFT]);
            wheelAngle[RIGHT] = getAngle(spidev[RIGHT]);
            
            wheelAngle[LEFT] *= 180.0/M_PI; // radian to degree
            wheelAngle[RIGHT] *= 180.0/M_PI;
            printf("wheelAngle: %f, %f\n",wheelAngle[LEFT], wheelAngle[RIGHT]);
            vTaskDelay(10 / portTICK_PERIOD_MS);
        }
    

    以上で説明終わりです。

    次回の記事

    次回は、モーションセンサの使い方を書きます。
    こちらもSPI機能が活躍します。

    タイトルとURLをコピーしました