見出し画像

ROS入門 (43) - toio風ロボットをURDFで作成して、Unityに配置して、ROS2コマンドで操作

toio風ロボットをURDFで作成して、Unityに配置して、ROS2コマンドで操作するまでの手順をまとめました。

・Galactic
・Unity 2020.3

前回

1. URDFの作成

toio風のロボットを作成します。

(1) URDFファイルを作成して編集。

・toio_style.urdf

<?xml version="1.0"?>
<robot name="toio_style">

  <!--ボディ-->
  <link name="base_link">
    <visual>
      <geometry>
        <box size="0.3 0.3 0.23" />
      </geometry>
      <material name="white">
        <color rgba="1.0 1.0 1.0 1.0" />
      </material>
    </visual>
    <collision>
      <geometry>
        <box size="0.3 0.3 0.23" />
      </geometry>
    </collision>
    <inertial>
      <mass value="1.0" />
      <inertia ixx="0.015" iyy="0.0375" izz="0.0375" ixy="0" ixz="0" iyz="0" />
    </inertial>
  </link>

  <!--右車輪-->
  <link name="right_wheel">
    <visual>
      <geometry>
        <cylinder length="0.05" radius="0.035" />
      </geometry>
      <material name="gray">
        <color rgba="0.2 0.2 0.2 1" />
      </material>
    </visual>
    <collision>
      <geometry>
        <cylinder length="0.05" radius="0.035" />
      </geometry>
    </collision>
    <inertial>
      <mass value="0.1" />
      <inertia ixx="5.1458e-5" iyy="5.1458e-5" izz="6.125e-5" ixy="0" ixz="0" iyz="0" />
    </inertial>
  </link>
  <joint name="right_wheel_joint" type="continuous">
    <axis xyz="0 0 1" />
    <parent link="base_link" />
    <child link="right_wheel" />
    <origin rpy="-1.5708 0 0" xyz="0.0 -0.125 -.09" />
  </joint>

  <!--左車輪-->
  <link name="left_wheel">
    <visual>
      <geometry>
        <cylinder length="0.05" radius="0.035" />
      </geometry>
      <material name="gray" />
    </visual>
    <collision>
      <geometry>
        <cylinder length="0.05" radius="0.035" />
      </geometry>
    </collision>
    <inertial>
      <mass value="0.1" />
      <inertia ixx="5.1458e-5" iyy="5.1458e-5" izz="6.125e-5" ixy="0" ixz="0" iyz="0" />
    </inertial>
  </link>
  <joint name="left_wheel_joint" type="continuous">
    <axis xyz="0 0 1" />
    <parent link="base_link" />
    <child link="left_wheel" />
    <origin rpy="-1.5708 0 0" xyz="0.0 0.125 -.09" />
  </joint>
</robot>

2. ROS側の準備

ROS側の準備の手順は、次のとおりです。

(1) Dockerイメージの起動時に、ポート番号「10000」「5005」のオープンを指定。
UnityとROSの間の通信は、ポート番号「10000」「5005」が必要です。

$ docker run -v ~/ros2_ws:/home/ubuntu/colcon_ws:cached -p 6080:80 -p 10000:10000 -p 5005:5005 --shm-size=1024m tiryoh/ros2-desktop-vnc:galactic

(2) 「ROS-TCP-Endpoint」パッケージのインストール。
「main-ros2」ブランチの「ROS-TCP-Endpoint」を使います。

$ cd ~/colcon_ws/src
$ git clone -b main-ros2 https://github.com/Unity-Technologies/ROS-TCP-Endpoint

(3) ワークスペースのビルドとセットアップ。

$ cd ~/colcon_ws
$ colcon build
$ source ~/colcon_ws/install/setup.bash

3. Unity側の準備

Unity側の準備の手順は、次のとおりです。

(1) Unityのメニュー「Window → Package Manager」で「Package Manager」を開く。
(2) 「Package Manager」で「+ → Add Package from Git URL」を選択し、以下のURLを入力し、「Add」ボタンを押す。
ROS-TCP-Connector」がインポートされます。

https://github.com/Unity-Technologies/ROS-TCP-Connector.git?path=/com.unity.robotics.ros-tcp-connector

(3) 「Package Manager」で「+ → Add Package from Git URL」を選択し、以下のURLを入力し、「Add」ボタンを押す。
URDF Importer」がインポートされます。

https://github.com/Unity-Technologies/URDF-Importer.git?path=/com.unity.robotics.urdf-importer

(4) Unityのメニュー「Robotics → ROS Settings」で「ROS2」を指定。

4. URDFのインポート

UnityのシーンにURDFモデルをインポートします。

(1) UnityのAssetsに「toio_style.urdf」を配置。
(2) Projectウィンドウで、「toio_style.urdf」を右クリックして、「Import Robot Select form URDF file」を選択。

(3) 「Import URDF」を押す。

(4) HierarchyウィンドウでPlaneで床を作成。

5. キーボードによる操作

URDFモデルを操作するには、URDFモデルに「Robotics-Nav2-SLAM-Example」の 「AGVController」を追加します。これによって、/cmd_velトピックをサブスクライブするようになり、外部から操作できます。

(1) HierarchyウィンドウでURDFモデル(toio_style)を選択し、InspectorウィンドウでControllerコンポーネントのチェックを外す。
(2) 「Robotics-Nav2-SLAM-Example」の 「AGVController」をダウンロードし、UnityのAssetsに配置。

(3) URDFモデル(toio_style)に「AGVController」を追加し、Wheel1にtoio_styleのleft_wheelWheel2にtoio_styleのright_wheelをドラッグ&ドロップ。

・Wheel 1 : ホイール1
・Wheel 2 : ホイール2
・Mode : モード (ROS / Keyboard)
・Max Linear Speed : 最大直進速度
・Max Rotation Speed : 最大回転速度
・Wheel Radius : ホイール半径
・Track Width : トラック幅
・Force Limit : 力の最大値
・Damping : 減衰
・ROS Timeout : 一定期間ROSメッセージがない時は停止

(4) 「AGVController」のModeKeyboardを指定し、Playボタンを押し、キーボードでロボットの動作を確認。
まだROS2と接続できてないので、左上の「ROS2 IP」の矢印が赤のままです。

6. ROS2コマンドによる操作

実行手順は、次のとおりです。

◎ ROS2側の準備
(1) ターミナルを開き、ROSのIPとポートを指定して、「ROS-TCP-Endpoint」を実行。

$ ros2 run ros_tcp_endpoint default_server_endpoint --ros-args -p ROS_IP:=0.0.0.0

◎ Unity側の準備
(1) 「AGVController」のModeROSを指定し、Playボタンを押す。
ROS2との接続に成功した場合は、左上の「ROS IP」の矢印が青くなります。

◎ ROS2側でのROS2コマンドの実行
(1) ROS2側で以下のコマンドを入力し、/cml_velトピックをサブスクライブしていることを確認。

$ ros2 topic list
/cmd_vel
/joint_states
/parameter_events
/robot_description
/rosout
/tf
/tf_static

$ ros2 topic info /cmd_vel
Type: geometry_msgs/msg/Twist
Publisher count: 0
Subscription count: 1

(2) ROS側で以下のコマンドを入力し、/cmd_velトピックをパブリッシュ。
Unity内のURDFモデルが動きます。

$ ros2 topic pub /cmd_vel geometry_msgs/Twist '{linear: {x: 0.5}, angular: {z: 0.5}}'

7. teleop-twist-keyboardによる操作

前回と同様に「teleop-twist-keyboard」でも操作できます。

$ sudo apt-get update
$ sudo apt-get install ros-galactic-teleop-twist-keyboard
$ ros2 run teleop_twist_keyboard teleop_twist_keyboard

次回



この記事が気に入ったらサポートをしてみませんか?