tugbotのモデルでいろいろやろうと思っていましたが。。。はまって全然うまくいかなかったので初めからモデルを作ります。
チュートリアルのページの通りですが。。。まずはワールドを定義。
必要なプラグインと床面とか太陽とかを設定しただけのファイル。
これは、下記の通りで適当にworld.sdfと保存しておく。
<?xml version="1.0" ?>
<sdf version="1.8">
<world name="car_world">
<physics name="1ms" type="ignored">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<plugin
filename="libignition-gazebo-physics-system.so"
name="ignition::gazebo::systems::Physics">
</plugin>
<plugin
filename="libignition-gazebo-user-commands-system.so"
name="ignition::gazebo::systems::UserCommands">
</plugin>
<plugin
filename="libignition-gazebo-scene-broadcaster-system.so"
name="ignition::gazebo::systems::SceneBroadcaster">
</plugin>
<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>
<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
</link>
</model>
</world>
</sdf>
上記は最低限のプラグインと環境だと思ってよい。
保存したら下記で実行すると何もない世界が出てくる。
ign gazebo world.sdf
あとは、Classic Gazeboと同じく四角い車体とタイヤを取り付けていくことになる。
チュートリアルを見てもらうとして、完成形は、ここのファイル。
このファイルに書き換えるか、ダウンロードして同じく実行する。
ign gazebo world.sdf
下記のように2車輪とボールキャスタのいつもの移動ロボットが完成。
これだけでは移動できないので、プラグインを追加して移動ができるようにする。Classic Gazeboとプラグイン名が当然変わっているので、IGN用に修正する必要がある。
ここのページの通りDiff_drive pluginを追加。
<plugin
filename="libignition-gazebo-diff-drive-system.so"
name="ignition::gazebo::systems::DiffDrive">
<left_joint>left_wheel_joint</left_joint>
<right_joint>right_wheel_joint</right_joint>
<wheel_separation>1.2</wheel_separation>
<wheel_radius>0.4</wheel_radius>
<odom_publish_frequency>1</odom_publish_frequency>
<topic>cmd_vel</topic>
</plugin>
上記の記載は、
<model name='vehicle_blue' canonical_link='chassis'>
<pose relative_to='world'>0 0 0 0 0 0</pose> <!--the pose is relative to the world by default-->
のvehicle_blueのタグの下にペーストするだけでOK.
記載後に下記でもう一度ign gazeboを立ち上げて、ツールのTeleopを選択してから、ign Gazeboの左下の再生ボタン「▷」を忘れずに押せば、すぐにした図のように移動ロボットが動かせる。
IMUセンサのプラグインとセンサのオブジェクトは下記を記載する。
下記プラグインは<world>タグの下に記載
<plugin filename="libignition-gazebo-imu-system.so"
name="ignition::gazebo::systems::Imu">
</plugin>
IMUは移動ロボット本体に取り付けるのでchassisのリンクのタグ内にペーストする。
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>1</update_rate>
<visualize>true</visualize>
<topic>imu</topic>
</sensor>
具体的には
<link name='chassis'>
の後ろでOK。
次に2D-Lidarを取り付ける。
Lidarは座標系が必要なので、lidar_frameの名前でchassisに下記の記載で取り付ける。
<frame name="lidar_frame" attached_to='chassis'>
<pose>0.8 0 0.5 0 0 0</pose>
</frame>
この記載もvehicle_blueの本体のタグの中に記載すればいいので、
<model name='vehicle_blue' canonical_link='chassis'>
<pose relative_to='world'>0 0 0 0 0 0</pose> <!--the pose is relative to the world by default-->
の下にペーストすればよい。
LidarのプラグインはIMUと同じく<world>タグの中にあればよいので、imuのプラグインの下にペーストしておく。
<plugin
filename="libignition-gazebo-sensors-system.so"
name="ignition::gazebo::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
最後に、下記lidarのオブジェクトをchassisリンクタグの下に取り付ける。
<sensor name='gpu_lidar' type='gpu_lidar'>
<pose relative_to='lidar_frame'>0 0 0 0 0 0</pose>
<topic>scan</topic> <!-- チュートリアルの"lidar"から変更 -->
<ignition_frame_id>base_scan</ignition_frame_id> <!-- 追加 -->
<update_rate>10</update_rate>
<ray>
<scan>
<horizontal>
<samples>640</samples>
<resolution>1</resolution>
<min_angle>-1.396263</min_angle>
<max_angle>1.396263</max_angle>
</horizontal>
<vertical>
<samples>1</samples>
<resolution>0.01</resolution>
<min_angle>0</min_angle>
<max_angle>0</max_angle>
</vertical>
</scan>
<range>
<min>0.08</min>
<max>20.0</max>
<resolution>0.01</resolution>
</range>
</ray>
<always_on>1</always_on>
<visualize>true</visualize>
</sensor>
<topic>をROS 2で使うscan二変更し,その下に<ignition_frame_id>base_scan</ignition_frame_id>というフレームIDを追加してある.
保存したらもう一度ign gazeboを立ち上げてみる。
ign gazebo world.sdf
立ち上げ後に、「Visualize lidar」のオプションを追加して、シミュレーションをスタートさせてから、下図のようにtopic名に/lidarを記載すると、青いLidarの照射状況が確認できる。
ここまでの記載の内容を下記に示す。
world.sdf
<?xml version="1.0" ?>
<sdf version="1.8">
<world name="car_world">
<physics name="1ms" type="ignored">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<plugin
filename="ignition-gazebo-physics-system"
name="ignition::gazebo::systems::Physics">
</plugin>
<plugin
filename="ignition-gazebo-user-commands-system"
name="ignition::gazebo::systems::UserCommands">
</plugin>
<plugin
filename="ignition-gazebo-scene-broadcaster-system"
name="ignition::gazebo::systems::SceneBroadcaster">
</plugin>
<plugin filename="libignition-gazebo-imu-system.so"
name="ignition::gazebo::systems::Imu">
</plugin>
<plugin
filename="libignition-gazebo-sensors-system.so"
name="ignition::gazebo::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>
<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
</link>
</model>
<model name='vehicle_blue'> <!-- 変更 <model name='vehicle_blue' canonical_link='chassis'> -->
<pose relative_to='world'>0 0 0 0 0 0</pose> <!--the pose is relative to the world by default-->
<!-- コメントアウト
<frame name="lidar_frame" attached_to='chassis'>
<pose>0.8 0 0.5 0 0 0</pose>
</frame>
-->
<link name="base_footprint"/> <!--追加-->
<plugin
filename="libignition-gazebo-diff-drive-system.so"
name="ignition::gazebo::systems::DiffDrive">
<left_joint>left_wheel_joint</left_joint>
<right_joint>right_wheel_joint</right_joint>
<wheel_separation>1.2</wheel_separation>
<wheel_radius>0.4</wheel_radius>
<!-- odom_publish_frequency>1</odom_publish_frequency コメントアウト-->
<topic>cmd_vel</topic>
</plugin>
<!-- Joint state publisherプラグイン追加 -->
<plugin filename="libignition-gazebo-joint-state-publisher-system.so"
name="ignition::gazebo::systems::JointStatePublisher">
<topic>joint_states</topic>
</plugin>
<!-- Global odometerプラグイン追加-->
<plugin
filename="ignition-gazebo-odometry-publisher-system"
name="ignition::gazebo::systems::OdometryPublisher">
<odom_publish_frequency>50</odom_publish_frequency>
<odom_topic>/odom</odom_topic>
<odom_frame>odom</odom_frame>
<robot_base_frame>base_footprint</robot_base_frame>
<tf_topic>/odom/tf</tf_topic>
</plugin>
<!--chassis をROS 2で使うbase_linkに変更 -->
<link name='base_link'> <!-- 変更 -->
<!-- link name='chassis' -->
<sensor name='gpu_lidar' type='gpu_lidar'>
<topic>scan</topic> <!-- チュートリアルの"lidar"から変更 -->
<ignition_frame_id>base_scan</ignition_frame_id> <!-- 追加 -->
<!-- pose relative_to='lidar_frame'>0 0 0 0 0 0</pose --> <!-- コメントアウト -->
<update_rate>5</update_rate> <!-- 重い場合は遅くしておく -->
<ray>
<scan>
<horizontal>
<samples>360</samples>
<resolution>1</resolution>
<min_angle>-3.14</min_angle>
<max_angle>3.14</max_angle>
</horizontal>
<vertical>
<samples>1</samples>
<resolution>0.01</resolution>
<min_angle>0</min_angle>
<max_angle>0</max_angle>
</vertical>
</scan>
<range>
<min>0.08</min>
<max>10.0</max>
<resolution>0.01</resolution>
</range>
</ray>
<always_on>1</always_on>
<visualize>true</visualize>
</sensor>
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>1</update_rate>
<visualize>true</visualize>
<topic>imu</topic>
</sensor>
<pose relative_to='__model__'>0.5 0 0.4 0 0 0</pose>
<inertial> <!--inertial properties of the link mass, inertia matix-->
<mass>1.14395</mass>
<inertia>
<ixx>0.095329</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.381317</iyy>
<iyz>0</iyz>
<izz>0.476646</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<box>
<size>2.0 1.0 0.5</size>
</box>
</geometry>
<!--Color of the link-->
<material>
<ambient>0.0 0.0 1.0 1</ambient>
<diffuse>0.0 0.0 1.0 1</diffuse>
<specular>0.0 0.0 1.0 1</specular>
</material>
</visual>
<collision name='collision'>
<geometry>
<box>
<size>2.0 1.0 0.5</size>
</box>
</geometry>
</collision>
</link>
<!--Left wheel-->
<link name='left_wheel'>
<pose relative_to="base_link">-0.5 0.6 0 -1.5707 0 0</pose> <!--angles are in radian-->
<inertial>
<mass>1</mass>
<inertia>
<ixx>0.043333</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.043333</iyy>
<iyz>0</iyz>
<izz>0.08</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<cylinder>
<radius>0.4</radius>
<length>0.2</length>
</cylinder>
</geometry>
<material>
<ambient>1.0 0.0 0.0 1</ambient>
<diffuse>1.0 0.0 0.0 1</diffuse>
<specular>1.0 0.0 0.0 1</specular>
</material>
</visual>
<collision name='collision'>
<geometry>
<cylinder>
<radius>0.4</radius>
<length>0.2</length>
</cylinder>
</geometry>
</collision>
</link>
<!--The same as left wheel but with different position-->
<link name='right_wheel'>
<pose relative_to="base_link">-0.5 -0.6 0 -1.5707 0 0</pose> <!--angles are in radian-->
<inertial>
<mass>1</mass>
<inertia>
<ixx>0.043333</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.043333</iyy>
<iyz>0</iyz>
<izz>0.08</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<cylinder>
<radius>0.4</radius>
<length>0.2</length>
</cylinder>
</geometry>
<material>
<ambient>1.0 0.0 0.0 1</ambient>
<diffuse>1.0 0.0 0.0 1</diffuse>
<specular>1.0 0.0 0.0 1</specular>
</material>
</visual>
<collision name='collision'>
<geometry>
<cylinder>
<radius>0.4</radius>
<length>0.2</length>
</cylinder>
</geometry>
</collision>
</link>
<!--arbitrary frame-->
<frame name="caster_frame" attached_to='base_link'>
<pose>0.8 0 -0.2 0 0 0</pose>
</frame>
<!--caster wheel-->
<link name='caster'>
<pose relative_to='caster_frame'/>
<inertial>
<mass>1</mass>
<inertia>
<ixx>0.016</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.016</iyy>
<iyz>0</iyz>
<izz>0.016</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<sphere>
<radius>0.2</radius>
</sphere>
</geometry>
<material>
<ambient>0.0 1 0.0 1</ambient>
<diffuse>0.0 1 0.0 1</diffuse>
<specular>0.0 1 0.0 1</specular>
</material>
</visual>
<collision name='collision'>
<geometry>
<sphere>
<radius>0.2</radius>
</sphere>
</geometry>
</collision>
</link>
<!--left wheel joint-->
<joint name='left_wheel_joint' type='revolute'>
<pose relative_to='left_wheel'/>
<parent>base_link</parent>
<child>left_wheel</child>
<axis>
<xyz expressed_in='__model__'>0 1 0</xyz> <!--can be descired to any frame or even arbitrary frames-->
<limit>
<lower>-1.79769e+308</lower> <!--negative infinity-->
<upper>1.79769e+308</upper> <!--positive infinity-->
</limit>
</axis>
</joint>
<!--right wheel joint-->
<joint name='right_wheel_joint' type='revolute'>
<pose relative_to='right_wheel'/>
<parent>base_link</parent>
<child>right_wheel</child>
<axis>
<xyz expressed_in='__model__'>0 1 0</xyz>
<limit>
<lower>-1.79769e+308</lower> <!--negative infinity-->
<upper>1.79769e+308</upper> <!--positive infinity-->
</limit>
</axis>
</joint>
<!--caster wheel joint--> <!--pose defult value is the child-->
<joint name='caster_wheel' type='ball'>
<parent>base_link</parent>
<child>caster</child>
</joint>
</model>
</world>
</sdf>
ROS 2にトピックをブリッジしてRviz2で表示できることを確認する。
適当にパッケージを作成する.
cd ~/ros2_ws/src/
ros2 pkg create --build-type ament_cmake sample_ignros
cd sample_ignros
mkdir models
mkdir launch
cd models
mkdir mobilerobot
mkdir worlds
作成したworldに先ほど作成したworld.sdfを保存.
world.sdfにロボットのモデルが含まれてしまっているので,分離する.
world.sdfは<model>のタグの部分をすべて切り取る.
mobilerobotのディレクトリ内にmodel.sddfを作成して先ほど切り取った<model>のタグをペーストする.ただし,下記の<sdf>タグで最初と最後を囲むこと.
<sdf version='1.8'>
<model>
・・・
</model>
</sdf>
ディレクトリ構成は下記.
sample_ignros/
launch/
models/
mobilerobot/
model.sdf
worlds/
world.sdf
launchファイルを作成する.
gedit sample_ignros.launch.py