Skip to content

ROBOTIS-JAPAN-GIT/DynamixelHandler-ros2

 
 

Repository files navigation

DynamixelHandler-ros2

Robotis社のDynamixelをROSから制御するための dynamixel_handlerパッケージとその周辺パッケージを提供するリポジトリ.

ROS2(Humble, Jazzy)に対応,ROS1 ver はこちら.ただし,開発が分離しているので機能はやや異なる.

X, P, Proシリーズに対応,X320シリーズ,Yシリーズは順次対応予定.

Table of Contents

Features of this package

  • Dynamixel制御に特化した最小単位のパッケージ

    詳細
    • dynamixel_handlerパッケージが提供する dynamixel_handler ノードは,サーボモータとの通信を担う.
    • サーボの動作制御はユーザーが開発する 別の制御ノードが行い,dynamixel_handlerノードは通信の仲介を行うイメージ.
    • ユーザーはシリアル通信の通信プロトコルや,コントロールテーブルついて知る必要が(あまり)ない.
    • Dynamixelの各種情報や機能が適切に分類され,ほぼすべての情報・機能を利用することが可能
  • ROSトピックのみで制御できるシンプルなインターフェース

    詳細

    トピック通信だけで利用できるので,このパッケージ自体のコードの編集は不要

    • Subscribe: /dynamixel/commands/x(他、/dynamixel/commands/pなど)
      • シリーズごとに定義された制御コマンドを送ることで動作制御.
      • 制御コマンドの内容に合わせてサーボの制御モードが自動変更.
    • Publish: /dynamixel/states
      • 分類された各情報を個別の周期で自動的に read & publish.
        • "status": torqueのオンオフ, errorの有無, pingの成否, 制御モード (デフォルト 約2Hz)
        • "error": overload エラー などのハードウェアエラー (デフォルト 約2Hz)
        • "present": current [mA], velocity [deg/s], position [deg] などの現在値 (デフォルト 約50Hz)
        • etc... (goal, limit, gain, extra)
  • 物理量ベースでのやり取り

    詳細
    • current [mA], velocity [deg/s], position [deg] などの物理量を直接扱える.
    • Dynamixelから read されたパルス値(0 ~ 4095 など)は物理量に変換してから publish される.
    • Dynamixelへの目標値は物理量で入力され,内部でパルス値に変換されてから write される.

    ※ 特に角度を rad (-π ~ π) ではなく degree (-180.0 ~ 180.0) で扱うので直感的.

  • 高速で安定したRead/Write

    詳細
    • 読み書きをできるだけ一括で行うことで通信回数を削減
      • 連続アドレスの一括読み書き
      • 複数サーボの一括読み書き (SyncRead/SyncWrite)
    • Fast Sync Read インストラクションによるReadの高速化
      • 通信形式についての細かい知識が無くてもros paramで設定するだけで利用可能.
    • dynamixel_handlerノードの loop 周期に同期したRead/Write
      • Topicの受信頻度に依存しないため,安定した通信が可能.

    ※ 12サーボ同時Read/Writeでも150Hz程度の通信が可能なことを確認
    ※※ 高速通信には適切な latency timer (1~4ms) と baudrate(推奨 1,000,000bps 以上) が必要

  • 開発の手間を減らす便利機能

    詳細
    • 初期化時の動作
      • 連結したDynamixelを自動で認識
      • 連結されるDynamixel数の指定 (Optional)
        • ロボットのサーボ数を事前に入力することで,断線などの異常を検知可能
      • エラーを自動でクリア (Optional)
      • トルクを自動でON (Optional)
      • baudrate の(簡易)一括設定 (Optional)
    • 終了時の動作
      • dynamixel_handlerノードを kill したタイミングで動作を停止 (Optional)
      • dynamixel_handlerノードを kill したタイミングでトルクをOFF (Optional)
    • Dummy Servo 機能 (Optional)
      • 未接続のサーボのIDを与えることで,そのIDのサーボの挙動を簡易シミュレート
      • 未接続のサーボを考慮したい時や実機を動かしたくない場合でも動作確認が可能
    • ハードウェアエラーのクリア
      • エラークリア時の回転数消失問題を homing offset により自動補正
    • baudrate の一括変更 (別ノードで提供)
      • パッケージに同梱している dynamixel_unify_baudrateノードで一括で変更可能
  • ROSパラメータによる各種ログ表示制御

    詳細
    • Read/Write にかかる平均時間とSerial通信の成功率
    • CallBackした内容 (Optional)
    • Read/Write されるパルス値 (Optional)
    • Readに失敗したID (Optional)
    • etc...

各機能の設定については ros param から可能なので,詳細は Parametersの章を参照.


How to install

このリポジトリをgit clone

cd ~/ros2_ws/src
# sshの場合
git clone --recursive git@github.com:ROBOTIS-JAPAN-GIT/DynamixelHandler-ros2.git
# httpsの場合
git clone --recursive https://github.com/ROBOTIS-JAPAN-GIT/DynamixelHandler-ros2.git
# 旧バージョンを使いたい場合
git clone --recursive https://github.com/ROBOTIS-JAPAN-GIT/DynamixelHandler-ros2.git dynamixel_handler -b ver0.1.0

Note

既存クローンでブランチ更新した場合(submodule の配置変更を含む変更を pull / merge した場合)は, リポジトリ直下で一度 git submodule update --init --recursive を実行してから build すること.

ビルド

cd ~/ros2_ws
colcon build --symlink-install --packages-up-to dynamixel_handler
source ~/ros2_ws/install/setup.bash # 初回 build 時のみ

How to use

  • コマンドラインを用いた dynamixel_handlerノードの動作確認
  • 他の制御用パッケージと連携した dynamixel_handlerノードの利用

上記を達成するための手順を以下に示す.

1. Dynamixelの接続

Dynamixel Wizardでモータの動作確認ができる程度の状態を想定.

  • Dynamixel をディジーチェーンにしてU2D2経由でUSB接続されていること.
  • ID に重複がないように事前に設定されていること.
  • baudrate が全て統一されていること.

Tip

init/baudrate_auto_setパラメータをtrueにすることで,接続時に自動で baudrate を変更することも可能. また,別ノードとして,baudrate を一括で変更するための dynamixel_unify_baudrateノード も用意してある

2. dynamixel_handlerノードの起動

2-1. 自分の環境とconfigの設定を合わせる

リポジトリ内のdynamixel_handler/config/config_dynamixel_handler.yamlの該当部分を編集し,保存.
以下は baudrate: $57600$ かつ device name: /dev/ttyUSB0かつ latency timer: $16$ ms の場合

# config/config_dynamixel_handler.yaml
/**:
    ros__parameters:
        # 通信機器の設定
        device_name: /dev/ttyUSB0 # 通信するデバイス名,
        baudrate: 57600           # 通信速度, Dynamixelのデフォルトは 57600 bps (で遅い) 
        latency_timer: 16         # 通信のインターバル, 多くの環境でデフォルトは 16 ms (で遅い)

通信環境の設定については Parameters の章の通信関係の設定を参照.

2-2. ターミナルから実行

ros2 launch dynamixel_handler dynamixel_handler_launch.xml
# 出力例
# ... 略 ...
[dynamixel_handler-1] 00000.00000: Initializing DynamixelHandler ..... 
[dynamixel_handler-1] 00000.00000:  Succeeded to open USB device
[dynamixel_handler-1] 00000.00000:   ------------ name '/dev/ttyUSB0' 
[dynamixel_handler-1] 00000.00000:   -------- baudrate '57600'
[dynamixel_handler-1] 00000.00000:   --- latency_timer '16'
[dynamixel_handler-1] 00000.00000:  Expected number of Dynamixel is not set. 
[dynamixel_handler-1] 00000.00000:  > Free number of Dynamixel is allowed.
[dynamixel_handler-1] 00000.00000:  Auto scanning Dynamixel (id range [0] to [30]) ...
[dynamixel_handler-1] 00000.00000:  > series: X [use], P [no use], PRO [no use]
[dynamixel_handler-1] 00000.00000:   * P series servo id [1] is ignored 
[dynamixel_handler-1] 00000.00000:   * X series servo id [6] is found 
[dynamixel_handler-1] 00000.00000:    ID [6] is enabled torque 
[dynamixel_handler-1] 00000.00000:   * X series servo id [7] is found 
[dynamixel_handler-1] 00000.00000:    ID [7] is enabled torque 
[dynamixel_handler-1] 00000.00000:  ... Finish scanning Dynamixel 
[dynamixel_handler-1] 00000.00000: ..... DynamixelHandler is initialized 
[dynamixel_handler-1] 00000.00000: time=0.03ms/loop(5.11ms/read), success=100%(full=100%) 
[dynamixel_handler-1] 00000.00000: time=0.50ms/loop(5.11ms/read), success=100%(full=100%)  
[dynamixel_handler-1] 00000.00000: time=0.56ms/loop(5.11ms/read), success=100%(full=100%)  
[dynamixel_handler-1] 00000.00000: time=0.89ms/loop(5.11ms/read), success=100%(full=100%) 

連結したDynamixelが自動で探索され,見つかったDynamixelの初期設定が行われる.
うまく見つからない場合は Trouble Shooting を参照.
初期化時の動作設定については Parameters の章の初期化・終了時等の挙動設定を参照.

3. Dynamixelの動作を制御

コマンドラインから指令する用の topic として/dynamixel/command/.../dynamixel/shortcutトピックが用意されている.
トピックを送るだけで動作の制御が可能である.

topic の詳細については Topic の章を参照.

以下の例では ros2 topic コマンドを利用して topic をコマンドラインから publish しているが,別のノードを作成して同様の topic を publish することでも動作を制御できる.

例:ID:5の Dynamixel(Xシリーズ) を位置制御モードで角度を90degに制御

/dynamixel/command/x/position_controlトピックにIDと角度を設定して publish.

# 2-2. とは別のターミナルを開いて $ source ~/ros2_ws/install/setup.bash 実行後
ros2 topic pub /dynamixel/command/x/position_control \
 dynamixel_handler_msgs/msg/DynamixelControlXPosition \
 "{id_list: [5], position_deg: [90], profile_vel_deg_s: [], profile_acc_deg_ss: []}" -1

実機のサーボの角度が90degになれば成功.

Note

ID:5のDynamixelの制御モードは自動的に位置制御に変換される.

例:ID:5の Dynamixel のトルクをOFF

/dynamixel/shortcutトピックにtorque_offコマンドとIDを設定して publish.

# 2-2. とは別のターミナルを開いて $ source ~/ros2_ws/install/setup.bash 実行後
ros2 topic pub /dynamixel/shortcut \
 dynamixel_handler_msgs/msg/DynamixelShortcut \
 "{command: 'torque_off', id_list: [5]}"

実機のサーボのトルクがOFFになれば成功.

/dynamixel/shortcutトピックで使えるコマンドについてはこちら を参照.

4. Dynamixelの情報を取得

コマンドラインから確認する用の topic として/dynamixel/state/.../dynamixel/debugトピックが一定周期で pub され続けている.

topic の詳細については Topic の章を参照.
また,read 周期については Parameters の章の実行時の動作設定を参照.

例: Dynamixel の現在値の確認

# 2-2. とは別のターミナルを開いて $ source ~/ros2_ws/install/setup.bash 実行後
ros2 topic echo --flow-style /dynamixel/state/present # status, goal, gain, limit, error... など. 
---                                                    # 出力例
id_list: [5, 6]                                        # 認識されているサーボのID
pwm_percent: [0.0, 0.0]                                # 現在のPWM値
current_ma: [0.0, -2.69]                               # 現在の電流値
velocity_deg_s: [0.1, 0.1]                             # 現在の各速度
position_deg: [89.91210937499999, -0.2636718750000023] # 現在の角度
vel_trajectory_deg_s: [0.0, 0.0]                       # 目標速度 みたいなもの
pos_trajectory_deg: [0.0, 0.0]                         # 目標角度 みたいなもの
temperature_degc: [0.0, 0.0]                           # 現在の温度
input_voltage_v: [0.0, 0.0]                            # 現在の入力電圧
---

上記は電流,速度,位置を読み込むように設定した場合なのでそれ以外の要素は初期値の0になっている.
read & publish される情報の選択については Parameters の章の実行時の動作設定を参照.

例: Dynamixel のデバッグ用情報の確認

# 2-2. とは別のターミナルを開いて $ source ~/ros2_ws/install/setup.bash 実行後
ros2 topic echo --flow-style /dynamixel/debug
---             # 出力例
status:         # /dynamixel/state/status と同じ
  id_list: [1, 6, 7, 8, 9]                                                 # 認識されているサーボのID
  torque: [true, true, true, true, true]                                   # トルクがONかOFFか
  error: [false, false, false, false, false]                               # エラーが発生しているか
  ping: [true, true, true, true, true]                                     # pingが通っているか
  mode: [velocity, cur_position, cur_position, cur_position, cur_position] # 制御モード
current_ma:     # 現在の電流値と目標電流値
  present: [0.0, 3.0, 2.0, 9.0, 4.0] 
  goal: [0.0, 900.0, 910.0, 910.0, 910.0]
velocity_deg_s: # 現在の速度と目標速度
  present: [0.0, 0.0, 0.0, 1.374, 0.0]
  goal: [0.0, 439.68, 439.68, 439.68, 439.68]
position_deg:   # 現在の角度と目標角度
  present: [1007.5781, -24.7852, 44.1211, -33.8379, -87.8906]
  goal: [1007.666, -24.7852, 44.1211, -33.8379, -87.8906]
---

トルクのオンオフ,制御モード,目標電流(実質的な最大電流)など,動作状況を確認するための情報が含まれる.

5. dynamixel_handler_examples パッケージの example1ノードを起動

以下では,dynamixel_handlerノードを別ノードと連携させて,Dynamixelの情報を取得しつつ,動作を制御する例を示す. 例に用いるのは dynamixel_handler_examples が提供する example1ノードである.

dynamixel_handler_examples パッケージをビルド

cd ~/ros2_ws
colcon build --symlink-install --packages-up-to dynamixel_handler_examples
source ~/ros2_ws/install/setup.bash # 初回 build 時のみ

example1ノードを起動

ros2 launch dynamixel_handler_examples example1.xml

実行が成功すると,example1ノードが /dynamixel/statesトピック (DxlStates型) を subscribe して,以下の情報が取得される.

  • statusフィールドにより,トルクのオンオフ,エラーの有無,pingの成否,制御モード.
  • presentフィールドにより,電流,速度,位置などの現在値.

取得された情報はターミナルに表示される.

また,example1ノードによって/dynamixel/commands/xトピック (DxlCommandsX型 ) が publish され,以下のように制御される.

  • statusフィールドを用いてトルクをオン
  • current_base_position_controlフィールド用いて
    • 電流を300mAに制限
    • +-45degで往復運動

IDにかかわらずすべてのサーボが上記の動作をしているはずである.

コードの解説や pkg の構成についてはdynamixel_handler_examplesのREADMEを参照.


6. ダミーサーボ機能を利用してデバッグする

init/dummy_servo_list パラメータに $1, \ldots, 254$ のIDを指定することで,実際のサーボが接続されていなくても,そのIDのサーボをダミーサーボとして簡易的にシミュレートすることができる. 最も簡単に利用する方法は,dynamixel_handlerノードの起動時にパラメータを指定することである.

ros2 run dynamixel_handler dynamixel_handler --ros-args -p init/dummy_servo_list:=[1,2]

実サーボとダミーサーボを同時に利用することも可能である.
その場合はリポジトリ内のdynamixel_handler/config/config_dynamixel_handler.yamlinit/dummy_servo_listパラメータを編集する.

# config/config_dynamixel_handler.yaml
    # サーボの設定
        init/dummy_servo_list: [1, 2] # ダミーのサーボを作成するIDのリスト,同じIDのサーボが存在する場合でもダミーが優先される. -1や255は無視される.

Note

dummy servo の extra は厳密な実機再現ではなく,簡易な初期値で扱う. 初期 publish 値は基本的に 0/false/空文字(例: bus_watchdog_ms=0, led={0,0,0}, shutdown=all false)で,必要な値は command/extra で上書きする運用を想定している。 protocol_type は dummy(SERIES_UNKNOWN) では publish 時に 0 を返す(実機は通常 2)。

Topics

Summary

Topic name Type Description How to enable
/dynamixel/states DxlStates 連結したサーボすべての状態をまとめた topic 常時 publish される
/dynamixel/commands/all DxlCommandsAll シリーズに関わらずすべてのサーボを制御するための topic 常時 subscribe される
/dynamixel/commands/x DxlCommandsX Xシリーズのサーボを制御するための topic init/used_servo_series.X: true 時のみ subscribe される
/dynamixel/commands/p DxlCommandsP Pシリーズのサーボを制御するための topic init/used_servo_series.P: true 時のみ subscribe される
/dynamixel/commands/pro DxlCommandsPro Proシリーズのサーボを制御するための topic init/used_servo_series.Pro: true 時のみ subscribe される
/dynamixel/debug DynamixelDebug 連結したサーボの最低限の情報をまとめた topic 常時 publish される
/dynamixel/shortcut DynamixelShortcut 全てのサーボへ基本的な指令を送るための topic 常時 subscribe される
/dynamixel/state/* Dynamixel* サーボの個々の状態をCLIで確認するための topic 常時 publish される
/dynamixel/command/x/* DynamixelControlX* XシリーズのサーボをCLIで制御するための topic init/used_servo_series.X: true 時のみ subscribe される
/dynamixel/command/p/* DynamixelControlP* PシリーズのサーボをCLIで制御するための topic init/used_servo_series.P: true 時のみ subscribe される
/dynamixel/command/pro/* DynamixelControlPro* ProシリーズのサーボをCLIで制御するための topic init/used_servo_series.Pro: true 時のみ subscribe される
/dynamixel/command/* Dynamixel* 各シリーズの共通項目をCLIで制御するための topic 常時 subscribe される

一般的なユースケースでは以下の4つの topic を利用すれば十分である.

  • /dynamixel/states : ノード内でサーボの状態を取得できる.
  • /dynamixel/commands/x : ノードからXシリーズサーボへ指令を送信できる.
  • /dynamixel/debug : コマンドライン上でサーボのトルクや角度を監視できる.
  • /dynamixel/shortcut : コマンドラインからサーボのトルクON/OFFなどを指令できる.

各シリーズの利用には,Parameters の章の初期化・終了時等の挙動設定における init/used_servo_seriesパラメータの設定が必要がある.
ヘッダーファイルや型など,具体的な使い方ついては,dynamixel_handler_examples を参照されたし.
型そのものについての詳細はメッセージの定義を参照のこと.

Published Topics

dynamixel_handler ノードが publish する topic を以下に示す.

全シリーズ共通のサーボ状態をまとめた topic. publish の周期と内容は Parameters の章の実行時の動作設定pub_ratioパラメータで設定される. すなわち,各情報は読み取り周期 pub_ratio/{~}に従って読み取られ,読み取られた場合のみ publish される.

Field Type Description Read & Publish
stamp builtin_interfaces/Time メッセージのタイムスタンプ -
status DynamixelStatus サーボの基本状態 (トルク, エラー有無, ping, 制御モード). pub_ratio/statusに一回
present DynamixelPresent サーボの現在値 (PWM, 電流, 速度, 位置, etc.).各要素のread周期は個別に設定可能. pub_ratio/present.{~}の最小値に一回
goal DynamixelGoal サーボの目標値 (PWM, 電流, 速度, 位置, etc.). pub_ratio/goalに一回
limit DynamixelLimit サーボの制限値 (温度, 電圧, PWM, 電流, 加速度, 速度, 位置). pub_ratio/limitに一回
gain DynamixelGain サーボの制御ゲイン (速度I/Pゲイン, 位置D/I/Pゲイン, FFゲイン). pub_ratio/gainに一回
error DynamixelError サーボのハードウェアエラー詳細 (入力電圧, ホールセンサ, 過熱, エンコーダ, 電子回路, 過負荷). pub_ratio/errorに一回
extra DynamixelExtra サーボが持つその他の情報 pub_ratio/extra.{~}の最小値に一回
`status` field の詳細

pub_ratio/status 周期で read され, read されたタイミングのみ全ての情報が埋められる.
id_listフィールドの長さとそれ以外の field の長さは必ず一致する.すなわち,id_list が空配列なら他の field も空配列であり,id_listが長さNの配列なら他の field も長さNの配列になる.

Field Type Description
id_list uint16[] サーボIDのリスト
torque bool[] トルクがONかOFFか
error bool[] ハードウェアエラーが発生しているか
ping bool[] pingが通っているか
mode string[] 制御モードの文字列 (以下の Operating Mode list を参照)

Operating mode list

  • "pwm": PWM制御モード, Proシリーズは無し
  • "current": 電流制御モード
  • "velocity": 速度制御モード
  • "position": 位置制御モード
  • "ex_position" = extended position: 拡張位置制御モード
  • "cur_position"= current base position: 電流ベース位置制御モード, Xシリーズのみ
`present` field の詳細
present field (dynamixel_handler_msgs::msg::DynamixelPresent)

高速化のため,位置,速度などの要素個別で読み取り周期pub_ratio/present.{~}を設定できる.
そのため最新のデータと非最新のデータが混在することになるが,非最新のデータを publish するかどうかは pub_outdated_present_value パラメータで設定可能.

  • pub_outdated_present_value: true の場合: 非最新のデータも含めて publish されるため,id_listフィールドの長さとそれ以外の field の長さは必ず一致する.
  • pub_outdated_present_value: false の場合: 非最新のデータは publish されないため,"サーボの数と同じ長さの配列" の field と "空配列" の field が混在することになる.
Field Type Description Note
id_list uint16[] サーボIDのリスト
pwm_percent float64[] 現在のPWM値 (%) Proシリーズは非対応であり,".nan"で埋められる
current_ma float64[] 現在の電流値 (mA)
velocity_deg_s float64[] 現在の速度 (deg/s)
position_deg float64[] 現在の位置 (deg)
vel_trajectory_deg_s float64[] profileによって生成された理想の速度 (deg/s) Proシリーズは非対応であり,".nan"で埋められる
pos_trajectory_deg float64[] profileによって生成された理想の位置 (deg) Proシリーズは非対応であり,".nan"で埋められる
input_voltage_v float64[] 現在の入力電圧 (V)
temperature_degc float64[] 現在の温度 (°C)

pub_ratio/present{current_ma: 1, velocity_deg_s: 1, position_deg: 1} が設定されており,その他の pub_ratio/present.{~}0 に設定されている場合の出力例を示す. pub_outdated_present_value はデフォルトで true なので読み取られなかったデータも含め全ての field が埋まる.

$ ros2 topic echo --flow-style /dynamixel/state/present 
present: # DynamixelPresent型, pub_ratio/present.~ に一回 read され,1要素でも読み取ったら埋める
  id_list: [2, 3]
  pwm_percent: [0.0,  0.0]         # 現在のPWM値, Proシリーズは無し.
  current_ma: [100.9, 200.6]       # 現在の電流値
  velocity_deg_s: [10.0, 15.1]     # 現在の速度
  position_deg: [40.2, 3.1]        # 現在の位置
  vel_trajectory_deg_s: [0.0, 0.0] # profileによって生成された理想の速度,Proシリーズは無し.
  pos_trajectory_deg: [0.0, 0.0]   # profileによって生成された理想の位置, Proシリーズは無し.
  input_voltage_v: [0.0, 0.0]      # 現在の入力電圧
  temperature_degc: [0.0, 0.0]     # 現在の温度

pub_outdated_present_value パラメータを false にすると以下のように読み取られなかった field は空配列となる.この場合は pwm_percent, vel_trajectory_deg_s, pos_trajectory_deg, input_voltage_v, temperature_degcpub_ratio/present.{~}0 なので読み取られない.

$ ros2 topic echo --flow-style /dynamixel/state/present 
present: # DynamixelPresent型, pub_ratio/present.~ に一回 read され,1要素でも読み取ったら埋める
  id_list: [2, 3]
  pwm_percent: []              # 現在のPWM値, Proシリーズは無し.
  current_ma: [100.9, 200.6]   # 現在の電流値
  velocity_deg_s: [10.0, 15.1] # 現在の速度
  position_deg: [40.2, 3.1]    # 現在の位置
  vel_trajectory_deg_s: []     # profileによって生成された理想の速度,Proシリーズは無し.
  pos_trajectory_deg: []       # profileによって生成された理想の位置, Proシリーズは無し.
  input_voltage_v: []          # 現在の入力電圧
  temperature_degc: []         # 現在の温度
`goal` field の詳細
goal field :

pub_ratio/goal 周期で read され, read されたタイミングのみ全ての情報が埋められる. id_listフィールドの長さとそれ以外の field の長さは必ず一致.すなわち,id_list が空配列なら他の field も空配列であり,id_listが長さNの配列なら他の field も長さNの配列になる.

Field Type Description Note
id_list uint16[] サーボIDのリスト
pwm_percent float64[] 目標PWM値 (%) Proシリーズは非対応であり,".nan"で埋められる
current_ma float64[] 目標電流値 (mA)
velocity_deg_s float64[] 目標速度 (deg/s)
profile_acc_deg_ss float64[] profileの加速度 (deg/s^2) Proシリーズのgoal_accelerationに対応
profile_vel_deg_s float64[] profileの速度 (deg/s) Proシリーズは非対応であり,".nan"で埋められる
position_deg float64[] 目標位置 (deg)
`limit` field の詳細
limit field :

pub_ratio/limit 周期で read され, read されたタイミングのみ全ての情報が埋められる. id_listフィールドの長さとそれ以外の field の長さは必ず一致.すなわち,id_list が空配列なら他の field も空配であり,id_listが長さNの配列なら他の field も長さNの配列になる.

Field Type Description Note
id_list uint16[] サーボIDのリスト
temperature_limit_degc float64[] 温度上限 (°C)
max_voltage_limit_v float64[] 入力電圧上限 (V)
min_voltage_limit_v float64[] 入力電圧下限 (V)
pwm_limit_percent float64[] PWM上限 (%) , goal_pwmはこの値に抑えられる. Proシリーズは非対応であり,".nan"で埋められる
current_limit_ma float64[] 電流値上限 (mA), goal_currentはこの値に抑えられる.
acceleration_limit_deg_ss float64[] 加速度上限 (deg/s^2), profile_accelerationはこの値に抑えられる. Xシリーズは非対応であり,".nan"で埋められる
velocity_limit_deg_s float64[] 速度上限 (deg/s), goal_velocity と profile_velocityはこの値に抑えられる
max_position_limit_deg float64[] 位置上限 (deg), 位置制御モードの場合,goal_positionはこの値に抑えられる.
min_position_limit_deg float64[] 位置下限 (deg), 位置制御モードの場合,goal_positionはこの値に抑えられる.
`gain` field の詳細
gain field :

pub_ratio/gain 周期で read され, read されたタイミングのみ全ての情報が埋められる. id_listフィールドの長さとそれ以外の field の長さは必ず一致.すなわち,id_list が空配列なら他の field も空配であり,id_listが長さNの配列なら他の field も長さNの配列になる.

Field Type Description Note
id_list uint16[] サーボIDのリスト
velocity_i_gain_pulse uint16[] 速度制御Iゲイン
velocity_p_gain_pulse uint16[] 速度制御Pゲイン
position_d_gain_pulse uint16[] 位置制御Dゲイン Proシリーズは非対応であり, "0"で埋められる
position_i_gain_pulse uint16[] 位置制御Iゲイン Proシリーズは非対応であり, "0"で埋められる
position_p_gain_pulse uint16[] 位置制御Pゲイン
feedforward_2nd_gain_pulse uint16[] FF第2ゲイン Proシリーズは非対応であり, "0"で埋められる
feedforward_1st_gain_pulse uint16[] FF第1ゲイン Proシリーズは非対応であり, "0"で埋められる
`error` field の詳細
error field :

pub_ratio/error 周期で read され, read されたタイミングのみ全ての情報が埋められる. id_listフィールドの長さとそれ以外の field の長さは必ず一致.すなわち,id_list が空配列なら他の field も空配であり,id_listが長さNの配列なら他の field も長さNの配列になる.

Field Type Description
id_list uint16[] サーボIDのリスト
input_voltage bool[] 入力電圧が上限下限に引っかかっている
motor_hall_sensor bool[] ホールセンサの異常
overheating bool[] 現在温度が温度上限を超えている
motor_encoder bool[] エンコーダの異常
electrical_shock bool[] 電子回路の異常
overload bool[] 過負荷 (判定アルゴリズムは不明)
`extra` field の詳細
extra field :

pub_ratio/extra.dynamic_itemspub_ratio/extra.static_items の周期で read される.
id_list フィールドの長さとそれ以外の配列要素の長さは必ず一致する.

Field Sub field Type Description Note
id_list - uint16[] サーボIDのリスト
model - string[] シリーズ名 (X, P, Pro)
model_number - uint16[] モデル番号
protocol_type - uint16[] プロトコル種別 通常 2
firmware_version - uint16[] ファームウェアバージョン
realtime_tick_s - float64[] Realtime tick(秒)
moving_status velocity_profile string[] 速度プロファイル種別 none/rectangular/triangular/trapezoidal
following_error bool[] 追従誤差フラグ
profile_ongoing bool[] プロファイル実行中フラグ
in_position bool[] 目標位置到達フラグ
moving - bool[] 動作中フラグ
return_delay_time_us - float64[] 応答遅延時間(us)
drive_mode torque_on_by_goal_update bool[] Goal受信時の自動トルクON設定
profile_configuration string[] 時間ベース/速度ベース設定 time_based/velocity_based
reverse_mode bool[] 逆回転モード
shadow_id - uint16[] Shadow ID 255=Disable
homing_offset_deg - float64[] 原点オフセット(deg)
moving_threshold_deg_s - float64[] Moving判定の速度閾値(deg/s)
restore_configuration ram_restore bool[] RAM復元設定
startup_torque_on bool[] 起動時トルクON設定
pwm_slope_percent - float64[] PWM slope(%) X330系のみ
shutdown overload_error bool[] 過負荷で停止
electrical_shock_error bool[] 電気衝撃で停止
motor_encoder_error bool[] エンコーダ異常で停止
motor_hall_sensor_error bool[] ホールセンサ異常で停止
overheating_error bool[] 過熱で停止
input_voltage_error bool[] 電圧異常で停止
led red_percent float64[] 赤LED (%) Xシリーズは 0/100 の二値
blue_percent float64[] 青LED (%) Pシリーズのみ
green_percent float64[] 緑LED (%) Pシリーズのみ
bus_watchdog_ms - float64[] 通信断時停止タイムアウト(ms)
reboot - bool[] reboot要求フラグ 状態topicでは通常 false

非対応項目の publish 値:

  • Pro 非対応の float64[].nan
  • Pro 非対応の整数系 (uint8[] 等) は 0
  • 文字列系の非対応項目は空文字 ""

サーボが動作しないときにコマンドラインで状況を確認するためのデバッグ用の topic.
現在値と目標値の更新タイミングが異なるので注意.

Field Sub field Type Description
status DynamixelStatus サーボの基本状態 (トルク, エラー有無, ping, 制御モード).pub_ratio/status 周期でread.
current_ma present float64[] 現在の電流値 (mA).pub_ratio/present.current 周期でread.
goal float64[] 目標電流値 (mA).pub_ratio/goal 周期でread.
velocity_deg_s present float64[] 現在の速度 (deg/s).pub_ratio/present.velocity 周期でread.
goal float64[] 目標速度 (deg/s).pub_ratio/goal 周期でread.
position_deg present float64[] 現在の位置 (deg).pub_ratio/present.position 周期でread.
goal float64[] 目標位置 (deg).pub_ratio/goal 周期でread.

/dynamixel/statesstatus フィールドを単独で publish する topic.

/dynamixel/statespresent フィールドを単独で publish する topic.

/dynamixel/statesgoal フィールドを単独で publish する topic.

/dynamixel/statesgain フィールドを単独で publish する topic.

/dynamixel/stateslimit フィールドを単独で publish する topic.

/dynamixel/stateserror フィールドを単独で publish する topic.

/dynamixel/statesextra フィールドを単独で publish する topic.

Subscribed Topics

dynamixel_handler ノードが subscribe する topic を以下に示す.
Subscribe 時にデータが一時保存され,直後のメインループ内で書き込みが行われるため,書き込みの最大周期はloop_rate[Hz]となる.

Xシリーズ用のコマンドを統合した topic. Subscribe したデータの各 field (pwm_control, status, ... など)の中で id_listフィールドが埋まっているfieldのみ処理される.
Parameters の章の初期化・終了時等の挙動設定における init/used_servo_series パラメータで X: true に設定されている場合に利用可能.

Field Type Description
pwm_control DynamixelControlXPwm PWM制御モードへの変更と目標PWM値の設定.
current_control DynamixelControlXCurrent 電流制御モードへの変更と目標電流値の設定.
velocity_control DynamixelControlXVelocity 速度制御モードへの変更と目標速度などの設定.
position_control DynamixelControlXPosition 位置制御モードへの変更と目標位置などの設定.
extended_position_control DynamixelControlXExtendedPosition 拡張位置制御モードへの変更と目標位置などの設定.
current_base_position_control DynamixelControlXCurrentBasePosition 電流制限付き位置制御モードへの変更と目標電流・目標位置などの設定.
status DynamixelStatus サーボの基本状態(トルクON/OFF, エラークリア, ID追加/削除, 制御モード変更)の設定.
gain DynamixelGain 各種制御ゲインの設定.
limit DynamixelLimit 各種制限値の設定.
extra DynamixelExtra その他の多様な項目の設定
`pwm_control` field の詳細

id_listpwm_percentの長さは一致する必要がある.

Field Type Description
id_list uint16[] 適用するサーボIDのリスト.
pwm_percent float64[] 目標PWM値 (%). goal_pwmアドレスに書き込まれる.
`current_control` field の詳細

id_listcurrent_maの長さは一致する必要がある.

Field Type Description
id_list uint16[] 適用するサーボIDのリスト.
current_ma float64[] 目標電流値 (mA). goal_currentアドレスに書き込まれる.
`velocity_control` field の詳細

velocity_deg_sprofile_acc_deg_ssのどちらかのみが空配列であってもよい. id_listvelocity_deg_s または profile_acc_deg_ssの長さは一致する必要がある.

Field Type Description
id_list uint16[] 適用するサーボIDのリスト.
velocity_deg_s float64[] 目標速度 (deg/s). goal_velocityアドレスに書き込まれる.
profile_acc_deg_ss float64[] プロファイル加速度 (deg/s^2). profile_accelerationアドレスに書き込まれる.
`position_control` field の詳細

全ての要素が指定されている必要はない. 指定された要素とid_listの長さは一致する必要がある.

Field Type Description
id_list uint16[] 適用するサーボIDのリスト.
position_deg float64[] 目標位置 (deg). goal_positionアドレスに書き込まれる.
profile_vel_deg_s float64[] プロファイル速度 (deg/s). profile_velocityアドレスに書き込まれる.
profile_acc_deg_ss float64[] プロファイル加速度 (deg/s^2). profile_accelerationアドレスに書き込まれる.
`extended_position_control` field の詳細

全ての要素が指定されている必要はない. 指定された要素とid_listの長さは一致する必要がある.

Field Type Description
id_list uint16[] 適用するサーボIDのリスト.
position_deg float64[] 目標位置 (deg).goal_positionアドレスに書き込まれる.
rotation float64[] 回転数. goal_positionアドレスに position_deg + rotation * 360 degに相当する値が書き込まれる.
profile_vel_deg_s float64[] プロファイル速度 (deg/s). profile_velocityアドレスに書き込まれる.
profile_acc_deg_ss float64[] プロファイル加速度 (deg/s^2). profile_accelerationアドレスに書き込まれる.
`current_base_position_control` field の詳細

全ての要素が指定されている必要はない. 指定された要素とid_listの長さは一致する必要がある.

Field Type Description
id_list uint16[] 適用するサーボIDのリスト.
current_ma float64[] 目標電流値 (mA). goal_currentアドレスに書き込まれる.
position_deg float64[] 目標位置 (deg). goal_positionアドレスに書き込まれる.
rotation float64[] 回転数. goal_positionアドレスに position_deg + rotation * 360 deg (例: 1.2*360 deg)に相当する値が書き込まれる.
profile_vel_deg_s float64[] プロファイル速度 (deg/s). profile_velocityアドレスに書き込まれる.
profile_acc_deg_ss float64[] プロファイル加速度 (deg/s^2). profile_accelerationアドレスに書き込まれる.

status, gain, limit, extra field は下記 /dynamixel/commands/all topic の説明を参照

Pシリーズ用のコマンドを統合した topic. Subscribe したデータの各 field (pwm_control, status, ... など)の中で id_listフィールドが埋まっているfieldのみ処理される.
Parameters の章の初期化・終了時等の挙動設定における init/used_servo_series パラメータで P: true に設定されている場合に利用可能.

Field Type Description
pwm_control DynamixelControlPPwm PWM制御モードへの変更と目標PWM値の設定.
current_control DynamixelControlPCurrent 電流制御モードへの変更と目標電流値の設定.
velocity_control DynamixelControlPVelocity 速度制御モードへの変更と目標速度などの設定.
position_control DynamixelControlPPosition 位置制御モードへの変更と目標位置などの設定.
extended_position_control DynamixelControlPExtendedPosition 拡張位置制御モードへの変更と目標位置などの設定.
status DynamixelStatus サーボの基本状態(トルクON/OFF, エラークリア, ID追加/削除, 制御モード変更)の設定.
gain DynamixelGain 各種制御ゲインの設定.
limit DynamixelLimit 各種制限値(温度, 電圧, PWM, 電流, 加速度, 速度, 位置上限/下限)の設定.
extra DynamixelExtra その他の多様な情報の設定
`pwm_control` field の詳細

id_listpwm_percentの長さは一致する必要がある.

Field Type Description
id_list uint16[] 適用するサーボIDのリスト.
pwm_percent float64[] 目標PWM値 (%). goal_pwmアドレスに書き込まれる.
`current_control` field の詳細

id_listcurrent_maの長さは一致する必要がある.

Field Type Description
id_list uint16[] 適用するサーボIDのリスト.
current_ma float64[] 目標電流値 (mA). goal_currentアドレスに書き込まれる.
`velocity_control` field の詳細

全ての要素が指定されている必要はない. 指定された要素とid_listの長さは一致する必要がある.

Field Type Description
id_list uint16[] 適用するサーボIDのリスト.
current_ma float64[] 目標電流値 (mA). goal_currentアドレスに書き込まれる.
velocity_deg_s float64[] 目標速度 (deg/s). goal_velocityアドレスに書き込まれる.
profile_acc_deg_ss float64[] プロファイル加速度 (deg/s^2). profile_accelerationアドレスに書き込まれる.
`position_control` field の詳細

全ての要素が指定されている必要はない. 指定された要素とid_listの長さは一致する必要がある.

Field Type Description
id_list uint16[] 適用するサーボIDのリスト.
current_ma float64[] 目標電流値 (mA). goal_currentアドレスに書き込まれる.
velocity_deg_s float64[] 目標速度 (deg/s). goal_velocityアドレスに書き込まれる.
position_deg float64[] 目標位置 (deg). goal_positionアドレスに書き込まれる.
profile_vel_deg_s float64[] プロファイル速度 (deg/s). profile_velocityアドレスに書き込まれる.
profile_acc_deg_ss float64[] プロファイル加速度 (deg/s^2). profile_accelerationアドレスに書き込まれる.
`extended_position_control` field の詳細

全ての要素が指定されている必要はない. 指定された要素とid_listの長さは一致する必要がある.

Field Type Description
id_list uint16[] 適用するサーボIDのリスト.
current_ma float64[] 目標電流値 (mA). goal_currentアドレスに書き込まれる.
velocity_deg_s float64[] 目標速度 (deg/s). goal_velocityアドレスに書き込まれる.
position_deg float64[] 目標位置 (deg).goal_positionアドレスに書き込まれる.
rotation float64[] 回転数. goal_positionアドレスに position_deg + rotation * 360 degに相当する値が書き込まれる.
profile_vel_deg_s float64[] プロファイル速度 (deg/s). profile_velocityアドレスに書き込まれる.
profile_acc_deg_ss float64[] プロファイル加速度 (deg/s^2). profile_accelerationアドレスに書き込まれる.

status, gain, limit, extra field は下記 /dynamixel/commands/all topic の説明を参照

Proシリーズ用のコマンドを統合した topic. Subscribe したデータの各 field (current_control, status, ... など)の中で id_listフィールドが埋まっているfieldのみ処理される.
Parameters の章の初期化・終了時等の挙動設定における init/used_servo_series パラメータで Pro: true に設定されている場合に利用可能.

Field Type Description
current_control DynamixelControlProCurrent 電流制御モードへの変更と目標電流値の設定.
velocity_control DynamixelControlProVelocity 速度制御モードへの変更と目標速度などの設定.
position_control DynamixelControlProPosition 位置制御モードへの変更と目標位置などの設定.
extended_position_control DynamixelControlProExtendedPosition 拡張位置制御モードへの変更と目標位置などの設定.
status DynamixelStatus サーボの基本状態(トルクON/OFF, エラークリア, ID追加/削除, 制御モード変更)の設定.
gain DynamixelGain 各種制御ゲインの設定.
limit DynamixelLimit 各種制限値の設定.
extra DynamixelExtra その他の多様な情報の設定
`current_control` field の詳細

id_listcurrent_maの長さは一致する必要がある.

Field Type Description
id_list uint16[] 適用するサーボIDのリスト.
current_ma float64[] 目標電流値 (mA). goal_currentアドレスに書き込まれる.
`velocity_control` field の詳細

全ての要素が指定されている必要はない. 指定された要素とid_listの長さは一致する必要がある.

Field Type Description
id_list uint16[] 適用するサーボIDのリスト.
current_ma float64[] 目標電流値 (mA). goal_currentアドレスに書き込まれる.
velocity_deg_s float64[] 目標速度 (deg/s). goal_velocityアドレスに書き込まれる.
acceleration_deg_ss float64[] 目標加速度 (deg/s^2). goal_accelerationアドレスに書き込まれる.
`position_control` field の詳細

全ての要素が指定されている必要はない. 指定された要素とid_listの長さは一致する必要がある.

Field Type Description
id_list uint16[] 適用するサーボIDのリスト.
current_ma float64[] 目標電流値 (mA). goal_currentアドレスに書き込まれる.
acceleration_deg_ss float64[] 目標加速度 (deg/s^2). goal_accelerationアドレスに書き込まれる.
velocity_deg_s float64[] 目標速度 (deg/s). goal_velocityアドレスに書き込まれる.
position_deg float64[] 目標位置 (deg). goal_positionアドレスに書き込まれる.
`extended_position_control` field の詳細

全ての要素が指定されている必要はない. 指定された要素とid_listの長さは一致する必要がある.

Field Type Description
id_list uint16[] 適用するサーボIDのリスト.
current_ma float64[] 目標電流値 (mA). goal_currentアドレスに書き込まれる.
acceleration_deg_ss float64[] 目標加速度 (deg/s^2). goal_accelerationアドレスに書き込まれる.
velocity_deg_s float64[] 目標速度 (deg/s). goal_velocityアドレスに書き込まれる.
position_deg float64[] 目標位置 (deg).goal_positionアドレスに書き込まれる.
rotation float64[] 回転数. goal_positionアドレスに position_deg + rotation * 360 degに相当する値が書き込まれる.

status, gain, limit, extra field は下記 /dynamixel/commands/all topic の説明を参照

全シリーズを共通で扱うための topic. シリーズ共通で扱うため,status.mode で制御モードを指定しgoal.~で各種目標値を与える.

Field Type Description
status DynamixelStatus サーボの基本状態(トルクON/OFF, エラークリア, ID追加/削除, 制御モード変更)の設定.
goal DynamixelGoal 各種目標値の設定.
gain DynamixelGain 各種制御ゲイン(速度I/Pゲイン, 位置D/I/Pゲイン, FFゲイン)の設定.
limit DynamixelLimit 各種制限値(温度, 電圧, PWM, 電流, 加速度, 速度, 位置上限/下限)の設定.
extra DynamixelExtra その他の多様な情報の設定

{~}_control系の field がないため制御モードの自動変更機能は無し.

`status` field の詳細

全ての要素が指定されている必要はない. 指定された要素とid_listの長さは一致する必要がある.

Field Type Description
id_list uint16[] 適用するサーボIDのリスト.
torque bool[] トルクON/OFF. 例: ID 1はON, ID 2はOFF.
error bool[] エラークリア試行. trueでもfalseでもエラー解除を試みる.
ping bool[] trueなら対応IDを認識リストに追加, falseなら削除.
mode string[] 制御モード変更. 文字列で指定. (詳細はDynamixelStatus型の説明を参照)

mode については,各モードの{~}_control系の topic を送ることでも自動設定されるので,基本的には使わなくもてOK.

`goal` field の詳細

全ての要素が指定されている必要はない. 指定された要素とid_listの長さは一致する必要がある.

Field Type Description Note
id_list uint16[] 適用するサーボIDのリスト.
pwm_percent float64[] 目標PWM値 (%). goal_pwmアドレスに書き込まれる. Proシリーズは非対応
current_ma float64[] 目標電流値 (mA). goal_currentアドレスに書き込まれる.
velocity_deg_s float64[] 目標速度 (deg/s). goal_velocityアドレスに書き込まれる.
profile_vel_deg_s float64[] プロファイル速度 (deg/s). profile_velocityアドレスに書き込まれる. Proシリーズは非対応
profile_acc_deg_ss float64[] プロファイル加速度 (deg/s^2). profile_accelerationアドレスに書き込まれる. Proシリーズではgoal_accelerationに対応する.
position_deg float64[] 目標位置 (deg). goal_positionアドレスに書き込まれる.
`gain` field の詳細

全ての要素が指定されている必要はない. 指定された要素とid_listの長さは一致する必要がある.

Field Type Description Note
id_list uint16[] 適用するサーボIDのリスト.
velocity_i_gain_pulse uint16[] 速度制御Iゲイン (パルス値).
velocity_p_gain_pulse uint16[] 速度制御Pゲイン (パルス値).
position_d_gain_pulse uint16[] 位置制御Dゲイン (パルス値). Proシリーズは非対応
position_i_gain_pulse uint16[] 位置制御Iゲイン (パルス値). Proシリーズは非対応
position_p_gain_pulse uint16[] 位置制御Pゲイン (パルス値).
feedforward_2nd_gain_pulse uint16[] FF第2ゲイン (パルス値). Pシリーズは非対応
feedforward_1st_gain_pulse uint16[] FF第1ゲイン (パルス値). Pシリーズは非対応
`limit` field の詳細

全ての要素が指定されている必要はない. 指定された要素とid_listの長さは一致する必要がある.

※ limit はROM領域の値なので,書き込む場合torqueが強制的にOFFになることに注意.

Field Type Description Note
id_list uint16[] 適用するサーボIDのリスト.
temperature_limit_degc float64[] 温度上限 (°C).
max_voltage_limit_v float64[] 入力電圧上限 (V).
min_voltage_limit_v float64[] 入力電圧下限 (V).
pwm_limit_percent float64[] PWM上限 (%) Proシリーズは非対応
current_limit_ma float64[] 電流値上限 (mA).
acceleration_limit_deg_ss float64[] 加速度上限 (deg/s^2). Xシリーズは非対応
velocity_limit_deg_s float64[] 速度上限 (deg/s).
max_position_limit_deg float64[] 位置上限 (deg).
min_position_limit_deg float64[] 位置下限 (deg).
`extra` field の詳細

/dynamixel/command/extra では、id_list に含まれる ID に対して指定項目を更新する。
更新したいフィールドの配列長は id_list と一致している必要がある。

以下では command/extra で書き込み可能な項目のみを記載する。
ここにない項目(model, model_number, protocol_type, firmware_version, realtime_tick_s, moving_status, moving など)は read-only である。

Field Sub field Type Description Note
id_list - uint16[] 書き込み対象のサーボID 必須
return_delay_time_us - float64[] 応答遅延時間(us) デフォルト値として一括設定も可能
drive_mode torque_on_by_goal_update bool[] Goal受信時の自動トルクON設定
profile_configuration string[] 時間ベース/速度ベース設定 time_based/velocity_based
reverse_mode bool[] 逆回転モード
shadow_id - uint16[] Shadow ID 255=Disable
homing_offset_deg - float64[] 原点オフセット(deg)
moving_threshold_deg_s - float64[] Moving判定の速度閾値(deg/s)
restore_configuration ram_restore bool[] RAM復元設定
startup_torque_on bool[] 起動時トルクON設定
pwm_slope_percent - float64[] PWM slope(%) X330系のみ
shutdown overload_error bool[] 過負荷で停止
electrical_shock_error bool[] 電気衝撃で停止
motor_encoder_error bool[] エンコーダ異常で停止
motor_hall_sensor_error bool[] ホールセンサ異常で停止
overheating_error bool[] 過熱で停止
input_voltage_error bool[] 電圧異常で停止
led red_percent float64[] 赤LED (%) Xシリーズは 0/100 の二値
blue_percent float64[] 青LED (%) Pシリーズのみ
green_percent float64[] 緑LED (%) Pシリーズのみ
bus_watchdog_ms - float64[] 通信断時停止タイムアウト(ms)
reboot - bool[] true で reboot 命令を送信

Dynamixelの起動、停止、エラー解除などのショートカットコマンド

Field Type Description
command string コマンドの文字列 (下記の Shortcut Command list 参照)
id_list uint16[] 適用するサーボのIDリスト. [] or [254] とすると認識されているすべてのIDを選択したのと同等となる.
Shortcut Command list

/dynamixel/shortcutトピックの commandフィールドに指定できる文字列. DynamixelShortcut型の定義内で定数として定義されている.

  • 高レベルコマンド:ユーザの利用を想定

    • torque_on/ TON : 安全にトルクをenableにする.目標姿勢を現在姿勢へ一致させ,速度を0にする.
    • torque_off/ TOFF: トルクをdisableにする.
    • clear_error/ CE: ハードウェアエラー(ex. overload)をrebootによって解除する.
      回転数の情報が喪失する問題を解消するために,homing offset用いて自動で補正する.
    • remove_id/ RMID: 指定したIDのサーボを認識リストから削除する.
    • add_id/ ADID : 指定したIDのサーボを認識リストに追加する.
  • 低レベルコマンド:開発者向け

    • reset_offset: homing offset アドレスに 0 を書き込む.
    • enable : torque enable アドレスに true を書き込む.
    • disable: torque enable アドレスに false を書き込む.
    • reboot : reboot インストラクションを送る

/dynamixel/command/status (DynamixelStatus)

/dynamixel/commands/{~} の status フィールドを単独で subscribe する topic.

/dynamixel/command/goal (DynamixelGoal)

/dynamixel/commands/{~} の goal フィールドを単独で subscribe する topic.

/dynamixel/command/gain (DynamixelGain)

/dynamixel/commands/{~} の gain フィールドを単独で subscribe する topic.

/dynamixel/command/limit (DynamixelLimit)

/dynamixel/commands/{~} の limit フィールドを単独で subscribe する topic.

/dynamixel/command/extra (DynamixelExtra)

/dynamixel/commands/{~} の extra フィールドを単独で subscribe する topic.

Xシリーズ用の制御コマンド

関連するgoal値の設定+制御モードの変更を行う.

Pシリーズ用の制御コマンド

関連するgoal値の設定+制御モードの変更を行う.

Proシリーズ用の制御コマンド

関連するgoal値の設定+制御モードの変更を行う.


Parameters

通信関係の設定

# 通信機器の設定
  device_name: /dev/ttyUSB0 # 通信するデバイス名
  baudrate: 1000000         # 通信速度
  latency_timer: 16         # 通信のインターバル

基本的な通信の設定.自分の環境に合わせて設定する.

初期化・終了時等の挙動設定

# サーボの初期設定
  init/dummy_servo_list: [-1]                                     # ダミーのサーボを作成するIDのリスト,同じIDのサーボが存在する場合でもダミーが優先される. [0, 254]の範囲外は無視される.
  init/baudrate_auto_set: false                                   # 探索前に,全てのサーボと全てのBaudrateに対して,baudrateの書き込みをするかどうか
  init/used_servo_series: {X: true, P: false, Pro: false}         # 使用するサーボのシリーズ
  init/expected_servo_num: 0
  init/servo_auto_search: {min_id: 0, max_id: 10, retry_times: 0} # サーボのIDを自動で探索するかどうか
  init/hardware_error_auto_clean: true                            # 初期化時に Hardware error を自動でクリアするかどうか
  init/torque_auto_enable: true                                   # 初期化時に Torque を自動でONにするかどうか
  term/torque_auto_disable: true                                  # 終了時に Torque を自動でOFFにするかどうか
  term/servo_auto_stop: true                                      # 終了時に電流・速度制御のサーボを停止するかどうか

init/dummy_servo_listに指定したIDは,実際のサーボが存在しなくても,プログラム上ダミーのサーボが作成される.つまり何もつながなくても /dynamixel/statesなどの topic がpublishされる.
実機がない場合での上位の node の動作確認などに便利. 指定したIDのサーボがつながれている場合でもIDが指定されていればダミーサーボが優先されるので,実際のサーボとの通信は行われない.
ロボットを動かさずに上位の node の動作確認がしたいときに,ロボット全部のサーボのIDをダミーに指定してやると安全に動作確認ができる. 利用できるIDは[0, 254]の範囲で,それ以外のIDは無視される.空配列を与えるとエラーが起きるので注意.

init/baudrate_auto_settrueの時は,全てのサーボと全ての baudrate に対して,事前に baudrateの書き込みを行う.
したがって,起動時にBaudrateが baudrateと異なるサーボがあっても自動的に baudrateに統一される.

init/expected_servo_num0の時は,1つ以上servoが見つかるまでスキャンを繰り返す.
init/expected_servo_num0でない場合は,その数だけservoが見つかるまでスキャンを繰り返す.
init/servo_auto_search.retry_timesの回数分のスキャンが失敗した場合,初期化失敗でdynamixel_handlerノードは落ちる.

# デフォルト値の設定
  default/profile_acc: 6008.0    # deg/s^2
  default/profile_vel: 1000.0    # deg/s
  default/return_delay_time: 0.0 # us [double]
  default/bus_watchdog: 500.0    # ms [double], auto_stop用のbus_watchdog既定値

default/profile_accdefault/profile_velは位置制御時の最大加速度と最大速度を決める. この値が大きければキビキビとした動作になり,小さければ滑らかな動作になる. {~}_control系の topic で動的に指定することも可能.

default/return_delay_timeはサーボの応答遅延時間を設定する.基本的に0でいいはず. default/bus_watchdogterm/servo_auto_stop=true かつ command/extra.bus_watchdog_ms 未指定IDに適用される既定値(ms).

# 通信の設定
  dyn_comm/retry_num: 5    # 通信失敗時のリトライ回数
  dyn_comm/inerval_msec: 4 # 通信失敗時のインターバル時間
  dyn_comm/verbose: false  # 通信失敗時の詳細をエラーとして出すか

主に ping などのサーボ単体との通信失敗時の挙動を決める.
基本的に数字が小さい方が初期化が早くなるが,サーボを発見できない可能性が高くなる.(デフォルト値は大きめに設定している)

dyn_comm/verbosetrueの時は,通信失敗時に詳細なエラーを出力する.基本は falseで問題ない.

実行時の動作設定

# ループの設定
  loop_rate: 100                   # メインループの周期
  verbose_ratio: 300               # メインループのlog出力の割合(処理時間,通信の成功率), ex 100なら100回に1回出力
  pub_outdated_present_value: true # 最新でないpresent_XXXをpublishするかどうか. false ならば 直近のループでreadした Present の要素のみmsgに含められる.
  pub_ratio/present:               # present_XXXを読み取り,/dynamixel/state/present トピックをpublishする割合
      pwm:                 2 # この回数に一回present_pwmを読み取る, 0=メインループで読み取らない
      current:             2 # この回数に一回present_currentを読み取る, 0=メインループで読み取らない
      velocity:            2 # この回数に一回present_velocityを読み取る, 0=メインループで読み取らない
      position:            2 # この回数に一回present_positionを読み取る, 0=メインループで読み取らない
      velocity_trajectory: 0 # この回数に一回velocity_trajectoryを読み取る, 0=メインループで読み取らない
      position_trajectory: 0 # この回数に一回position_trajectoryを読み取る, 0=メインループで読み取らない
      input_voltage:      29 # この回数に一回present_input_voltageを読み取る, 0=メインループで読み取らない
      temperature:        29 # この回数に一回present_temperatureを読み取る, 0=メインループで読み取らない
  pub_ratio/status: 47             # この回数に一回 Status を読み取り,/dynamixel/state/status トピックをpublishする, 0=メインループで読み取らない
  pub_ratio/goal: 11               # この回数に一回 Goal を読み取り,/dynamixel/state/goal トピックをpublishする, 0=メインループで読み取らない
  pub_ratio/gain: 101              # この回数に一回 Gain を読み取り,/dynamixel/state/gain トピックをpublishする, 0=メインループで読み取らない
  pub_ratio/limit: 307             # この回数に一回 Limit を読み取り,/dynamixel/state/limit トピックをpublishする, 0=メインループで読み取らない
  pub_ratio/error: 53              # この回数に一回 Hardware error を読み取り,/dynamixel/state/error トピックをpublishする, 0=メインループで読み取らない
  pub_ratio/extra:                 # この回数に一回 Extra を読み取る, 0=初回のみ
      dynamic_items: 31      # moving_status/realtime_tick/moving など動的に変化する項目
      static_items: 407      # それ以外の項目

pub_ratio/{~}の各情報 (status, present, goal, gain, limit, error, extra) は topic 名と対応.
read と publish 周期はloop_ratepub_ratio/{~}で割った値となる.

例: loop_rate= 100, pub_ratio/status= 47 の時 100/47 ≃ 2Hz.
pub_ratio0 の項目はメインループで read されない(初期化時の値は保持される). bus_watchdog の監視/解除/再設定は status 読み取りタイミングで実行されるため,pub_ratio/status 周期に依存する.

pub_ratio/extradynamic_itemsstatic_items の2系統で読み取る.
どちらかで更新があれば /dynamixel/state/extra はpublishされる.

デフォルト値を素数にしているのは, serial read のタイミングが被って1ループの処理時間が長くなるのを防ぐため.

present値のみ高速化のために各アドレス(pwm, current, ... , temperature)の読み取り割合を設定できる.
~/presentトピックの publish 周期はloop_ratepub_ratio/present.{~}の最小値で割った値となる.

例: loop_rate= 100, pub_ratio/present.current= 2 の時 100/2 = 50Hz.

このため,present値の直近で読み取った最新の値と,古い値が混在することになる.
pub_outdated_present_valuetrueの場合は古い値も含めて全てのアドレスの値を publish する.
pub_outdated_present_valuefalseの場合は,直近のループで読み取った値のみを publish する.

# Read/Write方式
  method/fast_read: false  # Fast Sync Read を使うかどうか
  method/split_read: false # 複数の情報を分割して読み取るかどうか
  method/split_write: true # 複数の情報を分割して書き込むかどうか

method/fast_readtrueの場合は Fast Sync Read を使い,falseの場合は Sync Read を使う.それぞれの違いは公式の動画を参照されたし.
基本的にtrueの方が高速.ファームウェアが古い場合は falseでないと情報が読み取れないのでデフォルトはfalse

method/split_readtrueの場合は,各情報を分割して読み取り,falseの場合は一括で読み取る.
falseの方が高速.trueの方が安定.

method/split_writetrueの場合は,各情報を分割して書き込み,falseの場合は一括で書き込む.
falseの方が高速だが,あまり差はない.trueの方が安定.

Note

上記のread方式による速度の違いについては速度に関してメモも参照.

log出力関係

# デバッグ用
  max_log_width: 6                  # 以下のlog出力で,サーボ何個ごとに改行を入れるか
  verbose/callback: false           # コールバック関数の呼び出しを出力
  verbose/write_status: false       # 書き込みするstatusデータのpulse値を出力
  verbose/write_goal: false         # 書き込みするgoalデータのpulse値を出力
  verbose/write_gain: false         # 書き込みするgainデータのpulse値を出力
  verbose/write_limit: false        # 書き込みするlimitデータのpulse値を出力
  verbose/read_status:  {raw: false, err: false}
  verbose/read_present: {raw: false, err: false}
  verbose/read_goal:    {raw: false, err: false}
  verbose/read_gain:    {raw: false, err: false}
  verbose/read_limit:   {raw: false, err: false}
  verbose/read_extra:   {raw: true, err: false}
  verbose/read_hardware_error: true # 検出したHardware errorを出力

基本的には上記の説明の通り. verbose/write_{~}verbose/read_{~}trueの場合は,書き込むアドレスと書き込むパルス値を直接確認できる.

開発用

# 開発用
  debug: false                        # true: デバイスとの接続に失敗してもエラーを出力しない/ false: エラーを出力して終了する
  no_use_command_line: false          # true: プログラム用の topic のみ使用する/ false: コマンドライン用の topic も出力する
  no_response_id_auto_remove_count: 0 # 連続で無応答になったIDを認識リストから自動削除する閾値(0=無効)

debugtrueの場合は,デバイスとの接続失敗やサーボが見つからなかった場合でもプログラムが続行する.

no_use_command_linetrueの場合は,コマンドライン用の topic を publish & subscribe しないので,$ ros2 topic listがすっきりする.起動時にDDSがネットワークにかける負荷も小さくなるかも?(未確認)

no_response_id_auto_remove_count0より大きい場合,指定回数を超えて無応答が続いたIDを実行中に認識リストから自動削除する.


Optional機能

Dynamixel本体の標準的な制御(status/goal/present/gain/limit/error)とは独立した拡張機能.
現状は External PortOpenCR IMU に対応している.

概要

Feature 有効化パラメータ Publish Subscribe 初期化時の挙動
External Port option/external_port.use dynamixel/external_port/read dynamixel/external_port/write 対象サーボが無くても継続
OpenCR IMU option/imu_opencr.use dynamixel/imu/raw dynamixel/imu/calibration_gyro WARNを出して継続

External Port

X540シリーズと P/Pro シリーズの外部ポート機能を扱う optional 機能.
利用する場合は option/external_port.usetrue に設定する.

option/external_port:
    use: false
    pub_ratio/data: 10  # Dataを読む周期(loop回数基準)
    pub_ratio/mode: 100 # Modeを読む周期(loop回数基準)
    verbose/callback: false
    verbose/write: false
    verbose/read: {raw: false, err: false}
  • Publish: dynamixel/external_port/read
  • Subscribe: dynamixel/external_port/write
  • Data項目: external_port_data_{1,2,...}
  • Mode項目: external_port_mode_{1,2,...}
  • デフォルトでは読み込み対象IDは空で,/dynamixel/external_port/write で指定されたIDのみを読む

/dynamixel/external_port/read (DxlExternalPort)

option/external_port.pub_ratio/modeoption/external_port.pub_ratio/data のいずれかで読み取りが発生したループで publish される.

Field Type Description
stamp builtin_interfaces/Time データが読み取れた時刻
id_list uint16[] サーボのID
port uint16[] External Portのポート番号
mode string[] ポートのモードの配列 (以下の External port mode list を参照)
data int16[] ポートのデータ (analog: 0~4096, digital: 0/1, unset: -1)
External port mode list
  • "a_in" = analog in : アナログ入力モードで,0-4096の値を読み取る.
  • "d_out" = digital out : デジタル出力モードで,High or Low の出力状態を表す.
  • "d_in_pu" = digital in (pull up) : プルアップ抵抗付きのデジタル入力モードで,0または1の値を読み取る.
  • "d_in_pd" = digital in (pull down) : プルダウン抵抗付きのデジタル入力モードで,0または1の値を読み取る.
  • "unset" : /dynamixel/external_port/read topic でポートを設定していない状態.

/dynamixel/external_port/write (DxlExternalPort)

サーボのIDとポート番号の組で External Port を指定する.
id_listport の長さは一致が必要で,mode / data は必要な方だけ指定できる(指定した要素は id_list と長さが一致する必要がある.).

Field Type Description
stamp builtin_interfaces/Time メッセージのタイムスタンプ(無効)
id_list uint16[] 適用するサーボのIDリスト.番号重複OK.
port uint16[] ポート番号 (X: 1-3, P/Pro: 1-4)
mode string[] ポートのモード.文字列で指定 (詳細はDxlExternalPort型の定数を参照)
data int16[] ポートのデータ.モードが digital out の場合のみ有効.(0: Low, 1: High)

OpenCR IMU

OpenCR上のIMUを sensor_msgs/msg/Imu として publish する optional 機能.

option/imu_opencr:
    use: false
    opencr_id: 40
    frame_id: base_link
    pub_ratio: 2
    model_number: 0
    adjust/rpy_deg: [0.0, 0.0, 180.0]
    adjust/flip_z_axis: true
    verbose/callback: false
    verbose/write: false
    verbose/read: {raw: false, err: false}
  • Publish: dynamixel/imu/raw (sensor_msgs/msg/Imu)
  • Subscribe: dynamixel/imu/calibration_gyro (std_msgs/msg/Empty)
  • 起動時に opencr_id への pingmodel_number を確認し,不一致時はWARNを出して機能を無効化
  • calibration_gyro 受信時はOpenCRへ校正コマンドを書き込み,現状実装では5秒待機
  • adjust/rpy_degadjust/flip_z_axis で座標補正を適用
  • OpenCRファームのControl Tableアドレスと src/optional_function/imu_opencr.cpp は必ず対応させること

dynamixel/imu/raw (sensor_msgs/msg/Imu)

loop_rate に対して pub_ratio ごとに read を実行し,read 成功時のみ publish する.

Field Type Description
header.stamp builtin_interfaces/Time publish時刻 (now)
header.frame_id string option/imu_opencr.frame_id
orientation.{x,y,z,w} float64 補正後クォータニオン(正規化済み)
angular_velocity.{x,y,z} float64 補正後角速度
linear_acceleration.{x,y,z} float64 補正後加速度
orientation_covariance float64[9] 現状は未設定(デフォルト値)
angular_velocity_covariance float64[9] 現状は未設定(デフォルト値)
linear_acceleration_covariance float64[9] 現状は未設定(デフォルト値)

dynamixel/imu/calibration_gyro (std_msgs/msg/Empty)

受信時に opencr_id 宛てにジャイロ校正コマンドを書き込む.
メッセージ本体のフィールドはなく,トリガー用途のみで使う.
コマンド送信後は現状実装で5秒待機する.


各種情報の分類と Control Table との対応

本パッケージでは,Dynamixelが持つ Control table 内の情報を,以下の様に分類して扱う.

状態 (status)

  • torque_enable : サーボが制御を受け付けるかどうか.falseだと脱力してトルクを出さない.
  • (ping) : Control table の情報ではないが,statusとして扱っている.pingが通るかどうか.
  • (error) : Control table の情報ではないが,statusとして扱っている.何らかのエラーを持っているかどうか.
  • operating_mode : サーボの制御モード,PWM, 電流制御, 速度制御, 位置制御, 拡張位置制御, 電流制御付き位置制御の6つのモードがある.
Subscribe / Write

Xシリーズの場合,/dynamixel/commands/xstatusフィールド or /dynamixel/command/statusによって設定され,loop_rateの周期で書き込まれる. operating_modeのみ,対応する/dynamixel/command/x/{~}_control系の topic を subscribe することでも自動で設定される.

Publish / Read

loop_rateの内pub_ratio/status毎に1回の周期で読みだされ,/dynamixel/statesstatusフィールド and /dynamixel/state/statusとして publish される.

目標値 (goal)

  • goal_pwm : 目標PWM値, PWM制御モードでのみ有効
  • goal_current : 目標電流値, 電流制御モードと電流制御付き位置制御でのみ有効
  • goal_velocity : 目標速度, 速度制御モードでのみ有効
  • goal_position : 目標角度, 位置制御モードと拡張位置制御モード,電流制御付き位置制御で有効
  • profile_acceleration : 最大加速度, 速度制御・位置制御・拡張位置制御・電流制御付き位置制御モードで有効
    • (goal_acceleration): Proシリーズでの表記.
  • profile_velocity : 目標速度値, 位置制御モードと拡張位置制御モード,電流制御付き位置制御で有効 (Proシリーズにはないが,goal_velocityで代用できる)
Subscribe / Write

Xシリーズの場合,/dynamixel/commands/xor /dynamixel/command/x/{~}_control系の topic or /dynamixel/command/goalによって設定され,loop_rateの周期で書き込まれる.

Publish / Read

loop_rateの内pub_ratio/goal毎に1回の周期で読みだされ,/dynamixel/statesgoalフィールド and /dynamixel/state/goalとして publish される.

現在値 (present)

  • present_pwm : 現在のPWM値 (Proシリーズにはない)
  • present_current : 現在の電流値
  • present_velocity : 現在の速度
  • present_position : 現在の角度
  • velocity_trajectory : 目標速度のようなもの (Proシリーズにはない)
  • position_trajectory : 目標角度のようなもの (Proシリーズにはない)
  • present_input_voltage: 現在の入力電圧
  • present_temperature : 現在の温度
Subscribe / Write

書き込みは不可.

Publish / Read

各アドレスの情報はloop_rateの内pub_ratio/present.{~}に一回の周期で読みだされる.
読みだされた情報は,loop_rateの内pub_ratio/present.{~}の最小値の割合で,/dynamixel/statespresentフィールド and /dynamixel/state/presentとして publish される.

ゲイン (gain)

  • velocity_i_gain :
  • velocity_p_gain :
  • position_d_gain : Proシリーズでは無効
  • position_i_gain : Proシリーズでは無効
  • position_p_gain :
  • feedforward_acc_gain : Proシリーズでは無効
  • feedforward_vel_gain : Proシリーズでは無効
Subscribe / Write

Xシリーズの場合,/dynamixel/commands/xgainフィールド or /dynamixel/command/gainによって設定され,loop_rateの周期で書き込まれる.

Publish / Read

loop_rateの内pub_ratio/gain毎に1回の周期で読みだされ,/dynamixel/statesgainフィールド and /dynamixel/state/gainとして publish される.

Note

制御モードによってデフォルト値が異なり,モードを変えると勝手に書き換えられてしまう.制御モードをまたぐ場合の処理については検討中.

制限 (limit)

  • temperature_limit : 温度がこの値を超えると Hardware error (overheating) が発生する.
  • max_voltage_limit : 入力電圧がこの値を超えると Hardware error (input_voltage) が発生する.
  • min_voltage_limit : 入力電圧がこの値を下回ると Hardware error (input_voltage) が発生する.
  • pwm_limit : 指定・発揮できるPWMの最大値 (Proシリーズにはない)
  • current_limit : 指定・発揮できる最大電流値
  • acceleration_limit : 最大加速度 (Xシリーズにはない)
  • velocity_limit : 最大速度
  • max_position_limit : 位置制御モードでの最大角度
  • min_position_limit : 位置制御モードでの最小角度
Subscribe / Write

Xシリーズの場合,/dynamixel/commands/xlimitフィールド or /dynamixel/command/limitによって設定され,loop_rateの周期で書き込まれる.

Publish / Read

loop_rateの内pub_ratio/limit毎に1回の周期で読みだされ,/dynamixel/stateslimitフィールド and /dynamixel/state/limitとして publish される.

Note

ROM領域の値の書き込みは torque が on 状態ではできないため,limit の書き込みが発生する場合は一瞬だけ torque を off にする処理が入ることに注意.

エラー (error)

  • hardware_error_status : サーボのハードウェアエラー情報
    検知されるエラーは以下の7種類.
    • input_voltage : 入力電圧が制限範囲外
    • motor_hall_sensor : モータのホールセンサの異常
    • overheating : 温度が最大値を超えた
    • motor_encoder : モータのエンコーダの異常
    • electrical_shock : 電子回路内での異常
    • overload : 過負荷
Subscribe / Write

書き込みは不可.

Publish / Read

loop_rateの内pub_ratio/error毎に1回の周期で読みだされ,/dynamixel/stateserrorフィールド and /dynamixel/state/errorとして publish される.

その他 (extra)

  • drive_mode : 駆動設定のビットフィールド.bit0=reverse, bit2=profile(time/velocity), bit3=goal受信時の自動トルクON,(X/Pのみ).
  • return_delay_time : Instruction受信からStatus Packet返送までの遅延時間.単位は 2[us],範囲は 0..254,初期値は 250(=500[us])
  • homing_offset : 原点オフセット.Present Position = Actual Position + Homing Offset として反映される.
  • moving_threshold : 速度閾値.|Present Velocity| > threshold のとき Moving1 になる.
  • startup_configuration : 起動時設定のビットフィールド.bit0=startup torque on, bit1=RAM restore(X/P)
  • pwm_slope : PWMの立ち上がり/立ち下がりのスロープ設定(X330系のみ).
  • shutdown : 保護条件のビットマスク.設定した異常を検出すると Torque Enable0 になり出力停止する.
  • bus_watchdog : 通信断のフェイルセーフ.1..127 の設定値に対し 設定値×20ms 無通信で停止し,watchdog error状態へ遷移する.
  • led : Xは単色LED (0/1).P/ProはRGB各チャネル (0..255) を設定できる.
  • realtime_tick : 内部時刻カウンタ.単位は 1ms,範囲は 0..32767 で周回する.
  • moving : 動作中フラグ.通常は moving_threshold で判定され,position profile実行中は 1 になる.
  • moving_status : 動作状態の詳細ビット.Xは profile_type + following_error + profile_ongoing + in_position,Pは profile_type + in_position を示す(Proは該当アドレスなし).

Note

(bus_watchdog の設定値が1以上の時) bus_watchdogの設定値 × 20ms 通信がないと自動で動作停止処理が実行される. しかし,位置制御系のモードかつ,homing_offset が設定されている状態でこの動作停止処理が走るとなぜか homing_offsetだけ回転する. firmwareのバグの模様,バージョンによってはこの問題が解消されているかもしれないが,危険なので位置制御系のモードで bus_watchdog を使うのは避けるべき. 本パッケージの既定では,term/servo_auto_stop=true かつ PWM・電流・速度制御モードの場合に bus_watchdog を自動管理する(既定値は default/bus_watchdog). command/extra.bus_watchdog_ms を指定したIDは,term/servo_auto_stop の値に関わらず指定値を優先して管理される(0 指定は watchdog無効値として扱う). 0 指定時の定期書き込みは term/servo_auto_stop=true のときのみ継続され,false のときは受信時書き込みのみとなる. command/extra.bus_watchdog_ms の書き込み自体は受信時に即時反映されるが,bus_watchdog の監視/解除/再設定は pub_ratio/status 周期で実行される. したがって pub_ratio/status=0 の場合,この監視/解除/再設定はメインループでは動作しない.

サポート外

  • status_return_level : Status Packetの返送条件 (0=PINGのみ, 1=PING/READ, 2=全Instruction) を設定する.
  • registered_instruction : REG_WRITE により未実行コマンドが登録済みかどうか (0/1) を示す.ACTION 実行後は 0 に戻る.
  • backup_ready : control table backup の可否状態 (0/1).

Note

registered_instruction と REG_WRITE + ACTION インストラクションを活用した制御はこのパッケージのtopicベースの制御に合わないため,除外する. serviceベースの制御を実装する場合にはそれ用にまとめ直す.

Baudrateの一括変更

config/config_dynamixel_unify_baudrate.yamlの以下の部分を編集し,保存

# config/config_dynamixel_unify_baudrate.yaml
/**:
    ros__parameters:
        # 通信機器の設定
        device_name: /dev/ttyUSB0 # 通信するデバイス名
        target_baudrate: 1000000  # 統一したい通信速度

ターミナルを開いて次を実行

ros2 launch dynamixel_handler dynamixel_unify_baudrate_launch.xml

全てのdynamixelの baudrate をtarget_baudrateに設定してくれる.

Note

dynamixel_unify_baudrate は Python ノードであり,内部で _mylib_dynamixel(pybind11モジュール)を利用する. _mylib_dynamixel が見つからない場合は,dynamixel_handler パッケージを再buildすること.


Latency Timer

シリアル通信にはパケットの送受信の間に latency timer 分のインターバルが挟まる. (USBデバイスのデフォルトは16msのようであり,高速な通信の妨げとなることが多い) 安定した通信のためには,使用するUSBデバイスの latency timer と ros param の latency_timer を一致させる必要がある.

ros param の変更には,config/config_dynamixel_handler.yamlの以下の部分を編集して保存する.

# config/config_dynamixel_handler.yaml
latency_timer: 4 # 通信のインターバル

使用するUSBデバイスの latency timer はコマンドラインから次のコマンドを実行することで変更できる. 基本的に1度だけ実行すればよい.

echo ACTION==\"add\", SUBSYSTEM==\"usb-serial\", DRIVER==\"ftdi_sio\", ATTR{latency_timer}=\"4\" > 99-dynamixelsdk-usb.rules
sudo cp ./99-dynamixelsdk-usb.rules /etc/udev/rules.d/
sudo udevadm control --reload-rules
sudo udevadm trigger --action=add
rm 99-dynamixelsdk-usb.rules
cat /sys/bus/usb-serial/devices/ttyUSB0/latency_timer # ttyUSB0の部分は環境に合わせて変更すること

一時的であれば以下のようにしてもよい. ttyUSB0 の部分は自分の環境に合わせて編集すること.

echo 4 | sudo tee /sys/bus/usb-serial/devices/ttyUSB0/latency_timer
cat /sys/bus/usb-serial/devices/ttyUSB0/latency_timer

速度に関してメモ

Sync Read vs Fast Sync Read(method/fast_readパラメータ)

結論としては,読み込むデータとサーボの数がそこまで多くないならFastを使う方がよい.

Fast Sync Readは受信するパケットが全サーボ分1つながりになっている.
つまり1回の通信でやり取りするパケット数が少なくなるので,同時に読み書きするサーボが多くなると速度に違いが出てくる.
少なくとも10サーボくらいで顕著にFast Sync Readの方が早くなる.
ただ,サーボが多すぎると通信が不安定になることがある.

Fast Sync Read側のデメリットとしては,直列しているサーボのどこかで断線等が起きた場合に弱いという点が挙げられる. Fast Sync Readはパケットがつながっているため,1つでも返事をしないサーボがあるとパケットが全滅してしまう.
(これはlib_dynamixelのパケット処理の実装が悪いかもしれないが,知識不足ですぐに改善できなさそう.)
通常のSync Readはパケットが独立しているため,断線するより前のサーボからの返事は受け取ることができる.
断線や接続不良が危惧されるような状況では通信周期を犠牲にして,Sync Readを使わざるを得ないだろう.

複数アドレスの同時読み込み(method/split_readパラメータ)

後述の書き込みと異なり,こちらは分割ではなく同時にするのが良い.
すなわちmethod/split_readfalseを推奨する.

複数のアドレスからデータを読み込みたいとき,分割して読み込む場合はシリアル通信の処理時間が,アドレス数分だけ長くなる.
100Hz以上で回そうと思うと,present_current, present_velocity, present_positionという基本の3つを取り出すだけでもきつい.
自分の環境では,前述の3つくらいの同時読み込みであれば,120-180Hzくらいでる.200Hzは場合によって出るか出ないかというところ.
分割読み込みでは60-80Hzくらいで頭打ちとなってしまった. present系の8つのアドレスすべてから読み込んでも,同時読み込みなら100Hzくらいはでる. 分割読み込みだと30Hzも怪しい.

(上記は全て, 14サーボ直列,lib_dynamixel側のLATENCY_TIMER=2ms, デバイス側のlatency timer=2ms, baudrate=1M での結果)

複数アドレスの同時書き込み(method/split_writeパラメータ)

書き込みに関しては,同時ではなく分割するのが良いだろう.
すなわちmethod/split_writetrueを推奨する.

自分の環境では,method/split_writefalseの状態で,12サーボに goal_current, goal_velocity, profile_acc, profile_vel, goal_position を同時にSync Writeしようとしたら,書き込みが失敗してうまく動かなかった.
書き込むサーボが少なければ動く.
また,use_split_writetrueにして,分割で書き込み,1度に書き込むアドレスを減らしても動く.
書き込みに関しては,分割して行っても処理時間はほぼ変わらない(1ms未満しか遅くならない)ので,基本はtrueとしておくべき.


Trouble Shooting

「dynamixel_handlerがない」もしくは,「メッセージがない」といったエラーが出る場合

ターミナルを立ち上げ直すか,以下を実行.

source ~/ros2_ws/install/setup.bash

colcon buildsrc/internal/mylib_dynamixel/... が見つからない場合

submodule 未初期化が原因のことが多い.以下を実行してから再buildする.

cd ~/ros2_ws/src/DynamixelHandler-ros2
git submodule update --init --recursive
cd ~/ros2_ws
colcon build --packages-select dynamixel_handler

dynamixel_unify_baudrate 実行時に _mylib_dynamixel が見つからない場合

dynamixel_handler の build が未完了か,ビルド成果物が古い.以下を再実行する.

cd ~/ros2_ws
colcon build --packages-select dynamixel_handler
source ~/ros2_ws/install/setup.bash

dynamixel_handlerノードを起動してもdynamixelが1つも見つからない場合

  1. デバイス名の確認
    どんな方法で確認しても良いが,Ubuntuの場合はDynamixelを認識するはずのUSBを抜く前後で $ ls /dev/ttyUSB*の出力を比較すれば,少なくとも正しいデバイス名がわかる.
  2. デバイスの実行権限の確認
    $ sudo chmod 777 /dev/{your_device_name}として改善すれば実行権限問題であることがわかる.
  3. Dynamixel側の baudrate の確認
    Dynamixel wizardで確認するのが最も確実. とりあえず動くようにするには init/baudrate_auto_setパラメータを trueにセットするか, dynamixel_unify_baudrateノード で目的の baudrate に強制変換してしまうのが良い.

dynamixel_handlerノードを起動したときにdynamixelが一部しか見つからない

  1. latency timer の確認
    $ cat /sys/bus/usb-serial/devices/{your_device_name}/latency_timerを実行して出てきたデバイス側の latency timer の数値が,ros parameter の latency_timerと一致しているかどうかを確認する.
    ros parameter 側の値を変えたい場合は config ファイルを修正すればよい.
    デバイス側値を変えたい場合は Latency Timer を参照.
  2. 通信状態が悪すぎる場合
    根本的にはケーブルやノイズ等を改善すべきだが,対症療法的にdyn_comm/retry_numを大きくすることでも改善する可能性がある. Parameters の該当パラメータを参照

dynamixel_handlerノードを起動したときにサーボの初期化が終わらない.

[dynamixel_handler-1] 1748119256.347349302: Initializing DynamixelHandler ..... 
[dynamixel_handler-1] 1748119256.352399757:  Succeeded to open device 
[dynamixel_handler-1] 1748119256.352459648:   ------------ name '/dev/ttyUSB0'
[dynamixel_handler-1] 1748119256.352463615:   -------- baudrate '1000000'
[dynamixel_handler-1] 1748119256.352466370:   --- latency_timer '1'
[dynamixel_handler-1] 1748119256.352996238:  Expected servo number is not set. 
[dynamixel_handler-1] 1748119256.353100349:  > Free number of Dynamixel is allowed 
[dynamixel_handler-1] 1748119256.353110024:  Auto scanning Dynamixel (id range '0' to '10') ...
[dynamixel_handler-1] 1748119256.353129157:  > series: X [use], P [no use], PRO [no use]
[dynamixel_handler-1] 1748119256.397073588:   *  X  series servo ID [1] is found
[dynamixel_handler-1] 1748119256.397073588:     Reading  present values...
[dynamixel_handler-1] 1748119256.397073588:     Reading  present values...
...

上記のような表記が続く.

  1. Read methodの確認 method/fast_readtrueになっているか確認する. 一部のモータは Fast Sync Readに対応しておらず,そうしたモータの場合初期の通信が失敗して無限ループに入ってしまう. Parameters のmethod/fast_readfalseにして,通常のSync Readに切り替えることで解決する.

dynamixel は見つかったが通信の成功率が極端に低い

  1. Dynamixelの接続状態の確認 TTLとRS485を並列に同時に使うと起きる.
  2. latency timerの確認 デバイス側の latency timer の値よりも,ros parameter の latency_timerの値が小さいときに起きる.
  3. 別のノードによるUSBデバイスの占有 他のノードがUSBデバイスを占有していると,通信がうまくいかないことがある. その場合は,$ ros2 node listで他のノードを確認し,必要に応じて停止する.

cannot publish dataといったようなエラーが出た場合

デフォルトのDDSはFast-RTPSであるが,固有のバグを持っているらしく,実行時にエラーが発生する. そのため,DDSをEclipse Cyclone DDSに変更しておく.

sudo apt update
sudo apt install ros-humble-rmw-cyclonedds-cpp
export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp

※ ~/.bashrcの下部にexport RMW_IMPLEMENTATION=rmw_cyclonedds_cppを追記しておくことで,
ターミナルの立ち上げ時に毎回コマンドを打たなくて済む.

wslにusbをアタッチしようとして以下のエラーが出たとき

usbipd: error: WSL 'usbip' client not correctly installed. See https://github.com/dorssel/usbipd-win/wiki/WSL-support for the latest instructions. 以下のコマンドをwsl内で実行すると解決する.

sudo update-alternatives --install /usr/local/bin/usbip usbip `ls /usr/lib/linux-tools/*/usbip | tail -n1` 20
usbipd: error: WSL kernel is not USBIP capable; update with 'wsl --update'.

以下のコマンドをwsl内で実行すると解決する.

sudo modprobe vhci_hcd

Launchファイルと設定(yaml)

launch_dynamixel_unify_baudrate.py

ros2 launch dynamixel_handler launch_dynamixel_unify_baudrate.py

対応するyamlconfig/config_dynamixel_unify_baudrate.yaml

launch_dynamixel_handler.py

ros2 launch dynamixel_handler launch_dynamixel_handler.py

対応するyamlconfig/config_dynamixel_handler.yaml

※ 一度ビルドしていれば,yamlファイルの変更に伴うビルドは不要

About

No description, website, or topics provided.

Resources

Stars

Watchers

Forks

Packages

 
 
 

Contributors

Languages

  • C++ 95.2%
  • Python 2.5%
  • CMake 2.3%