ROS講座67 車輪ロボットを作る7(カメラのシミュレーション)


この記事は以下の環境で動いています。

項目
CPU Core i5-8250U
Ubuntu 20.04
ROS Noetic
Gazebo 11.9.0

インストールについてはROS講座02 インストールを参照してください。
またこの記事のプログラムはgithubにアップロードされています。ROS講座11 gitリポジトリを参照してください。

概要

Gazeboを使ってWebカメラなどのカメラのシミュレーションを行います。カメラのシミュレーションを導入することで画像処理をシミュレーションと融合できます。

ソースコード

カメラのシミュレーションの部分のみを示します。

sim2_lecture/xacro/camera_macro.xacro
<robot name="dtw_robot" xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:macro name="camera_macro" params="parent prefix xyz">
    <joint name="${prefix}_joint" type="fixed">
      <parent link="${parent}"/>
      <child  link="${prefix}_link"/>
      <origin xyz="${xyz}" rpy="${radians(-90)} 0 ${radians(-90)}"/>
    </joint>
    <link name="${prefix}_link"/>
    <gazebo reference="${prefix}_link">
      <sensor type="camera" name="${prefix}">
        <update_rate>10.0</update_rate>
        <camera name="${prefix}">
          <pose>0 0 0 0 ${radians(-90)} ${radians(90)}</pose>
          <horizontal_fov>1.3962634</horizontal_fov>
          <image>
            <width>800</width>
            <height>600</height>
            <format>R8G8B8</format>
          </image>
          <clip>
            <near>0.02</near>
            <far>300</far>
          </clip>
          <noise>
            <type>gaussian</type>
            <mean>0.0</mean>
            <stddev>0.007</stddev>
          </noise>
        </camera>
        <plugin name="camera_controller" filename="libgazebo_ros_camera.so">
          <alwaysOn>true</alwaysOn>
          <updateRate>0.0</updateRate>
          <cameraName>${prefix}</cameraName>
          <imageTopicName>image_raw</imageTopicName>
          <cameraInfoTopicName>camera_info</cameraInfoTopicName>
          <frameName>${prefix}_link</frameName>
          <hackBaseline>0.0</hackBaseline>
          <distortionK1>0.0</distortionK1>
          <distortionK2>0.0</distortionK2>
          <distortionK3>0.0</distortionK3>
          <distortionT1>0.0</distortionT1>
          <distortionT2>0.0</distortionT2>
        </plugin>
      </sensor>
    </gazebo>
  </xacro:macro> 
</robot>

実行

各ターミナルごとに実行前にsource ~/catkin_ws/devel/setup.bashを実行する必要があります。

roscd sim2_lecture/xacro/
roslaunch sim2_lecture dtw_sensor.launch model:=dtw_camera.xacro 

Rvizの左下にシミュレーションしたカメラの画像が写っています。

Rvizで画像をImageトピックを表示するためには「Add」ボタン->「By topic」タブでImageトピックを選択します。

座標系について

カメラの座標を示すtfでは正面がZ軸、右がX軸、下がY軸になるようにするのが慣例です。しかしgazeboプラグインではX軸がカメラの正面になります。必要に応じて<pose>タグでカメラの正面の向きを回転させれます。

メモ

Kinetic標準で入るgazeboのバージョン(7.0.0)は問題があってカメラプラグインが動きません。gazeboのバージョンアップが必要です。

参考

gazeboのバージョンアップ方法
カメラのgazeboのplugin

目次ページへのリンク

ROS講座の目次へのリンク