スマートフォン・ジン | Smartphone-Zine

引っ越し先→ https://smartphone-zine.com/

差動二輪ロボットのsdfを作成

http://gazebosim.org/tutorials?tut=ros_gzplugins&cat=connect_ros

今日は上記を見ながら、ロボットを作成していきます。ただし、記述が古いのでそのままだとうまく行きません。
まずは、GazeboからROS2を動かすデモを起動して理解を深めます。
次のコマンドでGazeboを起動します。

gazebo --verbose /opt/ros/foxy/share/gazebo_plugins/worlds/gazebo_ros_diff_drive_demo.world


teleopで操作してみます。

ros2 run teleop_twist_keyboard teleop_twist_keyboard cmd_vel:=/demo/cmd_demo

今回は差動二輪ロボットであるので、Differential Driveを実装します。gazebo_ros_diff_drive_demo.worldの中身をみて、そのまま真似て作成します。以下のような記述をロボットのsdfに追加します。

    <!-- プラグインをロードします。 filenameは共有ライブラリのファイル名です。 -->
    <plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
      <ros>
        <namespace>/momo</namespace>
      </ros>

      <!-- 左右の車輪のジョイントを指定します。 このジョイントにアクチュエータが追加され、制御可能になります。 -->
      <left_joint>wheel_left_joint</left_joint>
      <right_joint>wheel_right_joint</right_joint>
      <!-- ロボットのオドメトリの中心となるフレームです。 rviz等でロボットの位置を可視化するときにこのフレームを利用します。 -->
      <robot_base_frame>base_link</robot_base_frame>
      <!-- 車輪の間の距離です。 -->
      <wheel_separation>0.540</wheel_separation>
      <!-- 車輪の直径です。ホイールの直径(メートル単位)は、デフォルトで0.15mです。 -->
      <wheel_diameter>0.615</wheel_diameter>
      <!-- ホイールの加速度(rad / s ^ 2)は、デフォルトで0.0 rad / s ^ 2になります。-->
      <max_wheel_acceleration>1.0</max_wheel_acceleration>
      <!-- ホイールが生成できる最大トルク(Nm)は、デフォルトで5Nmです。 -->
      <max_wheel_torque>20</max_wheel_torque>
      <!-- オドメトリフレーム、デフォルトは `odom` -->
      <odometry_frame>odom</odometry_frame>
      <!-- オドメトリを計算するロボットフレーム。デフォルトは `base_footprint`です。 -->
      <robotBaseFrame>base_footprint</robotBaseFrame>
      <!-- オドメトリソース、エンコーダの場合は0、WORLDの場合は1、デフォルトはWORLD -->
      <odometrySource>1</odometrySource>
      <!-- ホイールリンクの変換を公開するにはtrueに設定する。デフォルト設定はfalse。-->
      <publish_wheel_tf>true</publish_wheel_tf>
      <!-- オドメトリを公開するにはtrueに設定する。 -->
      <publish_odom>true</publish_odom>
      <!-- オドメトリの変換を公開するにはtrueに設定する。 -->
      <publish_odom_tf>true</publish_odom_tf>

    </plugin>

では実際に動作させてみます。空のworldに入れてチェックします。

<?xml version="1.0"?>
<sdf version="1.6">
  <world name="default">

    <include>
      <uri>model://ground_plane</uri>
    </include>

    <include>
      <uri>model://sun</uri>
    </include>

    <scene>
      <shadows>false</shadows>
    </scene>

    <gui fullscreen='0'>
      <camera name='user_camera'>
        <pose frame=''>0.319654 -0.235002 9.29441 0 1.5138 0.009599</pose>
        <view_controller>orbit</view_controller>
        <projection_type>perspective</projection_type>
      </camera>
    </gui>

    <physics type="ode">
      <real_time_update_rate>1000.0</real_time_update_rate>
      <max_step_size>0.001</max_step_size>
      <real_time_factor>1</real_time_factor>
      <ode>
        <solver>
          <type>quick</type>
          <iters>150</iters>
          <precon_iters>0</precon_iters>
          <sor>1.400000</sor>
          <use_dynamic_moi_rescaling>1</use_dynamic_moi_rescaling>
        </solver>
        <constraints>
          <cfm>0.00001</cfm>
          <erp>0.2</erp>
          <contact_max_correcting_vel>2000.000000</contact_max_correcting_vel>
          <contact_surface_layer>0.01000</contact_surface_layer>
        </constraints>
      </ode>
    </physics>

    <include>
      <uri>model://momo</uri>
    </include>

  </world>
</sdf>

実行します。

$ gazebo --verbose momo_ws/src/momo_gazebo/worlds/static_map_plugin_get.world 
Gazebo multi-robot simulator, version 11.5.1
Copyright (C) 2012 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

[Msg] Waiting for master.
Gazebo multi-robot simulator, version 11.5.1
Copyright (C) 2012 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

[Msg] Waiting for master.
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 192.168.86.42
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 192.168.86.42
[Msg] Loading world file [/home/hiroakikaneda/momo_ws/src/momo_gazebo/worlds/static_map_plugin_get.world]
[Wrn] [ColladaLoader.cc:1928] Triangle input semantic: 'COLOR' is currently not supported
[Wrn] [ColladaLoader.cc:1928] Triangle input semantic: 'COLOR' is currently not supported
[Wrn] [ColladaLoader.cc:1928] Triangle input semantic: 'COLOR' is currently not supported
[Wrn] [ColladaLoader.cc:1928] Triangle input semantic: 'COLOR' is currently not supported
[Wrn] [ColladaLoader.cc:1928] Triangle input semantic: 'COLOR' is currently not supported
[Wrn] [ColladaLoader.cc:1928] Triangle input semantic: 'COLOR' is currently not supported
[Wrn] [ColladaLoader.cc:1928] Triangle input semantic: 'COLOR' is currently not supported
[Wrn] [ColladaLoader.cc:1928] Triangle input semantic: 'COLOR' is currently not supported
[INFO] [1632923283.195835717] [gazebo_ros_node]: ROS was initialized without arguments.
[INFO] [1632923283.214245446] [momo.differential_drive_controller]: Wheel pair 1 separation set to [0.540000m]
[INFO] [1632923283.214581649] [momo.differential_drive_controller]: Wheel pair 1 diameter set to [0.615000m]
[INFO] [1632923283.216477829] [momo.differential_drive_controller]: Subscribed to [/momo/cmd_vel]
[INFO] [1632923283.217386722] [momo.differential_drive_controller]: Advertise odometry on [/momo/odom]
[INFO] [1632923283.218196407] [momo.differential_drive_controller]: Publishing odom transforms between [odom] and [base_link]
[INFO] [1632923283.218218133] [momo.differential_drive_controller]: Publishing wheel transforms between [base_link], [wheel_left_joint] and [wheel_right_joint]
^C[INFO] [1632924658.173345571] [rclcpp]: signal_handler(signal_value=2)
[Wrn] [Publisher.cc:136] Queue limit reached for topic /gazebo/default/visual, deleting message. This warning is printed only once.
hiroakikaneda@:~$ gazebo --verbose momo_ws/src/momo_gazebo/worlds/empty.world 
Gazebo multi-robot simulator, version 11.5.1
Copyright (C) 2012 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

[Msg] Waiting for master.
Gazebo multi-robot simulator, version 11.5.1
Copyright (C) 2012 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

[Msg] Waiting for master.
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 192.168.86.42
[Msg] Loading world file [/home/hiroakikaneda/momo_ws/src/momo_gazebo/worlds/empty.world]
[INFO] [1632924661.728514279] [gazebo_ros_node]: ROS was initialized without arguments.
[INFO] [1632924661.747010815] [momo.differential_drive_controller]: Wheel pair 1 separation set to [0.540000m]
[INFO] [1632924661.747259540] [momo.differential_drive_controller]: Wheel pair 1 diameter set to [0.615000m]
[INFO] [1632924661.748479147] [momo.differential_drive_controller]: Subscribed to [/momo/cmd_vel]
[INFO] [1632924661.749557110] [momo.differential_drive_controller]: Advertise odometry on [/momo/odom]
[INFO] [1632924661.750442843] [momo.differential_drive_controller]: Publishing odom transforms between [odom] and [base_link]
[INFO] [1632924661.750501497] [momo.differential_drive_controller]: Publishing wheel transforms between [base_link], [wheel_left_joint] and [wheel_right_joint]
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 192.168.86.42

teleopで操作します。

$ ros2 run teleop_twist_keyboard teleop_twist_keyboard --ros-args --remap cmd_vel:=/momo/cmd_vel

This node takes keypresses from the keyboard and publishes them
as Twist messages. It works best with a US keyboard layout.
---------------------------
Moving around:
   u    i    o
   j    k    l
   m    ,    .

For Holonomic mode (strafing), hold down the shift key:
---------------------------
   U    I    O
   J    K    L
   M    <    >

t : up (+z)
b : down (-z)

anything else : stop

q/z : increase/decrease max speeds by 10%
w/x : increase/decrease only linear speed by 10%
e/c : increase/decrease only angular speed by 10%

CTRL-C to quit

currently:  speed 0.5   turn 1.0