見出し画像

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

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

・Noetic

前回

1. ROS1のセットアップ

(1) ROS1のセットアップ。
ターミナルを開くたびに必要になるため、「~/.bashrc」にも追加します。

$ source /opt/ros/noestic/setup.bash

2. ワークスペースのセットアップ

「catkin」のワークスペースを作成します。

(1) ワークスペースのフォルダを作成し移動。

$ mkdir -p ~/catkin_ws/src
$ cd ~/catkin_ws​​

(2) ワークスペースの初期化とビルド。

$ catkin init

(3) ワークスペースのビルド。

$ catkin build

(4) ワークスペースのセットアップ。
ターミナルを開くたびに必要になるため、「~/.bashrc」にも追加します。

$ source ~/catkin_ws/devel/setup.bash

3. パッケージの作成

(1) 「~/catkin_ws/src」に移動し、「hello」という名前のパッケージを作成。

$ cd ~/catkin_ws/src
$ catkin_create_pkg hello rospy

4. URDFの作成

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

(1) パッケージのurdfフォルダでURDFファイルを作成して編集。

・~/catkin_ws/src/hello/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="front_wheel">
    <visual>
      <geometry>
        <cylinder length="0.05" radius="0.035" />
      </geometry>
      <material name="white" />
    </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="front_wheel_joint" type="continuous">
    <axis xyz="0 0 1" />
    <parent link="base_link" />
    <child link="front_wheel" />
    <origin rpy="-1.5708 0 0" xyz="0.1 0 -0.1" />
  </joint>

  <!--後輪-->
  <link name="back_wheel">
    <visual>
      <geometry>
        <cylinder length="0.05" radius="0.035" />
      </geometry>
      <material name="white" />
    </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="back_wheel_joint" type="continuous">
    <axis xyz="0 0 1" />
    <parent link="base_link" />
    <child link="back_wheel" />
    <origin rpy="-1.5708 0 0" xyz="-0.1 0 -0.1" />
  </joint>

  <!--右輪-->
  <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 -.1" />
  </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 -.1" />
  </joint>
</robot>

(2) 以下のコマンドで、rvizによるURDFの確認。

$ roslaunch urdf_tutorial display.launch model:=toio_style.urdf

5. URDFモデルをGazeboに配置

URDFモデルをGazeboに配置します。

(1) パッケージのlaunchフォルダでlaunchファイルを作成して編集。

・~/catkin_ws/src/hello/launch/toio_style.launch

<launch>
  <!--URDFをパラメータサーバに読み込み-->
  <param name="robot_description" textfile="$(find hello)/urdf/toio_style.urdf" />

  <!--空ワールドでGazeboを開始-->
  <include file="$(find gazebo_ros)/launch/empty_world.launch" />

  <!--Gazeboでロボットを生成し、パラメータサーバからURDFを読み込み-->
  <node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-param robot_description -urdf -model toio_style" />
</launch>

(2) 以下のコマンドで、Gazeboを起動し、URDFモデルを配置。

$ roslaunch hello toio_style.launch

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

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

(1) URDFにGazeboの「differential_drive_controller」プラグインを追加。
更新レート(updateRate)を1Hzとしています。

・~/catkin_ws/src/hello/urdf/toio_style.urdf

<robot>
    :
  <!--diff_drive_controllerプラグイン-->
  <gazebo>
    <plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
      <leftJoint>left_wheel_joint</leftJoint>
      <rightJoint>right_wheel_joint</rightJoint>
      <robotBaseFrame>base_link</robotBaseFrame>
      <wheelSeparation>0.25</wheelSeparation>
      <wheelDiameter>0.07</wheelDiameter>
      <updateRate>1</updateRate>
      <publishWheelJointState>true</publishWheelJointState>
    </plugin>
  </gazebo>
</robot>

(2) 以下のコマンドで、Gazeboを起動し、URDFモデルを配置。

$ roslaunch hello toio_style.launch

(3) 以下のコマンドで、/cml_velトピックがGazeboがサブスクライブしていることを確認。

$ rostopic list         
/clock
/cmd_vel
/gazebo/link_states
/gazebo/model_states
/gazebo/parameter_descriptions
/gazebo/parameter_updates
/gazebo/performance_metrics
/gazebo/set_link_state
/gazebo/set_model_state
/joint_states
/odom
/rosout
/rosout_agg
/tf

$ rostopic info /cmd_vel
Type: geometry_msgs/Twist
Publishers: None
Subscribers: 
 * /gazebo 

(4) 以下のコマンドで/cmd_velトピックをパブリッシュ。
Gazebo内のURDFモデルが動きます。

$ rostopic pub -1 /cmd_vel geometry_msgs/Twist '{linear: {x: 0.5}, angular: {z: 0.5}}'

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

teleop-twist-keyboard」は、cmd_velメッセージを配信するツールです。

(1) インストール。

$ sudo apt-get update
$ sudo apt-get install ros-noetic-teleop-twist-keyboard

(2) 実行。
更新レートは1Hzとしています。

$ rosrun teleop_twist_keyboard teleop_twist_keyboard.py _repeat_rate:=1

(3) キーボードで操作。
操作方法は、次のとおりです。

・U / I / O : ↖ ↑ ↗
・J / K / L : ← ・ →
・M / < / > : ↙ ↓ ↘

・t : 上 (+z)
・b : 下 (-z)

・q / z : 最大速度を10%増減
・w / x : 並進速度を10%増減
・e / c : 回転速度を10%増減
・space / k : 停止
・その他 : ゆっくり停止

次回



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