はじめに
今回は、ROSの自己位置認識にGPSデータを使うためのシミュレーション環境構築として、Gazebo上でGPSとIMUのPluginを有効化した手順を簡単にまとめます。
ロボットモデルは、fetch roboticsのモデルを使用します。
実行環境
CPU | Core i7-10875H |
Ubuntu | 18.04.5 |
ROS | Melodic |
IMUプラグインの有効化
GazeboにおけるIMUのプラグインは、GazeboRosImuとGazeboRosImuSensorの2種類が存在します。前者はROSプラグイン、後者はROSプラグインではなくGazeboプラグインという違いがあるそうです。
Gazebo Pluginのサイトには、他にも様々なプラグイン情報が記載されています。
URDFの編集
fetch_description/robotsにあるfetch.urdfを編集することで、Pluginを有効にします。urdfの中に下記を追記します。
<link name="imu_link" />
<joint name="imu_joint" type="fixed">
<parent link="base_link" />
<child link="imu_link" />
</joint> <gazebo reference="imu_link">
<gravity>true</gravity>
<sensor name="imu_sensor" type="imu">
<always_on>true</always_on>
<update_rate>100</update_rate>
<visualize>true</visualize>
<topic>__default_topic__</topic>
<plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin">
<topicName>imu/data</topicName>
<bodyName>imu_link</bodyName>
<updateRateHZ>10.0</updateRateHZ>
<gaussianNoise>0.0</gaussianNoise>
<xyzOffset>0 0 0</xyzOffset>
<rpyOffset>0 0 0</rpyOffset>
<frameName>imu_link</frameName>
<initialOrientationAsReference>false</initialOrientationAsReference>
</plugin>
<pose>0 0 0 0 0 0</pose>
</sensor>
</gazebo>
topicNameタグで、IMUデータをPublishするトピック名を設定します。このまま実行すると、frameNameタグのimu_linkが分からないとなるので、imu_linkに関する記述を追記します。
<link name="imu_link" />
<joint name="imu_joint" type="fixed">
<parent link="base_link" />
<child link="imu_link" />
</joint>
rostopic echoで確認
ここでは、fixed frameでbase_linkにimu_linkを固定しています。rostopic echoでimuが吐き出されていることを確認します。
$ rostopic echo -n1 imu

GPSプラグインの有効化
hector_gazebo_pluginのクローン
GPSデータに関するPluginを追加するために、まずhector_gazebo_pluginをgit cloneしてcatkin_wsに落とし、catkin buildでビルドします。こちらの解説を参考にしました。
$ cd catkin_ws/src
$ git clone https://github.com/tu-darmstadt-ros-pkg/hector_gazebo.git
$ cd ..
$ catkin build

URDFの編集
IMUプラグインと同様に、URDFを編集してプラグインを有効化します。こちらも同様に、topicNameタグにPublishするトピック名を記入します。
<gazebo>
<plugin name="gps" filename="libhector_gazebo_ros_gps.so">
<updateRate>10.0</updateRate>
<topicName>gps/fix</topicName>
<gaussianNoise>0.0 0.0 0.0</gaussianNoise>
<offset>0 0 0</offset>
<velocityGaussianNoise>0 0 0</velocityGaussianNoise>
<frameId>gps_link</frameId>
</plugin>
</gazebo>
また、gps_linkに関する情報も追記しておきます。
<link name="gps_link" />
<joint name="gps_joint" type="fixed">
<parent link="base_link" />
<child link="gps_link" />
</joint>
rostopic echoで確認
rostopic echoでGPSデータ(gps/fix)が吐き出されていることを確認します。

これで、無事にIMUとGPSのプラグインを有効化することができました。