3
0

Delete article

Deleted articles cannot be recovered.

Draft of this article would be also deleted.

Are you sure you want to delete this article?

Pyserial(RS485)でUnit-Roller485を動かす

Last updated at Posted at 2025-03-31

はじめに

Unit-Roller485とは、RS485・I2Cを介してモーション制御を実施できる統合型ブラシレス DC モーターである。

目的

本記事ではPython及びシリアル通信用パッケージであるPyserialを用いて、RS485による通信でのモータ制御を確認することを目的とする。

準備物

  • PC(Windows10)
  • Python実行環境
    →本記事はPython3.8.8を使用
  • Unit-Roller485(以降、Roller485)
  • 駆動用電源(5[V])
  • USB-RS485変換器
    →本記事はDTECH製のものを使用
  • 接続用ケーブル(電源、通信用)

本記事の確認環境

・概略図

・実環境

※詳細な接続方法については、Unit Roller485 Tutorialを参照とする。

インストール

実行するPython環境にPyserialをインストールする。

Pyserialのインストール
pip install pyserial

USB-RS485変換器のドライバについて、必要があればインストールする。
(本記事で使用のものはプラグアンドプレイ可能)

通信準備

通信に使用するPCのポートと、Roller485 RS485通信用のアドレスIDを確認する。

  • PC側
    「デバイスマネージャー」→「ポート(COMとLPT)」より、該当するデバイスに振り当てられたポートを確認する。
    →本記事ではCOM3を使用

  • Roller485側
    起動後、液晶画面内「ID」欄に表示されている「0x??(16進数表示)」の??部を確認する。
    →本記事では「0x0A」を使用。

任意のアドレスを設定したい場合
背面のボタンを押下しながら起動すると設定画面が現れるため、「485 ID」を選択後、任意の値を設定する。
※設定画面は10進数表示となる。

実行スクリプト

1. ライブラリのインポート

今回はPyserial内の「RS485」クラスを使用する。

ライブラリのインポート
import serial.RS485 as rs

2. ポートのオープン

通信準備」にて確認したポート経由で通信するために、対象のポートをオープンする。

ポートのオープン
PORT     = 'COM3'  # USB-RS485変換器のポート番号
BOUDRATE = 115200  # ボーレート
TIMEOUT  = 1       # 通信のタイムアウト時間[sec]

# ポートのオープン
port = rs.RS485(PORT, BOUDRATE, timeout=TIMEOUT)

3. コマンドの送信

Roller485 通信プロトコル一覧を参考にコマンドを作成・送信する。
基本的には送信データは15bytes長であり、上位から順に、

  • コマンドの種類(1byte)
  • デバイスのID(1byte)
  • コマンドに関するデータ(4bytes ×3)
    →回転速度[rpm]、回転位置[deg]、電流値[mA]等
  • CRC8により算出した値(1byte)

にて構成されている。

4bytes長のデータの並びについては、リトルエンディアンとなるため注意する。

CRC8について
CRCとはCyclic Redundancy Check(巡回冗長検査)の略称であり、誤り検出符号の一種である。Roller485では8bit幅で生成を行い、計算方法は以下の通りである。

CRC8
# bytes_dataはCRC8までのbytesデータ
crc = 0x00  # 初期値

for byte in bytes_data:
    crc ^= byte
    for idx in range(8):
        if crc & 0x01:
            crc = (crc >> 1) ^ 0x8c
        else:
            crc >>= 1

上記のCRC8により算出した値をコマンド末尾に結合し、コマンドを送信する。

4. 動作確認

上記を基に、モータを回転させるスクリプトを作成する。
また、使用するコマンドは、

  • モータ状態変更コマンド
    →モータのON・OFFを変更する。
  • 速度指令コマンド
    →モータ回転速度を設定する。
  • モータ状態取得コマンド
    →モータの現在状態(設定値等)を取得する。

となる。また本記事では、

  1. モータをONにする。
  2. 目標値として、
    モータ回転速度: 2400[rpm]
    最大電流値  : 1200[mA]
    を設定する。
  3. 2[sec]待機する。
  4. モータ状態を取得する。
  5. モータをOFFにする。

の動作を確認する。

実際に作成したスクリプトは以下の通りである。

main.py
# -*- coding: utf-8 -*-
"""
main.py

RS-485によりRoller485との通信を行うモジュール
"""
# インポート処理 ===============================================================
# ライブラリのインポート --------------------------------------------------------

import serial.rs485 as rs
import time

# -----------------------------------------------------------------------------

# モジュールのインポート --------------------------------------------------------

# -----------------------------------------------------------------------------
# =============================================================================

# 起動処理 =====================================================================

# グローバル定数の定義
PACKET_LENGTH = 15  # データ長

# =============================================================================

# オブジェクト生成部 ============================================================
# クラスの定義 -----------------------------------------------------------------

# -----------------------------------------------------------------------------

# 関数の定義 -------------------------------------------------------------------


# 受信データの確認
def chkMessage(msg):

    # 正常処理時は上位2bytesに0xAA、0x55が入ったデータを受信
    if str(bytes.hex(msg))[:4] == 'aa55':
        rtn_msg = str(bytes.hex(msg))
        print('return data: ' + rtn_msg + '\n')

    # 異常処理時
    else:
        ini_msg = str(bytes.hex(msg))[:4]
        rtn_msg = str(bytes.hex(msg))
        print('[return code Error]'
              + '\ninitial data:' + ini_msg
              + '\n(return data: ' + rtn_msg + ')\n')

    return rtn_msg


# CRC-8コード生成
def crc8(data):

    bytes_data = bytes.fromhex(data)  # 16進数(str) --> 16進数(bytes)に変換
    crc = 0x00  # 初期値

    # CRC8値算出
    # 1byteずつ使用
    for byte in bytes_data:

        # CRC8値と送信するデータ(CRC値を除く)1byteの排他敵論理和
        crc ^= byte

        # 8bit幅で生成
        for idx in range(8):

            # CRC8値が0x01の場合
            if crc & 0x01:

                # CRC8値を1bit下位シフトした値と0x8cの排他的論理和
                crc = (crc >> 1) ^ 0x8c

            else:

                # CRC値を1bit下位にシフト
                crc >>= 1

    # 算出したCRC値を末尾に追加
    data_crc = bytes_data + bytes.fromhex(str(hex(crc))[2:])

    return data_crc


# 文字列の0埋め
def fillZero(data, byte_num=0, forward=False):

    # 後方を0埋め(デフォルト)
    if not forward:
        # 0埋めするbyte数の指定がない場合
        if byte_num == 0:
            return data + '0' * ((PACKET_LENGTH - 1) * 2 - len(data))

        # 0埋めするbyte数の指定がある場合
        else:
            return data + '0' * (byte_num * 2)

    # 前方を0埋め
    else:
        # 0埋めするbyte数の指定がない場合
        if byte_num == 0:
            return '0' * ((PACKET_LENGTH - 1) * 2 - len(data)) + data

        # 0埋めするbyte数の指定がある場合
        else:
            return '0' * (byte_num * 2) + data


# モータ状態をONに変更
def motorOn(target):

    data = '00'  # モータON・OFFコマンド

    # 送信データの作成
    data += target + '01'  # ON
    data = fillZero(data)

    return crc8(data)


# モータ状態をOFFに変更
def motorOff(target):

    data = '00'  # モータON・OFFコマンド

    # 送信データの作成
    data += target + '00'  # OFF
    data = fillZero(data)

    return crc8(data)


# 4bytes長のデータを1byteずつひっくり返す
def bytes4(data):

    hex_data = hex(data)  # int --> bytesに変換
    str_data = str(hex_data)[2:]  # bytes --> strに変換
    # 4bytes長にするため0埋め
    str_data = '0' * (8-len(str_data)) + str_data
    bytes_data = str_data[6:] + str_data[4:6] + str_data[2:4] + str_data[:2]

    return bytes_data


# 速度指令
def ctrlSpeed(target, rpm, current):
    """
    rpm    : [rpm](21000000~-21000000)
    current: [mA](1200~-1200)
    """

    data = '20'  # モータ回転速度制御コマンド

    # 入力値のオーバーレンジ対策
    # 回転速度
    if rpm > 21000000:
        rpm = 210000000
    elif rpm < -21000000:
        rpm = -210000000

    # 電流
    if current > 1200:
        current = 1200
    elif current < -1200:
        current = -1200

    # 回転速度[rpm]
    bytes_rpm = bytes4(rpm*100)

    # 電流[mA]
    bytes_cur = bytes4(current*100)

    # 送信データの作成
    data += target + bytes_rpm + bytes_cur
    data = fillZero(data)

    return crc8(data)


# モータ状態の取得
def readMotorStatus(target):

    data = '40'  # モータ状態取得コマンド

    data += target + '00'

    return crc8(data)


# -----------------------------------------------------------------------------
# =============================================================================


if __name__ == '__main__':  # デバッグ用処理

    # 事前準備部 ===============================================================
    # 定数の宣言・定義 ----------------------------------------------------------

    PORT = 'COM3'  # ポート番号
    TARGET = '0A'  # Roller485 アドレスID
    BOUDRATE = 115200  # ボーレート
    TIMEOUT = 1  # タイムアウト時間[s]

    # -------------------------------------------------------------------------
    # =========================================================================

    # メイン処理部 =============================================================

    try:

        # ポートのオープン
        port = rs.RS485(PORT, BOUDRATE, timeout=TIMEOUT)

        # ポートがオープンしたかどうかの確認
        while(True):
            # ポート状態の取得
            if port.isOpen():
                print(PORT + ' is opened.\n')
                break  # ブレークする

        # モータON ------------------------------------------------------------
        data = motorOn(TARGET)
        print('send data  : ' + str(bytes.hex(data)))
        port.write(data)  # 送信処理

        time.sleep(0.05)  # 少し待機

        msg = port.read(PACKET_LENGTH+2)  # 受信処理
        rtn_data = chkMessage(msg)

        time.sleep(0.05)  # 少し待機
        # --------------------------------------------------------------------

        # 目標モータ速度を設定--------------------------------------------------
        # 2400[rpm]、電流上限1200[mA]に設定
        data = ctrlSpeed(TARGET, 2400, 1200)
        print('send data  : ' + str(bytes.hex(data)))
        port.write(data)  # 送信処理

        time.sleep(2)  # 2[sec]待機

        msg = port.read(PACKET_LENGTH+2)  # 受信処理
        rtn_data = chkMessage(msg)

        time.sleep(0.05)  # 少し待機
        # -------------------------------------------------------------------

        # モータ状態の取得 ---------------------------------------------------
        data = readMotorStatus(TARGET)
        print('send data  : ' + str(bytes.hex(data)))
        port.write(data)  # 送信処理

        time.sleep(0.05)  # 少し待機

        msg = port.read(PACKET_LENGTH+5)  # 受信処理
        rtn_data = chkMessage(msg)

        time.sleep(0.05)  # 少し待機
        # -------------------------------------------------------------------

        # モータOFF ----------------------------------------------------------
        data = motorOff(TARGET)
        print('send data  : ' + str(bytes.hex(data)))
        port.write(data)  # 送信処理

        time.sleep(0.05)  # 少し待機

        msg = port.read(PACKET_LENGTH+2)  # 受信処理
        rtn_data = chkMessage(msg)
        # -------------------------------------------------------------------

    # 何かエラーが発生した場合
    except Exception as e:
        print(str(e))  # エラーメッセージの表示

    # 送信バッファをクリア
    port.flush()

    # ポートをクローズ
    port.close()
    # =======================================================================

また、上記スクリプト実行時のコンソール出力は以下の通りである。

コンソール
COM3 is opened.

send data  : 000a0100000000000000000000007a
return data: aa55100a01000000000000000000000088

send data  : 200a80a90300c0d40100000000006e
return data: aa55300a80a90300c0d40100000000009c

send data  : 400a00d6
return data: aa55500a311c01000ab10d003e130000010100e1

send data  : 000a00000000000000000000000012
return data: aa55100a000000000000000000000000e0

Roller485 通信プロトコル一覧に記載あるように、受信データが「0xAA 0x55」から始まっていることが確認できる。
また、モータ状態の取得に関しては受信データが20bytes長となる。詳細は通信プロトコル一覧参照とするが、モータ状態取得時のデータのうち5~8byte(上記では「311c0100(→リトルエンディアンなので72753)」)が回転速度を示し、実際の回転速度が727.5[rpm]だと読み取ることができる。

5. 実際の動作

動画から2秒程度回転後、停止しているのが確認できると思う。
よってPyserialを用いて、RS485による通信でUnit-Roller485を操作できることが確認できた。

今後の展望

今回はPyserialを用いてRoller485の動作を確認したのみであるため、次回は実際に制御をしてみようと思う。

3
0
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
3
0

Delete article

Deleted articles cannot be recovered.

Draft of this article would be also deleted.

Are you sure you want to delete this article?