Dynamixel - ais-lab/UD_wiki GitHub Wiki

Pan-Tilt機構

プロジェクタの姿勢を変形させるための機構.横と縦の首振り(pan, tilt)が可能である.二つのDynamixelにより実現されている. Dynamixelは内部にEEEROMを持っており,設定が保存されている. この設定により、ハードウェア的に回転制限がかかっている。

panは350度回転可能である。一周首が回るわけではない。 Tiltは上向きに約15度、下向きに約45度可動できる。 ただし、panが向いている方向によっては,本体が邪魔になり投影映像が欠ける状況が発生する.

これはDynamixel Wizardで設定が可能である. 具体的なDynamixelの値は

  • pan
    • id : 1
    • 正面方向 : 3072
    • 制限 : 1705(上約15度) ~ 2729(下約45度)
  • tilt
    • id : 2
    • 正面方向 : 2048
    • 制限 : 454(左約170度) ~ 3867(右170度)

となっている.

準備

UDを起動するで電源を供給している状態で,以下のコマンドを実行し、ノードを起動する.

roslaunch ubiquitous_display start_pantilt_dxl.launch 

動作確認

以下のコマンドを実行する.

rostopic echo /motor_states/pan_tilt_port

以下のようにidやpositionが出力されれば接続は正常にされている.pan_tilt_portはlaunchファイルの設定によって変わるので注意

---
motor_states: 
  - 
    timestamp: 1480925479.47
    id: 3
    goal: 1501
    position: 1058
    error: -443
    speed: 0
    load: 0.0
    voltage: 11.7
    temperature: 39
    moving: False
  - 
    timestamp: 1480925479.47
    id: 5
    goal: 731
    position: 733
    error: 2
    speed: 0
    load: 0.0
    voltage: 11.8
    temperature: 40
    moving: False
---

データ受信

動作確認のように,motor_states/pan_tilt_portをsubscribeすれば一応データは取得できる. しかし,このままではパースの必要や座標変換などに支障がある

そこで,pan_controller/stateをsubscribeする. 例えば,

rostopic echo /pan_controller/state

でid=4のDynamixelのデータの内容を確認できる.

命令送信

topicpan_controller/commandまたはtilt_controller/commandに対してmessagestd_msgs/Float64を送ると動作する.ただし単位はラジアンなので注意. 以下のコマンドを実行することで動作確認ができる.

rostopic pub -1 /tilt_controller/command std_msgs/Float64 -- 1.5

id=3のDynaxmielがファイルで指定したデフォルト位置から1.5ラジアン分だけ動く.なお,-1は一回のみ送信するオプションである.

送信についてはラッパーを用意してあります.

scripts/demo_pantilt_move.shを以下のように実行します.

./demo_pantilt_move.sh 0 0

引数は

  1. パンの基準からの回転(ラジアン)
  2. チルトの基準からの回転(ラジアン)

です.制限範囲を超えた値を代入しても,Dynamixel側で勝手に回転制限をかけてくれています.

座標変換

プロジェクタの位置姿勢を取り出したい場合は,座標管理で説明しています.

トラブルシューティング

  • /dev/ttyUSB*に権限がないとpermission denyで弾かれるので注意 (*は番号)
    • 解決策 : sudo chmod 6666 /dev/ttyUSB*
  • USB2Dynamixel(透明コネクタ)の設定スイッチ(TTL,RS486,RS232)が正しい位置にあるか
  • Dynamixelに電源供給されているか
  • DynamixelのID,Baud Rateは正しいか(Dynamixel Wizardというソフトで調べられます)
  • launchファイル内のargsのmanager,conrtollerの名称が正しいか
  • ノードが本当に立ち上がっているかをrostopic listで確認してみる
  • dynamixel_joint_state_publisher not found
  • ~/catkin_ws/srcdynamixel_joint_state_publisherがないのが原因
  • システム構築の方法みてインストールしてないのが原因
  • git clone https://github.com/RobotRose/dynamixel_joint_state_publisher しましょう

環境構築法

インストールするソフトウェア

設定

下記に記載されているソースはあくまでサンプルです.最新版をリポジトリ内で参考にすること

設定ファイルは

  • launch/start_pantilt_dxl.launch
  • config/pantilt.yaml
  • launch/pantilt_dxl_manager.launch
  • launch/pantilt_dxl_controller.launch
  • launch/pantilt_dxl_joint_state_publisher.launch

である.

また,Dynamixelのハードウェア的設定(ID,可動制限など)はDynamixel Wizardを用いてWindowsで事前に設定する.

start_pantilt_dxl.launch

後で説明するlaunchファイルをまとめて起動するためのlaunchファイル. ファイル名変更や起動ファイルを追加する場合は,このファイルを変更する必要がある.

pantilt.yaml

使用するDynamixelのidや関節の制御範囲を指定するファイル. 一つのDynamixelにつき,一つのコントローラを用意する必要がある. 例えば二つのDynamixelを制御したければ,

pan_controller:
    controller:
        package: dynamixel_controllers
        module: joint_position_controller
        type: JointPositionController
    joint_name: pan_joint
    joint_speed: 2.0
    motor:
        id: 3
        init: 512
        min: 0
        max: 2048

tilt_controller:
    controller:
        package: dynamixel_controllers
        module: joint_position_controller
        type: JointPositionController
    joint_name: tilt_joint
    joint_speed: 2.0
    motor:
        id: 4
        init: 512
        min: 0
        max: 2048

のようにする必要がある.ここでのコントローラー名(pan_controller, tilt_controller)は,後にlaunchファイルで使用する.ここで設定した稼働範囲自体にはあまり意味はなく.実際にはDynaxmiel Wizardで設定したDynamixel内部の制限値が使用される. 反対にjoint_speedはここで設定した値が使用される.

また,joint_nameはURDFファイル内のjoint名と一致している必要がある. 具体的に依存関係がファイルは,座標管理pantilt.urdf.xacroである.

pantilt_dxl_manager.launch

USBとDynamixelとの通信をするノードを起動するlaunchファイル.例としては,

<launch>
    <node name="dynamixel_manager" pkg="dynamixel_controllers" type="controller_manager.py" required="true" output="screen">
        <rosparam>
            namespace: dxl_manager
            serial_ports:
                pan_tilt_port:
                    port_name: "/dev/ttyUSB0"
                    baud_rate: 1000000
                    min_motor_id: 1
                    max_motor_id: 25
                    update_rate: 20
        </rosparam>
    </node>
</launch>

となる.

特に注意して設定する値を以下に記述する.

  • pan_tilt_port : この名前はtopic名に影響する
  • baud_rate : 使用するDynamixelと同じ値にする
  • port_name : ls /dev/ttyUSB*でUSB2Dynamixelが挿してある場所を特定し,その場所を記述する.

pantilt_dxl_controller.launch

上記で起動したノードを用いて,Dynamixelの制御用ノードを起動するlaunchファイル.使用するDynamixelの数だけノードを起動する必要がある.例としては,

<launch>
    <rosparam file="$(find ubiquitous_display)/config/pantilt.yaml" command="load"/>
    <node name="pan_controller_spawner" pkg="dynamixel_controllers" type="controller_spawner.py"
          args="--manager=dxl_manager
                --port pan_tilt_port
                pan_controller"
          output="screen"/>

    <node name="tilt_controller_spawner" pkg="dynamixel_controllers" type="controller_spawner.py"
          args="--manager=dxl_manager
                --port pan_tilt_port
                tilt_controller"
          output="screen"/>
</launch>

となる.注意点としては

  • file="$(find ubiquitous_display)/config/pantilt.yaml" : ファイル名を指定
  • args内--manager : pantilt_dx_controller_manager.launchのnamespaceと同じにする
  • args内--port pantilt_port : ud_dxl_manager.launchで指定した名前と同じにする
  • args内pan_contorller or tilt_controller(最後のパラメータ) : pantilt.yaml内のcontroller名と同じ

pantilt_dxl_joint_state_publisher.launch

tf(座標管理)を利用するために必要なノードを起動するためのlaunchファイルである.

上記で使用しているdynamixel_motorのノードはdynamixel_msgs/JointState型のmessageをpublishしているが, tfに対応しているmessageはsensor_msgs/JointStateである. つまり、変換が必要になるため、このlaunchファイルで変換用のノードを起動している.

<?xml version="1.0"?>
<launch>    
    <!-- Start the Dynamixel Joint States Publisher -->
    <node name="dynamixel_joint_states_publisher" pkg="dynamixel_joint_state_publisher" type="dynamixel_joint_state_publisher.py" output="screen">       
        <rosparam>
            joint_controllers: ['pan_controller', 'tilt_controller']
       </rosparam>
   </node>
</launch>
⚠️ **GitHub.com Fallback** ⚠️