Dobot MG400 の gazebo_ros2_control の設定方法について【ROS2-Foxy】

ROS2
スポンサーリンク

スポンサーリンク

はじめに

前回は MG400 を Gazebo 上で表示する方法について説明しました。

今回は、Gazebo 上で表示する際に使用した gazebo_ros2_control の設定方法の詳細について説明します。

前提条件

前提条件は、以下の通りです。

  • MG400 を Gazebo 上で表示できる。

URDF の gazebo_ros2_control 設定

まずは、前回使用した mg400_training.urdf の gazebo_ros2_control 部分を再掲します。

<gazebo>
  <plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
    <robot_sim_type>gazebo_ros2_control/GazeboSystem</robot_sim_type>
    <parameters>/home/wsl-ubuntu/mg400_workspace/src/mg400_training/config/jtc.yaml</parameters>
  </plugin>
</gazebo>

<ros2_control name="GazeboSystem" type="system">
    <hardware>
      <plugin>gazebo_ros2_control/GazeboSystem</plugin>
    </hardware>

    <joint name="mg400_j1">
      <command_interface name="position">
        <param name="min">-3.14</param>
        <param name="max">3.14</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-3.15</param>
        <param name="max">3.15</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
      <param name="initial_position">0.0</param>   
    </joint>
    <joint name="mg400_j2_1">
      <command_interface name="position">
        <param name="min">-3.14</param>
        <param name="max">3.14</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-3.15</param>
        <param name="max">3.15</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
      <param name="initial_position">-1.57</param>   
    </joint>
    <joint name="mg400_j2_2">
      <command_interface name="position">
        <param name="min">-3.14</param>
        <param name="max">3.14</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-3.15</param>
        <param name="max">3.15</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
      <param name="initial_position">0.0</param>   
    </joint>
    <joint name="mg400_j3_1">
      <command_interface name="position">
        <param name="min">-3.14</param>
        <param name="max">3.14</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-3.2</param>
        <param name="max">3.2</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
      <param name="initial_position">-1.57</param>   
    </joint>
    <joint name="mg400_j3_2">
      <command_interface name="position">
        <param name="min">-3.14</param>
        <param name="max">3.14</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-3.2</param>
        <param name="max">3.2</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
      <param name="initial_position">0.0</param>   
    </joint>
    <joint name="mg400_j4_1">
      <command_interface name="position">
        <param name="min">-3.14</param>
        <param name="max">3.14</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-3.2</param>
        <param name="max">3.2</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
      <param name="initial_position">0.0</param>   
    </joint>

    <joint name="mg400_j4_2">
      <command_interface name="position">
        <param name="min">-3.14</param>
        <param name="max">3.14</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-3.2</param>
        <param name="max">3.2</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
      <param name="initial_position">0.0</param>   
    </joint>

    <joint name="mg400_j4_3">
      <command_interface name="position">
        <param name="min">-3.14</param>
        <param name="max">3.14</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-3.2</param>
        <param name="max">3.2</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
      <param name="initial_position">0.0</param>   
    </joint>

    <joint name="mg400_j5_1">
      <command_interface name="position">
        <param name="min">-3.14</param>
        <param name="max">3.14</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-3.2</param>
        <param name="max">3.2</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
      <param name="initial_position">0.0</param>   
    </joint>

    <joint name="mg400_j5">
      <command_interface name="position">
        <param name="min">-3.14</param>
        <param name="max">3.14</param>
      </command_interface>
      <command_interface name="velocity">
        <param name="min">-3.2</param>
        <param name="max">3.2</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
      <state_interface name="effort"/>
      <param name="initial_position">0.0</param>   
    </joint>

  </ros2_control>

上から順に説明していきます。

Gazebo 上へのプラグイン設定

gazebo_ros2_control の説明はこちらにあります。

<gazebo>
  <plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
    <robot_sim_type>gazebo_ros2_control/GazeboSystem</robot_sim_type>
    <parameters>/home/wsl-ubuntu/mg400_workspace/src/mg400_training/config/jtc.yaml</parameters>
  </plugin>
</gazebo>

<gazebo>タグは、AGV の時に説明したのと同様に、Gazebo シミュレート上へ適用するプラグインを指定します。

<pluginfilename> はプラグインの名称を指定します。
今回のプラグインは <ros2_control> で書かれた内容を Gazebo へ適用します。
<robot_sim_type> は、<ros2_control> の <plugin/hardware> と合わせます。

<parameters> は、yaml ファイルの場所を指します。

<plugin> タグには、ほかにも設定できる内容があります。

  • <robot_param> … 一般に robot_description のような URDF がパブリッシュされるトピックを指定します。(デフォルトは robot_description)
  • <robot_param_node> … robot_state_publisher のようなロボットの状態が出力されるノードを指定します。(デフォルトは robot_state_publisher)

ros2_control の設定 (hardware)

ros2_control の説明はこちらにあります。github はこちらです。

<ros2_control name="GazeboSystem" type="system">
    <hardware>
      <plugin>gazebo_ros2_control/GazeboSystem</plugin>
    </hardware>

<ros2_control> タグ内にロボットの状態を記載していきます。
<hardware> タグは、どんなロボットを使用するかによって内容を変えます。

  • Gazebo 上でシミュレーションする場合 … gazebo_ros2_control/GazeboSystem
  • interface が一つのみ = 一つの pub/subの場合 … ros2_control_demo_hardware/RRBotSystemPositionOnlyHardware
  • 複数の interface の場合 … ros2_control_demo_hardware/RRBotSystemMultiInterfaceHardware
  • 複数の interface かつ複数の書込 … ros2_control_demo_hardware/RRBotSystemMultiInterfaceMultiWriteHardware
  • センサー内蔵型 … ros2_control_demo_hardware/RRBotSystemWithSensorHardware
  • 外付けセンサ … ros2_control_demo_hardware/RRBotSystemPositionOnlyHardware

他にも色々ありますが、このくらいにしておきます。

ros2_control の設定 (joint)

joint の設定方法について説明していきます。
詳細な説明はこちらにあります。

<joint name="mg400_j1">
  <command_interface name="position">
    <param name="min">-3.14</param>
    <param name="max">3.14</param>
  </command_interface>
  <command_interface name="velocity">
    <param name="min">-3.15</param>
    <param name="max">3.15</param>
  </command_interface>
  <state_interface name="position"/>
  <state_interface name="velocity"/>
  <state_interface name="effort"/>
  <param name="initial_position">0.0</param>   
</joint>

<joint_name> は、joint名を指定します。
<command_interface> は、position, velocity, effort の三つから選択します。
各<command_interface> の <param> は、最大値・最小値を指定します。

<state_interface> は、パブリッシュ(フィードバック)する position, velocity, effort を指定します。
今回はすべて出力します。

<param name=”initial_position> は、初期位置を指定します。

これらの設定は、別で色々いじっていきます。

jtc.yaml の設定

gazebo_ros2_control で読み込む jtc.yaml についての説明をしていきます。
gazebo_ros2_control の設定ファイルの説明は 公式ドキュメントgithub にあります。

まずは、jtc.yaml を再掲します。

controller_manager:
  ros__parameters:
    update_rate: 100
    joint_state_broadcaster:
      type: joint_state_broadcaster/JointStateBroadcaster
    joint_trajectory_controller:
      type: joint_trajectory_controller/JointTrajectoryController

joint_trajectory_controller:
  ros__parameters:
    joints:
      - mg400_j1
      - mg400_j2_1
      - mg400_j2_2
      - mg400_j3_1
      - mg400_j3_2
      - mg400_j4_1
      - mg400_j4_2
      - mg400_j4_3
      - mg400_j5_1
      - mg400_j5

    command_interfaces:
      - position

    state_interfaces:
      - position

    state_publish_rate: 50.0
    action_monitor_rate: 20.0

    allow_partial_joints_goal: false
    open_loop_control: true
    constraints:
      stopped_velocity_tolerance: 0.01
      goal_time: 0.0
      joint1:
        trajectory: 0.05
        goal: 0.03

controller_manager の設定

controller_manager の設定について説明します。こちらの公式ドキュメントをご参考ください。

controller_manager:
  ros__parameters:
    update_rate: 100
    joint_state_broadcaster:
      type: joint_state_broadcaster/JointStateBroadcaster
    joint_trajectory_controller:
      type: joint_trajectory_controller/JointTrajectoryController

update_rate は Hz で指定します。今回は 100Hz です。

joint_state_broadcaster は、関節の状態をパブリッシュします。
joint_states の トピックが複数ある場合は、use_local_topics: /my_state_broadcaster/joint_states のように指定します。

joint_trajectory_controller は、関節の軌跡を制御します。別タブで設定します。

joint_trajectory_controller の設定

joint_trajectory_controller の設定について説明します。公式ドキュメントをご参考ください。

joint_trajectory_controller:
  ros__parameters:
    joints:
      - mg400_j1
      - mg400_j2_1
      - mg400_j2_2
      - mg400_j3_1
      - mg400_j3_2
      - mg400_j4_1
      - mg400_j4_2
      - mg400_j4_3
      - mg400_j5_1
      - mg400_j5

joints は、joint_trajectory で取扱う joint 名を指定します。

command_interfaces:
  - position
state_interfaces:
  - position
state_publish_rate: 50.0
action_monitor_rate: 20.0

command_interfaces は外部から受け付ける操作方法です。position のみ受け付けます。
state_interfaces はパブリッシュする position, velocity, effort を選択します。
state_publish_rate は 50.0Hz に設定しました。
action_monitor_rate は 20.0Hz に設定しました。これは、ロボットが動作中に joint の値を監視する周期です。

allow_partial_joints_goal: false
open_loop_control: true
constraints:
  stopped_velocity_tolerance: 0.01
  goal_time: 0.0
  joint1:
    trajectory: 0.05
    goal: 0.03

allow_partial_joints_goal は、一部の joint のみの起動を定義するかどうか設定します。
open_loop_control は、起動時にコマンドインターフェイスから 各joint の値を読み取ります。

constrains は、ゴールに関するデフォルト値を指定します。
stopped_velocity_tolearance は、終了する際の速度の範囲を指定します。
goal_time は、時間内に目標地点へ到達しない場合の許容範囲を指定します。

joint1 は、joint1 という名前の joint について指定します。
trajectory は、joint1 のターゲット軌道からの許容値を指定します。
goal は、joint1 の目標地点の許容値を指定します。

おわりに

今回は、gazebo_ros2_control の設定方法の詳細について説明しました。
これらの値は実際に動かせるようになってから変化させていきます。

次回は、目的地からロボットの姿勢を逆算する方法 (逆運動学) について説明します。

コメント

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