TOPに戻る

ラズパイ5 +Python+CANopenでモータを回す ⑪ モーション CiA 402の規格<Profile Position Mode (PPM)-前編> canPPMread.py

 前回、Homing modeを設定し、pythonの原点復帰プログラムを動かしました。

 現在、設定されている運転モード(Modes of operation)を確認します。MEXE02の「(m12) CANopen通信ステータス」のPDOモニタを見ます。

6060h: Modes of operation

  • 0 There is no mode change or no mode assigned.
  • 1 Profile Position Mode
  • 3 Profile Velocity Mode
  • 4 Profile Torque Mode
  • 6 Homing Mode

6061h: Modes of operation display
This object provides the actual operation mode. <-和訳「このオブジェクトは実際の動作モードを提供します」

 上記の情報から、Profile Velocity ModeにPDOがマッピングされていることがわかります。このモードは、

  Velocity Mode 指定した目標速度Target velocity (60FFh)にする。

に加えて、Profileと書かれているので、ユーザが指定した加速(Profile acceleration)と減速(Profile deceleration)の加速度データに従って、すばやく目標速度に到達させ維持します。

 Quick stop deceleration、Quick stop deceleration、Polarityは、利用開始時に指定できます。なお、最大速度は、Max motor speed(6080h)に制限されます。

  • 6083h - Profile acceleration プロファイル加速
  • 6084h - Profile deceleration プロファイル減速
  • 6085h - Quick stop deceleration 急速停止減速
  • 607Eh  - Polarity 極性
  • 6080h - Max motor speed 最大モータ速度

Profile Position Mode (pp)を利用する

 ここでは、デフォルトのProfile Velocity Modeではなく、Profile Position Modeを利用するプログラムを作ります。このモードは、指定したpositionに回転させて止まるという、位置決めモードです。

  Brushless Motor BLV series R type Driver CANopen communication profile

上記の資料から、Profile Position Modeの構成とパラメタを下の図に示します。

 たくさんのオブジェクトによる設定値は、四角い箱のTrajectory Generator(位置決めの際に使われる軌道ジェネレータ)に入力されます。その出力側にあるPosisiton control、Speed control、Torque controlは、それぞれ、位置、速度、トルクを制御するPID制御ブロックです。

 Posisiton actual value、Speed actual value、Torque actual valueは、リアルタイムに出力される、位置、速度、トルクの値です。

 残りはwindow関連とエラー関連の出力です。

 とてもたくさんの設定しなくてはならないように見えますが、

  • Target position (607Ah)
  • Profile velocity (6081h)
  • Profile acceleration (6083h)
  • Profile deceleration (6084h)

を設定すれば、目標位置に動きそうです。しかし、どのような手順で設定していけばよいかはこの資料には書かれていませんし、オリエンタルモーター社の資料には該当するものはありません。


 EPOS4 Application Notes Collection (english, PDF 29 MB)バージョン March 2021

の中に、Profile Position Mode (PPM)のSET POSITIONの手順が説明されています。しかし、最初に見たPDOの情報には触れられていません。

 ベクター社の下記の資料に、PDOを含めた一連の設定、運用手順が書かれています。PDOのマッピングの変更は、同社のツールを使っています。EPOSを販売しているMaxonのツール・ソフトStudio 3.7でも、可能です。
 このオリエンタルモーターのサポート・ソフトMEXE2では「(p5) CANopen object通信初期値・設定」でPDOの設定ができます。もちろん、Python+canopenライブラリを使って書き換えるプログラムを作れば可能です。 

 EPOS と CANsetter で学ぶ CANopen Version 1.2 2010/03/15 Application Note AN-JON-1-701

Profile Position Modeの設定に必要なパラメタを読み出すプログラム

 デフォルト状態、電源を入れた直後の、上記のオブジェクト(設定パラメタ)を読み出すプログラムです。canPPMread.pyで保存しました。

import canopen
import time
import logging
#logging.basicConfig(level=logging.DEBUG)

# Start with creating a network representing one CAN bus
network = canopen.Network()

# Add some nodes with corresponding Object Dictionaries
node = canopen.RemoteNode(12,'Downloads/BLVD-KRD_CANopen_V200.eds')
network.add_node(node)

# Connect to the CAN bus
# sudo ip link set can0 up type can bitrate 1000000
network.connect(bustype='socketcan', channel='can0')

print("\n===start  ID=12 OrientalMotor\n")

print('\n@@need PP setting parameter\n')
Max_torqe    = node.sdo[0x6072].raw
print('Max torque',Max_torqe)
Target_position    = node.sdo[0x607a].raw
print('Target position',Target_position)
Software_position_limit_min    = node.sdo[0x607d][1].raw
print('Software position limit min',Software_position_limit_min)
Software_position_limit_max    = node.sdo[0x607d][2].raw
print('Software position limit max',Software_position_limit_max)
Positioning_option_code    = node.sdo[0x60f2].raw
print('Positioning option code',Positioning_option_code)
Profile_velocity    = node.sdo[0x6081].raw
print('Profile velocity',Profile_velocity)
End_velocity     = node.sdo[0x6082].raw
print('End velocity ',End_velocity )
Profile_acceleration    = node.sdo[0x6083].raw
print('Profile acceleration ',Profile_acceleration)
Profile_deceleration     = node.sdo[0x6084].raw
print('Profile deceleration ',Profile_deceleration )
Quick_stop_deceleration    = node.sdo[0x6085].raw
print('Quick stop deceleration',Quick_stop_deceleration)
Quick_stop_option_code    = node.sdo[0x605a].raw
print('Quick stop option code',Quick_stop_option_code)
Halt_option_code    = node.sdo[0x605d].raw
print('Halt option code',Halt_option_code)
Position_window    = node.sdo[0x6067].raw
print('Position window',Position_window)
Following_error_window    = node.sdo[0x6065].raw
print('Following error window',Following_error_window)
print("------")

# Disconnect from CAN bus
network.disconnect()

 仮想環境で動かしています。

$ source envcan/bin/activate
(envcan) yoshi@ras05:~ $ 

 
$ sudo ip link set can0 up type can bitrate 1000000

(envcan) yoshi@ras05:~ $ python canPPMread.py

===start  ID=12 OrientalMotor


@@need PP setting parameter

Max torque 10000
Target position 0
Software position limit min 0
Software position limit max 0
Positioning option code 0
Profile velocity 1
End velocity  0
Profile acceleration  1000
Profile deceleration  1000
Quick stop deceleration 1000
Quick stop option code 2
Halt option code 1
Position window 18
Following error window 108000
------

 読み出したそれぞれの値に単位がないです。このPPMは、回転を意識していなく、回転を直線運動に変換する機構を使っていて、それに合わせた単位が決められています。

 けれど、おおざっぱに言えば、1000という桁数で、いろいろな設定をすると、モータが動いているのがわかります。なので、Target position=0は、目標位置が書かれていないので、動きません。何らかの数値、例えば、2000とかを書き込んでおく必要があります。

 同様に、Profile velocity=1は遅すぎて動いているのがわからないので、これにも1000ぐらいの値を書き込みます。

 PPMの動作では、Profile velocity=設定した速度に達するように、台形駆動が行われます。これは、コントローラが内部で計算して徐々に速度を上げ、Profile velocityに達したら、Target positionの手前まで、その速度を維持します。最後は、減速して、目標位置で止まります。

  最低限、下の図のように、四つのパラメタが決まれば、位置決めができます。

 途中で、モータの軸に負荷がかかったりして速度が変わったとしても、PIDコントローラが自動で修正をします。

 次回は、設定手順を具体的に説明します。

●(メモ)エラー・コード

エラー・ (エラー・
コード   レジスタ)  詳細

0000h        (00h)        Error Reset or no error
8110h        (11h)        CAN overrun
8120h        (11h)        CAN in error passive mode
8130h        (11h)        Node guarding error or heartbeat error
8140h        (11h)        Recover from Bus-Off state
8210h        (11h)        PDO not processed due to length error
FF10h        (81h)        Position deviation Possible
FF20h        (81h)        Overcurrent Not possible Non-excitation
FF21h        (81h)        Main circuit overheat
FF22h        (81h)        Overvoltage Non-excitation
FF25h        (81h)        Undervoltage Non-excitation after
FF26h        (81h)        Motor overheat deceleration
FF28h        (81h)        Encoder error
FF29h        (81h)        Internal circuit error
FF2Ah        (81h)        Encoder communication error
FF30h        (81h)        Overload
FF31h        (81h)        Overspeed
FF41h        (81h)        EEPROM error
FF42h        (81h)        Initial encoder error
FF44h        (81h)        Encoder EEPROM error
FF45h        (81h)        Motor combination error
FF4Ah        (81h)        Return-to-home incomplete
FF50h        (81h)        Electromagnetic brake overcurrent
FF53h        (81h)        HWTO input circuit error
FF55h        (81h)        Electromagnetic brake connection error
FF60h        (81h)        ±LS both sides active
FF61h        (81h)        Reverse ±LS connection
FF62h        (81h)        Return-to-home operation error
FF63h        (81h)        No HOMES
FF64h        (81h)        Z, SLIT signal error
FF66h        (81h)        Hardware overtravel
FF67h        (81h)        Software overtravel
FF68h        (81h)        HWTO input detection Non-excitation
FF6Ah        (81h)        Return-to-home additional operation error
FF70h        (81h)        Operation data error
FF71h        (81h)        Unit setting error
FF81h        (81h)        Network bus error
FF84h        (81h)        RS-485 communication error
FF85h        (81h)        RS-485 communication timeout
FF8Ch        (81h)        Outside setting range
FFF0h        (81h)        CPU error
FFF3h        (81h)        CPU overload

連載 ラズパイ5 +Python+CANopenでモータを回す

(1) 構成と環境(オリエンタルモーター の「BLMR5100K-A-B」 + 「BLVD-KRD」)

(2) サポート・ソフト MEXE02

(3) PythonでSDOの読み出し(仮)caninfo.py

(4) CANopenのベーシックな規格とSDO/PDO、オブジェクト・ディクショナリ<前編>

(5) CANopenのベーシックな規格とSDO/PDO、オブジェクト・ディクショナリ<後編>

(6) 二つの状態遷移(NMTとStatus Machine)

(7) CANバス信号を見る<前編>canreset.py candump0.py

(8) CANバス信号を見る<中編>Arduino

(9) CANバス信号を見る<後編>CANopenのデコードができ無償で使えるツールAnalog Devices TMCL-IDE

(10) モーション CiA 402の規格<Homing mode> canHome.py

(11) モーション CiA 402の規格<Profile Position Mode (PPM)-前編> canPPMread.py

(12) モーション CiA 402の規格<Profile Position Mode (PPM)-中編> caninfo2.py canppm.py

(13) モーション CiA 402の規格<Profile Position Mode (PPM)-後編> canppm2.py

(14) モーション CiA 402の規格<Profile Velocity Mode (PVM)> campvm.py